Skip to content

Commit a282456

Browse files
authored
Merge pull request #132 from neufieldrobotics/hotfix/will_fix_rate_issues
will fix rate issues when in external trigger
2 parents aa66a9f + 3627e56 commit a282456

File tree

2 files changed

+22
-39
lines changed

2 files changed

+22
-39
lines changed

include/spinnaker_sdk_camera_driver/capture.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -109,7 +109,6 @@ namespace acquisition {
109109
int nframes_;
110110
float init_delay_;
111111
int skip_num_;
112-
float master_fps_;
113112
int binning_;
114113
bool color_;
115114
string dump_img_;
@@ -133,7 +132,6 @@ namespace acquisition {
133132
bool EXTERNAL_TRIGGER_;
134133
bool SAVE_;
135134
bool SAVE_BIN_;
136-
bool MANUAL_TRIGGER_;
137135
bool LIVE_;
138136
bool CAM_DIRS_CREATED_;
139137
bool GRID_VIEW_;

src/capture.cpp

Lines changed: 22 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,6 @@ void acquisition::Capture::init_variables_register_to_ros() {
9797
region_of_interest_set_ = false;
9898
skip_num_ = 20;
9999
init_delay_ = 1;
100-
master_fps_ = 20.0;
101100
binning_ = 1;
102101
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000;
103102
todays_date_ = todays_date();
@@ -126,7 +125,6 @@ void acquisition::Capture::init_variables_register_to_ros() {
126125

127126
// default flag values
128127

129-
MANUAL_TRIGGER_ = false;
130128
CAM_DIRS_CREATED_ = false;
131129

132130
GRID_CREATED_ = false;
@@ -385,8 +383,9 @@ void acquisition::Capture::read_parameters() {
385383
found = true;
386384
}
387385
ROS_ASSERT_MSG(found,"Specified master cam is not in the cam_ids list!");
386+
388387
}
389-
388+
390389
if (nh_pvt_.getParam("utstamps", MASTER_TIMESTAMP_FOR_ALL_)){
391390
MASTER_TIMESTAMP_FOR_ALL_ = !MASTER_TIMESTAMP_FOR_ALL_;
392391
ROS_INFO(" Unique time stamps for each camera: %s",!MASTER_TIMESTAMP_FOR_ALL_?"true":"false");
@@ -462,15 +461,6 @@ void acquisition::Capture::read_parameters() {
462461
}
463462
} else ROS_WARN(" 'delay' Parameter not set, using default behavior: delay=%f",init_delay_);
464463

465-
if (nh_pvt_.getParam("fps", master_fps_)){
466-
if (master_fps_>=0) ROS_INFO(" Master cam fps set to : %0.2f",master_fps_);
467-
else {
468-
master_fps_=20;
469-
ROS_WARN(" Provided 'fps' is not valid, using default behavior, fps=%0.2f",master_fps_);
470-
}
471-
}
472-
else ROS_WARN(" 'fps' Parameter not set, using default behavior: fps=%0.2f",master_fps_);
473-
474464
if (nh_pvt_.getParam("exposure_time", exposure_time_)){
475465
if (exposure_time_ >0) ROS_INFO(" Exposure set to: %.1f",exposure_time_);
476466
else ROS_INFO(" 'exposure_time'=%0.f, Setting autoexposure",exposure_time_);
@@ -489,7 +479,6 @@ void acquisition::Capture::read_parameters() {
489479
else ROS_INFO(" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto",target_grey_value_);}
490480
else ROS_WARN(" 'target_grey_value' Parameter not set, using default behavior: AutoExposureTargetGreyValueAuto to auto");
491481

492-
493482
if (nh_pvt_.getParam("binning", binning_)){
494483
if (binning_ >0) ROS_INFO(" Binning set to: %d",binning_);
495484
else {
@@ -499,13 +488,13 @@ void acquisition::Capture::read_parameters() {
499488
} else ROS_WARN(" 'binning' Parameter not set, using default behavior: Binning = %d",binning_);
500489

501490
if (nh_pvt_.getParam("soft_framerate", soft_framerate_)){
502-
if (soft_framerate_ >0) {
503-
SOFT_FRAME_RATE_CTRL_=true;
504-
ROS_INFO(" Using Software rate control, rate set to: %d",soft_framerate_);
505-
}
506-
else ROS_INFO(" 'soft_framerate'=%d, software rate control set to off",soft_framerate_);
491+
if (soft_framerate_ >0) {
492+
SOFT_FRAME_RATE_CTRL_=true;
493+
ROS_INFO(" Using Software rate control, rate set to: %d",soft_framerate_);
494+
}
495+
else ROS_INFO(" 'soft_framerate'=%d, software rate control set to off",soft_framerate_);
507496
}
508-
else ROS_WARN(" 'soft_framerate' Parameter not set, using default behavior: No Software Rate Control ");
497+
else ROS_WARN(" 'soft_framerate' Parameter not set, using default behavior: No Software Rate Control ");
509498

510499
if (nh_pvt_.getParam("save", SAVE_))
511500
ROS_INFO(" Saving images set to: %d",SAVE_);
@@ -880,7 +869,8 @@ void acquisition::Capture::export_to_ROS() {
880869
else if (latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){
881870
double wait_time_start = ros::Time::now().toSec();
882871
ROS_WARN("Difference in trigger count zero, latest_count = %d and prev_count = %d",latest_imu_trigger_count_,prev_imu_trigger_count_);
883-
while(latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){
872+
while(latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0){
873+
884874
ros::Duration(0.0001).sleep();
885875
}
886876
ROS_INFO_STREAM("Time gap for sync messages: "<<ros::Time::now().toSec() - wait_time_start);
@@ -1067,20 +1057,17 @@ void acquisition::Capture::run_soft_trig() {
10671057
} else if( (key & 255)==81 ) { // LEFT ARROW
10681058
if (CAM_>0)
10691059
CAM_--;
1070-
} else if( (key & 255)==84 && MANUAL_TRIGGER_) { // t
1071-
cams[MASTER_CAM_].trigger();
1072-
get_mat_images();
10731060
} else if( (key & 255)==32 && !SAVE_) { // SPACE
10741061
ROS_INFO_STREAM("Saving frame...");
10751062
if (SAVE_BIN_)
10761063
save_binary_frames(0);
1077-
else{
1078-
save_mat_frames(0);
1079-
if (!EXPORT_TO_ROS_){
1080-
ROS_INFO_STREAM("Exporting frames to ROS...");
1081-
export_to_ROS();
1082-
}
1064+
else{
1065+
save_mat_frames(0);
1066+
if (!EXPORT_TO_ROS_){
1067+
ROS_INFO_STREAM("Exporting frames to ROS...");
1068+
export_to_ROS();
10831069
}
1070+
}
10841071
} else if( (key & 255)==27 ) { // ESC
10851072
ROS_INFO_STREAM("Terminating...");
10861073
cvDestroyAllWindows();
@@ -1093,12 +1080,11 @@ void acquisition::Capture::run_soft_trig() {
10931080
double disp_time_ = ros::Time::now().toSec() - t;
10941081

10951082
// Call update functions
1096-
if (!MANUAL_TRIGGER_) {
1097-
if (!EXTERNAL_TRIGGER_) {
1098-
cams[MASTER_CAM_].trigger();
1099-
}
1100-
get_mat_images();
1083+
1084+
if (!EXTERNAL_TRIGGER_) {
1085+
cams[MASTER_CAM_].trigger();
11011086
}
1087+
get_mat_images();
11021088

11031089
if (SAVE_) {
11041090
count++;
@@ -1109,7 +1095,7 @@ void acquisition::Capture::run_soft_trig() {
11091095
}
11101096

11111097
if (FIXED_NUM_FRAMES_) {
1112-
cout<<"Nframes "<< nframes_<<endl;
1098+
ROS_INFO_STREAM(" Recorded frames "<<count<<" / "<<nframes_);
11131099
if (count > nframes_) {
11141100
ROS_INFO_STREAM(nframes_ << " frames recorded. Terminating...");
11151101
cvDestroyAllWindows();
@@ -1135,8 +1121,7 @@ void acquisition::Capture::run_soft_trig() {
11351121

11361122
achieved_time_=ros::Time::now().toSec();
11371123

1138-
if (SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep();}
1139-
1124+
if (!EXTERNAL_TRIGGER_ && SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep();}
11401125
}
11411126
}
11421127
catch(const std::exception &e){

0 commit comments

Comments
 (0)