Skip to content

Commit ba39c63

Browse files
asainilocusbmagyar
andauthored
Locus service trigger (#4)
I wanted to setup this PR to start getting some feedback. Need a bit more cleanup and corner cases check, but I can trigger and get images in service response. I have few more things to add on thread safety but any suggestions are welcome. --------- Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
1 parent 09101d2 commit ba39c63

File tree

13 files changed

+260
-34
lines changed

13 files changed

+260
-34
lines changed

orbbec_camera/include/orbbec_camera/ob_camera_node.h

Lines changed: 24 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848

4949
#include "orbbec_camera_msgs/msg/device_info.hpp"
5050
#include "orbbec_camera_msgs/srv/get_device_info.hpp"
51+
#include "orbbec_camera_msgs/srv/camera_trigger.hpp"
5152
#include "orbbec_camera_msgs/msg/extrinsics.hpp"
5253
#include "orbbec_camera_msgs/msg/metadata.hpp"
5354
#include "orbbec_camera_msgs/msg/imu_info.hpp"
@@ -111,6 +112,7 @@ using SetBool = std_srvs::srv::SetBool;
111112
using GetBool = orbbec_camera_msgs::srv::GetBool;
112113
using SetFilter = orbbec_camera_msgs::srv::SetFilter;
113114
using SetArrays = orbbec_camera_msgs::srv::SetArrays;
115+
using CameraTrigger = orbbec_camera_msgs::srv::CameraTrigger;
114116

115117
typedef std::pair<ob_stream_type, int> stream_index_pair;
116118

@@ -313,8 +315,10 @@ class OBCameraNode {
313315
std::shared_ptr<SetFilter ::Response>& response);
314316
void setSYNCHostimeCallback(const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
315317
std::shared_ptr<std_srvs::srv::SetBool::Response>& response);
316-
void sendSoftwareTriggerCallback(const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
317-
std::shared_ptr<std_srvs::srv::SetBool::Response>& response);
318+
319+
void resetCaptureServiceVariables();
320+
void sendSoftwareTriggerCallback(const std::shared_ptr<CameraTrigger::Request>& request,
321+
std::shared_ptr<CameraTrigger::Response>& response);
318322

319323
bool toggleSensor(const stream_index_pair& stream_index, bool enabled, std::string& msg);
320324

@@ -495,8 +499,24 @@ class OBCameraNode {
495499
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_reset_timestamp_srv_;
496500
rclcpp::Service<SetInt32>::SharedPtr set_interleaver_laser_sync_srv_;
497501
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_sync_host_time_srv_;
498-
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr send_software_trigger_srv_;
502+
rclcpp::Service<CameraTrigger>::SharedPtr send_service_trigger_srv_;
499503
rclcpp::Service<SetFilter>::SharedPtr set_filter_srv_;
504+
rclcpp::Service<CameraTrigger>::SharedPtr capture_camera_images_srv_;
505+
506+
507+
std::atomic_bool service_capture_started_{false};
508+
std::atomic_int number_of_rgb_frames_captured_{0};
509+
std::atomic_int number_of_depth_frames_captured_{0};
510+
std::mutex service_capture_lock_;
511+
std::condition_variable service_capture_cv_;
512+
sensor_msgs::msg::CameraInfo color_image_camera_info_;
513+
sensor_msgs::msg::CameraInfo depth_image_camera_info_;
514+
sensor_msgs::msg::Image::UniquePtr color_image_;
515+
sensor_msgs::msg::Image::UniquePtr depth_image_;
516+
sensor_msgs::msg::Image::UniquePtr undistorted_color_images_;
517+
518+
// timeout in ms
519+
float service_capture_time_out_ = 1000;
500520

501521
bool enable_sync_output_accel_gyro_ = false;
502522
bool publish_tf_ = false;
@@ -585,6 +605,7 @@ class OBCameraNode {
585605
int trigger2image_delay_us_ = 0;
586606
int trigger_out_delay_us_ = 0;
587607
bool trigger_out_enabled_ = false;
608+
bool service_trigger_enabled_ = false;
588609
bool software_trigger_enabled_ = false;
589610
int frames_per_trigger_ = 2;
590611
bool enable_ptp_config_ = false;

orbbec_camera/launch/gemini_330_series.launch.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ def generate_launch_description():
8585
DeclareLaunchArgument('color_ae_roi_top', default_value='-1'),
8686
DeclareLaunchArgument('color_ae_roi_bottom', default_value='-1'),
8787
DeclareLaunchArgument('color_exposure', default_value='-1'),
88+
DeclareLaunchArgument('trigger_mode', default_value='false'),
8889
DeclareLaunchArgument('color_gain', default_value='-1'),
8990
DeclareLaunchArgument('enable_color_auto_white_balance', default_value='true'),
9091
DeclareLaunchArgument('color_white_balance', default_value='-1'),
@@ -180,7 +181,8 @@ def generate_launch_description():
180181
DeclareLaunchArgument('trigger2image_delay_us', default_value='0'),
181182
DeclareLaunchArgument('trigger_out_delay_us', default_value='0'),
182183
DeclareLaunchArgument('trigger_out_enabled', default_value='true'),
183-
DeclareLaunchArgument('software_trigger_enabled', default_value='true'),
184+
DeclareLaunchArgument('software_trigger_enabled', default_value='false'),
185+
DeclareLaunchArgument('service_trigger_enabled', default_value='false'),
184186
DeclareLaunchArgument('frames_per_trigger', default_value='2'),
185187
DeclareLaunchArgument('software_trigger_period', default_value='33'), # ms
186188
DeclareLaunchArgument('enable_ptp_config', default_value='false'), # Only for Gemini 335Le

orbbec_camera/src/ob_camera_node.cpp

Lines changed: 35 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -300,7 +300,7 @@ void OBCameraNode::setupDevices() {
300300
RCLCPP_INFO_STREAM(logger_,
301301
"Software trigger period " << software_trigger_period_.count() << " ms");
302302
software_trigger_timer_ = node_->create_wall_timer(software_trigger_period_, [this]() {
303-
if (software_trigger_enabled_) {
303+
if (!service_trigger_enabled_ and software_trigger_enabled_) {
304304
TRY_EXECUTE_BLOCK(device_->triggerCapture());
305305
}
306306
});
@@ -1655,7 +1655,8 @@ void OBCameraNode::getParameters() {
16551655
setAndGetNodeParameter<int>(trigger2image_delay_us_, "trigger2image_delay_us", 0);
16561656
setAndGetNodeParameter<int>(trigger_out_delay_us_, "trigger_out_delay_us", 0);
16571657
setAndGetNodeParameter<bool>(trigger_out_enabled_, "trigger_out_enabled", true);
1658-
setAndGetNodeParameter<bool>(software_trigger_enabled_, "software_trigger_enabled", true);
1658+
setAndGetNodeParameter<bool>(software_trigger_enabled_, "software_trigger_enabled", false);
1659+
setAndGetNodeParameter<bool>(service_trigger_enabled_, "service_trigger_enabled", false);
16591660
setAndGetNodeParameter<bool>(enable_ptp_config_, "enable_ptp_config", false);
16601661
setAndGetNodeParameter<std::string>(cloud_frame_id_, "cloud_frame_id", "");
16611662
if (enable_colored_point_cloud_ || enable_d2c_viewer_) {
@@ -2660,7 +2661,7 @@ bool OBCameraNode::decodeColorFrameToBuffer(const std::shared_ptr<ob::Frame> &fr
26602661
if (enable_colored_point_cloud_ && depth_registration_cloud_pub_->get_subscription_count() > 0) {
26612662
has_subscriber = true;
26622663
}
2663-
if (!has_subscriber) {
2664+
if (!has_subscriber && !service_capture_started_) {
26642665
return false;
26652666
}
26662667
if (metadata_publishers_.count(COLOR) &&
@@ -2753,7 +2754,7 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
27532754
has_subscriber =
27542755
has_subscriber || (metadata_publishers_.count(stream_index) &&
27552756
metadata_publishers_[stream_index]->get_subscription_count() > 0);
2756-
if (!has_subscriber) {
2757+
if (!has_subscriber && !service_capture_started_) {
27572758
return;
27582759
}
27592760
std::shared_ptr<ob::VideoFrame> video_frame;
@@ -2835,9 +2836,6 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
28352836
publishMetadata(frame, stream_index, camera_info.header);
28362837
}
28372838
CHECK_NOTNULL(image_publishers_[stream_index]);
2838-
if (image_publishers_[stream_index]->get_subscription_count() == 0) {
2839-
return;
2840-
}
28412839
auto &image = images_[stream_index];
28422840
if (image.empty() || image.cols != width || image.rows != height) {
28432841
image.create(height, width, image_format_[stream_index]);
@@ -2848,7 +2846,7 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
28482846
}
28492847
if (frame->getType() == OB_FRAME_COLOR && frame->format() != OB_FORMAT_Y8 &&
28502848
frame->format() != OB_FORMAT_Y16 && frame->format() != OB_FORMAT_BGRA &&
2851-
frame->format() != OB_FORMAT_RGBA && image_publishers_[COLOR]->get_subscription_count() > 0) {
2849+
frame->format() != OB_FORMAT_RGBA && (image_publishers_[COLOR]->get_subscription_count() > 0 || service_capture_started_)) {
28522850
memcpy(image.data, rgb_buffer_, video_frame->getWidth() * video_frame->getHeight() * 3);
28532851
} else {
28542852
memcpy(image.data, video_frame->getData(), video_frame->getDataSize());
@@ -2868,10 +2866,32 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
28682866
image_msg->step = width * unit_step_size_[stream_index];
28692867
image_msg->header.frame_id = frame_id;
28702868
CHECK(image_publishers_.count(stream_index) > 0);
2871-
saveImageToFile(stream_index, image, *image_msg);
2872-
image_publishers_[stream_index]->publish(std::move(image_msg));
2873-
if (stream_index == COLOR && enable_color_undistortion_ &&
2874-
color_undistortion_publisher_->get_subscription_count() > 0) {
2869+
2870+
if (image_publishers_[stream_index]->get_subscription_count() > 0) {
2871+
// saveImageToFile(stream_index, image, *image_msg);
2872+
image_publishers_[stream_index]->publish(std::move(image_msg));
2873+
}
2874+
2875+
if (service_trigger_enabled_ and service_capture_started_) {
2876+
std::unique_lock<std::mutex> lock(service_capture_lock_);
2877+
if (stream_index == COLOR) {
2878+
if (image_msg) {
2879+
number_of_rgb_frames_captured_++;
2880+
color_image_ = std::move(image_msg);
2881+
color_image_camera_info_ = camera_info;
2882+
}
2883+
}
2884+
else if (stream_index == DEPTH) {
2885+
if (image_msg) {
2886+
number_of_depth_frames_captured_++;
2887+
depth_image_ = std::move(image_msg);
2888+
depth_image_camera_info_ = camera_info;
2889+
}
2890+
}
2891+
service_capture_cv_.notify_all();
2892+
}
2893+
2894+
if (stream_index == COLOR && enable_color_undistortion_) {
28752895
auto undistorted_image = undistortImage(image, intrinsic, distortion);
28762896
sensor_msgs::msg::Image::UniquePtr undistorted_image_msg(new sensor_msgs::msg::Image());
28772897
cv_bridge::CvImage(std_msgs::msg::Header(), encoding_[stream_index], undistorted_image)
@@ -2881,7 +2901,9 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
28812901
undistorted_image_msg->is_bigendian = false;
28822902
undistorted_image_msg->step = width * unit_step_size_[stream_index];
28832903
undistorted_image_msg->header.frame_id = frame_id;
2884-
color_undistortion_publisher_->publish(std::move(undistorted_image_msg));
2904+
if (color_undistortion_publisher_->get_subscription_count() > 0) {
2905+
color_undistortion_publisher_->publish(std::move(undistorted_image_msg));
2906+
}
28852907
}
28862908
}
28872909

orbbec_camera/src/ros_service.cpp

Lines changed: 52 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -206,9 +206,9 @@ void OBCameraNode::setupCameraCtrlServices() {
206206
std::shared_ptr<SetBool::Response> response) {
207207
setSYNCHostimeCallback(request, response);
208208
});
209-
send_software_trigger_srv_ = node_->create_service<SetBool>(
210-
"send_software_trigger", [this](const std::shared_ptr<SetBool::Request> request,
211-
std::shared_ptr<SetBool::Response> response) {
209+
send_service_trigger_srv_ = node_->create_service<CameraTrigger>(
210+
"send_service_trigger", [this](const std::shared_ptr<CameraTrigger::Request> request,
211+
std::shared_ptr<CameraTrigger::Response> response) {
212212
sendSoftwareTriggerCallback(request, response);
213213
});
214214
set_write_customerdata_srv_ = node_->create_service<SetString>(
@@ -1063,23 +1063,58 @@ void OBCameraNode::setSYNCHostimeCallback(
10631063
}
10641064
}
10651065

1066+
void OBCameraNode::resetCaptureServiceVariables() {
1067+
service_capture_started_ = false;
1068+
number_of_rgb_frames_captured_ = 0;
1069+
number_of_depth_frames_captured_ = 0;
1070+
}
1071+
10661072
void OBCameraNode::sendSoftwareTriggerCallback(
1067-
const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
1068-
std::shared_ptr<std_srvs::srv::SetBool::Response>& response) {
1069-
try {
1070-
if (request->data) {
1073+
const std::shared_ptr<CameraTrigger::Request>& request,
1074+
std::shared_ptr<CameraTrigger::Response>& response) {
1075+
(void)request;
1076+
if (service_trigger_enabled_ and !software_trigger_enabled_) {
1077+
service_capture_started_ = true;
1078+
try {
1079+
RCLCPP_DEBUG_STREAM(logger_, "Triggering");
10711080
device_->triggerCapture();
1081+
1082+
RCLCPP_DEBUG_STREAM(logger_, "Capturing images");
1083+
std::unique_lock<std::mutex> lock(service_capture_lock_);
1084+
service_capture_cv_.wait_until(
1085+
lock, std::chrono::system_clock::now() + std::chrono::seconds(1), [this]() {
1086+
return (number_of_rgb_frames_captured_ >= frames_per_trigger_ &&
1087+
number_of_depth_frames_captured_ >= frames_per_trigger_);
1088+
});
1089+
RCLCPP_DEBUG_STREAM(logger_, "Captured " << number_of_rgb_frames_captured_ << " "
1090+
<< number_of_depth_frames_captured_ << " "
1091+
<< (color_image_ == nullptr) << " "
1092+
<< (depth_image_ == nullptr));
1093+
1094+
if (number_of_rgb_frames_captured_ >= frames_per_trigger_ &&
1095+
number_of_depth_frames_captured_ >= frames_per_trigger_ && color_image_ && depth_image_) {
1096+
response->success = true;
1097+
response->rgb_image = *(color_image_);
1098+
response->depth_image = *(depth_image_);
1099+
response->rgb_camera_info = color_image_camera_info_;
1100+
response->depth_camera_info = depth_image_camera_info_;
1101+
} else {
1102+
response->success = false;
1103+
response->message = "Failed to capture images";
1104+
}
1105+
} catch (const ob::Error& e) {
1106+
response->message = e.getMessage();
1107+
response->success = false;
1108+
} catch (const std::exception& e) {
1109+
response->message = e.what();
1110+
response->success = false;
1111+
} catch (...) {
1112+
response->message = "unknown error";
1113+
response->success = false;
10721114
}
1073-
response->success = true;
1074-
} catch (const ob::Error& e) {
1075-
response->message = e.getMessage();
1076-
response->success = false;
1077-
} catch (const std::exception& e) {
1078-
response->message = e.what();
1079-
response->success = false;
1080-
} catch (...) {
1081-
response->message = "unknown error";
1082-
response->success = false;
1115+
resetCaptureServiceVariables();
1116+
} else {
1117+
RCLCPP_INFO_STREAM(logger_, "Service not enabled");
10831118
}
10841119
}
10851120

orbbec_camera_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ rosidl_generate_interfaces(
2121
"msg/Metadata.msg"
2222
"msg/IMUInfo.msg"
2323
"msg/RGBD.msg"
24+
"srv/CameraTrigger.srv"
2425
"srv/GetBool.srv"
2526
"srv/GetDeviceInfo.srv"
2627
"srv/GetCameraInfo.srv"
Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# Copyright (C) 2024, Locus Robotics. All rights reserved.
2+
# Unauthorized copying of this file, via any medium, is strictly prohibited
3+
# Proprietary and confidential
4+
5+
---
6+
bool success
7+
string message
8+
sensor_msgs/Image rgb_image
9+
sensor_msgs/Image depth_image
10+
sensor_msgs/CameraInfo rgb_camera_info
11+
sensor_msgs/CameraInfo depth_camera_info
Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<launch>
2+
3+
<arg name="use_tote_pose" default="true" />
4+
5+
<node pkg="orbbec_camera_py" exec="run_orbbec_trigger" output="both">
6+
<param name="camera_name" value="/inward_a_right_camera"/>
7+
<param name="trigger_period" value="5.0"/>
8+
</node>
9+
10+
</launch>

orbbec_camera_py/orbbec_camera_py/__init__.py

Whitespace-only changes.
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
# Copyright (C) 2023, Locus Robotics. All rights reserved.
2+
# Unauthorized copying of this file, via any medium, is strictly prohibited
3+
# Proprietary and confidential
4+
5+
from typing import cast
6+
7+
import time
8+
import rclpy
9+
from rclpy.node import Node
10+
from cv_bridge import CvBridge
11+
from sensor_msgs.msg import Image, CameraInfo
12+
from orbbec_camera_msgs.srv import CameraTrigger
13+
14+
15+
class OrbbecTriggerNode(Node):
16+
def __init__(self):
17+
super().__init__("orbbec_camera_trigger")
18+
19+
self.declare_parameter("camera_name", rclpy.Parameter.Type.STRING)
20+
self.declare_parameter("trigger_period", rclpy.Parameter.Type.DOUBLE)
21+
22+
self.img_publisher = self.create_publisher(
23+
Image, "~/trigger_rgb_image", 1
24+
)
25+
self.bridge = CvBridge()
26+
27+
self.camera_name = cast(str, self.get_parameter("camera_name").value)
28+
self.trigger_period = cast(float, self.get_parameter("trigger_period").value)
29+
30+
self.client = self.create_client(CameraTrigger, self.camera_name + "/send_service_trigger")
31+
while not self.client.wait_for_service(timeout_sec=1.0):
32+
self.get_logger().info("Service not available, waiting...")
33+
self.get_logger().info("Service available")
34+
self.request = CameraTrigger.Request()
35+
36+
def spin(self):
37+
time.sleep(self.trigger_period)
38+
self.get_logger().info("Calling service...")
39+
self.future = self.client.call_async(self.request)
40+
rclpy.spin_until_future_complete(self, self.future)
41+
42+
if self.future.result() is not None and self.future.result().success:
43+
response = self.future.result()
44+
45+
self.img_publisher.publish(self.future.result().rgb_image)
46+
self.get_logger().error("Received Images!")
47+
else:
48+
self.get_logger().error("Service call failed!")
49+
50+
51+
def main(args=None):
52+
rclpy.init(args=args)
53+
node = OrbbecTriggerNode()
54+
55+
while rclpy.ok():
56+
try:
57+
node.spin()
58+
except KeyboardInterrupt:
59+
pass
60+
61+
node.destroy_node()
62+
rclpy.shutdown()
63+
64+
65+
if __name__ == "__main__":
66+
main()

orbbec_camera_py/package.xml

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>orbbec_camera_py</name>
5+
<version>0.1.0</version>
6+
<description>Test python nodes for orbbec.</description>
7+
<maintainer email="asaini@locusrobotics.com">Amritpal Saini</maintainer>
8+
<license>Proprietary</license>
9+
10+
<depend>orbbec_camera_msgs</depend>
11+
<depend>geometry_msgs</depend>
12+
<depend>sensor_msgs</depend>
13+
<depend>sensor_msgs_py</depend>
14+
15+
<exec_depend>message_filters</exec_depend>
16+
<exec_depend>rosidl_runtime_py</exec_depend>
17+
18+
<test_depend>python3-pytest</test_depend>
19+
20+
<export>
21+
<build_type>ament_python</build_type>
22+
</export>
23+
</package>

0 commit comments

Comments
 (0)