Skip to content

Commit b799b30

Browse files
authored
Merge pull request #117 from neufieldrobotics/feature/gain_parameter2
Feature/gain parameter2
2 parents c6e0c23 + 5d33dfd commit b799b30

File tree

8 files changed

+154
-31
lines changed

8 files changed

+154
-31
lines changed

Diff for: CMakeLists.txt

+3
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,9 @@ if(${CMAKE_SYSTEM_PROCESSOR} MATCHES aarch64 OR arm)
113113

114114
endif(${CMAKE_SYSTEM_PROCESSOR} MATCHES aarch64 OR arm)
115115

116+
# Make package version available in CPP as a defination
117+
add_definitions("-D${PROJECT_NAME}_VERSION=\"${${PROJECT_NAME}_VERSION}\"")
118+
116119
add_library (acquilib SHARED
117120
src/capture.cpp
118121
src/camera.cpp

Diff for: include/spinnaker_sdk_camera_driver/camera.h

+2-1
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,8 @@ namespace acquisition {
5959
// void setTrigMode();
6060
// void setTriggerOverlapOff();
6161

62-
string get_node_value(string node_string);
62+
string getTLNodeStringValue(string node_string);
63+
double getFloatValueMax(string node_string);
6364
string get_id();
6465
void make_master() { MASTER_ = true; ROS_DEBUG_STREAM( "camera " << get_id() << " set as master"); }
6566
bool is_master() { return MASTER_; }

Diff for: include/spinnaker_sdk_camera_driver/capture.h

+1
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,7 @@ namespace acquisition {
115115
string dump_img_;
116116
string ext_;
117117
float exposure_time_;
118+
float gain_;
118119
double target_grey_value_;
119120
bool first_image_received;
120121
// int decimation_;

Diff for: launch/acquisition.launch

+26-19
Original file line numberDiff line numberDiff line change
@@ -3,23 +3,29 @@
33
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>
44

55
<!-- acquisition spinnaker params-->
6-
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
7-
<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_time setting for cameras"/>
9-
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
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" />
11-
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
12-
<arg name="live" default="false" doc="Show images on screen GUI"/>
13-
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
14-
<arg name="output" default="screen" doc="display output to screen or log file"/>
15-
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
16-
<arg name="save_path" default="~" doc="location to save the image data"/>
17-
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
18-
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
19-
<arg name="time" default="false" doc="Show time/FPS on output"/>
20-
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
21-
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
22-
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
6+
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
7+
<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_time setting for cameras"/>
9+
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
10+
<arg name="gain" default="0" doc="Gain setting. Gain should be positive (full range - 0 - 18 dB for blackfly-s camera)
11+
or zero (auto gain). if gain > max, it will be set to max allowed value.
12+
Default is 0, auto gain which is set according to target grey value or autoexposure settings"/>
13+
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4,
14+
AutoExposureTargetGreyValueAuto will be set to continuous(auto)
15+
also available as dynamic reconfigurable parameter.
16+
This parameter has no meaning when auto exposure and auto gain are off" />
17+
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
18+
<arg name="live" default="false" doc="Show images on screen GUI"/>
19+
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
20+
<arg name="output" default="screen" doc="display output to screen or log file"/>
21+
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
22+
<arg name="save_path" default="~" doc="location to save the image data"/>
23+
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
24+
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
25+
<arg name="time" default="false" doc="Show time/FPS on output"/>
26+
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
27+
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
28+
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
2329

2430

2531
<!-- nodelet manager params-->
@@ -29,7 +35,7 @@
2935

3036
<!-- Capture nodelet params-->
3137
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
32-
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
38+
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
3339

3440
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
3541
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen" unless="$(arg external_manager)" />
@@ -38,12 +44,13 @@
3844
<node pkg="nodelet" type="nodelet" name="acquisition_node"
3945
args="load acquisition/Capture $(arg manager)" >
4046
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
41-
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
47+
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
4248
<rosparam command="load" file="$(arg config_file)" />
4349

4450
<!-- Load parameters onto server using argument or default values above -->
4551
<param name="exposure_time" value="$(arg exposure_time)" />
4652
<param name="external_trigger" value="$(arg external_trigger)" />
53+
<param name="gain" value="$(arg gain)"/>
4754
<param name="target_grey_value" value="$(arg target_grey_value)" />
4855
<param name="binning" value="$(arg binning)" />
4956
<param name="color" value="$(arg color)" />

Diff for: launch/acquisition_external_trigger.launch

+72
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
<launch>
2+
<!-- configure console output verbosity mode:debug_console.conf or std_console.conf -->
3+
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>
4+
5+
<!-- acquisition spinnaker params-->
6+
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
7+
<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_time setting for cameras"/>
9+
<arg name="external_trigger" default="true" doc="External trigger (No camera is master)"/>
10+
<arg name="gain" default="0" doc="Gain setting. Gain should be positive (full range - 0 - 18 dB for blackfly-s camera)
11+
or zero (auto gain). if gain > max, it will be set to max allowed value.
12+
Default is 0, auto gain which is set according to target grey value or autoexposure settings"/>
13+
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4,
14+
AutoExposureTargetGreyValueAuto will be set to continuous(auto)
15+
also available as dynamic reconfigurable parameter.
16+
This parameter has no meaning when auto exposure and auto gain are off" />
17+
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
18+
<arg name="live" default="false" doc="Show images on screen GUI"/>
19+
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
20+
<arg name="output" default="screen" doc="display output to screen or log file"/>
21+
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
22+
<arg name="save_path" default="~" doc="location to save the image data"/>
23+
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
24+
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
25+
<arg name="time" default="false" doc="Show time/FPS on output"/>
26+
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
27+
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
28+
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
29+
30+
31+
<!-- nodelet manager params-->
32+
<arg name="manager" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
33+
<arg name="external_manager" default="false" doc="If set to False(default), creates a nodelet manager with $(arg manager).
34+
If True, the acquisition/Capture waits for the nodelet_manager name $(arg manager)" />
35+
36+
<!-- Capture nodelet params-->
37+
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
38+
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/external_trigger_params.yaml" doc="File specifying the parameters of the camera_array"/>
39+
40+
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
41+
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen" unless="$(arg external_manager)" />
42+
43+
<!-- load the acquisition nodelet -->
44+
<node pkg="nodelet" type="nodelet" name="acquisition_node"
45+
args="load acquisition/Capture $(arg manager)" >
46+
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
47+
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
48+
<rosparam command="load" file="$(arg config_file)" />
49+
50+
<!-- Load parameters onto server using argument or default values above -->
51+
<param name="exposure_time" value="$(arg exposure_time)" />
52+
<param name="external_trigger" value="$(arg external_trigger)" />
53+
<param name="gain" value="$(arg gain)"/>
54+
<param name="target_grey_value" value="$(arg target_grey_value)" />
55+
<param name="binning" value="$(arg binning)" />
56+
<param name="color" value="$(arg color)" />
57+
<param name="frames" value="$(arg frames)" />
58+
<param name="live" value="$(arg live)" />
59+
<param name="live_grid" value="$(arg live_grid)" />
60+
<param name="save" value="$(arg save)" />
61+
<param name="save_type" value="$(arg save_type)" />
62+
<param name="save_path" value="$(arg save_path)" />
63+
<param name="soft_framerate" value="$(arg soft_framerate)" />
64+
<param name="time" value="$(arg time)" />
65+
<param name="utstamps" value="$(arg utstamps)" />
66+
<param name="to_ros" value="$(arg to_ros)"/>
67+
<param name="max_rate_save" value="$(arg max_rate_save)" />
68+
<param name="tf_prefix" value="$(arg tf_prefix)" />
69+
70+
</node>
71+
72+
</launch>

Diff for: package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>spinnaker_sdk_camera_driver</name>
4-
<version>0.0.0</version>
4+
<version>1.1.0</version>
55
<description>Point Grey (FLIR) Spinnaker based camera driver (Blackfly S etc.)</description>
66

77
<maintainer email="[email protected]">Vikrant Shah</maintainer>

Diff for: src/camera.cpp

+20-3
Original file line numberDiff line numberDiff line change
@@ -306,17 +306,34 @@ void acquisition::Camera::trigger() {
306306

307307
}
308308

309-
string acquisition::Camera::get_node_value(string node_string) {
309+
double acquisition::Camera::getFloatValueMax(string node_string) {
310+
INodeMap& nodeMap = pCam_->GetNodeMap();
311+
312+
CFloatPtr ptrNodeValue = nodeMap.GetNode(node_string.c_str());
313+
314+
if (IsAvailable(ptrNodeValue)){
315+
//cout << "\tMax " << ptrNodeValue->GetValue() << "..." << endl;
316+
return ptrNodeValue->GetMax();
317+
} else {
318+
ROS_FATAL_STREAM("Node " << node_string << " not available" << endl);
319+
return -1;
320+
}
321+
}
322+
323+
324+
string acquisition::Camera::getTLNodeStringValue(string node_string) {
310325
INodeMap& nodeMap = pCam_->GetTLDeviceNodeMap();
311326
CStringPtr ptrNodeValue = nodeMap.GetNode(node_string.c_str());
312327
if (IsReadable(ptrNodeValue)){
313328
return string(ptrNodeValue->GetValue());
329+
} else{
330+
ROS_FATAL_STREAM("Node " << node_string << " not readable" << endl);
331+
return "";
314332
}
315-
return "";
316333
}
317334

318335
string acquisition::Camera::get_id() {
319-
return get_node_value("DeviceSerialNumber");
336+
return getTLNodeStringValue("DeviceSerialNumber");
320337
}
321338

322339
void acquisition::Camera::targetGreyValueTest() {

Diff for: src/capture.cpp

+29-7
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,7 @@ void acquisition::Capture::init_variables_register_to_ros() {
8080
// default values for the parameters are set here. Should be removed eventually!!
8181
exposure_time_ = 0 ; // default as 0 = auto exposure
8282
soft_framerate_ = 20; //default soft framrate
83+
gain_ = 0;
8384
ext_ = ".bmp";
8485
SOFT_FRAME_RATE_CTRL_ = false;
8586
LIVE_ = false;
@@ -138,6 +139,7 @@ void acquisition::Capture::init_variables_register_to_ros() {
138139
// Retrieve singleton reference to system object
139140
ROS_INFO_STREAM("*** SYSTEM INFORMATION ***");
140141
ROS_INFO_STREAM("Creating system instance...");
142+
ROS_INFO_STREAM("spinnaker_sdk_camera_driver package version: " << spinnaker_sdk_camera_driver_VERSION);
141143
system_ = System::GetInstance();
142144

143145
const LibraryVersion spinnakerLibraryVersion = system_->GetLibraryVersion();
@@ -187,8 +189,8 @@ void acquisition::Capture::load_cameras() {
187189
for (int i=0; i<numCameras_; i++) {
188190
acquisition::Camera cam(camList_.GetByIndex(i));
189191
ROS_INFO_STREAM(" -"<< cam.get_id()
190-
<<" "<< cam.get_node_value("DeviceModelName")
191-
<<" "<< cam.get_node_value("DeviceVersion") );
192+
<<" "<< cam.getTLNodeStringValue("DeviceModelName")
193+
<<" "<< cam.getTLNodeStringValue("DeviceVersion") );
192194
}
193195

194196
bool master_set = false;
@@ -297,9 +299,6 @@ void acquisition::Capture::load_cameras() {
297299
}
298300
ROS_ASSERT_MSG(cams.size(),"None of the connected cameras are in the config list!");
299301

300-
if (!EXTERNAL_TRIGGER_){
301-
ROS_ASSERT_MSG(master_set,"The camera supposed to be the master isn't connected!");
302-
}
303302
// Setting numCameras_ variable to reflect number of camera objects used.
304303
// numCameras_ variable is used in other methods where it means size of cams list.
305304
numCameras_ = cams.size();
@@ -477,6 +476,14 @@ void acquisition::Capture::read_parameters() {
477476
else ROS_INFO(" 'exposure_time'=%0.f, Setting autoexposure",exposure_time_);
478477
} else ROS_WARN(" 'exposure_time' Parameter not set, using default behavior: Automatic Exposure ");
479478

479+
if(nh_pvt_.getParam("gain", gain_)){
480+
if(gain_>0){
481+
ROS_INFO("gain value set to:%.1f",gain_);
482+
}
483+
else ROS_INFO(" 'gain' Parameter was zero or negative, using Auto gain based on target grey value");
484+
}
485+
else ROS_WARN(" 'gain' Parameter not set, using default behavior: Auto gain based on target grey value");
486+
480487
if (nh_pvt_.getParam("target_grey_value", target_grey_value_)){
481488
if (target_grey_value_ >0) ROS_INFO(" target_grey_value set to: %.1f",target_grey_value_);
482489
else ROS_INFO(" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto",target_grey_value_);}
@@ -697,6 +704,21 @@ void acquisition::Capture::init_cameras(bool soft = false) {
697704
} else {
698705
cams[i].setEnumValue("ExposureAuto", "Continuous");
699706
}
707+
708+
if(gain_>0){ //fixed gain
709+
cams[i].setEnumValue("GainAuto", "Off");
710+
double max_gain_allowed = cams[i].getFloatValueMax("Gain");
711+
if (gain_ <= max_gain_allowed)
712+
cams[i].setFloatValue("Gain", gain_);
713+
else {
714+
cams[i].setFloatValue("Gain", max_gain_allowed);
715+
ROS_WARN("Provided Gain value is higher than max allowed, setting gain to %f", max_gain_allowed);
716+
}
717+
target_grey_value_ = 50;
718+
} else {
719+
cams[i].setEnumValue("GainAuto","Continuous");
720+
}
721+
700722
if (target_grey_value_ > 4.0) {
701723
cams[i].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
702724
cams[i].setFloatValue("AutoExposureTargetGreyValue", target_grey_value_);
@@ -709,7 +731,7 @@ void acquisition::Capture::init_cameras(bool soft = false) {
709731
// cams[i].setFloatValue("AcquisitionFrameRate", 5.0);
710732

711733
if (color_)
712-
cams[i].setEnumValue("PixelFormat", "BGR8");
734+
cams[i].setEnumValue("PixelFormat", "BGR8");
713735
else
714736
cams[i].setEnumValue("PixelFormat", "Mono8");
715737
cams[i].setEnumValue("AcquisitionMode", "Continuous");
@@ -1233,7 +1255,7 @@ void acquisition::Capture::write_queue_to_disk(queue<ImagePtr>* img_q, int cam_n
12331255
convertedImage->Save(filename.str().c_str());
12341256
// release the image before popping out to save memory
12351257
convertedImage->Release();
1236-
ROS_INFO("image Queue size for cam %d is = %d",cam_no,img_q->size());
1258+
ROS_INFO("image Queue size for cam %d is = %zu",cam_no, img_q->size());
12371259
queue_mutex_.lock();
12381260
img_q->pop();
12391261
queue_mutex_.unlock();

0 commit comments

Comments
 (0)