-
Notifications
You must be signed in to change notification settings - Fork 47
/
sample_capture_2d.cpp
94 lines (79 loc) · 3.02 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
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <stdexcept>
/*
* This sample shows how to set the settings_2d_yaml parameter of the zivid node, subscribe for the
* color/image_color topic, and invoke the capture_2d service. When an image is received, a new
* capture is triggered.
*/
void fatal_error(const rclcpp::Logger & logger, const std::string & message)
{
RCLCPP_ERROR_STREAM(logger, message);
throw std::runtime_error(message);
}
void set_settings_2d(const std::shared_ptr<rclcpp::Node> & node)
{
RCLCPP_INFO_STREAM(node->get_logger(), "Setting parameter `settings_2d_yaml`");
const std::string settings_2d_yaml =
R"(
__version__:
serializer: 1
data: 3
Settings2D:
Acquisitions:
- Acquisition:
Aperture: 2.83
Brightness: 1.0
ExposureTime: 10000
Gain: 2.5
)";
auto param_client = std::make_shared<rclcpp::AsyncParametersClient>(node, "zivid_camera");
while (!param_client->wait_for_service(std::chrono::seconds(3))) {
if (!rclcpp::ok()) {
fatal_error(node->get_logger(), "Client interrupted while waiting for service to appear.");
}
RCLCPP_INFO(node->get_logger(), "Waiting for the parameters client to appear...");
}
auto result =
param_client->set_parameters({rclcpp::Parameter("settings_2d_yaml", settings_2d_yaml)});
if (
rclcpp::spin_until_future_complete(node, result, std::chrono::seconds(30)) !=
rclcpp::FutureReturnCode::SUCCESS) {
fatal_error(node->get_logger(), "Failed to set `settings_2d_yaml` parameter");
}
}
auto create_capture_2d_client(std::shared_ptr<rclcpp::Node> & node)
{
auto client = node->create_client<std_srvs::srv::Trigger>("capture_2d");
while (!client->wait_for_service(std::chrono::seconds(3))) {
if (!rclcpp::ok()) {
fatal_error(node->get_logger(), "Client interrupted while waiting for service to appear.");
}
RCLCPP_INFO(node->get_logger(), "Waiting for the capture_2d service to appear...");
}
RCLCPP_INFO(node->get_logger(), "capture_2d service is available");
return client;
}
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("sample_capture_2d");
RCLCPP_INFO(node->get_logger(), "Started the sample_capture_2d node");
set_settings_2d(node);
auto capture_2d_client = create_capture_2d_client(node);
auto trigger_capture = [&]() {
RCLCPP_INFO(node->get_logger(), "Triggering 2d capture");
capture_2d_client->async_send_request(std::make_shared<std_srvs::srv::Trigger::Request>());
};
auto color_image_color_subscription = node->create_subscription<sensor_msgs::msg::Image>(
"color/image_color", 10, [&](sensor_msgs::msg::Image::ConstSharedPtr msg) -> void {
RCLCPP_INFO(node->get_logger(), "Received image of size %d x %d", msg->width, msg->height);
trigger_capture();
});
trigger_capture();
RCLCPP_INFO(node->get_logger(), "Spinning node.. Press Ctrl+C to abort.");
rclcpp::spin(node);
rclcpp::shutdown();
return EXIT_SUCCESS;
}