Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions orbbec_camera/include/orbbec_camera/ob_camera_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -425,6 +425,7 @@ class OBCameraNode {
std::unique_ptr<ob::Pipeline> imuPipeline_ = nullptr;
std::atomic_bool pipeline_started_{false};
std::string camera_name_ = "camera";
std::string namespace_ = "";
std::string accel_gyro_frame_id_ = "camera_accel_gyro_optical_frame";
const std::string imu_frame_id_ = "camera_gyro_frame";
std::shared_ptr<ob::Config> pipeline_config_ = nullptr;
Expand Down
17 changes: 9 additions & 8 deletions orbbec_camera/src/ob_camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1520,7 +1520,8 @@ void OBCameraNode::setupDefaultImageFormat() {

void OBCameraNode::getParameters() {
setAndGetNodeParameter<std::string>(camera_name_, "camera_name", "camera");
camera_link_frame_id_ = camera_name_ + "_link";
setAndGetNodeParameter<std::string>(namespace_, "namespace", "");
camera_link_frame_id_ = namespace_ + "/" + camera_name_ + "_link";
for (auto stream_index : IMAGE_STREAMS) {
std::string param_name = stream_name_[stream_index] + "_width";
setAndGetNodeParameter(width_[stream_index], param_name, 0);
Expand All @@ -1540,11 +1541,11 @@ void OBCameraNode::getParameters() {
setAndGetNodeParameter<bool>(mirror_stream_[stream_index], param_name, false);
param_name = stream_name_[stream_index] + "_rotation";
setAndGetNodeParameter<int>(rotation_stream_[stream_index], param_name, -1);
param_name = camera_name_ + "_" + stream_name_[stream_index] + "_frame_id";
param_name = namespace_ + "/" + camera_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 =
camera_name_ + "_" + stream_name_[stream_index] + "_optical_frame";
namespace_ + "/" + camera_name_ + "_" + stream_name_[stream_index] + "_optical_frame";
param_name = stream_name_[stream_index] + "_optical_frame_id";
setAndGetNodeParameter(optical_frame_id_[stream_index], param_name, default_optical_frame_id);
param_name = stream_name_[stream_index] + "_format";
Expand All @@ -1561,7 +1562,7 @@ void OBCameraNode::getParameters() {
depth_aligned_frame_id_[stream_index] = optical_frame_id_[COLOR];
}

accel_gyro_frame_id_ = camera_name_ + "_accel_gyro_optical_frame";
accel_gyro_frame_id_ = namespace_ + "/" + camera_name_ + "_accel_gyro_optical_frame";

setAndGetNodeParameter<bool>(enable_sync_output_accel_gyro_, "enable_sync_output_accel_gyro",
false);
Expand All @@ -1577,15 +1578,15 @@ void OBCameraNode::getParameters() {
setAndGetNodeParameter<std::string>(imu_rate_[stream_index], param_name, "");
param_name = stream_name_[stream_index] + "_range";
setAndGetNodeParameter<std::string>(imu_range_[stream_index], param_name, "");
param_name = camera_name_ + "_" + stream_name_[stream_index] + "_frame_id";
std::string default_frame_id = camera_name_ + "_" + stream_name_[stream_index] + "_frame";
param_name = namespace_ + "/" + camera_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 =
camera_name_ + "_" + stream_name_[stream_index] + "_optical_frame";
namespace_ + "/" + camera_name_ + "_" + stream_name_[stream_index] + "_optical_frame";
param_name = stream_name_[stream_index] + "_optical_frame_id";
setAndGetNodeParameter(optical_frame_id_[stream_index], param_name, default_optical_frame_id);
depth_aligned_frame_id_[stream_index] =
camera_name_ + "_" + stream_name_[COLOR] + "_optical_frame";
namespace_ + "/" + camera_name_ + "_" + stream_name_[COLOR] + "_optical_frame";
}
setAndGetNodeParameter<bool>(publish_tf_, "publish_tf", true);
setAndGetNodeParameter<double>(tf_publish_rate_, "tf_publish_rate", 0.0);
Expand Down
66 changes: 33 additions & 33 deletions orbbec_camera/src/ros_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,75 +29,75 @@ void OBCameraNode::setupCameraCtrlServices() {
continue;
}
auto stream_name = stream_name_[stream_index];
std::string service_name = "get_" + stream_name + "_exposure";
std::string service_name = camera_name_ + "/" + "get_" + stream_name + "_exposure";
get_exposure_srv_[stream_index] = node_->create_service<GetInt32>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<GetInt32::Request> request,
std::shared_ptr<GetInt32::Response> response) {
getExposureCallback(request, response, stream_index);
});

service_name = "set_" + stream_name + "_exposure";
service_name = camera_name_ + "/" + "set_" + stream_name + "_exposure";
set_exposure_srv_[stream_index] = node_->create_service<SetInt32>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetInt32::Request> request,
std::shared_ptr<SetInt32::Response> response) {
setExposureCallback(request, response, stream_index);
});
service_name = "get_" + stream_name + "_gain";
service_name = camera_name_ + "/" + "get_" + stream_name + "_gain";
get_gain_srv_[stream_index] = node_->create_service<GetInt32>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<GetInt32::Request> request,
std::shared_ptr<GetInt32::Response> response) {
getGainCallback(request, response, stream_index);
});

