Skip to content

Commit b84f07e

Browse files
authored
Add autoexposure params (#692)
1 parent b2d152a commit b84f07e

File tree

1 file changed

+44
-0
lines changed

1 file changed

+44
-0
lines changed

depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,14 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::MonoCamera> mo
109109
if(declareAndLogParam("r_set_luma_denoise", false)) {
110110
monoCam->initialControl.setLumaDenoise(lumaDenoise);
111111
}
112+
bool setAutoExpRegion = declareAndLogParam<bool>("r_set_auto_exp_region", false);
113+
int autoExpStartX = declareAndLogParam<int>("r_auto_exp_region_start_x", 0);
114+
int autoExpStartY = declareAndLogParam<int>("r_auto_exp_region_start_y", 0);
115+
int autoExpWidth = declareAndLogParam<int>("r_auto_exp_region_width", 0);
116+
int autoExpHeight = declareAndLogParam<int>("r_auto_exp_region_height", 0);
117+
if(setAutoExpRegion) {
118+
monoCam->initialControl.setAutoExposureRegion(autoExpStartX, autoExpStartY, autoExpWidth, autoExpHeight);
119+
}
112120
}
113121
void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> colorCam, dai_nodes::sensor_helpers::ImageSensor sensor, bool publish) {
114122
declareAndLogParam<bool>("i_publish_topic", publish);
@@ -225,6 +233,14 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> c
225233
if(declareAndLogParam("r_set_luma_denoise", false)) {
226234
colorCam->initialControl.setLumaDenoise(lumaDenoise);
227235
}
236+
bool setAutoExpRegion = declareAndLogParam<bool>("r_set_auto_exp_region", false);
237+
int autoExpStartX = declareAndLogParam<int>("r_auto_exp_region_start_x", 0);
238+
int autoExpStartY = declareAndLogParam<int>("r_auto_exp_region_start_y", 0);
239+
int autoExpWidth = declareAndLogParam<int>("r_auto_exp_region_width", 0);
240+
int autoExpHeight = declareAndLogParam<int>("r_auto_exp_region_height", 0);
241+
if(setAutoExpRegion) {
242+
colorCam->initialControl.setAutoExposureRegion(autoExpStartX, autoExpStartY, autoExpWidth, autoExpHeight);
243+
}
228244
}
229245
dai::CameraControl SensorParamHandler::setRuntimeParams(const std::vector<rclcpp::Parameter>& params) {
230246
dai::CameraControl ctrl;
@@ -295,6 +311,34 @@ dai::CameraControl SensorParamHandler::setRuntimeParams(const std::vector<rclcpp
295311
if(getParam<bool>("r_set_luma_denoise")) {
296312
ctrl.setLumaDenoise(p.get_value<int>());
297313
}
314+
} else if(p.get_name() == getFullParamName("r_auto_exp_region_start_x")) {
315+
if(getParam<bool>("r_set_auto_exp_region")) {
316+
ctrl.setAutoExposureRegion(p.get_value<int>(),
317+
getParam<int>("r_auto_exp_region_start_y"),
318+
getParam<int>("r_auto_exp_region_width"),
319+
getParam<int>("r_auto_exp_region_height"));
320+
}
321+
} else if(p.get_name() == getFullParamName("r_auto_exp_region_start_y")) {
322+
if(getParam<bool>("r_set_auto_exp_region")) {
323+
ctrl.setAutoExposureRegion(getParam<int>("r_auto_exp_region_start_x"),
324+
p.get_value<int>(),
325+
getParam<int>("r_auto_exp_region_width"),
326+
getParam<int>("r_auto_exp_region_height"));
327+
}
328+
} else if(p.get_name() == getFullParamName("r_auto_exp_region_width")) {
329+
if(getParam<bool>("r_set_auto_exp_region")) {
330+
ctrl.setAutoExposureRegion(getParam<int>("r_auto_exp_region_start_x"),
331+
getParam<int>("r_auto_exp_region_start_y"),
332+
p.get_value<int>(),
333+
getParam<int>("r_auto_exp_region_height"));
334+
}
335+
} else if(p.get_name() == getFullParamName("r_auto_exp_region_height")) {
336+
if(getParam<bool>("r_set_auto_exp_region")) {
337+
ctrl.setAutoExposureRegion(getParam<int>("r_auto_exp_region_start_x"),
338+
getParam<int>("r_auto_exp_region_start_y"),
339+
getParam<int>("r_auto_exp_region_width"),
340+
p.get_value<int>());
341+
}
298342
}
299343
}
300344
return ctrl;

0 commit comments

Comments
 (0)