Skip to content

Commit d1b34eb

Browse files
committed
added target_gray_value to params and launch file, fixed dynamic reconfigure to make changes for all cameras instead of just master cam, dynamic reconfigure now loads params in nodelet/node namspace correctly, variable names changed for dynamic recfg server and target grayvalue
1 parent 2945642 commit d1b34eb

10 files changed

+47
-24
lines changed

README.md

+4-2
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,8 @@ All the parameters can be set via the launch file or via the yaml config_file.
6666
Should color images be used (only works on models that support color images)
6767
* ~exposure_time (int, default: 0, 0:auto)
6868
Exposure setting for cameras, also available as dynamic reconfiguarble parameter.
69+
* ~target_grey_value (double, default: 0 , 0:Continous/auto)
70+
Setting target_grey_value > 4 (min:4 , max:99) will turn AutoExposureTargetGreyValueAuto to 'off' and set AutoExposureTargetGreyValue to target_grey_value. Also available as dynamic reconfigurable parameter. see below in Dynamic reconfigurable parameter section.
6971
* ~frames (int, default: 50)
7072
Number of frames to save/view 0=ON
7173
* ~live (bool, default: false)
@@ -103,11 +105,11 @@ This is the names that would be given to the cameras for filenames and rostopics
103105

104106

105107
### Dynamic Reconfigure parameters
106-
* ~target_grey_val (double)
108+
* ~target_grey_value (double)
107109
Target Grey Value is a parameter that helps to compensate for various lighting conditions by adjusting brightness to achieve optimal imaging results. The value is linear and is a percentage of the maximum pixel value.
108110
Explained in detail at [FLIR webpage](https://www.flir.com/support-center/iis/machine-vision/application-note/using-auto-exposure-in-blackfly-s/).
109111

110-
Setting target_grey_val invokes setting AutoExposureTargetGreyValueAuto to 'off' and AutoExposureTargetGreyValue is set to target_grey_val.
112+
Setting target_grey_value invokes setting AutoExposureTargetGreyValueAuto to 'off' and AutoExposureTargetGreyValue is set to target_grey_value.
111113
* ~exposure_time (int, default= 0, 0:auto)
112114
Exposure time for the sensor.
113115
When Exposure time is set within minimum and maximum exposure time limits(varies with camera model), ExposureAuto is set to 'off' and ExposureTime is set to exposure_time param value.

cfg/spinnaker_cam.cfg

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ from dynamic_reconfigure.parameter_generator_catkin import *
66
gen = ParameterGenerator()
77

88

9-
gen.add("target_grey_val", double_t, 1, "Set Target Grey Value", 50, 4, 90)
9+
gen.add("target_grey_value", double_t, 1, "Set Target Grey Value", 50, 4, 90)
1010
gen.add("exposure_time", int_t, 2, "Set Exposure time (0:auto)", 0, 0, 15000)
1111

1212

include/spinnaker_sdk_camera_driver/capture.h

+1
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,7 @@ namespace acquisition {
102102
string dump_img_;
103103
string ext_;
104104
float exposure_time_;
105+
double target_grey_value_;
105106
// int decimation_;
106107

107108
int soft_framerate_; // Software (ROS) frame rate

launch/acquisition.launch

+3-1
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,8 @@
55
<!-- acquisition spinnaker params-->
66
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
77
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
8-
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
8+
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
9+
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4, AutoExposureTargetGreyValueAuto will be set to continuous(auto) also available as dynamic reconfigurable parameter" />
910
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
1011
<arg name="live" default="false" doc="Show images on screen GUI"/>
1112
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
@@ -37,6 +38,7 @@
3738

3839
<!-- Load parameters onto server using argument or default values above -->
3940
<param name="exposure_time" value="$(arg exposure_time)" />
41+
<param name="target_grey_value" value="$(arg target_grey_value)" />
4042
<param name="binning" value="$(arg binning)" />
4143
<param name="color" value="$(arg color)" />
4244
<param name="frames" value="$(arg frames)" />

launch/acquisition_node.launch

+3-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,8 @@
66

77
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
88
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
9-
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
9+
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
10+
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4, AutoExposureTargetGreyValueAuto will be set to continuous(auto) also available as dynamic reconfigurable parameter" />
1011
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
1112
<arg name="live" default="false" doc="Show images on screen GUI"/>
1213
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
@@ -30,6 +31,7 @@
3031

3132
<!-- Load parameters onto server using argument or default values above -->
3233
<param name="exposure_time" value="$(arg exposure_time)" />
34+
<param name="target_grey_value" value="$(arg target_grey_value)" />
3335
<param name="binning" value="$(arg binning)" />
3436
<param name="color" value="$(arg color)" />
3537
<param name="frames" value="$(arg frames)" />

launch/nodelet_subscriber_example.launch

+3-1
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,8 @@
55
<!-- acquisition spinnaker params-->
66
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
77
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
8-
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
8+
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
9+
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4, AutoExposureTargetGreyValueAuto will be set to continuous(auto) also available as dynamic reconfigurable parameter" />
910
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
1011
<arg name="live" default="false" doc="Show images on screen GUI"/>
1112
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
@@ -39,6 +40,7 @@
3940

4041
<!-- Load parameters onto server using argument or default values above -->
4142
<param name="exposure_time" value="$(arg exposure_time)" />
43+
<param name="target_grey_value" value="$(arg target_grey_value)" />
4244
<param name="binning" value="$(arg binning)" />
4345
<param name="color" value="$(arg color)" />
4446
<param name="frames" value="$(arg frames)" />

nodelet_plugins.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
<library path="lib/libcapture_nodelet">
22
<class name="acquisition/capture_nodelet" type="acquisition::capture_nodelet" base_class_type="nodelet::Nodelet">
33
<description>
4-
This is my nodelet.
4+
Nodelet for image acquisition using spinnaker sdk
55
</description>
66
</class>
77
<class name="acquisition/subscriber_nodelet" type="acquisition::subscriber_nodelet" base_class_type="nodelet::Nodelet">
88
<description>
9-
This is my nodelet.
9+
Example Subscriber nodelet demonstrates subscribing to acquisition/capture_nodelet and display delay time w.r.t imagemsg.header.stamp
1010
</description>
1111
</class>
1212
</library>

params/multi-cam_example.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ binning: 2 # going from 2 to 1 requires cameras to be unplugged and replugged
1616
color: true
1717
# frames: 50
1818
soft_framerate: 10 # this frame rate reflects to the software frame rate set using ros::rate
19-
exp: 0
19+
exposure_time: 0
2020
skip: 5
2121

2222
#Camera info message details

params/test_params.yaml

-6
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,7 @@
11
cam_ids:
22
- 18080155
3-
#- 17197547
43
cam_aliases:
54
- cam0
6-
#- cam1
75
master_cam: 18080155
86
skip: 20
97
delay: 1.0
@@ -25,18 +23,14 @@ image_height: 1536
2523
image_width: 2048
2624
distortion_coeffs:
2725
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
28-
#- [-0.06001035588294054, 0.3466585291091072, -1.0932356940133992, 3.4511959617065253]
2926

3027

3128
#specified as [fx 0 cx 0 fy cy 0 0 1]
3229
intrinsic_coeffs:
3330
- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]
34-
#- [1872.1392958276606, 0.0, 583.2925844388025, 0.0, 1872.6168324818198, 483.72597760530056, 0.0, 0.0, 1.0]
3531

3632
rectification_coeffs:
3733
- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
38-
#- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
3934

4035
projection_coeffs:
4136
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
42-
#- [703.910323, 0.000000, 815.113302, 0.000000, 0.000000, 958.319231, 636.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]

src/capture.cpp

+29-9
Original file line numberDiff line numberDiff line change
@@ -435,6 +435,12 @@ void acquisition::Capture::read_parameters() {
435435
else ROS_INFO(" 'exposure_time'=%0.f, Setting autoexposure",exposure_time_);
436436
} else ROS_WARN(" 'exposure_time' Parameter not set, using default behavior: Automatic Exposure ");
437437

438+
if (nh_pvt_.getParam("target_grey_value", target_grey_value_)){
439+
if (target_grey_value_ >0) ROS_INFO(" target_grey_value set to: %.1f",target_grey_value_);
440+
else ROS_INFO(" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto",target_grey_value_);}
441+
else ROS_WARN(" 'target_grey_value' Parameter not set, using default behavior: AutoExposureTargetGreyValueAuto to auto");
442+
443+
438444
if (nh_pvt_.getParam("binning", binning_)){
439445
if (binning_ >0) ROS_INFO(" Binning set to: %d",binning_);
440446
else {
@@ -611,7 +617,13 @@ void acquisition::Capture::init_cameras(bool soft = false) {
611617
} else {
612618
cams[i].setEnumValue("ExposureAuto", "Continuous");
613619
}
614-
620+
if (target_grey_value_ > 4.0) {
621+
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
622+
cams[i].setFloatValue("AutoExposureTargetGreyValue", target_grey_value_);
623+
} else {
624+
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Continuous");
625+
}
626+
615627
// cams[i].setIntValue("DecimationHorizontal", decimation_);
616628
// cams[i].setIntValue("DecimationVertical", decimation_);
617629
// cams[i].setFloatValue("AcquisitionFrameRate", 5.0);
@@ -1177,20 +1189,28 @@ void acquisition::Capture::dynamicReconfigureCallback(spinnaker_sdk_camera_drive
11771189

11781190
ROS_INFO_STREAM("Dynamic Reconfigure: Level : " << level);
11791191
if(level == 1 || level ==3){
1180-
ROS_INFO_STREAM("Target grey value : " << config.target_grey_val);
1181-
cams[MASTER_CAM_].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
1182-
cams[MASTER_CAM_].setFloatValue("AutoExposureTargetGreyValue", config.target_grey_val);
1192+
ROS_INFO_STREAM("Target grey value : " << config.target_grey_value);
1193+
for (int i = numCameras_-1 ; i >=0 ; i--) {
1194+
1195+
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
1196+
cams[i].setFloatValue("AutoExposureTargetGreyValue", config.target_grey_value);
1197+
}
11831198
}
11841199
if (level == 2 || level ==3){
11851200
ROS_INFO_STREAM("Exposure "<<config.exposure_time);
11861201
if(config.exposure_time > 0){
1187-
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Off");
1188-
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
1189-
cams[MASTER_CAM_].setFloatValue("ExposureTime", config.exposure_time);
1202+
for (int i = numCameras_-1 ; i >=0 ; i--) {
1203+
1204+
cams[i].setEnumValue("ExposureAuto", "Off");
1205+
cams[i].setEnumValue("ExposureMode", "Timed");
1206+
cams[i].setFloatValue("ExposureTime", config.exposure_time);
1207+
}
11901208
}
11911209
else if(config.exposure_time ==0){
1192-
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Continuous");
1193-
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
1210+
for (int i = numCameras_-1 ; i >=0 ; i--) {
1211+
cams[i].setEnumValue("ExposureAuto", "Continuous");
1212+
cams[i].setEnumValue("ExposureMode", "Timed");
1213+
}
11941214
}
11951215
}
11961216
}

0 commit comments

Comments
 (0)