@@ -97,7 +97,6 @@ void acquisition::Capture::init_variables_register_to_ros() {
97
97
region_of_interest_set_ = false ;
98
98
skip_num_ = 20 ;
99
99
init_delay_ = 1 ;
100
- master_fps_ = 20.0 ;
101
100
binning_ = 1 ;
102
101
SPINNAKER_GET_NEXT_IMAGE_TIMEOUT_ = 2000 ;
103
102
todays_date_ = todays_date ();
@@ -126,7 +125,6 @@ void acquisition::Capture::init_variables_register_to_ros() {
126
125
127
126
// default flag values
128
127
129
- MANUAL_TRIGGER_ = false ;
130
128
CAM_DIRS_CREATED_ = false ;
131
129
132
130
GRID_CREATED_ = false ;
@@ -385,8 +383,9 @@ void acquisition::Capture::read_parameters() {
385
383
found = true ;
386
384
}
387
385
ROS_ASSERT_MSG (found," Specified master cam is not in the cam_ids list!" );
386
+
388
387
}
389
-
388
+
390
389
if (nh_pvt_.getParam (" utstamps" , MASTER_TIMESTAMP_FOR_ALL_)){
391
390
MASTER_TIMESTAMP_FOR_ALL_ = !MASTER_TIMESTAMP_FOR_ALL_;
392
391
ROS_INFO (" Unique time stamps for each camera: %s" ,!MASTER_TIMESTAMP_FOR_ALL_?" true" :" false" );
@@ -462,15 +461,6 @@ void acquisition::Capture::read_parameters() {
462
461
}
463
462
} else ROS_WARN (" 'delay' Parameter not set, using default behavior: delay=%f" ,init_delay_);
464
463
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
-
474
464
if (nh_pvt_.getParam (" exposure_time" , exposure_time_)){
475
465
if (exposure_time_ >0 ) ROS_INFO (" Exposure set to: %.1f" ,exposure_time_);
476
466
else ROS_INFO (" 'exposure_time'=%0.f, Setting autoexposure" ,exposure_time_);
@@ -489,7 +479,6 @@ void acquisition::Capture::read_parameters() {
489
479
else ROS_INFO (" 'target_grey_value'=%0.f, Setting AutoExposureTargetGreyValueAuto to Continuous/ auto" ,target_grey_value_);}
490
480
else ROS_WARN (" 'target_grey_value' Parameter not set, using default behavior: AutoExposureTargetGreyValueAuto to auto" );
491
481
492
-
493
482
if (nh_pvt_.getParam (" binning" , binning_)){
494
483
if (binning_ >0 ) ROS_INFO (" Binning set to: %d" ,binning_);
495
484
else {
@@ -499,13 +488,13 @@ void acquisition::Capture::read_parameters() {
499
488
} else ROS_WARN (" 'binning' Parameter not set, using default behavior: Binning = %d" ,binning_);
500
489
501
490
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_);
507
496
}
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 " );
509
498
510
499
if (nh_pvt_.getParam (" save" , SAVE_))
511
500
ROS_INFO (" Saving images set to: %d" ,SAVE_);
@@ -880,7 +869,8 @@ void acquisition::Capture::export_to_ROS() {
880
869
else if (latest_imu_trigger_count_ - prev_imu_trigger_count_ == 0 ){
881
870
double wait_time_start = ros::Time::now ().toSec ();
882
871
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
+
884
874
ros::Duration (0.0001 ).sleep ();
885
875
}
886
876
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() {
1067
1057
} else if ( (key & 255 )==81 ) { // LEFT ARROW
1068
1058
if (CAM_>0 )
1069
1059
CAM_--;
1070
- } else if ( (key & 255 )==84 && MANUAL_TRIGGER_) { // t
1071
- cams[MASTER_CAM_].trigger ();
1072
- get_mat_images ();
1073
1060
} else if ( (key & 255 )==32 && !SAVE_) { // SPACE
1074
1061
ROS_INFO_STREAM (" Saving frame..." );
1075
1062
if (SAVE_BIN_)
1076
1063
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 ();
1083
1069
}
1070
+ }
1084
1071
} else if ( (key & 255 )==27 ) { // ESC
1085
1072
ROS_INFO_STREAM (" Terminating..." );
1086
1073
cvDestroyAllWindows ();
@@ -1093,12 +1080,11 @@ void acquisition::Capture::run_soft_trig() {
1093
1080
double disp_time_ = ros::Time::now ().toSec () - t;
1094
1081
1095
1082
// 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 ();
1101
1086
}
1087
+ get_mat_images ();
1102
1088
1103
1089
if (SAVE_) {
1104
1090
count++;
@@ -1109,7 +1095,7 @@ void acquisition::Capture::run_soft_trig() {
1109
1095
}
1110
1096
1111
1097
if (FIXED_NUM_FRAMES_) {
1112
- cout<< " Nframes " << nframes_<<endl ;
1098
+ ROS_INFO_STREAM ( " Recorded frames " <<count<< " / " <<nframes_) ;
1113
1099
if (count > nframes_) {
1114
1100
ROS_INFO_STREAM (nframes_ << " frames recorded. Terminating..." );
1115
1101
cvDestroyAllWindows ();
@@ -1135,8 +1121,7 @@ void acquisition::Capture::run_soft_trig() {
1135
1121
1136
1122
achieved_time_=ros::Time::now ().toSec ();
1137
1123
1138
- if (SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep ();}
1139
-
1124
+ if (!EXTERNAL_TRIGGER_ && SOFT_FRAME_RATE_CTRL_) {ros_rate.sleep ();}
1140
1125
}
1141
1126
}
1142
1127
catch (const std::exception &e){
0 commit comments