forked from zivid/zivid-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsample_capture_with_settings_from_yml.cpp
59 lines (46 loc) · 2.24 KB
/
sample_capture_with_settings_from_yml.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
#include <zivid_camera/SettingsAcquisitionConfig.h>
#include <zivid_camera/SettingsConfig.h>
#include <zivid_camera/Capture.h>
#include <zivid_camera/LoadSettingsFromFile.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/client.h>
#include <sensor_msgs/PointCloud2.h>
#include <ros/ros.h>
#include <ros/package.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 service");
zivid_camera::Capture capture;
CHECK(ros::service::call("/zivid_camera/capture", capture));
}
} // namespace
int main(int argc, char** argv)
{
ros::init(argc, argv, "sample_capture_with_settings_from_yml_cpp");
ros::NodeHandle n;
ROS_INFO("Starting sample_capture_with_settings_from_yml.cpp");
CHECK(ros::service::waitForService("/zivid_camera/capture", default_wait_duration));
ros::AsyncSpinner spinner(1);
spinner.start();
std::string samples_path = ros::package::getPath("zivid_samples");
std::string settings_path = samples_path + "/settings/camera_settings.yml";
ROS_INFO("Loading settings from: %s", settings_path.c_str());
zivid_camera::LoadSettingsFromFile load_settings_from_file;
load_settings_from_file.request.file_path = settings_path;
CHECK(ros::service::call("/zivid_camera/load_settings_from_file", load_settings_from_file));
ROS_INFO("Calling capture");
capture();
ros::waitForShutdown();
return 0;
}