forked from zivid/zivid-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
sample_capture_assistant.cpp
74 lines (57 loc) · 2.63 KB
/
sample_capture_assistant.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
#include <zivid_camera/Capture.h>
#include <zivid_camera/CaptureAssistantSuggestSettings.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <ros/ros.h>
#define CHECK(cmd) \
do \
{ \
if (!cmd) \
{ \
throw std::runtime_error{ "\"" #cmd "\" failed!" }; \
} \
} while (false)
namespace
{
const ros::Duration default_wait_duration{ 30 };
constexpr auto ca_suggest_settings_service_name = "/zivid_camera/capture_assistant/suggest_settings";
void capture_assistant_suggest_settings()
{
zivid_camera::CaptureAssistantSuggestSettings cass;
cass.request.max_capture_time = ros::Duration{ 1.20 };
cass.request.ambient_light_frequency =
zivid_camera::CaptureAssistantSuggestSettings::Request::AMBIENT_LIGHT_FREQUENCY_NONE;
ROS_INFO_STREAM("Calling " << ca_suggest_settings_service_name
<< " with max capture time = " << cass.request.max_capture_time << " sec");
CHECK(ros::service::call(ca_suggest_settings_service_name, cass));
}
void capture()
{
ROS_INFO("Calling capture service");
zivid_camera::Capture capture;
CHECK(ros::service::call("/zivid_camera/capture", capture));
}
void on_points(const sensor_msgs::PointCloud2ConstPtr&)
{
ROS_INFO("PointCloud received");
}
void on_image_color(const sensor_msgs::ImageConstPtr&)
{
ROS_INFO("2D color image received");
}
} // namespace
int main(int argc, char** argv)
{
ros::init(argc, argv, "sample_capture_assistant_cpp");
ros::NodeHandle n;
ROS_INFO("Starting sample_capture_assistant.cpp");
CHECK(ros::service::waitForService(ca_suggest_settings_service_name, default_wait_duration));
ros::AsyncSpinner spinner(1);
spinner.start();
auto points_sub = n.subscribe("/zivid_camera/points/xyzrgba", 1, on_points);
auto image_color_sub = n.subscribe("/zivid_camera/color/image_color", 1, on_image_color);
capture_assistant_suggest_settings();
capture();
ros::waitForShutdown();
return 0;
}