@@ -12,7 +12,7 @@ acquisition::Capture::~Capture(){
1212 end_acquisition ();
1313 deinit_cameras ();
1414
15- // pCam = NULL ;
15+ // pCam = nullptr ;
1616
1717 ROS_INFO_STREAM (" Clearing camList..." );
1818 camList_.Clear ();
@@ -147,7 +147,8 @@ void acquisition::Capture::load_cameras() {
147147 MASTER_CAM_ = cam_counter;
148148 }
149149
150- pResultImages_.push_back (NULL );
150+ ImagePtr a_null;
151+ pResultImages_.push_back (a_null);
151152
152153 Mat img;
153154 frames_.push_back (img);
@@ -194,13 +195,11 @@ void acquisition::Capture::read_parameters() {
194195
195196 if (nh_pvt_.getParam (" save_path" , path_)){
196197 if (path_.front () ==' ~' ){
197- // ROS_INFO("Front is tilda");
198198 const char *homedir;
199199 if ((homedir = getenv (" HOME" )) == NULL )
200200 homedir = getpwuid (getuid ())->pw_dir ;
201201 std::string hd (homedir);
202202 path_.replace (0 ,1 ,hd);
203- // ROS_INFO_STREAM("Path ="<<path_);
204203 }
205204 ROS_INFO_STREAM (" Save path set via parameter to: " << path_);
206205 }
@@ -252,56 +251,56 @@ void acquisition::Capture::read_parameters() {
252251
253252 if (nh_pvt_.getParam (" utstamps" , MASTER_TIMESTAMP_FOR_ALL_)){
254253 MASTER_TIMESTAMP_FOR_ALL_ = !MASTER_TIMESTAMP_FOR_ALL_;
255- ROS_INFO (" Unique time stamps for each camera: %d " ,!MASTER_TIMESTAMP_FOR_ALL_);
254+ ROS_INFO (" Unique time stamps for each camera: %s " ,!MASTER_TIMESTAMP_FOR_ALL_? " true " : " false " );
256255 }
257- else ROS_WARN (" 'utstamps' Parameter not set, using default behavior utstamps=%d " ,!MASTER_TIMESTAMP_FOR_ALL_);
256+ else ROS_WARN (" 'utstamps' Parameter not set, using default behavior utstamps=%s " ,!MASTER_TIMESTAMP_FOR_ALL_? " true " : " false " );
258257
259258 if (nh_pvt_.getParam (" color" , color_))
260- ROS_INFO (" color set to: %d " ,color_);
261- else ROS_WARN (" 'color' Parameter not set, using default behavior color=%d " ,color_);
259+ ROS_INFO (" color set to: %s " ,color_? " true " : " false " );
260+ else ROS_WARN (" 'color' Parameter not set, using default behavior color=%s " ,color_? " true " : " false " );
262261
263262 if (nh_pvt_.getParam (" to_ros" , EXPORT_TO_ROS_))
264- ROS_INFO (" Exporting images to ROS: %d " ,EXPORT_TO_ROS_);
265- else ROS_WARN (" 'to_ros' Parameter not set, using default behavior to_ros=%d " ,EXPORT_TO_ROS_);
263+ ROS_INFO (" Exporting images to ROS: %s " ,EXPORT_TO_ROS_? " true " : " false " );
264+ else ROS_WARN (" 'to_ros' Parameter not set, using default behavior to_ros=%s " ,EXPORT_TO_ROS_? " true " : " false " );
266265
267266 if (nh_pvt_.getParam (" live" , LIVE_))
268- ROS_INFO (" Showing live images setting: %d " ,LIVE_);
269- else ROS_WARN (" 'live' Parameter not set, using default behavior live=%d " ,LIVE_);
267+ ROS_INFO (" Showing live images setting: %s " ,LIVE_? " true " : " false " );
268+ else ROS_WARN (" 'live' Parameter not set, using default behavior live=%s " ,LIVE_? " true " : " false " );
270269
271270 if (nh_pvt_.getParam (" live_grid" , GRID_VIEW_)){
272271 LIVE_=LIVE_|| GRID_VIEW_;
273- ROS_INFO (" Showing grid-style live images setting: %d " ,LIVE_ );
274- } else ROS_WARN (" 'live_grid' Parameter not set, using default behavior live_grid=%d " ,GRID_VIEW_);
272+ ROS_INFO (" Showing grid-style live images setting: %s " ,GRID_VIEW_? " true " : " false " );
273+ } else ROS_WARN (" 'live_grid' Parameter not set, using default behavior live_grid=%s " ,GRID_VIEW_? " true " : " false " );
275274
276275 if (nh_pvt_.getParam (" max_rate_save" , MAX_RATE_SAVE_))
277- ROS_INFO (" Max Rate Save Mode: %d " ,MAX_RATE_SAVE_);
278- else ROS_WARN (" 'max_rate_save' Parameter not set, using default behavior max_rate_save=%d " ,MAX_RATE_SAVE_);
276+ ROS_INFO (" Max Rate Save Mode: %s " ,MAX_RATE_SAVE_? " true " : " false " );
277+ else ROS_WARN (" 'max_rate_save' Parameter not set, using default behavior max_rate_save=%s " ,MAX_RATE_SAVE_? " true " : " false " );
279278
280279 if (nh_pvt_.getParam (" time" , TIME_BENCHMARK_))
281- ROS_INFO (" Displaying timing details: %d " ,TIME_BENCHMARK_);
282- else ROS_WARN (" 'time' Parameter not set, using default behavior time=%d " ,TIME_BENCHMARK_);
280+ ROS_INFO (" Displaying timing details: %s " ,TIME_BENCHMARK_? " true " : " false " );
281+ else ROS_WARN (" 'time' Parameter not set, using default behavior time=%s " ,TIME_BENCHMARK_? " true " : " false " );
283282
284283 if (nh_pvt_.getParam (" skip" , skip_num_)){
285284 if (skip_num_ >0 ) ROS_INFO (" No. of images to skip set to: %d" ,skip_num_);
286285 else {
287286 skip_num_=20 ;
288- ROS_WARN (" Provided 'skip'=%d is not valid, using default behavior, skip=%d" ,skip_num_);
287+ ROS_WARN (" Provided 'skip' is not valid, using default behavior, skip=%d" ,skip_num_);
289288 }
290289 } else ROS_WARN (" 'skip' Parameter not set, using default behavior: skip=%d" ,skip_num_);
291290
292291 if (nh_pvt_.getParam (" delay" , init_delay_)){
293- if (init_delay_>=0 ) ROS_INFO (" Init sleep delays set to : %d sec" ,skip_num_ );
292+ if (init_delay_>=0 ) ROS_INFO (" Init sleep delays set to : %0.2f sec" ,init_delay_ );
294293 else {
295294 init_delay_=1 ;
296- ROS_WARN (" Provided 'delay'=%d is not valid, using default behavior, delay=%d" ,init_delay_);
295+ ROS_WARN (" Provided 'delay' is not valid, using default behavior, delay=%d" ,init_delay_);
297296 }
298- } else ROS_WARN (" 'delay' Parameter not set, using default behavior: delay=%d" ,skip_num_ );
297+ } else ROS_WARN (" 'delay' Parameter not set, using default behavior: delay=%d" ,init_delay_ );
299298
300299 if (nh_pvt_.getParam (" fps" , master_fps_)){
301- if (master_fps_>=0 ) ROS_INFO (" Master cam fps set to : %0.2 " ,master_fps_);
300+ if (master_fps_>=0 ) ROS_INFO (" Master cam fps set to : %0.2f " ,master_fps_);
302301 else {
303302 master_fps_=20 ;
304- ROS_WARN (" Provided 'fps'=%0.2f is not valid, using default behavior, fps=%d " ,master_fps_);
303+ ROS_WARN (" Provided 'fps' is not valid, using default behavior, fps=%0.2f " ,master_fps_);
305304 }
306305 }
307306 else ROS_WARN (" 'fps' Parameter not set, using default behavior: fps=%0.2f" ,master_fps_);
@@ -345,7 +344,7 @@ void acquisition::Capture::read_parameters() {
345344 if (nframes_>0 ){
346345 FIXED_NUM_FRAMES_ = true ;
347346 ROS_INFO (" Number of frames to be recorded: %d" , nframes_ );
348- }else ROS_INFO (" Frames will be recorded until user termination" , nframes_ );
347+ }else ROS_INFO (" Frames will be recorded until user termination" );
349348 }else ROS_WARN (" 'frames' Parameter not set, using defult behavior, frames will be recorded until user termination" );
350349 }
351350
@@ -728,7 +727,7 @@ void acquisition::Capture::run_soft_trig() {
728727 } else {
729728 imshow (" Acquisition" , frames_[CAM_]);
730729 char title[50 ];
731- sprintf (title, " cam # = %d, cam ID = %s, cam name = %s" , CAM_, cam_ids_[CAM_], cam_names_[CAM_]);
730+ sprintf (title, " cam # = %d, cam ID = %s, cam name = %s" , CAM_, cam_ids_[CAM_]. c_str () , cam_names_[CAM_]. c_str () );
732731 displayOverlay (" Acquisition" , title);
733732 }
734733 }
@@ -814,8 +813,11 @@ void acquisition::Capture::run_soft_trig() {
814813
815814 }
816815 }
816+ catch (const std::exception &e){
817+ ROS_FATAL_STREAM (" Excption: " <<e.what ());
818+ }
817819 catch (...){
818- ROS_FATAL_STREAM (" Some exception occured. \v Exiting gracefully, \n possible reason could be Camera Disconnection..." );
820+ ROS_FATAL_STREAM (" Some unknown exception occured. \v Exiting gracefully, \n possible reason could be Camera Disconnection..." );
819821 }
820822}
821823
@@ -1003,7 +1005,6 @@ std::string acquisition::Capture::todays_date()
10031005 char out[9 ];
10041006 std::time_t t=std::time (NULL );
10051007 std::strftime (out, sizeof (out), " %Y%m%d" , std::localtime (&t));
1006- std::cout<<out;
10071008 std::string td (out);
10081009 return td;
10091010}
0 commit comments