Skip to content

Commit

Permalink
added target_gray_value to params and launch file, fixed dynamic reco…
Browse files Browse the repository at this point in the history
…nfigure 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
  • Loading branch information
mithundiddi committed Jun 13, 2019
1 parent 2945642 commit d1b34eb
Show file tree
Hide file tree
Showing 10 changed files with 47 additions and 24 deletions.
6 changes: 4 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ All the parameters can be set via the launch file or via the yaml config_file.
Should color images be used (only works on models that support color images)
* ~exposure_time (int, default: 0, 0:auto)
Exposure setting for cameras, also available as dynamic reconfiguarble parameter.
* ~target_grey_value (double, default: 0 , 0:Continous/auto)
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.
* ~frames (int, default: 50)
Number of frames to save/view 0=ON
* ~live (bool, default: false)
Expand Down Expand Up @@ -103,11 +105,11 @@ This is the names that would be given to the cameras for filenames and rostopics


### Dynamic Reconfigure parameters
* ~target_grey_val (double)
* ~target_grey_value (double)
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.
Explained in detail at [FLIR webpage](https://www.flir.com/support-center/iis/machine-vision/application-note/using-auto-exposure-in-blackfly-s/).

Setting target_grey_val invokes setting AutoExposureTargetGreyValueAuto to 'off' and AutoExposureTargetGreyValue is set to target_grey_val.
Setting target_grey_value invokes setting AutoExposureTargetGreyValueAuto to 'off' and AutoExposureTargetGreyValue is set to target_grey_value.
* ~exposure_time (int, default= 0, 0:auto)
Exposure time for the sensor.
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.
Expand Down
2 changes: 1 addition & 1 deletion cfg/spinnaker_cam.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()


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


Expand Down
1 change: 1 addition & 0 deletions include/spinnaker_sdk_camera_driver/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ namespace acquisition {
string dump_img_;
string ext_;
float exposure_time_;
double target_grey_value_;
// int decimation_;

int soft_framerate_; // Software (ROS) frame rate
Expand Down
4 changes: 3 additions & 1 deletion launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@
<!-- acquisition spinnaker params-->
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<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" />
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
<arg name="live" default="false" doc="Show images on screen GUI"/>
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
Expand Down Expand Up @@ -37,6 +38,7 @@

<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
<param name="color" value="$(arg color)" />
<param name="frames" value="$(arg frames)" />
Expand Down
4 changes: 3 additions & 1 deletion launch/acquisition_node.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@

<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<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" />
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
<arg name="live" default="false" doc="Show images on screen GUI"/>
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
Expand All @@ -30,6 +31,7 @@

<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
<param name="color" value="$(arg color)" />
<param name="frames" value="$(arg frames)" />
Expand Down
4 changes: 3 additions & 1 deletion launch/nodelet_subscriber_example.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@
<!-- acquisition spinnaker params-->
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure setting for cameras"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<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" />
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
<arg name="live" default="false" doc="Show images on screen GUI"/>
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
Expand Down Expand Up @@ -39,6 +40,7 @@

<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
<param name="color" value="$(arg color)" />
<param name="frames" value="$(arg frames)" />
Expand Down
4 changes: 2 additions & 2 deletions nodelet_plugins.xml
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<library path="lib/libcapture_nodelet">
<class name="acquisition/capture_nodelet" type="acquisition::capture_nodelet" base_class_type="nodelet::Nodelet">
<description>
This is my nodelet.
Nodelet for image acquisition using spinnaker sdk
</description>
</class>
<class name="acquisition/subscriber_nodelet" type="acquisition::subscriber_nodelet" base_class_type="nodelet::Nodelet">
<description>
This is my nodelet.
Example Subscriber nodelet demonstrates subscribing to acquisition/capture_nodelet and display delay time w.r.t imagemsg.header.stamp
</description>
</class>
</library>
2 changes: 1 addition & 1 deletion params/multi-cam_example.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ binning: 2 # going from 2 to 1 requires cameras to be unplugged and replugged
color: true
# frames: 50
soft_framerate: 10 # this frame rate reflects to the software frame rate set using ros::rate
exp: 0
exposure_time: 0
skip: 5

#Camera info message details
Expand Down
6 changes: 0 additions & 6 deletions params/test_params.yaml
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
cam_ids:
- 18080155
#- 17197547
cam_aliases:
- cam0
#- cam1
master_cam: 18080155
skip: 20
delay: 1.0
Expand All @@ -25,18 +23,14 @@ image_height: 1536
image_width: 2048
distortion_coeffs:
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
#- [-0.06001035588294054, 0.3466585291091072, -1.0932356940133992, 3.4511959617065253]


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

rectification_coeffs:
- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
#- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]

projection_coeffs:
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
#- [703.910323, 0.000000, 815.113302, 0.000000, 0.000000, 958.319231, 636.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
38 changes: 29 additions & 9 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -435,6 +435,12 @@ void acquisition::Capture::read_parameters() {
else ROS_INFO(" 'exposure_time'=%0.f, Setting autoexposure",exposure_time_);
} else ROS_WARN(" 'exposure_time' Parameter not set, using default behavior: Automatic Exposure ");

if (nh_pvt_.getParam("target_grey_value", target_grey_value_)){
if (target_grey_value_ >0) ROS_INFO(" target_grey_value set to: %.1f",target_grey_value_);
else ROS_INFO(" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto",target_grey_value_);}
else ROS_WARN(" 'target_grey_value' Parameter not set, using default behavior: AutoExposureTargetGreyValueAuto to auto");


if (nh_pvt_.getParam("binning", binning_)){
if (binning_ >0) ROS_INFO(" Binning set to: %d",binning_);
else {
Expand Down Expand Up @@ -611,7 +617,13 @@ void acquisition::Capture::init_cameras(bool soft = false) {
} else {
cams[i].setEnumValue("ExposureAuto", "Continuous");
}

if (target_grey_value_ > 4.0) {
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
cams[i].setFloatValue("AutoExposureTargetGreyValue", target_grey_value_);
} else {
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Continuous");
}

// cams[i].setIntValue("DecimationHorizontal", decimation_);
// cams[i].setIntValue("DecimationVertical", decimation_);
// cams[i].setFloatValue("AcquisitionFrameRate", 5.0);
Expand Down Expand Up @@ -1177,20 +1189,28 @@ void acquisition::Capture::dynamicReconfigureCallback(spinnaker_sdk_camera_drive

ROS_INFO_STREAM("Dynamic Reconfigure: Level : " << level);
if(level == 1 || level ==3){
ROS_INFO_STREAM("Target grey value : " << config.target_grey_val);
cams[MASTER_CAM_].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
cams[MASTER_CAM_].setFloatValue("AutoExposureTargetGreyValue", config.target_grey_val);
ROS_INFO_STREAM("Target grey value : " << config.target_grey_value);
for (int i = numCameras_-1 ; i >=0 ; i--) {

cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
cams[i].setFloatValue("AutoExposureTargetGreyValue", config.target_grey_value);
}
}
if (level == 2 || level ==3){
ROS_INFO_STREAM("Exposure "<<config.exposure_time);
if(config.exposure_time > 0){
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Off");
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
cams[MASTER_CAM_].setFloatValue("ExposureTime", config.exposure_time);
for (int i = numCameras_-1 ; i >=0 ; i--) {

cams[i].setEnumValue("ExposureAuto", "Off");
cams[i].setEnumValue("ExposureMode", "Timed");
cams[i].setFloatValue("ExposureTime", config.exposure_time);
}
}
else if(config.exposure_time ==0){
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Continuous");
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
for (int i = numCameras_-1 ; i >=0 ; i--) {
cams[i].setEnumValue("ExposureAuto", "Continuous");
cams[i].setEnumValue("ExposureMode", "Timed");
}
}
}
}

0 comments on commit d1b34eb

Please sign in to comment.