Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Noetic additional camera control #639

Open
wants to merge 4 commits into
base: noetic
Choose a base branch
from
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
26 changes: 25 additions & 1 deletion depthai_ros_driver/cfg/parameters.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,14 @@ camera.add("left_r_set_man_exposure", bool_t, 0, "Enable manual exposure", False
camera.add("left_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
camera.add("left_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
camera.add("left_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
camera.add("left_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
camera.add("left_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
camera.add("left_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
camera.add("left_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
camera.add("left_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
camera.add("left_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
camera.add("left_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
camera.add("left_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)

camera.add("right_r_keep_preview_aspect_ratio", bool_t, 0, "Keep preview aspect ratio", True)
camera.add("right_r_exposure", int_t, 0, "Sensor exposure", 1000, 1, 33000)
Expand All @@ -30,6 +38,14 @@ camera.add("right_r_set_man_exposure", bool_t, 0, "Enable manual exposure", Fals
camera.add("right_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
camera.add("right_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
camera.add("right_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
camera.add("right_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
camera.add("right_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
camera.add("right_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
camera.add("right_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
camera.add("right_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
camera.add("right_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
camera.add("right_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
camera.add("right_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)

camera.add("rgb_r_keep_preview_aspect_ratio", bool_t, 0, "Keep preview aspect ratio", True)
camera.add("rgb_r_exposure", int_t, 0, "Sensor exposure", 1000, 1, 33000)
Expand All @@ -39,5 +55,13 @@ camera.add("rgb_r_set_man_exposure", bool_t, 0, "Enable manual exposure", False)
camera.add("rgb_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
camera.add("rgb_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
camera.add("rgb_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
camera.add("rgb_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
camera.add("rgb_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
camera.add("rgb_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
camera.add("rgb_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
camera.add("rgb_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
camera.add("rgb_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
camera.add("rgb_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
camera.add("rgb_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)

exit(gen.generate(PACKAGE, "depthai_ros_driver", "parameters"))
exit(gen.generate(PACKAGE, "depthai_ros_driver", "parameters"))
4 changes: 2 additions & 2 deletions depthai_ros_driver/launch/camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,8 @@
<param name="$(arg name)/infra2_i_fps"
value="$(eval depth_module_infra_profile.split(',')[2])" />

<param name="$(arg name)/depth_i_publish_left_rect" value="true" />
<param name="$(arg name)/depth_i_publish_right_rect" value="true" />
<param name="$(arg name)/depth_i_left_rect_publish_topic" value="true" />
<param name="$(arg name)/depth_i_right_rect_publish_topic" value="true" />
</group>

<arg name="params_file" default="$(find depthai_ros_driver)/config/camera.yaml" />
Expand Down
2 changes: 1 addition & 1 deletion depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ void Stereo::setupRectQueue(std::shared_ptr<dai::Device> device,
pubConfig.width = ph->getOtherNodeParam<int>(sensorName, "i_width");
pubConfig.height = ph->getOtherNodeParam<int>(sensorName, "i_height");
pubConfig.topicName = sensorName;
pubConfig.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_raw";
pubConfig.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_rect";
pubConfig.maxQSize = ph->getOtherNodeParam<int>(sensorName, "i_max_q_size");
pubConfig.socket = sensorInfo.socket;
pubConfig.infoMgrSuffix = "rect";
Expand Down
68 changes: 68 additions & 0 deletions depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,22 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::MonoCamera> mo
}
monoCam->setImageOrientation(
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
monoCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
monoCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
monoCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
monoCam->initialControl.setLumaDenoise(lumaDenoise);
}
}

void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> colorCam, dai_nodes::sensor_helpers::ImageSensor sensor, bool publish) {
Expand Down Expand Up @@ -166,6 +182,22 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> c
}
colorCam->setImageOrientation(
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
colorCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
colorCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
colorCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
colorCam->initialControl.setLumaDenoise(lumaDenoise);
}
}
dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config) {
dai::CameraControl ctrl;
Expand All @@ -187,6 +219,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
} else {
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
}
if(config.rgb_r_set_auto_exposure_limit) {
ctrl.setAutoExposureLimit(config.rgb_r_auto_exposure_limit);
}
if(config.rgb_r_set_sharpness) {
ctrl.setSharpness(config.rgb_r_sharpness);
}
if(config.rgb_r_set_chroma_denoise) {
ctrl.setChromaDenoise(config.rgb_r_chroma_denoise);
}
if(config.rgb_r_set_luma_denoise) {
ctrl.setLumaDenoise(config.rgb_r_luma_denoise);
}
} else if(getName() == "left") {
if(config.left_r_set_man_exposure) {
ctrl.setManualExposure(config.left_r_exposure, config.left_r_iso);
Expand All @@ -204,6 +248,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
} else {
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
}
if(config.left_r_set_auto_exposure_limit) {
ctrl.setAutoExposureLimit(config.left_r_auto_exposure_limit);
}
if(config.left_r_set_sharpness) {
ctrl.setSharpness(config.left_r_sharpness);
}
if(config.left_r_set_chroma_denoise) {
ctrl.setChromaDenoise(config.left_r_chroma_denoise);
}
if(config.left_r_set_luma_denoise) {
ctrl.setLumaDenoise(config.left_r_luma_denoise);
}
} else if(getName() == "right") {
if(config.right_r_set_man_exposure) {
ctrl.setManualExposure(config.right_r_exposure, config.right_r_iso);
Expand All @@ -221,6 +277,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
} else {
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
}
if(config.right_r_set_auto_exposure_limit) {
ctrl.setAutoExposureLimit(config.right_r_auto_exposure_limit);
}
if(config.right_r_set_sharpness) {
ctrl.setSharpness(config.right_r_sharpness);
}
if(config.right_r_set_chroma_denoise) {
ctrl.setChromaDenoise(config.right_r_chroma_denoise);
}
if(config.right_r_set_luma_denoise) {
ctrl.setLumaDenoise(config.right_r_luma_denoise);
}
}

return ctrl;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ void StereoParamHandler::declareParams(std::shared_ptr<dai::node::StereoDepth> s
declareAndLogParam<bool>("i_left_rect_add_exposure_offset", false);
declareAndLogParam<int>("i_left_rect_exposure_offset", 0);
declareAndLogParam<bool>("i_left_rect_enable_feature_tracker", false);
declareAndLogParam<bool>("i_left_rect_synced", true);
declareAndLogParam<bool>("i_left_rect_synced", false);
declareAndLogParam<bool>("i_left_rect_publish_compressed", false);

declareAndLogParam<bool>("i_right_rect_publish_topic", false);
Expand All @@ -91,7 +91,7 @@ void StereoParamHandler::declareParams(std::shared_ptr<dai::node::StereoDepth> s
declareAndLogParam<bool>("i_right_rect_enable_feature_tracker", false);
declareAndLogParam<bool>("i_right_rect_add_exposure_offset", false);
declareAndLogParam<int>("i_right_rect_exposure_offset", 0);
declareAndLogParam<bool>("i_right_rect_synced", true);
declareAndLogParam<bool>("i_right_rect_synced", false);
declareAndLogParam<bool>("i_right_rect_publish_compressed", false);

declareAndLogParam<bool>("i_enable_spatial_nn", false);
Expand Down
Loading