Skip to content

Commit

Permalink
update param ranges
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam committed Nov 6, 2024
1 parent d899375 commit 4670095
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 17 deletions.
18 changes: 9 additions & 9 deletions depthai_ros_driver/cfg/parameters.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@ 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, 1, 4)
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, 1, 4)
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, 1, 4)
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 @@ -41,11 +41,11 @@ 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, 1, 4)
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, 1, 4)
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, 1, 4)
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 @@ -58,10 +58,10 @@ 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, 1, 4)
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, 1, 4)
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, 1, 4)
camera.add("rgb_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)

exit(gen.generate(PACKAGE, "depthai_ros_driver", "parameters"))
24 changes: 16 additions & 8 deletions depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,17 +75,21 @@ 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(declareAndLogParam<int>("r_auto_exposure_limit", 1000));
monoCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
monoCam->initialControl.setSharpness(declareAndLogParam<int>("r_sharpness", 1));
monoCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
monoCam->initialControl.setChromaDenoise(declareAndLogParam<int>("r_chroma_denoise", 1));
monoCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
monoCam->initialControl.setLumaDenoise(declareAndLogParam<int>("r_luma_denoise", 1));
monoCam->initialControl.setLumaDenoise(lumaDenoise);
}
}

Expand Down Expand Up @@ -178,17 +182,21 @@ 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(declareAndLogParam<int>("r_auto_exposure_limit", 1000));
colorCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
colorCam->initialControl.setSharpness(declareAndLogParam<int>("r_sharpness", 1));
colorCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
colorCam->initialControl.setChromaDenoise(declareAndLogParam<int>("r_chroma_denoise", 1));
colorCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
colorCam->initialControl.setLumaDenoise(declareAndLogParam<int>("r_luma_denoise", 1));
colorCam->initialControl.setLumaDenoise(lumaDenoise);
}
}
dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config) {
Expand Down

0 comments on commit 4670095

Please sign in to comment.