service_name = "set_" + stream_name + "_gain";
service_name = camera_name_ + "/" + "set_" + stream_name + "_gain";
set_gain_srv_[stream_index] = node_->create_service<SetInt32>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetInt32::Request> request,
std::shared_ptr<SetInt32::Response> response) {
setGainCallback(request, response, stream_index);
});
service_name = "set_" + stream_name + "_auto_exposure";
service_name = camera_name_ + "/" + "set_" + stream_name + "_auto_exposure";
set_auto_exposure_srv_[stream_index] = node_->create_service<SetBool>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setAutoExposureCallback(request, response, stream_index);
});

service_name = "set_" + stream_name + "_ae_roi";
service_name = camera_name_ + "/" + "set_" + stream_name + "_ae_roi";
set_ae_roi_srv_[stream_index] = node_->create_service<SetArrays>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetArrays::Request> request,
std::shared_ptr<SetArrays::Response> response) {
setAeRoiCallback(request, response, stream_index);
});

service_name = "toggle_" + stream_name;
service_name = camera_name_ + "/" + "toggle_" + stream_name;

toggle_sensor_srv_[stream_index] = node_->create_service<SetBool>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
toggleSensorCallback(request, response, stream_index);
});
service_name = "set_" + stream_name + "_mirror";
service_name = camera_name_ + "/" + "set_" + stream_name + "_mirror";
set_mirror_srv_[stream_index] = node_->create_service<SetBool>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setMirrorCallback(request, response, stream_index);
});
service_name = "set_" + stream_name + "_flip";
service_name = camera_name_ + "/" + "set_" + stream_name + "_flip";
set_flip_srv_[stream_index] = node_->create_service<SetBool>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setFlipCallback(request, response, stream_index);
});
service_name = "set_" + stream_name + "_rotation";
service_name = camera_name_ + "/" + "set_" + stream_name + "_rotation";
set_rotation_srv_[stream_index] = node_->create_service<SetInt32>(
service_name,
[this, stream_index = stream_index](const std::shared_ptr<SetInt32::Request> request,
Expand All @@ -106,123 +106,123 @@ void OBCameraNode::setupCameraCtrlServices() {
});
}
set_fan_work_mode_srv_ = node_->create_service<SetInt32>(
"set_fan_work_mode", [this](const std::shared_ptr<SetInt32::Request> request,
camera_name_ + "/" + "set_fan_work_mode", [this](const std::shared_ptr<SetInt32::Request> request,
std::shared_ptr<SetInt32::Response> response) {
setFanWorkModeCallback(request, response);
});
set_floor_enable_srv_ = node_->create_service<SetBool>(
"set_floor_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
camera_name_ + "/" + "set_floor_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setFloorEnableCallback(request_header, request, response);
});
set_laser_enable_srv_ = node_->create_service<SetBool>(
"set_laser_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
camera_name_ + "/" + "set_laser_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setLaserEnableCallback(request_header, request, response);
});
set_ldp_enable_srv_ = node_->create_service<SetBool>(
"set_ldp_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
camera_name_ + "/" + "set_ldp_enable", [this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setLdpEnableCallback(request_header, request, response);
});
get_ldp_status_srv_ = node_->create_service<GetBool>(
"get_ldp_status", [this](const std::shared_ptr<rmw_request_id_t> request_header,
camera_name_ + "/" + "get_ldp_status", [this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<GetBool::Request> request,
std::shared_ptr<GetBool::Response> response) {
(void)request_header;
getLdpStatusCallback(request, response);
});

get_white_balance_srv_ = node_->create_service<GetInt32>(
"get_white_balance", [this](const std::shared_ptr<GetInt32::Request> request,
camera_name_ + "/" + "get_white_balance", [this](const std::shared_ptr<GetInt32::Request> request,
std::shared_ptr<GetInt32::Response> response) {
getWhiteBalanceCallback(request, response);
});

set_white_balance_srv_ = node_->create_service<SetInt32>(
"set_white_balance", [this](const std::shared_ptr<SetInt32::Request> request,
camera_name_ + "/" + "set_white_balance", [this](const std::shared_ptr<SetInt32::Request> request,
std::shared_ptr<SetInt32::Response> response) {
setWhiteBalanceCallback(request, response);
});
get_auto_white_balance_srv_ = node_->create_service<GetInt32>(
"get_auto_white_balance", [this](const std::shared_ptr<GetInt32::Request> request,
camera_name_ + "/" + "get_auto_white_balance", [this](const std::shared_ptr<GetInt32::Request> request,
std::shared_ptr<GetInt32::Response> response) {
getAutoWhiteBalanceCallback(request, response);
});
set_auto_white_balance_srv_ = node_->create_service<SetBool>(
"set_auto_white_balance", [this](const std::shared_ptr<SetBool::Request> request,
camera_name_ + "/" + "set_auto_white_balance", [this](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setAutoWhiteBalanceCallback(request, response);
});
get_device_srv_ = node_->create_service<GetDeviceInfo>(
"get_device_info", [this](const std::shared_ptr<GetDeviceInfo::Request> request,
camera_name_ + "/" + "get_device_info", [this](const std::shared_ptr<GetDeviceInfo::Request> request,
std::shared_ptr<GetDeviceInfo::Response> response) {
getDeviceInfoCallback(request, response);
});
get_sdk_version_srv_ = node_->create_service<GetString>(
"get_sdk_version",
camera_name_ + "/" + "get_sdk_version",
[this](const std::shared_ptr<GetString::Request> request,
std::shared_ptr<GetString::Response> response) { getSDKVersion(request, response); });
save_images_srv_ = node_->create_service<std_srvs::srv::Empty>(
"save_images", [this](const std::shared_ptr<std_srvs::srv::Empty::Request> request,
camera_name_ + "/" + "save_images", [this](const std::shared_ptr<std_srvs::srv::Empty::Request> request,
std::shared_ptr<std_srvs::srv::Empty::Response> response) {
saveImageCallback(request, response);
});
save_point_cloud_srv_ = node_->create_service<std_srvs::srv::Empty>(
"save_point_cloud", [this](const std::shared_ptr<std_srvs::srv::Empty::Request> request,
camera_name_ + "/" + "save_point_cloud", [this](const std::shared_ptr<std_srvs::srv::Empty::Request> request,
std::shared_ptr<std_srvs::srv::Empty::Response> response) {
savePointCloudCallback(request, response);
});
switch_ir_camera_srv_ = node_->create_service<SetString>(
"switch_ir", [this](const std::shared_ptr<SetString::Request> request,
camera_name_ + "/" + "switch_ir", [this](const std::shared_ptr<SetString::Request> request,
std::shared_ptr<SetString::Response> response) {
switchIRCameraCallback(request, response);
});
set_ir_long_exposure_srv_ = node_->create_service<SetBool>(
"set_ir_long_exposure", [this](const std::shared_ptr<SetBool::Request> request,
camera_name_ + "/" + "set_ir_long_exposure", [this](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setIRLongExposureCallback(request, response);
});
get_lrm_measure_distance_srv_ = node_->create_service<GetInt32>(
"get_lrm_measure_distance", [this](const std::shared_ptr<GetInt32::Request> request,
camera_name_ + "/" + "get_lrm_measure_distance", [this](const std::shared_ptr<GetInt32::Request> request,
std::shared_ptr<GetInt32::Response> response) {
getLrmMeasureDistanceCallback(request, response);
});
set_reset_timestamp_srv_ = node_->create_service<SetBool>(
"set_reset_timestamp", [this](const std::shared_ptr<SetBool::Request> request,
camera_name_ + "/" + "set_reset_timestamp", [this](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setRESETTimestampCallback(request, response);
});
set_interleaver_laser_sync_srv_ = node_->create_service<SetInt32>(
"set_sync_interleaverlaser", [this](const std::shared_ptr<SetInt32::Request> request,
camera_name_ + "/" + "set_sync_interleaverlaser", [this](const std::shared_ptr<SetInt32::Request> request,
std::shared_ptr<SetInt32::Response> response) {
setSYNCInterleaveLaserCallback(request, response);
});
set_sync_host_time_srv_ = node_->create_service<SetBool>(
"set_sync_hosttime", [this](const std::shared_ptr<SetBool::Request> request,
camera_name_ + "/" + "set_sync_hosttime", [this](const std::shared_ptr<SetBool::Request> request,
std::shared_ptr<SetBool::Response> response) {
setSYNCHostimeCallback(request, response);
});
send_service_trigger_srv_ = node_->create_service<CameraTrigger>(
"send_service_trigger", [this](const std::shared_ptr<CameraTrigger::Request> request,
camera_name_ + "/" + "send_service_trigger", [this](const std::shared_ptr<CameraTrigger::Request> request,
std::shared_ptr<CameraTrigger::Response> response) {
sendSoftwareTriggerCallback(request, response);
});
set_write_customerdata_srv_ = node_->create_service<SetString>(
"set_write_customer_data", [this](const std::shared_ptr<SetString::Request> request,
camera_name_ + "/" + "set_write_customer_data", [this](const std::shared_ptr<SetString::Request> request,
std::shared_ptr<SetString::Response> response) {
setWriteCustomerData(request, response);
});
set_read_customerdata_srv_ = node_->create_service<SetString>(
"set_read_customer_data", [this](const std::shared_ptr<SetString::Request> request,
camera_name_ + "/" + "set_read_customer_data", [this](const std::shared_ptr<SetString::Request> request,
std::shared_ptr<SetString::Response> response) {
setReadCustomerData(request, response);
});
change_state_srv_ = node_->create_service<lifecycle_msgs::srv::ChangeState>(
"change_state", std::bind(&OBCameraNode::handleChangeStateRequest, this,
camera_name_ + "/" + "change_state", std::bind(&OBCameraNode::handleChangeStateRequest, this,
std::placeholders::_1, std::placeholders::_2));
}

Expand Down
7 changes: 4 additions & 3 deletions orbbec_camera_py/launch/orbbec_camera_trigger.launch.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
<launch>

<arg name="use_tote_pose" default="true" />
<arg name="namespace" default="" />
<arg name="camera_name" default="inward_a_right_camera" />

<node pkg="orbbec_camera_py" exec="run_orbbec_trigger" output="both">
<param name="camera_name" value="/inward_a_right_camera"/>
<param name="trigger_period" value="5.0"/>
<param name="camera_name" value="/$(var namespace)/$(var camera_name)"/>
<param name="trigger_period" value="1.0"/>
</node>

</launch>