48 m_grabber_type("opencv"),
59 m_img_dir_left_format("imL_%04d.jpg"),
60 m_img_dir_right_format("imR_%04d.jpg"),
62 m_external_image_saver_count(
std::thread::hardware_concurrency()),
64 m_hook_pre_save(
nullptr)
67 m_sensorLabel =
"CAMERA";
76 cout <<
"[CCameraSensor::initialize] Opening camera..." << endl;
83 if (m_grabber_type ==
"opencv")
92 catch (std::exception&)
98 "[CCameraSensor::initialize] opencv camera, index: %i type: " 100 int(m_cv_camera_index), (
int)ct);
101 m_cap_cv = std::make_unique<CImageGrabber_OpenCV>(
102 m_cv_camera_index, ct, m_cv_options);
104 if (!m_cap_cv->isOpen())
108 "[CCameraSensor::initialize] ERROR: Couldn't open OpenCV " 112 else if (m_grabber_type ==
"dc1394")
116 "[CCameraSensor::initialize] dc1394 camera, GUID: 0x%lX " 118 long(m_dc1394_camera_guid), m_dc1394_camera_unit);
119 m_cap_dc1394 = std::make_unique<CImageGrabber_dc1394>(
120 m_dc1394_camera_guid, m_dc1394_camera_unit, m_dc1394_options,
123 if (!m_cap_dc1394->isOpen())
127 "[CCameraSensor::initialize] ERROR: Couldn't open dc1394 " 131 else if (m_grabber_type ==
"bumblebee_dc1394")
134 "[CCameraSensor::initialize] bumblebee_libdc1394 camera: " 135 "GUID:0x%08X Index:%i FPS:%f...\n",
136 (
unsigned int)(m_bumblebee_dc1394_camera_guid),
137 m_bumblebee_dc1394_camera_unit, m_bumblebee_dc1394_framerate);
138 m_cap_bumblebee_dc1394 =
139 std::make_unique<CStereoGrabber_Bumblebee_libdc1394>(
140 m_bumblebee_dc1394_camera_guid, m_bumblebee_dc1394_camera_unit,
141 m_bumblebee_dc1394_framerate);
143 else if (m_grabber_type ==
"svs")
146 "[CCameraSensor::initialize] SVS camera: %u...\n",
147 (
unsigned int)(m_svs_camera_index));
148 m_cap_svs = std::make_unique<CStereoGrabber_SVS>(
149 m_svs_camera_index, m_svs_options);
151 else if (m_grabber_type ==
"ffmpeg")
155 "[CCameraSensor::initialize] FFmpeg stream: %s...\n",
156 m_ffmpeg_url.c_str());
157 m_cap_ffmpeg = std::make_unique<CFFMPEG_InputStream>();
159 if (!m_cap_ffmpeg->openURL(m_ffmpeg_url, m_capture_grayscale))
163 "Error opening FFmpeg stream: %s", m_ffmpeg_url.c_str());
166 else if (m_grabber_type ==
"swissranger")
168 cout <<
"[CCameraSensor::initialize] SwissRanger camera...\n";
169 m_cap_swissranger = std::make_unique<CSwissRanger3DCamera>();
171 m_cap_swissranger->setOpenFromUSB(m_sr_open_from_usb);
172 m_cap_swissranger->setOpenIPAddress(m_sr_ip_address);
174 m_cap_swissranger->setSave3D(m_sr_save_3d);
175 m_cap_swissranger->setSaveRangeImage(m_sr_save_range_img);
176 m_cap_swissranger->setSaveIntensityImage(m_sr_save_intensity_img);
177 m_cap_swissranger->setSaveConfidenceImage(m_sr_save_confidence);
179 if (!m_path_for_external_images.empty())
180 m_cap_swissranger->setPathForExternalImages(
181 m_path_for_external_images);
189 catch (std::exception&)
195 else if (m_grabber_type ==
"kinect")
197 cout <<
"[CCameraSensor::initialize] Kinect camera...\n";
198 m_cap_kinect = std::make_unique<CKinect>();
199 m_cap_kinect->enableGrab3DPoints(m_kinect_save_3d);
200 m_cap_kinect->enableGrabDepth(m_kinect_save_range_img);
201 m_cap_kinect->enableGrabRGB(m_kinect_save_intensity_img);
202 m_cap_kinect->setVideoChannel(
206 if (!m_path_for_external_images.empty())
207 m_cap_kinect->setPathForExternalImages(m_path_for_external_images);
215 catch (std::exception&)
221 else if (m_grabber_type ==
"openni2")
223 cout <<
"[CCameraSensor::initialize] OpenNI2 sensor...\n";
224 m_cap_openni2 = std::make_unique<COpenNI2Sensor>();
225 m_cap_openni2->enableGrab3DPoints(m_kinect_save_3d);
229 m_cap_openni2->enableGrabDepth(m_kinect_save_range_img);
230 m_cap_openni2->enableGrabRGB(m_kinect_save_intensity_img);
232 if (!m_path_for_external_images.empty())
233 m_cap_openni2->setPathForExternalImages(m_path_for_external_images);
241 catch (
const std::exception& e)
247 else if (m_grabber_type ==
"image_dir")
251 "[CCameraSensor::initialize] Image dir: %s...\n",
252 m_img_dir_url.c_str());
253 m_cap_image_dir = std::make_unique<std::string>();
255 else if (m_grabber_type ==
"rawlog")
259 "[CCameraSensor::initialize] Rawlog stream: %s...\n",
260 m_rawlog_file.c_str());
261 m_cap_rawlog = std::make_unique<CFileGZInputStream>();
263 if (!m_cap_rawlog->open(m_rawlog_file))
267 "Error opening rawlog file: %s", m_rawlog_file.c_str());
271 m_rawlog_detected_images_dir =
272 CRawlog::detectImagesDirectory(m_rawlog_file);
274 else if (m_grabber_type ==
"flycap")
276 cout <<
"[CCameraSensor::initialize] PGR FlyCapture2 camera...\n";
281 std::make_unique<CImageGrabber_FlyCapture2>(m_flycap_options);
283 catch (std::exception&)
289 else if (m_grabber_type ==
"flycap_stereo")
292 <<
"[CCameraSensor::initialize] PGR FlyCapture2 stereo camera...\n";
296 m_cap_flycap_stereo_l =
297 std::make_unique<CImageGrabber_FlyCapture2>();
298 m_cap_flycap_stereo_r =
299 std::make_unique<CImageGrabber_FlyCapture2>();
301 cout <<
"[CCameraSensor::initialize] PGR FlyCapture2 stereo " 302 "camera: Opening LEFT camera...\n";
303 m_cap_flycap_stereo_l->open(
304 m_flycap_stereo_options[0],
false );
306 cout <<
"[CCameraSensor::initialize] PGR FlyCapture2 stereo " 307 "camera: Opening RIGHT camera...\n";
308 m_cap_flycap_stereo_r->open(
309 m_flycap_stereo_options[1],
false );
312 if (m_fcs_start_synch_capture)
315 m_cap_flycap_stereo_l.get(), m_cap_flycap_stereo_r.get()};
320 m_cap_flycap_stereo_l->startCapture();
321 m_cap_flycap_stereo_r->startCapture();
324 catch (std::exception&)
330 else if (m_grabber_type ==
"duo3d")
333 cout <<
format(
"[CCameraSensor::initialize] DUO3D stereo camera ...\n");
338 m_cap_duo3d = std::make_unique<CDUO3DCamera>(m_duo3d_options);
340 catch (
const std::exception& e)
348 "Unknown 'grabber_type' found: %s", m_grabber_type.c_str());
351 cout <<
"[CCameraSensor::initialize] Done!" << endl;
355 if (m_external_images_own_thread)
357 m_threadImagesSaverShouldEnd =
false;
359 m_threadImagesSaver.clear();
360 m_threadImagesSaver.resize(m_external_image_saver_count);
362 m_toSaveList.clear();
363 m_toSaveList.resize(m_external_image_saver_count);
365 for (
unsigned int i = 0; i < m_external_image_saver_count; ++i)
366 m_threadImagesSaver[i] =
377 m_cap_dc1394.reset();
378 m_cap_flycap.reset();
379 m_cap_flycap_stereo_l.reset();
380 m_cap_flycap_stereo_r.reset();
381 m_cap_bumblebee_dc1394.reset();
382 m_cap_ffmpeg.reset();
383 m_cap_rawlog.reset();
384 m_cap_swissranger.reset();
385 m_cap_kinect.reset();
387 m_cap_image_dir.reset();
393 if (!m_threadImagesSaver.empty())
395 m_threadImagesSaverShouldEnd =
true;
396 for (
auto& i : m_threadImagesSaver) i.join();
412 if (m_grab_decimation > 0)
414 m_camera_grab_decimator = m_grab_decimation;
415 m_camera_grab_decimator_counter = 0;
417 m_grab_decimation = 0;
420 m_camera_grab_decimator = m_camera_grab_decimator_counter = 0;
423 iniSection,
"grabber_type", m_grabber_type);
425 preview_decimation,
int, m_preview_decimation, configSource, iniSection)
427 preview_reduction,
int, m_preview_reduction, configSource, iniSection)
431 iniSection,
"cv_camera_type", m_cv_camera_type);
433 configSource.
read_int(iniSection,
"cv_camera_index", m_cv_camera_index);
435 m_cv_options.frame_width = configSource.
read_int(
436 iniSection,
"cv_frame_width", m_cv_options.frame_width);
437 m_cv_options.frame_height = configSource.
read_int(
438 iniSection,
"cv_frame_height", m_cv_options.frame_height);
440 configSource.
read_double(iniSection,
"cv_gain", m_cv_options.gain);
441 m_cv_options.ieee1394_fps = configSource.
read_double(
442 iniSection,
"cv_fps", m_cv_options.ieee1394_fps);
444 m_capture_grayscale =
445 configSource.
read_bool(iniSection,
"capture_grayscale",
false);
447 m_cv_options.ieee1394_grayscale = m_capture_grayscale;
451 dc1394_camera_guid,
uint64_t, m_dc1394_camera_guid, configSource,
454 dc1394_camera_unit,
int, m_dc1394_camera_unit, configSource, iniSection)
457 dc1394_frame_width,
int, m_dc1394_options.frame_width, configSource,
460 dc1394_frame_height,
int, m_dc1394_options.frame_height, configSource,
464 dc1394_mode7,
int, m_dc1394_options.mode7, configSource, iniSection)
467 dc1394_shutter,
int, m_dc1394_options.shutter, configSource, iniSection)
469 dc1394_gain,
int, m_dc1394_options.gain, configSource, iniSection)
471 dc1394_gamma,
int, m_dc1394_options.gamma, configSource, iniSection)
473 dc1394_brightness,
int, m_dc1394_options.brightness, configSource,
476 dc1394_exposure,
int, m_dc1394_options.exposure, configSource,
479 dc1394_sharpness,
int, m_dc1394_options.sharpness, configSource,
482 dc1394_white_balance,
int, m_dc1394_options.white_balance, configSource,
486 dc1394_shutter_mode,
int, m_dc1394_options.shutter_mode, configSource,
489 dc1394_gain_mode,
int, m_dc1394_options.gain_mode, configSource,
492 dc1394_gamma_mode,
int, m_dc1394_options.gamma_mode, configSource,
495 dc1394_brightness_mode,
int, m_dc1394_options.brightness_mode,
496 configSource, iniSection)
498 dc1394_exposure_mode,
int, m_dc1394_options.exposure_mode, configSource,
501 dc1394_sharpness_mode,
int, m_dc1394_options.sharpness_mode,
502 configSource, iniSection)
504 dc1394_white_balance_mode,
int, m_dc1394_options.white_balance_mode,
505 configSource, iniSection)
508 dc1394_trigger_power,
int, m_dc1394_options.trigger_power, configSource,
511 dc1394_trigger_mode,
int, m_dc1394_options.trigger_mode, configSource,
514 dc1394_trigger_source,
int, m_dc1394_options.trigger_source,
515 configSource, iniSection)
517 dc1394_trigger_polarity,
int, m_dc1394_options.trigger_polarity,
518 configSource, iniSection)
520 dc1394_ring_buffer_size,
int, m_dc1394_options.ring_buffer_size,
521 configSource, iniSection)
525 bumblebee_dc1394_camera_guid,
uint64_t, m_bumblebee_dc1394_camera_guid,
526 configSource, iniSection)
528 bumblebee_dc1394_camera_unit,
int, m_bumblebee_dc1394_camera_unit,
529 configSource, iniSection)
531 bumblebee_dc1394_framerate,
double, m_bumblebee_dc1394_framerate,
532 configSource, iniSection)
535 m_svs_camera_index = configSource.
read_int(
536 iniSection,
"svs_camera_index", m_svs_camera_index);
537 m_svs_options.frame_width = configSource.
read_int(
538 iniSection,
"svs_frame_width", m_svs_options.frame_width);
539 m_svs_options.frame_height = configSource.
read_int(
540 iniSection,
"svs_frame_height", m_svs_options.frame_height);
541 m_svs_options.framerate = configSource.
read_double(
542 iniSection,
"svs_framerate", m_svs_options.framerate);
543 m_svs_options.m_NDisp =
544 configSource.
read_int(iniSection,
"svs_NDisp", m_svs_options.m_NDisp);
545 m_svs_options.m_Corrsize = configSource.
read_int(
546 iniSection,
"svs_Corrsize", m_svs_options.m_Corrsize);
548 configSource.
read_int(iniSection,
"svs_LR", m_svs_options.m_LR);
549 m_svs_options.m_Thresh =
550 configSource.
read_int(iniSection,
"svs_Thresh", m_svs_options.m_Thresh);
551 m_svs_options.m_Unique =
552 configSource.
read_int(iniSection,
"svs_Unique", m_svs_options.m_Unique);
553 m_svs_options.m_Horopter = configSource.
read_int(
554 iniSection,
"svs_Horopter", m_svs_options.m_Horopter);
555 m_svs_options.m_SpeckleSize = configSource.
read_int(
556 iniSection,
"svs_SpeckleSize", m_svs_options.m_SpeckleSize);
557 m_svs_options.m_procesOnChip = configSource.
read_bool(
558 iniSection,
"svs_procesOnChip", m_svs_options.m_procesOnChip);
559 m_svs_options.m_calDisparity = configSource.
read_bool(
560 iniSection,
"svs_calDisparity", m_svs_options.m_calDisparity);
564 configSource.
read_string(iniSection,
"ffmpeg_url", m_ffmpeg_url));
568 configSource.
read_string(iniSection,
"rawlog_file", m_rawlog_file));
570 iniSection,
"rawlog_camera_sensor_label",
571 m_rawlog_camera_sensor_label));
575 configSource.
read_string(iniSection,
"image_dir_url", m_img_dir_url));
577 iniSection,
"left_format", m_img_dir_left_format));
579 configSource.
read_string(iniSection,
"right_format",
""));
580 m_img_dir_start_index =
581 configSource.
read_int(iniSection,
"start_index", m_img_dir_start_index);
583 m_img_dir_end_index =
584 configSource.
read_int(iniSection,
"end_index", m_img_dir_end_index);
586 m_img_dir_is_stereo = !m_img_dir_right_format.empty();
587 m_img_dir_counter = m_img_dir_start_index;
590 m_duo3d_options.loadOptionsFrom(configSource,
"DUO3DOptions");
594 configSource.
read_bool(iniSection,
"sr_use_usb", m_sr_open_from_usb);
596 configSource.
read_string(iniSection,
"sr_IP", m_sr_ip_address);
599 configSource.
read_bool(iniSection,
"sr_grab_3d", m_sr_save_3d);
600 m_sr_save_intensity_img = configSource.
read_bool(
601 iniSection,
"sr_grab_grayscale", m_sr_save_intensity_img);
602 m_sr_save_range_img = configSource.
read_bool(
603 iniSection,
"sr_grab_range", m_sr_save_range_img);
604 m_sr_save_confidence = configSource.
read_bool(
605 iniSection,
"sr_grab_confidence", m_sr_save_confidence);
608 configSource.
read_bool(iniSection,
"kinect_grab_3d", m_kinect_save_3d);
609 m_kinect_save_intensity_img = configSource.
read_bool(
610 iniSection,
"kinect_grab_intensity", m_kinect_save_intensity_img);
611 m_kinect_save_range_img = configSource.
read_bool(
612 iniSection,
"kinect_grab_range", m_kinect_save_range_img);
613 m_kinect_video_rgb = configSource.
read_bool(
614 iniSection,
"kinect_video_rgb", m_kinect_video_rgb);
617 m_flycap_options.loadOptionsFrom(configSource, iniSection,
"flycap_");
620 m_fcs_start_synch_capture = configSource.
read_bool(
621 iniSection,
"fcs_start_synch_capture", m_fcs_start_synch_capture);
622 m_flycap_stereo_options[0].loadOptionsFrom(
623 configSource, iniSection,
"fcs_LEFT_");
624 m_flycap_stereo_options[1].loadOptionsFrom(
625 configSource, iniSection,
"fcs_RIGHT_");
628 map<double, grabber_dc1394_framerate_t> map_fps;
629 map<double, grabber_dc1394_framerate_t>::iterator it_fps;
641 configSource.
read_double(iniSection,
"dc1394_framerate", 15.0);
642 it_fps = map_fps.find(the_fps);
643 if (it_fps == map_fps.end())
645 "ERROR: DC1394 framerate seems to be not a valid number: %f",
648 m_dc1394_options.framerate = it_fps->second;
651 map<string, grabber_dc1394_color_coding_t> map_color;
652 map<string, grabber_dc1394_color_coding_t>::iterator it_color;
653 #define ADD_COLOR_MAP(c) map_color[#c] = c; 661 string the_color_coding =
663 iniSection,
"dc1394_color_coding",
"COLOR_CODING_YUV422"));
664 it_color = map_color.find(the_color_coding);
665 if (it_color == map_color.end())
667 "ERROR: Color coding seems not to be valid : '%s'",
668 the_color_coding.c_str());
669 m_dc1394_options.color_coding = it_color->second;
672 iniSection,
"external_images_format", m_external_images_format));
673 m_external_images_jpeg_quality = configSource.
read_int(
674 iniSection,
"external_images_jpeg_quality",
675 m_external_images_jpeg_quality);
676 m_external_images_own_thread = configSource.
read_bool(
677 iniSection,
"external_images_own_thread", m_external_images_own_thread);
678 m_external_image_saver_count = configSource.
read_int(
679 iniSection,
"external_images_own_thread_count",
680 m_external_image_saver_count);
683 m_sensorPose.setFromValues(
684 configSource.
read_float(iniSection,
"pose_x", 0),
685 configSource.
read_float(iniSection,
"pose_y", 0),
686 configSource.
read_float(iniSection,
"pose_z", 0),
699 m_preview_win1.reset();
700 m_preview_win2.reset();
707 vector<CSerializable::Ptr> out_obs;
708 getNextFrame(out_obs);
709 return std::dynamic_pointer_cast<
CObservation>(out_obs[0]);
723 bool capture_ok =
false;
727 obs = std::make_shared<CObservationImage>();
728 if (!m_cap_cv->getObservation(*obs))
736 else if (m_cap_dc1394)
738 obs = std::make_shared<CObservationImage>();
739 if (!m_cap_dc1394->getObservation(*obs))
747 else if (m_cap_swissranger)
749 obs3D = std::make_shared<CObservation3DRangeScan>();
751 bool there_is_obs, hardware_error;
752 m_cap_swissranger->getNextObservation(
753 *obs3D, there_is_obs, hardware_error);
755 if (!there_is_obs || hardware_error)
763 else if (m_cap_kinect)
765 obs3D = std::make_shared<CObservation3DRangeScan>();
770 double max_timeout = 3.0;
774 const char* envVal = getenv(
"MRPT_CCAMERA_KINECT_TIMEOUT_MS");
775 if (envVal) max_timeout = atoi(envVal) * 0.001;
777 bool there_is_obs, hardware_error;
780 m_cap_kinect->getNextObservation(
781 *obs3D, there_is_obs, hardware_error);
782 if (!there_is_obs) std::this_thread::sleep_for(1ms);
786 if (!there_is_obs || hardware_error)
794 else if (m_cap_openni2)
796 obs3D = std::make_shared<CObservation3DRangeScan>();
800 double max_timeout = 3.0;
801 bool there_is_obs, hardware_error;
804 m_cap_openni2->getNextObservation(
805 *obs3D, there_is_obs, hardware_error);
806 if (!there_is_obs) std::this_thread::sleep_for(1ms);
810 if (!there_is_obs || hardware_error)
818 else if (m_cap_bumblebee_dc1394)
820 stObs = std::make_shared<CObservationStereoImages>();
821 if (!m_cap_bumblebee_dc1394->getStereoObservation(*stObs))
833 stObs = std::make_shared<CObservationStereoImages>();
835 if (!m_cap_svs->getStereoObservation(*stObs))
844 else if (m_cap_ffmpeg)
846 obs = std::make_shared<CObservationImage>();
848 if (!m_cap_ffmpeg->retrieveFrame(obs->image))
856 else if (m_cap_image_dir)
858 if (m_img_dir_counter > m_img_dir_end_index)
865 "%s/%s", m_img_dir_url.c_str(), m_img_dir_left_format.c_str());
866 if (m_img_dir_is_stereo)
868 stObs = std::make_shared<CObservationStereoImages>();
869 if (!stObs->imageLeft.loadFromFile(
870 format(auxL.c_str(), m_img_dir_counter)))
876 "%s/%s", m_img_dir_url.c_str(), m_img_dir_right_format.c_str());
877 if (!stObs->imageRight.loadFromFile(
878 format(auxR.c_str(), m_img_dir_counter++)))
889 obs = std::make_shared<CObservationImage>();
890 if (!obs->image.loadFromFile(
891 format(auxL.c_str(), m_img_dir_counter++)))
900 else if (m_cap_rawlog)
905 while (!obs && !stObs && !obs3D)
912 if (!m_rawlog_camera_sensor_label.empty() &&
913 m_rawlog_camera_sensor_label != o->sensorLabel)
917 obs = std::dynamic_pointer_cast<CObservationImage>(o);
920 std::dynamic_pointer_cast<CObservationStereoImages>(o);
923 std::dynamic_pointer_cast<CObservation3DRangeScan>(o);
932 if (!m_rawlog_camera_sensor_label.empty() &&
933 m_rawlog_camera_sensor_label != o->sensorLabel)
957 if (obs || stObs || obs3D)
962 CImage::getImagesPathBase();
963 CImage::setImagesPathBase(m_rawlog_detected_images_dir);
965 if (obs && obs->image.isExternallyStored())
966 obs->image.loadFromFile(
967 obs->image.getExternalStorageFileAbsolutePath());
969 if (obs3D && obs3D->hasIntensityImage &&
970 obs3D->intensityImage.isExternallyStored())
971 obs3D->intensityImage.loadFromFile(
972 obs3D->intensityImage
973 .getExternalStorageFileAbsolutePath());
975 if (stObs && stObs->imageLeft.isExternallyStored())
976 stObs->imageLeft.loadFromFile(
977 stObs->imageLeft.getExternalStorageFileAbsolutePath());
979 if (stObs && stObs->hasImageRight &&
980 stObs->imageRight.isExternallyStored())
981 stObs->imageRight.loadFromFile(
982 stObs->imageRight.getExternalStorageFileAbsolutePath());
984 if (stObs && stObs->hasImageDisparity &&
985 stObs->imageDisparity.isExternallyStored())
986 stObs->imageDisparity.loadFromFile(
987 stObs->imageDisparity
988 .getExternalStorageFileAbsolutePath());
990 CImage::setImagesPathBase(old_dir);
997 else if (m_cap_flycap)
1000 if (!m_cap_flycap->isStereo())
1002 obs = std::make_shared<CObservationImage>();
1003 ok = m_cap_flycap->getObservation(*obs);
1007 stObs = std::make_shared<CObservationStereoImages>();
1008 ok = m_cap_flycap->getObservation(*stObs);
1019 else if (m_cap_flycap_stereo_l && m_cap_flycap_stereo_r)
1021 stObs = std::make_shared<CObservationStereoImages>();
1025 bool ok1, ok2 =
false;
1027 ok1 = m_cap_flycap_stereo_r->getObservation(obsL);
1028 if (ok1) ok2 = m_cap_flycap_stereo_l->getObservation(obsR);
1041 if (std::abs(At) > 0.1)
1043 cout <<
"[CCamera, flycap_stereo] Warning: Too large delay " 1044 "between left & right images: " 1053 stObs->imageLeft = std::move(obsL.image);
1054 stObs->imageRight = std::move(obsR.image);
1058 else if (m_cap_duo3d)
1060 stObs = std::make_shared<CObservationStereoImages>();
1061 obsIMU = std::make_shared<CObservationIMU>();
1063 bool thereIsIMG, thereIsIMU;
1064 m_cap_duo3d->getObservations(*stObs, *obsIMU, thereIsIMG, thereIsIMU);
1070 else if (m_cap_duo3d->captureIMUIsSet() && !thereIsIMU)
1072 cout <<
"[CCamera, duo3d] Warning: There are no IMU data from the " 1073 "device. Only images are being grabbed.";
1080 "There is no initialized camera driver: has 'initialize()' been " 1087 m_camera_grab_decimator_counter++;
1088 if (m_camera_grab_decimator_counter < m_camera_grab_decimator)
1095 m_camera_grab_decimator_counter = 0;
1097 ASSERT_(obs || stObs || obs3D || obsIMU);
1101 obs->sensorLabel = m_sensorLabel;
1102 obs->setSensorPose(m_sensorPose);
1106 stObs->sensorLabel = (m_cap_duo3d && m_cap_duo3d->captureIMUIsSet())
1107 ? m_sensorLabel +
"_IMG" 1109 stObs->setSensorPose(m_sensorPose);
1113 obs3D->sensorLabel = m_sensorLabel;
1114 obs3D->setSensorPose(m_sensorPose);
1118 obsIMU->sensorLabel = m_sensorLabel +
"_IMU";
1119 obsIMU->setSensorPose(m_sensorPose);
1123 if (m_capture_grayscale)
1127 if (obs->image.isColor()) obs->image = obs->image.grayscale();
1131 if (stObs->imageLeft.isColor())
1132 stObs->imageLeft = stObs->imageLeft.grayscale();
1133 if (stObs->hasImageRight && stObs->imageRight.isColor())
1134 stObs->imageRight = stObs->imageRight.grayscale();
1135 if (stObs->hasImageDisparity && stObs->imageDisparity.isColor())
1136 stObs->imageDisparity = stObs->imageDisparity.grayscale();
1140 if (obs3D->hasIntensityImage && obs3D->intensityImage.isColor())
1141 obs3D->intensityImage = obs3D->intensityImage.grayscale();
1146 CImage img4gui, img4guiR;
1147 if (m_preview_win1 && m_preview_win1->isOpen())
1151 img4gui = stObs->imageLeft.makeDeepCopy();
1152 img4guiR = stObs->imageRight.makeDeepCopy();
1155 img4gui = obs->image.makeDeepCopy();
1157 img4gui = obs3D->intensityImage.makeDeepCopy();
1163 bool delayed_insertion_in_obs_queue =
false;
1164 if (!m_path_for_external_images.empty())
1168 if (m_external_images_own_thread)
1170 m_csToSaveList.lock();
1174 for (
size_t i = 0; i < m_toSaveList.size(); ++i)
1175 if (m_toSaveList[i].
size() < m_toSaveList[idx_min].size())
1178 m_toSaveList[idx_min].insert(
1181 m_csToSaveList.unlock();
1183 delayed_insertion_in_obs_queue =
true;
1187 const string filNameL =
1191 m_external_images_format.c_str());
1192 const string filNameR =
1196 m_external_images_format.c_str());
1197 const string filNameD =
1201 m_external_images_format.c_str());
1203 stObs->imageLeft.saveToFile(
1204 m_path_for_external_images +
string(
"/") + filNameL,
1205 m_external_images_jpeg_quality);
1206 stObs->imageLeft.setExternalStorage(filNameL);
1208 if (stObs->hasImageRight)
1210 stObs->imageRight.saveToFile(
1211 m_path_for_external_images +
string(
"/") + filNameR,
1212 m_external_images_jpeg_quality);
1213 stObs->imageRight.setExternalStorage(filNameR);
1215 if (stObs->hasImageDisparity)
1217 stObs->imageDisparity.saveToFile(
1218 m_path_for_external_images +
string(
"/") + filNameD,
1219 m_external_images_jpeg_quality);
1220 stObs->imageDisparity.setExternalStorage(filNameD);
1226 if (m_external_images_own_thread)
1228 m_csToSaveList.lock();
1232 for (
size_t i = 0; i < m_toSaveList.size(); ++i)
1233 if (m_toSaveList[i].
size() < m_toSaveList[idx_min].size())
1237 m_toSaveList[idx_min].insert(
TListObsPair(obs->timestamp, obs));
1239 m_csToSaveList.unlock();
1240 delayed_insertion_in_obs_queue =
true;
1248 m_external_images_format.c_str());
1250 obs->image.saveToFile(
1251 m_path_for_external_images +
string(
"/") + filName,
1252 m_external_images_jpeg_quality);
1253 obs->image.setExternalStorage(filName);
1259 if (m_preview_decimation > 0)
1261 if (++m_preview_counter > m_preview_decimation)
1263 m_preview_counter = 0;
1266 if (!m_preview_win1)
1268 string caption =
string(
"Preview of ") + m_sensorLabel;
1269 if (stObs) caption +=
"-LEFT";
1270 if (m_preview_decimation > 1)
1272 format(
" (decimation: %i)", m_preview_decimation);
1275 if (stObs && !m_preview_win2)
1277 string caption =
string(
"Preview of ") + m_sensorLabel;
1278 if (stObs) caption +=
"-RIGHT";
1279 if (m_preview_decimation > 1)
1281 format(
" (decimation: %i)", m_preview_decimation);
1285 if (m_preview_win1->isOpen() && img4gui.
getWidth() > 0)
1288 if (m_preview_reduction >= 2)
1294 auxImg,
w / m_preview_reduction,
1296 m_preview_win1->showImage(auxImg);
1299 m_preview_win1->showImage(img4gui);
1303 if (m_preview_win2 && m_preview_win2->isOpen() && stObs &&
1304 stObs->hasImageRight && img4gui.
getWidth() > 0)
1307 if (m_preview_reduction >= 2)
1313 auxImg,
w / m_preview_reduction,
1315 m_preview_win2->showImage(auxImg);
1318 m_preview_win2->showImage(img4guiR);
1322 if (m_preview_win2 && m_preview_win2->isOpen() && stObs &&
1323 stObs->hasImageDisparity)
1326 if (m_preview_reduction >= 2)
1328 unsigned int w = stObs->imageDisparity.getWidth();
1329 unsigned int h = stObs->imageDisparity.getHeight();
1331 stObs->imageDisparity.scaleImage(
1332 auxImg,
w / m_preview_reduction,
1334 m_preview_win2->showImage(auxImg);
1337 m_preview_win2->showImage(stObs->imageDisparity);
1342 if (delayed_insertion_in_obs_queue)
1344 if (m_cap_duo3d && m_cap_duo3d->captureIMUIsSet() && obsIMU)
1361 vector<CSerializable::Ptr> out_obs;
1362 getNextFrame(out_obs);
1363 appendObservations(out_obs);
1373 if (!m_cap_dc1394->setSoftwareTriggerLevel(
level))
1382 "Software trigger is not implemented for this camera type");
1394 "Error: Cannot create the directory for externally saved images: " 1398 m_path_for_external_images = directory;
1406 #if MRPT_HAS_WXWIDGETS 1410 std::cerr <<
"[mrpt::hwdrivers::prepareVideoSourceFromUserSelection] " 1411 "Error initiating Wx subsystem." 1416 std::promise<void> semDlg;
1417 std::promise<mrpt::gui::detail::TReturnAskUserOpenCamera> dlgSelection;
1422 REQ->sourceCameraSelectDialog =
true;
1423 REQ->voidPtr =
reinterpret_cast<void*
>(&semDlg);
1424 REQ->voidPtr2 =
reinterpret_cast<void*
>(&dlgSelection);
1425 WxSubsystem::pushPendingWxRequest(REQ);
1428 if (!WxSubsystem::isConsoleApp())
1430 std::this_thread::sleep_for(
1432 wxApp::GetInstance()->Yield(
true);
1444 const char* envVal = getenv(
"MRPT_WXSUBSYS_TIMEOUT_MS");
1445 if (envVal) maxTimeout = atoi(envVal);
1447 if (semDlg.get_future().wait_for(std::chrono::milliseconds(maxTimeout)) ==
1448 std::future_status::timeout)
1450 cerr <<
"[prepareVideoSourceFromUserSelection] Timeout waiting window " 1457 auto future = dlgSelection.get_future();
1459 const auto& ret = future.get();
1467 cam->loadConfig(selectedConfig,
"CONFIG");
1473 #endif // MRPT_HAS_WXWIDGETS 1481 #if MRPT_HAS_WXWIDGETS 1490 video->loadConfig(cfg,
"CONFIG");
1493 video->initialize();
1497 catch (
const std::exception& e)
1499 cerr << endl << e.what() << endl;
1500 wxMessageBox(_(
"Couldn't open video source"), _(
"Error"));
1505 #endif // MRPT_HAS_WXWIDGETS 1515 #if MRPT_HAS_WXWIDGETS 1519 panel,
"panel must be of type mrpt::gui::CPanelCameraSelection *");
1520 panel->writeConfigFromVideoSourcePanel(sect, cfg);
1524 #endif // MRPT_HAS_WXWIDGETS 1536 #if MRPT_HAS_WXWIDGETS 1540 panel,
"panel must be of type mrpt::gui::CPanelCameraSelection *");
1542 panel->readConfigIntoVideoSourcePanel(sect, cfg);
1546 #endif // MRPT_HAS_WXWIDGETS 1555 while (!m_threadImagesSaverShouldEnd)
1560 m_csToSaveList.lock();
1561 m_toSaveList[my_working_thread_index].swap(newObs);
1562 m_csToSaveList.unlock();
1564 for (
auto i = newObs.begin(); i != newObs.end(); ++i)
1567 if (m_hook_pre_save)
1574 m_hook_pre_save(obs, m_hook_pre_save_param);
1587 m_external_images_format.c_str());
1589 obs->image.saveToFile(
1590 m_path_for_external_images +
string(
"/") + filName,
1591 m_external_images_jpeg_quality);
1592 obs->image.setExternalStorage(filName);
1600 const string filNameL =
1604 m_external_images_format.c_str());
1605 const string filNameR =
1609 m_external_images_format.c_str());
1610 const string filNameD =
1614 m_external_images_format.c_str());
1616 stObs->imageLeft.saveToFile(
1617 m_path_for_external_images +
string(
"/") + filNameL,
1618 m_external_images_jpeg_quality);
1619 stObs->imageLeft.setExternalStorage(filNameL);
1621 if (stObs->hasImageRight)
1623 stObs->imageRight.saveToFile(
1624 m_path_for_external_images +
string(
"/") + filNameR,
1625 m_external_images_jpeg_quality);
1626 stObs->imageRight.setExternalStorage(filNameR);
1628 if (stObs->hasImageDisparity)
1630 stObs->imageDisparity.saveToFile(
1631 m_path_for_external_images +
string(
"/") + filNameD,
1632 m_external_images_jpeg_quality);
1633 stObs->imageDisparity.setExternalStorage(filNameD);
1638 appendObservation(i->second);
1641 std::this_thread::sleep_for(2ms);
This class implements a config file-like interface over a memory-stored string list.
Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored.
bool createDirectory(const std::string &dirName)
Creates a directory.
TCameraType
These capture types are like their OpenCV equivalents.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
The data structure for each inter-thread request:
CCameraSensor::Ptr prepareVideoSourceFromUserSelection()
Show to the user a list of possible camera drivers and creates and open the selected camera...
#define THROW_EXCEPTION(msg)
A wrapper for Point Gray Research (PGR) FlyCapture2 API for capturing images from Firewire...
std::pair< mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr > TListObsPair
double DEG2RAD(const double x)
Degrees to radians.
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &iniSection) override
See the class documentation at the top for expected parameters.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
size_t getHeight() const override
Returns the height of the image in pixels.
void readConfigIntoVideoSourcePanel(void *panel, const std::string &in_cfgfile_section_name, const mrpt::config::CConfigFileBase *in_cfgfile)
Parse the given section of the given configuration file and set accordingly the controls of the wxWid...
void scaleImage(CImage &out_img, unsigned int width, unsigned int height, TInterpolationMethod interp=IMG_INTERP_CUBIC) const
Scales this image to a new size, interpolating as needed, saving the new image in a different output ...
void doProcess() override
This method will be invoked at a minimum rate of "process_rate" (Hz)
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores ('_') or any other user-given char. ...
~CCameraSensor() override
Destructor.
int OPCODE
Valid codes are: For CDisplayWindow:
GLubyte GLubyte GLubyte GLubyte w
void writeConfigFromVideoSourcePanel(void *panel, const std::string &in_cfgfile_section_name, mrpt::config::CConfigFileBase *out_cfgfile)
Parse the user options in the wxWidgets "panel" and write the configuration into the given section of...
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream, std::istream, std::ostream, std::stringstream.
void thread_save_images(unsigned int my_working_thread_index)
Thread to save images to files.
#define ASSERT_(f)
Defines an assertion mechanism.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
This class allows loading and storing values and vectors of different types from a configuration text...
void close()
Close the camera (if open).
size_t getWidth() const override
Returns the width of the image in pixels.
The central class for camera grabbers in MRPT, implementing the "generic sensor" interface.
std::string lowerCase(const std::string &str)
Returns an lower-case version of a string.
std::shared_ptr< CCameraSensor > Ptr
Versatile class for consistent logging and management of output messages.
double timestampTotime_t(const mrpt::system::TTimeStamp t) noexcept
Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of...
#define IS_DERIVED(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given ...
Observation class for either a pair of left+right or left+disparity images from a stereo camera...
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
static std::string & trim(std::string &s)
std::string read_string_first_word(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
Reads a configuration parameter of type "string", and keeps only the first word (this can be used to ...
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
GLsizei const GLchar ** string
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
static void startSyncCapture(int numCameras, const CImageGrabber_FlyCapture2 **cameras_array)
Starts a synchronous capture of several cameras, which must have been already opened.
unsigned __int64 uint64_t
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void initialize() override
Tries to open the camera, after setting all the parameters with a call to loadConfig.
std::multimap< mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr > TListObservations
Declares a class that represents any robot's observation.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
std::string upperCase(const std::string &str)
Returns a upper-case version of a string.
mrpt::obs::CObservation::Ptr getNextFrame()
Retrieves the next frame from the video source, raising an exception on any error.
void setSoftwareTriggerLevel(bool level)
Set Software trigger level value (ON or OFF) for cameras with this function available.
A panel to select the camera input from all the formats supported by MRPT.
#define MRPT_LOAD_HERE_CONFIG_VAR( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
std::string trim(const std::string &str)
Removes leading and trailing spaces.
GLenum GLsizei GLenum format
Classes for creating GUI windows for 2D and 3D visualization.
static CDisplayWindow::Ptr Create(const std::string &windowCaption, unsigned int initWidth=400, unsigned int initHeight=400)
Class factory returning a smart pointer.
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
void setPathForExternalImages(const std::string &directory) override
Set the path where to save off-rawlog image files (this class DOES take into account this path)...
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
static bool createOneInstanceMainThread()
Thread-safe method to create one single instance of the main wxWidgets thread: it will create the thr...
CCameraSensor::Ptr prepareVideoSourceFromPanel(void *panel)
Used only from MRPT apps: Use with caution since "panel" MUST be a "mrpt::gui::CPanelCameraSelection ...
A class for storing images as grayscale or RGB bitmaps.