diff --git a/orbbec_camera/include/orbbec_camera/ob_camera_node.h b/orbbec_camera/include/orbbec_camera/ob_camera_node.h index 0e1b68ec..91691941 100644 --- a/orbbec_camera/include/orbbec_camera/ob_camera_node.h +++ b/orbbec_camera/include/orbbec_camera/ob_camera_node.h @@ -405,6 +405,7 @@ class OBCameraNode { bool enable_soft_filter_ = true; bool enable_color_auto_exposure_ = true; bool enable_ir_auto_exposure_ = true; + bool enable_ir_long_exposure_ = false; bool enable_ldp_ = true; int soft_filter_max_diff_ = -1; int soft_filter_speckle_size_ = -1; diff --git a/orbbec_camera/launch/dabai_max_pro.launch.py b/orbbec_camera/launch/dabai_max_pro.launch.py index be5fa087..983cdd25 100644 --- a/orbbec_camera/launch/dabai_max_pro.launch.py +++ b/orbbec_camera/launch/dabai_max_pro.launch.py @@ -51,6 +51,7 @@ def generate_launch_description(): DeclareLaunchArgument('ir_qos', default_value='default'), DeclareLaunchArgument('ir_camera_info_qos', default_value='default'), DeclareLaunchArgument('enable_ir_auto_exposure', default_value='true'), + DeclareLaunchArgument('enable_ir_long_exposure', default_value='false'), DeclareLaunchArgument('publish_tf', default_value='true'), DeclareLaunchArgument('tf_publish_rate', default_value='10.0'), DeclareLaunchArgument('ir_info_url', default_value=''), diff --git a/orbbec_camera/launch/gemini_uw.launch.py b/orbbec_camera/launch/gemini_uw.launch.py index be5fa087..983cdd25 100644 --- a/orbbec_camera/launch/gemini_uw.launch.py +++ b/orbbec_camera/launch/gemini_uw.launch.py @@ -51,6 +51,7 @@ def generate_launch_description(): DeclareLaunchArgument('ir_qos', default_value='default'), DeclareLaunchArgument('ir_camera_info_qos', default_value='default'), DeclareLaunchArgument('enable_ir_auto_exposure', default_value='true'), + DeclareLaunchArgument('enable_ir_long_exposure', default_value='false'), DeclareLaunchArgument('publish_tf', default_value='true'), DeclareLaunchArgument('tf_publish_rate', default_value='10.0'), DeclareLaunchArgument('ir_info_url', default_value=''), diff --git a/orbbec_camera/src/ob_camera_node.cpp b/orbbec_camera/src/ob_camera_node.cpp index f6172742..9aaa6af3 100644 --- a/orbbec_camera/src/ob_camera_node.cpp +++ b/orbbec_camera/src/ob_camera_node.cpp @@ -205,6 +205,10 @@ void OBCameraNode::setupDevices() { device_->setBoolProperty(OB_PROP_IR_AUTO_EXPOSURE_BOOL, enable_ir_auto_exposure_); } + if (device_->isPropertySupported(OB_PROP_IR_LONG_EXPOSURE_BOOL, OB_PERMISSION_WRITE)) { + device_->setBoolProperty(OB_PROP_IR_LONG_EXPOSURE_BOOL, enable_ir_long_exposure_); + } + if (device_->isPropertySupported(OB_PROP_DEPTH_MAX_DIFF_INT, OB_PERMISSION_WRITE)) { auto default_soft_filter_max_diff = device_->getIntProperty(OB_PROP_DEPTH_MAX_DIFF_INT); if (soft_filter_max_diff_ != -1 && default_soft_filter_max_diff != soft_filter_max_diff_) { @@ -579,6 +583,7 @@ void OBCameraNode::getParameters() { setAndGetNodeParameter(enable_frame_sync_, "enable_frame_sync", false); setAndGetNodeParameter(enable_color_auto_exposure_, "enable_color_auto_exposure", true); setAndGetNodeParameter(enable_ir_auto_exposure_, "enable_ir_auto_exposure", true); + setAndGetNodeParameter(enable_ir_long_exposure_, "enable_ir_long_exposure", true); setAndGetNodeParameter(depth_work_mode_, "depth_work_mode", ""); setAndGetNodeParameter(sync_mode_str_, "sync_mode", "close"); setAndGetNodeParameter(depth_delay_us_, "depth_delay_us", 0);