forked from zivid/zivid-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
sample_capture_2d.cpp
71 lines (55 loc) · 2.79 KB
/
sample_capture_2d.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
#include <zivid_camera/Settings2DAcquisitionConfig.h>
#include <zivid_camera/Capture2D.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/client.h>
#include <sensor_msgs/Image.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 };
void capture()
{
ROS_INFO("Calling capture_2d service");
zivid_camera::Capture2D capture_2d;
CHECK(ros::service::call("/zivid_camera/capture_2d", capture_2d));
}
void on_image_color(const sensor_msgs::ImageConstPtr&)
{
ROS_INFO("2D color image received");
capture();
}
} // namespace
int main(int argc, char** argv)
{
ros::init(argc, argv, "sample_capture_2d");
ros::NodeHandle n;
ROS_INFO("Starting sample_capture_2d.cpp");
CHECK(ros::service::waitForService("/zivid_camera/capture_2d", default_wait_duration));
ros::AsyncSpinner spinner(1);
spinner.start();
auto image_color_sub = n.subscribe("/zivid_camera/color/image_color", 1, on_image_color);
ROS_INFO("Configuring image settings");
dynamic_reconfigure::Client<zivid_camera::Settings2DAcquisitionConfig> acquisition_0_client("/zivid_camera/"
"settings_2d/"
"acquisition_0/");
// To initialize the cfg object we need to load the default configuration from the server.
// The default values of settings depends on which Zivid camera model is connected.
zivid_camera::Settings2DAcquisitionConfig acquisition_0_config;
CHECK(acquisition_0_client.getDefaultConfiguration(acquisition_0_config, default_wait_duration));
acquisition_0_config.enabled = true;
acquisition_0_config.aperture = 5.66;
acquisition_0_config.exposure_time = 10000;
acquisition_0_config.brightness = 1.0;
CHECK(acquisition_0_client.setConfiguration(acquisition_0_config));
capture();
ros::waitForShutdown();
return 0;
}