Skip to content

Commit 9e1ba96

Browse files
committed
Add set_software_trigger_enabled param and service
1 parent e52169a commit 9e1ba96

File tree

6 files changed

+44
-3
lines changed

6 files changed

+44
-3
lines changed

docs/all_available_service_for_camera_control.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -326,3 +326,9 @@ ros2 service call /camera/set_sync_interleaverlaser orbbec_camera_msgs/srv/SetIn
326326
```
327327
ros2 service call /camera/set_sync_hosttime std_srvs/srv/SetBool '{data: true}'
328328
```
329+
330+
* `/camera/set_software_trigger_enabled`
331+
332+
```
333+
ros2 service call /camera/set_software_trigger_enabled std_srvs/srv/SetBool '{data: true}'
334+
```

docs/launch_parameters.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,8 @@ The following are the launch parameters available:
151151
* The delay time of the trigger signal output after receiving the capture command or trigger signal in microseconds,this parameter is usually used [multi camera synced](../orbbec_camera/examples/multi_camera_synced/README.MD)
152152
* **trigger_out_enabled**
153153
* Enable the trigger out signal,this parameter is usually used [multi camera synced](../orbbec_camera/examples/multi_camera_synced/README.MD)
154+
* **software_trigger_enabled**
155+
* Enable the software trigger out signal,this parameter is usually used [multi camera synced](../orbbec_camera/examples/multi_camera_synced/README.MD)
154156
* **frames_per_trigger**
155157
* The frame number of each stream after each trigger in triggering mode,this parameter is usually used [multi camera synced](../orbbec_camera/examples/multi_camera_synced/README.MD)
156158
* **software_trigger_period**

orbbec_camera/include/orbbec_camera/ob_camera_node.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -313,6 +313,9 @@ class OBCameraNode {
313313
std::shared_ptr<SetFilter ::Response>& response);
314314
void setSYNCHostimeCallback(const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
315315
std::shared_ptr<std_srvs::srv::SetBool::Response>& response);
316+
void setSoftwareTriggerEnabledCallback(
317+
const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
318+
std::shared_ptr<std_srvs::srv::SetBool::Response>& response);
316319

317320
bool toggleSensor(const stream_index_pair& stream_index, bool enabled, std::string& msg);
318321

