From 5c5f1aae1fd0e618e4c2e2d1cf2682ac12843fb8 Mon Sep 17 00:00:00 2001 From: Sushant Date: Tue, 11 Nov 2025 16:46:26 -0500 Subject: [PATCH 1/4] fix frame param --- orbbec_camera/src/ob_camera_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/orbbec_camera/src/ob_camera_node.cpp b/orbbec_camera/src/ob_camera_node.cpp index 13669378..bcf2b63f 100644 --- a/orbbec_camera/src/ob_camera_node.cpp +++ b/orbbec_camera/src/ob_camera_node.cpp @@ -1582,7 +1582,7 @@ void OBCameraNode::getParameters() { setAndGetNodeParameter(imu_rate_[stream_index], param_name, ""); param_name = stream_name_[stream_index] + "_range"; setAndGetNodeParameter(imu_range_[stream_index], param_name, ""); - param_name = namespace_ + camera_name_ + "_" + stream_name_[stream_index] + "_frame_id"; + param_name = stream_name_[stream_index] + "_frame_id"; std::string default_frame_id = namespace_ + camera_name_ + "_" + stream_name_[stream_index] + "_frame"; setAndGetNodeParameter(frame_id_[stream_index], param_name, default_frame_id); std::string default_optical_frame_id = From 79cee13ecf6dd299108583e21c5b5c831c7e7f06 Mon Sep 17 00:00:00 2001 From: Sushant Date: Tue, 11 Nov 2025 17:31:53 -0500 Subject: [PATCH 2/4] fix other frame id --- orbbec_camera/src/ob_camera_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/orbbec_camera/src/ob_camera_node.cpp b/orbbec_camera/src/ob_camera_node.cpp index bcf2b63f..2df8531e 100644 --- a/orbbec_camera/src/ob_camera_node.cpp +++ b/orbbec_camera/src/ob_camera_node.cpp @@ -1545,7 +1545,7 @@ void OBCameraNode::getParameters() { setAndGetNodeParameter(mirror_stream_[stream_index], param_name, false); param_name = stream_name_[stream_index] + "_rotation"; setAndGetNodeParameter(rotation_stream_[stream_index], param_name, -1); - param_name = namespace_ + camera_name_ + "_" + stream_name_[stream_index] + "_frame_id"; + param_name = stream_name_[stream_index] + "_frame_id"; std::string default_frame_id = camera_name_ + "_" + stream_name_[stream_index] + "_frame"; setAndGetNodeParameter(frame_id_[stream_index], param_name, default_frame_id); std::string default_optical_frame_id = From e3265a09b13e16b28301f4dfc7ca9826edbd4981 Mon Sep 17 00:00:00 2001 From: Sushant Date: Tue, 11 Nov 2025 17:48:58 -0500 Subject: [PATCH 3/4] add namespacing --- orbbec_camera/src/ob_camera_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/orbbec_camera/src/ob_camera_node.cpp b/orbbec_camera/src/ob_camera_node.cpp index 2df8531e..459eb538 100644 --- a/orbbec_camera/src/ob_camera_node.cpp +++ b/orbbec_camera/src/ob_camera_node.cpp @@ -1546,7 +1546,7 @@ void OBCameraNode::getParameters() { param_name = stream_name_[stream_index] + "_rotation"; setAndGetNodeParameter(rotation_stream_[stream_index], param_name, -1); param_name = stream_name_[stream_index] + "_frame_id"; - std::string default_frame_id = camera_name_ + "_" + stream_name_[stream_index] + "_frame"; + std::string default_frame_id = namespace_ + camera_name_ + "_" + stream_name_[stream_index] + "_frame"; setAndGetNodeParameter(frame_id_[stream_index], param_name, default_frame_id); std::string default_optical_frame_id = namespace_ + camera_name_ + "_" + stream_name_[stream_index] + "_optical_frame"; From cdbf46a3afbc3425d8b5b1672a9fd8e7463d4a92 Mon Sep 17 00:00:00 2001 From: Sushant Date: Wed, 12 Nov 2025 11:11:22 -0500 Subject: [PATCH 4/4] add namespacing to a couple more services --- orbbec_camera/src/ob_camera_node.cpp | 2 +- orbbec_camera/src/ob_camera_node_driver.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/orbbec_camera/src/ob_camera_node.cpp b/orbbec_camera/src/ob_camera_node.cpp index 459eb538..4ae8dcd4 100644 --- a/orbbec_camera/src/ob_camera_node.cpp +++ b/orbbec_camera/src/ob_camera_node.cpp @@ -992,7 +992,7 @@ void OBCameraNode::setupDepthPostProcessFilter() { } } set_filter_srv_ = node_->create_service( - "set_filter", [this](const std::shared_ptr request, + camera_name_ + "/set_filter", [this](const std::shared_ptr request, std::shared_ptr response) { setFilterCallback(request, response); }); diff --git a/orbbec_camera/src/ob_camera_node_driver.cpp b/orbbec_camera/src/ob_camera_node_driver.cpp index bb1565b4..c168d220 100644 --- a/orbbec_camera/src/ob_camera_node_driver.cpp +++ b/orbbec_camera/src/ob_camera_node_driver.cpp @@ -150,7 +150,7 @@ void OBCameraNodeDriver::init() { return; } reboot_device_srv_ = this->create_service( - "reboot_device", std::bind(&OBCameraNodeDriver::rebootDeviceCallback, this, + g_camera_name + "/reboot_device", std::bind(&OBCameraNodeDriver::rebootDeviceCallback, this, std::placeholders::_1, std::placeholders::_2)); pthread_mutexattr_init(&orb_device_lock_attr_); pthread_mutexattr_setpshared(&orb_device_lock_attr_, PTHREAD_PROCESS_SHARED);