Skip to content

Commit 9fba1be

Browse files
Vikrant Shahmithundiddi
authored andcommitted
External trigger feature !!! (#35)
* Allowing for external trigger (without a master camera), to be used with an IMU sync out * Cleaning up capture.cpp and adding parameter to launch files * Increasing timeout in external trigger mode to infinite * Updating README to add external trigger param * Update README.md cmaera --> camera
1 parent c6cdb9c commit 9fba1be

File tree

9 files changed

+71
-22
lines changed

9 files changed

+71
-22
lines changed

README.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,7 @@ The pre-requisites for this repo include:
1414
* ros-kinetic-cv-bridge
1515
* ros-kinetic-image-transport
1616

17-
# Incase of x86_64 or x86_32 architecture, install the following:
18-
* libunwind-dev
17+
**Incase of x86_64 or x86_32 architecture, also install *libunwind-dev* **
1918

2019
```bash
2120
# after installing spinnaker verify that you can run your cameras with SpinView
@@ -66,6 +65,8 @@ All the parameters can be set via the launch file or via the yaml config_file.
6665
Should color images be used (only works on models that support color images)
6766
* ~exposure_time (int, default: 0, 0:auto)
6867
Exposure setting for cameras, also available as dynamic reconfiguarble parameter.
68+
* ~external_trigger (bool, default: false)
69+
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.
6970
* ~target_grey_value (double, default: 0 , 0:Continous/auto)
7071
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.
7172
* ~frames (int, default: 50)
@@ -78,7 +79,7 @@ All the parameters can be set via the launch file or via the yaml config_file.
7879
Flag whether images should be saved or not (via opencv mat objects to disk)
7980
* ~save_path (string, default: "\~/projects/data")
8081
Location to save the image data
81-
* \~save_type (string, default: "bmp")
82+
* ~save_type (string, default: "bmp")
8283
Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc.
8384
* ~soft_framerate (int, default: 20)
8485
When hybrid software triggering is used, this controls the FPS, 0=as fast as possible

include/spinnaker_sdk_camera_driver/camera.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ namespace acquisition {
6363
void make_master() { MASTER_ = true; ROS_DEBUG_STREAM( "camera " << get_id() << " set as master"); }
6464
bool is_master() { return MASTER_; }
6565
void set_color(bool flag) { COLOR_ = flag; }
66+
void setGetNextImageTimeout(uint64_t get_next_image_timeout) { GET_NEXT_IMAGE_TIMEOUT_ = get_next_image_timeout; }
6667

6768
private:
6869

include/spinnaker_sdk_camera_driver/capture.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ namespace acquisition {
4444
void deinit_cameras();
4545
void acquire_mat_images(int);
4646
void run();
47+
void run_external_trig();
4748
void run_soft_trig();
4849
void run_mt();
4950
void publish_to_ros(int, char**, float);
@@ -113,6 +114,7 @@ namespace acquisition {
113114
bool FIXED_NUM_FRAMES_;
114115
bool TIME_BENCHMARK_;
115116
bool MASTER_TIMESTAMP_FOR_ALL_;
117+
bool EXTERNAL_TRIGGER_;
116118
bool SAVE_;
117119
bool SAVE_BIN_;
118120
bool MANUAL_TRIGGER_;
@@ -124,6 +126,7 @@ namespace acquisition {
124126
bool EXPORT_TO_ROS_;
125127
bool MAX_RATE_SAVE_;
126128
bool PUBLISH_CAM_INFO_;
129+
uint64_t SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_;
127130

128131
// grid view related variables
129132
bool GRID_CREATED_;

launch/acquisition.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
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)"/>
88
<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)"/>
910
<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"/>
@@ -40,6 +41,7 @@
4041

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

launch/acquisition_node.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
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)"/>
99
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
10+
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
1011
<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" />
1112
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
1213
<arg name="live" default="false" doc="Show images on screen GUI"/>
@@ -34,6 +35,7 @@
3435

3536
<!-- Load parameters onto server using argument or default values above -->
3637
<param name="exposure_time" value="$(arg exposure_time)" />
38+
<param name="external_trigger" value="$(arg external_trigger)" />
3739
<param name="target_grey_value" value="$(arg target_grey_value)" />
3840
<param name="binning" value="$(arg binning)" />
3941
<param name="color" value="$(arg color)" />

launch/nodelet_subscriber_example.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
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)"/>
88
<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)"/>
910
<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"/>
@@ -40,6 +41,7 @@
4041

4142
<!-- Load parameters onto server using argument or default values above -->
4243
<param name="exposure_time" value="$(arg exposure_time)" />
44+
<param name="external_trigger" value="$(arg external_trigger)" />
4345
<param name="target_grey_value" value="$(arg target_grey_value)" />
4446
<param name="binning" value="$(arg binning)" />
4547
<param name="color" value="$(arg color)" />
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
cam_ids:
2+
- 17197559
3+
cam_aliases:
4+
- cam0
5+
skip: 20
6+
delay: 1.0
7+
8+
# Assign all the follwing via launch file to prevent confusion and conflict
9+
10+
#save_path: ~/projects/data
11+
#save_type: .bmp #binary or .tiff or .bmp
12+
#binning: 1 # going from 2 to 1 requires cameras to be unplugged and replugged
13+
#color: false
14+
#frames: 50
15+
#soft_framerate: 4 # this frame rate reflects to the software frame rate set using ros::rate
16+
#exp: 997
17+
#to_ros: true #When to_ros is not selected, but live is selected, pressing 'space' exports single image to ROS

src/camera.cpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,7 @@ acquisition::Camera::Camera(CameraPtr pCam) {
2121
frameID_ = -1;
2222
MASTER_ = false;
2323
timestamp_ = 0;
24-
GET_NEXT_IMAGE_TIMEOUT_ = 2000;
25-
24+
GET_NEXT_IMAGE_TIMEOUT_ = EVENT_TIMEOUT_INFINITE;
2625
}
2726

2827
void acquisition::Camera::init() {
@@ -38,7 +37,6 @@ void acquisition::Camera::deinit() {
3837
}
3938

4039
ImagePtr acquisition::Camera::grab_frame() {
41-
4240
ImagePtr pResultImage = pCam_->GetNextImage(GET_NEXT_IMAGE_TIMEOUT_);
4341
// Check if the Image is complete
4442

@@ -235,7 +233,6 @@ void acquisition::Camera::adcBitDepth(gcstring bitDep) {
235233
}
236234

237235
void acquisition::Camera::setBufferSize(int numBuf) {
238-
239236
INodeMap & sNodeMap = pCam_->GetTLStreamNodeMap();
240237
CIntegerPtr StreamNode = sNodeMap.GetNode("StreamDefaultBufferCount");
241238
int64_t bufferCount = StreamNode->GetValue();
@@ -318,4 +315,4 @@ void acquisition::Camera::exposureTest() {
318315
float expTime=ptrExpTest->GetValue();
319316
ROS_DEBUG_STREAM("Exposure Time: "<<expTime<<endl);
320317

321-
}
318+
}

src/capture.cpp

Lines changed: 38 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,7 @@ acquisition::Capture::Capture(): it_(nh_), nh_pvt_ ("~") {
7070
LIVE_ = false;
7171
TIME_BENCHMARK_ = false;
7272
MASTER_TIMESTAMP_FOR_ALL_ = true;
73+
EXTERNAL_TRIGGER_ = false;
7374
EXPORT_TO_ROS_ = false;
7475
PUBLISH_CAM_INFO_ = false;
7576
SAVE_ = false;
@@ -81,6 +82,7 @@ acquisition::Capture::Capture(): it_(nh_), nh_pvt_ ("~") {
8182
init_delay_ = 1;
8283
master_fps_ = 20.0;
8384
binning_ = 1;
85+
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000;
8486
todays_date_ = todays_date();
8587

8688
dump_img_ = "dump" + ext_;
@@ -149,6 +151,7 @@ acquisition::Capture::Capture(ros::NodeHandle nodehandl, ros::NodeHandle private
149151
LIVE_ = false;
150152
TIME_BENCHMARK_ = false;
151153
MASTER_TIMESTAMP_FOR_ALL_ = true;
154+
EXTERNAL_TRIGGER_ = false;
152155
EXPORT_TO_ROS_ = false;
153156
PUBLISH_CAM_INFO_ = false;
154157
SAVE_ = false;
@@ -160,6 +163,7 @@ acquisition::Capture::Capture(ros::NodeHandle nodehandl, ros::NodeHandle private
160163
init_delay_ = 1;
161164
master_fps_ = 20.0;
162165
binning_ = 1;
166+
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000;
163167
todays_date_ = todays_date();
164168

165169
dump_img_ = "dump" + ext_;
@@ -229,7 +233,10 @@ void acquisition::Capture::load_cameras() {
229233
for (int i=0; i<numCameras_; i++) {
230234

231235
acquisition::Camera cam(camList_.GetByIndex(i));
232-
236+
if (!EXTERNAL_TRIGGER_){
237+
cam.setGetNextImageTimeout(SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_); // set to finite number when not using external triggering
238+
}
239+
233240
if (cam.get_id().compare(cam_ids_[j]) == 0) {
234241
current_cam_found=true;
235242
if (cam.get_id().compare(master_cam_id_) == 0) {
@@ -309,7 +316,8 @@ void acquisition::Capture::load_cameras() {
309316
if (!current_cam_found) ROS_WARN_STREAM(" Camera "<<cam_ids_[j]<<" not detected!!!");
310317
}
311318
ROS_ASSERT_MSG(cams.size(),"None of the connected cameras are in the config list!");
312-
ROS_ASSERT_MSG(master_set,"The camera supposed to be the master isn't connected!");
319+
if (!EXTERNAL_TRIGGER_)
320+
ROS_ASSERT_MSG(master_set,"The camera supposed to be the master isn't connected!");
313321
}
314322

315323

@@ -363,17 +371,26 @@ void acquisition::Capture::read_parameters() {
363371
for (int i=0; i<cam_ids_.size(); i++)
364372
cam_names_.push_back(cam_ids_[i]);
365373
}
374+
375+
if (nh_pvt_.getParam("external_trigger", EXTERNAL_TRIGGER_)){
376+
ROS_INFO(" External trigger: %s",EXTERNAL_TRIGGER_?"true":"false");
377+
}
378+
else ROS_WARN(" 'external_trigger' Parameter not set, using default behavior external_trigger=%s",EXTERNAL_TRIGGER_?"true":"false");
366379

380+
// Unless external trigger is being used, a master cam needs to be specified
367381
int mcam_int;
368-
ROS_ASSERT_MSG(nh_pvt_.getParam("master_cam", mcam_int),"master_cam is required!");
382+
if (!EXTERNAL_TRIGGER_){
383+
ROS_ASSERT_MSG(nh_pvt_.getParam("master_cam", mcam_int),"master_cam is required!");
384+
369385
master_cam_id_=to_string(mcam_int);
370386
bool found = false;
371387
for (int i=0; i<cam_ids_.size(); i++) {
372388
if (master_cam_id_.compare(cam_ids_[i]) == 0)
373389
found = true;
374390
}
375391
ROS_ASSERT_MSG(found,"Specified master cam is not in the cam_ids list!");
376-
392+
}
393+
377394
if (nh_pvt_.getParam("utstamps", MASTER_TIMESTAMP_FOR_ALL_)){
378395
MASTER_TIMESTAMP_FOR_ALL_ = !MASTER_TIMESTAMP_FOR_ALL_;
379396
ROS_INFO(" Unique time stamps for each camera: %s",!MASTER_TIMESTAMP_FOR_ALL_?"true":"false");
@@ -842,8 +859,8 @@ void acquisition::Capture::save_binary_frames(int dump) {
842859

843860
void acquisition::Capture::get_mat_images() {
844861
//ros time stamp creation
845-
mesg.header.stamp = ros::Time::now();
846-
mesg.time = ros::Time::now();
862+
//mesg.header.stamp = ros::Time::now();
863+
//mesg.time = ros::Time::now();
847864
double t = ros::Time::now().toSec();
848865

849866
ostringstream ss;
@@ -872,6 +889,8 @@ void acquisition::Capture::get_mat_images() {
872889
ss << cams[i].get_frame_id() << ", ";
873890

874891
}
892+
mesg.header.stamp = ros::Time::now();
893+
mesg.time = ros::Time::now();
875894
string message = ss.str();
876895
ROS_DEBUG_STREAM(message);
877896

@@ -894,7 +913,10 @@ void acquisition::Capture::run_soft_trig() {
894913

895914
int count = 0;
896915

897-
cams[MASTER_CAM_].trigger();
916+
if (!EXTERNAL_TRIGGER_) {
917+
cams[MASTER_CAM_].trigger();
918+
}
919+
898920
get_mat_images();
899921
if (SAVE_) {
900922
count++;
@@ -960,7 +982,9 @@ void acquisition::Capture::run_soft_trig() {
960982

961983
// Call update functions
962984
if (!MANUAL_TRIGGER_) {
963-
cams[MASTER_CAM_].trigger();
985+
if (!EXTERNAL_TRIGGER_) {
986+
cams[MASTER_CAM_].trigger();
987+
}
964988
get_mat_images();
965989
}
966990

@@ -1004,7 +1028,7 @@ void acquisition::Capture::run_soft_trig() {
10041028
}
10051029
}
10061030
catch(const std::exception &e){
1007-
ROS_FATAL_STREAM("Excption: "<<e.what());
1031+
ROS_FATAL_STREAM("Exception: "<<e.what());
10081032
}
10091033
catch(...){
10101034
ROS_FATAL_STREAM("Some unknown exception occured. \v Exiting gracefully, \n possible reason could be Camera Disconnection...");
@@ -1184,10 +1208,10 @@ void acquisition::Capture::run_mt() {
11841208
}
11851209

11861210
void acquisition::Capture::run() {
1187-
if(!MAX_RATE_SAVE_)
1188-
run_soft_trig();
1189-
else
1190-
run_mt();
1211+
if (MAX_RATE_SAVE_)
1212+
run_mt();
1213+
else
1214+
run_soft_trig();
11911215
}
11921216

11931217
std::string acquisition::Capture::todays_date()
@@ -1227,4 +1251,4 @@ void acquisition::Capture::dynamicReconfigureCallback(spinnaker_sdk_camera_drive
12271251
}
12281252
}
12291253
}
1230-
}
1254+
}

0 commit comments

Comments
 (0)