@@ -493,6 +496,7 @@ class OBCameraNode {
493496
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_reset_timestamp_srv_;
494497
rclcpp::Service<SetInt32>::SharedPtr set_interleaver_laser_sync_srv_;
495498
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_sync_host_time_srv_;
499+
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_software_trigger_enabled_srv_;
496500
rclcpp::Service<SetFilter>::SharedPtr set_filter_srv_;
497501

498502
bool enable_sync_output_accel_gyro_ = false;
@@ -582,6 +586,7 @@ class OBCameraNode {
582586
int trigger2image_delay_us_ = 0;
583587
int trigger_out_delay_us_ = 0;
584588
bool trigger_out_enabled_ = false;
589+
bool software_trigger_enabled_ = false;
585590
int frames_per_trigger_ = 2;
586591
bool enable_ptp_config_ = false;
587592
std::string depth_precision_str_;

orbbec_camera/launch/gemini_330_series.launch.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,7 @@ def generate_launch_description():
178178
DeclareLaunchArgument('trigger2image_delay_us', default_value='0'),
179179
DeclareLaunchArgument('trigger_out_delay_us', default_value='0'),
180180
DeclareLaunchArgument('trigger_out_enabled', default_value='true'),
181+
DeclareLaunchArgument('software_trigger_enabled', default_value='true'),
181182
DeclareLaunchArgument('frames_per_trigger', default_value='2'),
182183
DeclareLaunchArgument('software_trigger_period', default_value='33'), # ms
183184
DeclareLaunchArgument('enable_ptp_config', default_value='false'),#Only for Gemini 335Le

orbbec_camera/src/ob_camera_node.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -299,8 +299,11 @@ void OBCameraNode::setupDevices() {
299299
RCLCPP_INFO_STREAM(logger_, "Frames per trigger: " << sync_config.framesPerTrigger);
300300
RCLCPP_INFO_STREAM(logger_,
301301
"Software trigger period " << software_trigger_period_.count() << " ms");
302-
software_trigger_timer_ = node_->create_wall_timer(
303-
software_trigger_period_, [this]() { TRY_EXECUTE_BLOCK(device_->triggerCapture()); });
302+
software_trigger_timer_ = node_->create_wall_timer(software_trigger_period_, [this]() {
303+
if (software_trigger_enabled_) {
304+
TRY_EXECUTE_BLOCK(device_->triggerCapture());
305+
}
306+
});
304307
}
305308
}
306309
if (device_->isPropertySupported(OB_DEVICE_PTP_CLOCK_SYNC_ENABLE_BOOL,
@@ -1652,7 +1655,8 @@ void OBCameraNode::getParameters() {
16521655
setAndGetNodeParameter<int>(color_delay_us_, "color_delay_us", 0);
16531656
setAndGetNodeParameter<int>(trigger2image_delay_us_, "trigger2image_delay_us", 0);
16541657
setAndGetNodeParameter<int>(trigger_out_delay_us_, "trigger_out_delay_us", 0);
1655-
setAndGetNodeParameter<bool>(trigger_out_enabled_, "trigger_out_enabled", false);
1658+
setAndGetNodeParameter<bool>(trigger_out_enabled_, "trigger_out_enabled", true);
1659+
setAndGetNodeParameter<bool>(software_trigger_enabled_, "software_trigger_enabled", true);
16561660
setAndGetNodeParameter<bool>(enable_ptp_config_, "enable_ptp_config", false);
16571661
setAndGetNodeParameter<std::string>(cloud_frame_id_, "cloud_frame_id", "");
16581662
if (enable_colored_point_cloud_ || enable_d2c_viewer_) {

orbbec_camera/src/ros_service.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -206,6 +206,11 @@ void OBCameraNode::setupCameraCtrlServices() {
206206
std::shared_ptr<SetBool::Response> response) {
207207
setSYNCHostimeCallback(request, response);
208208
});
209+
set_software_trigger_enabled_srv_ = node_->create_service<SetBool>(
210+
"set_software_trigger_enabled", [this](const std::shared_ptr<SetBool::Request> request,
211+
std::shared_ptr<SetBool::Response> response) {
212+
setSoftwareTriggerEnabledCallback(request, response);
213+
});
209214
set_write_customerdata_srv_ = node_->create_service<SetString>(
210215
"set_write_customer_data", [this](const std::shared_ptr<SetString::Request> request,
211216
std::shared_ptr<SetString::Response> response) {
@@ -1058,6 +1063,24 @@ void OBCameraNode::setSYNCHostimeCallback(
10581063
}
10591064
}
10601065

1066+
void OBCameraNode::setSoftwareTriggerEnabledCallback(
1067+
const std::shared_ptr<std_srvs::srv::SetBool::Request>& request,
1068+
std::shared_ptr<std_srvs::srv::SetBool::Response>& response) {
1069+
try {
1070+
software_trigger_enabled_ = request->data;
1071+
response->success = true;
1072+
} catch (const ob::Error& e) {
1073+
response->message = e.getMessage();
1074+
response->success = false;
1075+
} catch (const std::exception& e) {
1076+
response->message = e.what();
1077+
response->success = false;
1078+
} catch (...) {
1079+
response->message = "unknown error";
1080+
response->success = false;
1081+
}
1082+
}
1083+
10611084
void OBCameraNode::setWriteCustomerData(const std::shared_ptr<SetString::Request>& request,
10621085
std::shared_ptr<SetString::Response>& response) {
10631086
if (request->data.empty()) {

0 commit comments

Comments
 (0)