Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

will add auto exposure time upper and lower limits, so we can acheive… #56

Open
wants to merge 2 commits into
base: dev
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 22 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,14 +58,33 @@ rqt_image_view
## Parmeters
All the parameters can be set via the launch file or via the yaml config_file. It is good practice to specify all the 'task' specific parameters via launch file and all the 'system configuration' specific parameters via a config_file.


### Auto Exposure Parameters
* ~exposure_time (int, default: 0, 0:auto)
Exposure setting for cameras, also available as dynamic reconfiguarble parameter.


* For auto_exposure mode (~exposure_time=0), following parameters will be used:


The upper and lower limits are the time duration for auto exposure algorithm on chip. On spinview software for Blackfly s, default upper limit = 15000 us
default lower limits = 100 us and acceptable minimum value >= 6 us


Setting an higher auto_exposure_upper_limit could potentially slow down the desired fps based on scene. Especially when collecting data greater than 45 fps in auto_exposure it is recommended to have a lower value on auto_exposure_upper_limit.


* ~auto_exposure_lower_limit (int, default: 100 us)
Auto Exposure lower limit setting to be used in auto_exposure mode, min:6 us for blackfly s model.
* ~auto_exposure_upper_limit (int, default: 2000 us)
Auto Exposure upper limit setting to be used in auto_exposure mode.

### Task Specific Parameters
* ~binning (int, default: 1)
Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged
* ~color (bool, default: false)
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.
* ~external_trigger (bool, default: false)
* ~external_trigger (bool, default: false)
Camera triggering setting when using an external trigger. In this mode, none of the cameras would be set as a master camera. All cameras are setup to use external trigger. In this mode the main loop runs at rate set by soft_framerate, so if the external trigger rate is higher than the soft_framerate, the buffer will get filled and images will have a lag. Also in this mode, the getnextimage timeout is set to infinite so that the node dosen't die if a trigger is not received for a while.
* ~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.
Expand Down
3 changes: 2 additions & 1 deletion include/spinnaker_sdk_camera_driver/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,12 +105,13 @@ namespace acquisition {
int nframes_;
float init_delay_;
int skip_num_;
float master_fps_;
//float master_fps_;
int binning_;
bool color_;
string dump_img_;
string ext_;
float exposure_time_;
float auto_exposure_lower_limit_,auto_exposure_upper_limit_;
double target_grey_value_;
// int decimation_;
string tf_prefix_;
Expand Down
8 changes: 6 additions & 2 deletions launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,11 @@
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>

<!-- 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="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_time setting for cameras"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<arg name="auto_exposure_lower_limit" default="100" doc="auto_exposure lower limit setting for auto_exposure mode, min:6 for blackfly s"/>
<arg name="auto_exposure_upper_limit" default="2000" doc="auto_exposure upper limit setting for auto_exposure mode"/>
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
<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"/>
Expand Down Expand Up @@ -43,6 +45,8 @@

<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="auto_exposure_lower_limit" value="$(arg auto_exposure_lower_limit)" />
<param name="auto_exposure_upper_limit" value="$(arg auto_exposure_upper_limit)" />
<param name="external_trigger" value="$(arg external_trigger)" />
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
Expand Down
8 changes: 6 additions & 2 deletions launch/node_acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,10 @@
<!-- acquisition.launch -->

<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_time setting for cameras"/>
<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_time setting for cameras"/>
<arg name="auto_exposure_lower_limit" default="100" doc="auto_exposure lower limit setting for auto_exposure mode, min:6 for blackfly s"/>
<arg name="auto_exposure_upper_limit" default="2000" doc="auto_exposure upper limit setting for auto_exposure mode"/>
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
<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"/>
Expand Down Expand Up @@ -36,6 +38,8 @@

<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="auto_exposure_lower_limit" value="$(arg auto_exposure_lower_limit)" />
<param name="auto_exposure_upper_limit" value="$(arg auto_exposure_upper_limit)" />
<param name="external_trigger" value="$(arg external_trigger)" />
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
Expand Down
4 changes: 2 additions & 2 deletions params/stereo_camera_example.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
cam_ids:
- 17197555
- 17197554
- 17197556
cam_aliases:
- cam0
- cam1
master_cam: 17197554
master_cam: 17197555
skip: 20
delay: 1.0

Expand Down
4 changes: 2 additions & 2 deletions params/test_params.yaml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
cam_ids:
- 17197556
- 17197554
cam_aliases:
- cam0
master_cam: 17197556
master_cam: 17197554
skip: 20
delay: 1.0

Expand Down
22 changes: 19 additions & 3 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,8 @@ void acquisition::Capture::init_variables_register_to_ros() {

// default values for the parameters are set here. Should be removed eventually!!
exposure_time_ = 0 ; // default as 0 = auto exposure
auto_exposure_lower_limit_ = 100; // 0.1 ms(min value blackfly s=6us)
auto_exposure_upper_limit_ = 2000; // 2ms
soft_framerate_ = 20; //default soft framrate
ext_ = ".bmp";
SOFT_FRAME_RATE_CTRL_ = false;
Expand All @@ -99,7 +101,7 @@ void acquisition::Capture::init_variables_register_to_ros() {
region_of_interest_set_ = false;
skip_num_ = 20;
init_delay_ = 1;
master_fps_ = 20.0;
//master_fps_ = 20.0;
binning_ = 1;
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000;
todays_date_ = todays_date();
Expand Down Expand Up @@ -425,6 +427,8 @@ void acquisition::Capture::read_parameters() {
}
} else ROS_WARN(" 'delay' Parameter not set, using default behavior: delay=%f",init_delay_);


/*
if (nh_pvt_.getParam("fps", master_fps_)){
if (master_fps_>=0) ROS_INFO(" Master cam fps set to : %0.2f",master_fps_);
else {
Expand All @@ -433,12 +437,21 @@ void acquisition::Capture::read_parameters() {
}
}
else ROS_WARN(" 'fps' Parameter not set, using default behavior: fps=%0.2f",master_fps_);

*/
if (nh_pvt_.getParam("exposure_time", exposure_time_)){
if (exposure_time_ >0) ROS_INFO(" Exposure set to: %.1f",exposure_time_);
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 (exposure_time_ == 0) {
// if exposure is auto, exposure_time param is 0
// min exposure is usually > 5 fro blackfly s and varies with camera model
if (nh_pvt_.getParam("auto_exposure_lower_limit", auto_exposure_lower_limit_)) ROS_INFO(" auto_exposure_lower_limit set to: %.1f",auto_exposure_lower_limit_);
else ROS_WARN(" 'auto_exposure_lower_limit' Parameter not set, using default behavior: auto_exposure_lower_limit=%.1f",auto_exposure_lower_limit_);

if (nh_pvt_.getParam("auto_exposure_upper_limit", auto_exposure_upper_limit_)) ROS_INFO(" auto_exposure_upper_limit set to: %.1f",auto_exposure_upper_limit_);
else ROS_WARN(" 'auto_exposure_upper_limit' Parameter not set, using default behavior: auto_exposure_upper_limit=%.1f",auto_exposure_upper_limit_);
}

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_);}
Expand Down Expand Up @@ -658,7 +671,10 @@ void acquisition::Capture::init_cameras(bool soft = false) {
cams[i].setFloatValue("ExposureTime", exposure_time_);
} else {
cams[i].setEnumValue("ExposureAuto", "Continuous");
cams[i].setFloatValue("AutoExposureExposureTimeLowerLimit",auto_exposure_lower_limit_);
cams[i].setFloatValue("AutoExposureExposureTimeUpperLimit",auto_exposure_upper_limit_);
}

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