Skip to content

Commit 816cfcc

Browse files
authored
Noetic additional camera control (#639)
1 parent d65a596 commit 816cfcc

File tree

5 files changed

+98
-6
lines changed

5 files changed

+98
-6
lines changed

depthai_ros_driver/cfg/parameters.cfg

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,14 @@ camera.add("left_r_set_man_exposure", bool_t, 0, "Enable manual exposure", False
2121
camera.add("left_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
2222
camera.add("left_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
2323
camera.add("left_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
24+
camera.add("left_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
25+
camera.add("left_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
26+
camera.add("left_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
27+
camera.add("left_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
28+
camera.add("left_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
29+
camera.add("left_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
30+
camera.add("left_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
31+
camera.add("left_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)
2432

2533
camera.add("right_r_keep_preview_aspect_ratio", bool_t, 0, "Keep preview aspect ratio", True)
2634
camera.add("right_r_exposure", int_t, 0, "Sensor exposure", 1000, 1, 33000)
@@ -30,6 +38,14 @@ camera.add("right_r_set_man_exposure", bool_t, 0, "Enable manual exposure", Fals
3038
camera.add("right_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
3139
camera.add("right_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
3240
camera.add("right_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
41+
camera.add("right_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
42+
camera.add("right_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
43+
camera.add("right_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
44+
camera.add("right_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
45+
camera.add("right_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
46+
camera.add("right_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
47+
camera.add("right_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
48+
camera.add("right_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)
3349

3450
camera.add("rgb_r_keep_preview_aspect_ratio", bool_t, 0, "Keep preview aspect ratio", True)
3551
camera.add("rgb_r_exposure", int_t, 0, "Sensor exposure", 1000, 1, 33000)
@@ -39,5 +55,13 @@ camera.add("rgb_r_set_man_exposure", bool_t, 0, "Enable manual exposure", False)
3955
camera.add("rgb_r_set_man_focus", bool_t, 0, "Enable manual focus", False)
4056
camera.add("rgb_r_set_man_whitebalance", bool_t, 0, "Enable manual whitebalance", False)
4157
camera.add("rgb_r_whitebalance", int_t, 0, "Whitebalance", 3300, 1000, 12000)
58+
camera.add("rgb_r_set_auto_exposure_limit", bool_t, 0, "Enable auto exposure limit", False)
59+
camera.add("rgb_r_auto_exposure_limit", int_t, 0, "Auto exposure limit", 1000, 1, 33000)
60+
camera.add("rgb_r_set_sharpness", bool_t, 0, "Enable sharpness", False)
61+
camera.add("rgb_r_sharpness", int_t, 0, "Sharpness", 0, 0, 4)
62+
camera.add("rgb_r_set_chroma_denoise", bool_t, 0, "Enable chroma denoise", False)
63+
camera.add("rgb_r_chroma_denoise", int_t, 0, "Chroma denoise", 0, 0, 4)
64+
camera.add("rgb_r_set_luma_denoise", bool_t, 0, "Enable luma denoise", False)
65+
camera.add("rgb_r_luma_denoise", int_t, 0, "Luma denoise", 0, 0, 4)
4266

43-
exit(gen.generate(PACKAGE, "depthai_ros_driver", "parameters"))
67+
exit(gen.generate(PACKAGE, "depthai_ros_driver", "parameters"))

depthai_ros_driver/launch/camera.launch

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,8 @@
7373
<param name="$(arg name)/infra2_i_fps"
7474
value="$(eval depth_module_infra_profile.split(',')[2])" />
7575

76-
<param name="$(arg name)/depth_i_publish_left_rect" value="true" />
77-
<param name="$(arg name)/depth_i_publish_right_rect" value="true" />
76+
<param name="$(arg name)/depth_i_left_rect_publish_topic" value="true" />
77+
<param name="$(arg name)/depth_i_right_rect_publish_topic" value="true" />
7878
</group>
7979

8080
<arg name="params_file" default="$(find depthai_ros_driver)/config/camera.yaml" />

depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -150,7 +150,7 @@ void Stereo::setupRectQueue(std::shared_ptr<dai::Device> device,
150150
pubConfig.width = ph->getOtherNodeParam<int>(sensorName, "i_width");
151151
pubConfig.height = ph->getOtherNodeParam<int>(sensorName, "i_height");
152152
pubConfig.topicName = sensorName;
153-
pubConfig.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_raw";
153+
pubConfig.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_rect";
154154
pubConfig.maxQSize = ph->getOtherNodeParam<int>(sensorName, "i_max_q_size");
155155
pubConfig.socket = sensorInfo.socket;
156156
pubConfig.infoMgrSuffix = "rect";

depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,22 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::MonoCamera> mo
7575
}
7676
monoCam->setImageOrientation(
7777
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
78+
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
79+
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
80+
monoCam->initialControl.setAutoExposureLimit(expLimit);
81+
}
82+
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
83+
if(declareAndLogParam("r_set_sharpness", false)) {
84+
monoCam->initialControl.setSharpness(sharpness);
85+
}
86+
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
87+
if(declareAndLogParam("r_set_chroma_denoise", false)) {
88+
monoCam->initialControl.setChromaDenoise(chromaDenoise);
89+
}
90+
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
91+
if(declareAndLogParam("r_set_luma_denoise", false)) {
92+
monoCam->initialControl.setLumaDenoise(lumaDenoise);
93+
}
7894
}
7995

8096
void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> colorCam, dai_nodes::sensor_helpers::ImageSensor sensor, bool publish) {
@@ -166,6 +182,22 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> c
166182
}
167183
colorCam->setImageOrientation(
168184
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
185+
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
186+
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
187+
colorCam->initialControl.setAutoExposureLimit(expLimit);
188+
}
189+
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
190+
if(declareAndLogParam("r_set_sharpness", false)) {
191+
colorCam->initialControl.setSharpness(sharpness);
192+
}
193+
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
194+
if(declareAndLogParam("r_set_chroma_denoise", false)) {
195+
colorCam->initialControl.setChromaDenoise(chromaDenoise);
196+
}
197+
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
198+
if(declareAndLogParam("r_set_luma_denoise", false)) {
199+
colorCam->initialControl.setLumaDenoise(lumaDenoise);
200+
}
169201
}
170202
dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config) {
171203
dai::CameraControl ctrl;
@@ -187,6 +219,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
187219
} else {
188220
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
189221
}
222+
if(config.rgb_r_set_auto_exposure_limit) {
223+
ctrl.setAutoExposureLimit(config.rgb_r_auto_exposure_limit);
224+
}
225+
if(config.rgb_r_set_sharpness) {
226+
ctrl.setSharpness(config.rgb_r_sharpness);
227+
}
228+
if(config.rgb_r_set_chroma_denoise) {
229+
ctrl.setChromaDenoise(config.rgb_r_chroma_denoise);
230+
}
231+
if(config.rgb_r_set_luma_denoise) {
232+
ctrl.setLumaDenoise(config.rgb_r_luma_denoise);
233+
}
190234
} else if(getName() == "left") {
191235
if(config.left_r_set_man_exposure) {
192236
ctrl.setManualExposure(config.left_r_exposure, config.left_r_iso);
@@ -204,6 +248,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
204248
} else {
205249
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
206250
}
251+
if(config.left_r_set_auto_exposure_limit) {
252+
ctrl.setAutoExposureLimit(config.left_r_auto_exposure_limit);
253+
}
254+
if(config.left_r_set_sharpness) {
255+
ctrl.setSharpness(config.left_r_sharpness);
256+
}
257+
if(config.left_r_set_chroma_denoise) {
258+
ctrl.setChromaDenoise(config.left_r_chroma_denoise);
259+
}
260+
if(config.left_r_set_luma_denoise) {
261+
ctrl.setLumaDenoise(config.left_r_luma_denoise);
262+
}
207263
} else if(getName() == "right") {
208264
if(config.right_r_set_man_exposure) {
209265
ctrl.setManualExposure(config.right_r_exposure, config.right_r_iso);
@@ -221,6 +277,18 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(parametersConfig& config
221277
} else {
222278
ctrl.setAutoWhiteBalanceMode(dai::CameraControl::AutoWhiteBalanceMode::AUTO);
223279
}
280+
if(config.right_r_set_auto_exposure_limit) {
281+
ctrl.setAutoExposureLimit(config.right_r_auto_exposure_limit);
282+
}
283+
if(config.right_r_set_sharpness) {
284+
ctrl.setSharpness(config.right_r_sharpness);
285+
}
286+
if(config.right_r_set_chroma_denoise) {
287+
ctrl.setChromaDenoise(config.right_r_chroma_denoise);
288+
}
289+
if(config.right_r_set_luma_denoise) {
290+
ctrl.setLumaDenoise(config.right_r_luma_denoise);
291+
}
224292
}
225293

226294
return ctrl;

depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ void StereoParamHandler::declareParams(std::shared_ptr<dai::node::StereoDepth> s
7878
declareAndLogParam<bool>("i_left_rect_add_exposure_offset", false);
7979
declareAndLogParam<int>("i_left_rect_exposure_offset", 0);
8080
declareAndLogParam<bool>("i_left_rect_enable_feature_tracker", false);
81-
declareAndLogParam<bool>("i_left_rect_synced", true);
81+
declareAndLogParam<bool>("i_left_rect_synced", false);
8282
declareAndLogParam<bool>("i_left_rect_publish_compressed", false);
8383

8484
declareAndLogParam<bool>("i_right_rect_publish_topic", false);
@@ -91,7 +91,7 @@ void StereoParamHandler::declareParams(std::shared_ptr<dai::node::StereoDepth> s
9191
declareAndLogParam<bool>("i_right_rect_enable_feature_tracker", false);
9292
declareAndLogParam<bool>("i_right_rect_add_exposure_offset", false);
9393
declareAndLogParam<int>("i_right_rect_exposure_offset", 0);
94-
declareAndLogParam<bool>("i_right_rect_synced", true);
94+
declareAndLogParam<bool>("i_right_rect_synced", false);
9595
declareAndLogParam<bool>("i_right_rect_publish_compressed", false);
9696

9797
declareAndLogParam<bool>("i_enable_spatial_nn", false);

0 commit comments

Comments
 (0)