Go to the documentation of this file.
16 #include <mrpt/otherlibs/do_opencv_includes.h>
31 std::map<const mrpt::hwdrivers::TCaptureOptions_DUO3D*, TDUOParams>
duo_params;
39 #define M_DUO_PTR (reinterpret_cast<DUOInstance*>(m_duo))
40 #define M_DUO_VALUE (*M_DUO_PTR)
55 TCaptureOptions_DUO3D::TCaptureOptions_DUO3D()
63 m_capture_rectified(false),
64 m_calibration_from_file(true),
65 m_rectify_map_filename(
""),
66 m_intrinsic_filename(
""),
67 m_extrinsic_filename(
""),
82 const string file_name =
88 const size_t found = aux.find(
90 if (found == std::string::npos)
97 FileStorage fs(file_name, FileStorage::READ);
111 THROW_EXCEPTION(
"This function requires building with OpenCV support");
117 const string& _file_name)
120 const string file_name =
127 const size_t found = aux.find(
129 if (found == std::string::npos)
135 FileStorage fs(file_name, FileStorage::READ);
142 if (aux_mat.size() == Size(3, 3))
144 for (
size_t k1 = 0; k1 < 3; ++k1)
145 for (
size_t k2 = 0; k2 < 3; ++k2)
146 M(k1, k2) = aux_mat.at<
double>(k1, k2);
156 if (aux_mat.size() == Size(1, 3))
158 t(0, 0) = aux_mat.at<
double>(0, 0) / 1000.0;
159 t(0, 1) = aux_mat.at<
double>(1, 0) / 1000.0;
160 t(0, 2) = aux_mat.at<
double>(2, 0) / 1000.0;
173 THROW_EXCEPTION(
"This function requires building with OpenCV support");
179 const string& _file_name)
182 const string file_name =
189 const size_t found = aux.find(
191 if (found == std::string::npos)
201 FileStorage fs(file_name, FileStorage::READ);
205 if (aux_mat.size() == Size(0, 0))
211 aux_mat.at<
double>(0, 0), aux_mat.at<
double>(1, 1),
212 aux_mat.at<
double>(0, 2), aux_mat.at<
double>(1, 2));
215 if (aux_mat.size() == Size(0, 0))
221 aux_mat.at<
double>(0, 0), aux_mat.at<
double>(0, 1),
222 aux_mat.at<
double>(0, 2), aux_mat.at<
double>(0, 3),
223 aux_mat.at<
double>(0, 4));
226 if (aux_mat.size() == Size(0, 0))
232 aux_mat.at<
double>(0, 0), aux_mat.at<
double>(1, 1),
233 aux_mat.at<
double>(0, 2), aux_mat.at<
double>(1, 2));
236 if (aux_mat.size() == Size(0, 0))
242 aux_mat.at<
double>(0, 0), aux_mat.at<
double>(0, 1),
243 aux_mat.at<
double>(0, 2), aux_mat.at<
double>(0, 3),
244 aux_mat.at<
double>(0, 4));
248 THROW_EXCEPTION(
"This function requires building with OpenCV support");
294 static void CALLBACK DUOCallback(
const PDUOFrame pFrameData,
void* pUserData)
298 SetEvent(
reinterpret_cast<HANDLE
>(
obj->getEvent()));
307 m_duo =
new DUOInstance[1];
314 "MRPT has been compiled with 'MRPT_BUILD_DUO3D'=OFF, so this class "
324 m_duo =
new DUOInstance[1];
332 "MRPT has been compiled with 'MRPT_BUILD_DUO3D'=OFF, so this class "
365 cout <<
"[CDUO3DCamera] Warning: Some of the intrinsic params "
366 "could not be read (size=0). Check file content."
369 cout <<
"[CDUO3DCamera] Warning: Intrinsic params filename is not "
370 "consistent with image size. Are you using the correct "
371 "calibration?. All params set to zero."
377 cout <<
"[CDUO3DCamera] Warning: Some of the extrinsic params "
378 "could not be read (size!=3x3). Check file content."
381 cout <<
"[CDUO3DCamera] Warning: Extrinsic params filename is not "
382 "consistent with image size. Are you using the correct "
383 "calibration?. All params set to zero."
393 cout <<
"[CDUO3DCamera] Warning: Rectification map could "
394 "not be read (size==0). Check file content."
397 cout <<
"[CDUO3DCamera] Warning: Rectification map "
398 "filename is not consistent with image size. Are "
399 "you using the correct calibration?. Rectification "
410 vector<int16_t> v_left_x(area), v_right_x(area);
411 vector<uint16_t> v_left_y(area), v_right_y(area);
413 for (
size_t k = 0; k < area; ++k)
435 cout <<
"[CDUO3DCamera] Warning: Calibration information is "
436 "set to be read from a file, but the file was not "
437 "specified. Unrectified images will be grabbed."
449 int binning = DUO_BIN_NONE;
452 binning += DUO_BIN_VERTICAL4;
454 binning += DUO_BIN_VERTICAL2;
457 DUOResolutionInfo ri;
458 if (!EnumerateResolutions(
460 binning, this->m_options.m_fps))
467 char name[260], version[260];
470 cout <<
"[CDUO3DCamera::open] DUO3DCamera name: " <<
name <<
" (v"
471 << version <<
")" << endl;
484 if (!StartDUO(
M_DUO_VALUE, DUOCallback,
reinterpret_cast<void*
>(
this)))
486 "[CDUO3DCamera] Error: Camera could not be started.")
497 CObservationIMU& outObservation_imu,
bool& there_is_img,
bool& there_is_imu)
500 there_is_img =
false;
501 there_is_imu =
false;
515 (
unsigned char*)
reinterpret_cast<PDUOFrame
>(
m_pframe_data)->leftData);
519 (
unsigned char*)
reinterpret_cast<PDUOFrame
>(
m_pframe_data)->rightData);
528 if (!
reinterpret_cast<PDUOFrame
>(
m_pframe_data)->accelerometerPresent)
530 cout <<
"[CDUO3DCamera] Warning: This device does not provide IMU "
531 "data. No IMU observations will be created."
538 for (
size_t k = 0; k < 3; ++k)
546 for (
size_t k = 0; k < 3; ++k)
574 if (WaitForSingleObject(
m_evFrame, 1000) == WAIT_OBJECT_0)
613 std::cout <<
"DUO3D Camera library version: " << version << std::endl;
void setStereoCameraParams(const mrpt::img::TStereoCamera &in_params)
Sets leftCamera, rightCamera and rightCameraPose from a TStereoCamera structure.
std::string m_intrinsic_filename
Intrinsic parameters file provided by DUO3D Calibration App (YML format).
mrpt::img::TStereoCamera m_stereo_camera
cv::Mat m_rectify_map_left_x
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates)
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
std::string m_extrinsic_filename
Extrinsic parameters file provided by DUO3D Calibration App (YML format).
@ yrr_NAME_NON_CONSISTENT
void m_set_exposure(float value)
Sets DUO3D camera Exposure setting.
unsigned __int16 uint16_t
This "software driver" implements the communication protocol for interfacing a DUO3D Stereo Camera.
float m_fps
(Default = 30) Frames per second <= 30.
void setDataFrame(void *frame)
frame is a reinterpreted PDUOFrame
void close()
Stop capture and closes the opened camera, if any.
void setDistortionParamsFromValues(double k1, double k2, double p1, double p2, double k3=0)
Set the vector of distortion params of the camera from the individual values of the distortion coeffi...
cv::Mat m_rectify_map_right_y
mrpt::math::TPose3DQuat asTPose() const
uint32_t ncols
Camera resolution.
GLsizei GLsizei GLuint * obj
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
TCaptureOptions_DUO3D m_options
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Contains classes for various device interfaces.
void * m_pframe_data
Pointer, to be reinterpreted as "PDUOFrame".
std::string m_rectify_map_filename
Rectification map file provided by DUO3D Calibration App (YML format).
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
int m_img_height
(Default = 480) Height of the captured image.
Options used when creating a camera capture object of type CImageGrabber_FlyCapture2.
void * m_duo
Opaque pointer to DUO's DUOInstance.
#define THROW_EXCEPTION(msg)
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,...
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void loadOptionsFrom(const mrpt::config::CConfigFileBase &configSource, const std::string §ionName, const std::string &prefix=std::string())
Loads all the options from a config file.
mrpt::img::CImage imageRight
Image from the right camera, only contains a valid image if hasImageRight == true.
This namespace contains representation of robot actions and observations.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
GLuint const GLchar * name
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
TYMLReadResult m_camera_ext_params_from_yml(const std::string &_file_name=std::string())
void loadFromMemoryBuffer(unsigned int width, unsigned int height, bool color, unsigned char *rawpixels, bool swapRedBlue=false)
Reads the image from raw pixels buffer in memory.
bool m_capture_imu
(Default = false) Capture IMU data.
mrpt::img::CImage imageLeft
Image from the left camera (this image will be ALWAYS present)
void loadFromConfigFile(const std::string §ion, const mrpt::config::CConfigFileBase &cfg)
Load all the params from a config source, in the same format that used in saveToConfigFile().
int m_img_width
(Default = 640) Width of the captured image.
Structure to hold the parameters of a pinhole stereo camera model.
This class allows loading and storing values and vectors of different types from a configuration text...
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::math::TPose3DQuat rightCameraPose
Pose of the right camera with respect to the coordinate origin of the left camera.
float m_led
(Default = 25) Led intensity (some device models).
void m_set_gain(float value)
Sets DUO3D camera Gain setting
cv::Mat m_rectify_map_right_x
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
TYMLReadResult m_camera_int_params_from_yml(const std::string &_file_name=std::string())
void setIntrinsicParamsFromValues(double fx, double fy, double cx, double cy)
Set the matrix of intrinsic params of the camera from the individual values of focal length and princ...
bool queryVersion(std::string version, bool printOutVersion=false)
Queries the DUO3D Camera firmware version.
std::vector< bool > dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
float m_gain
(Default = 10) Camera gain.
float m_exposure
(Default = 50) Exposure value.
void setFromCamParams(const mrpt::img::TStereoCamera ¶ms)
Prepares the mapping from the intrinsic, distortion and relative pose parameters of a stereo camera.
std::array< double, 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
Lightweight 3D pose (three spatial coordinates, plus a quaternion ).
virtual ~CDUO3DCamera()
Destructor
void rectify(const mrpt::img::CImage &in_left_image, const mrpt::img::CImage &in_right_image, mrpt::img::CImage &out_left_image, mrpt::img::CImage &out_right_image) const
Rectify the input image pair and save the result in a different output images - setFromCamParams() mu...
TYMLReadResult m_rectify_map_from_yml(const std::string &_file_name=std::string())
GLsizei const GLfloat * value
bool m_calibration_from_file
(Default = true) Get calibration information from files provided by DUO3D Calibration App.
std::string extractFileName(const std::string &filePath)
Extract just the name (without extension) of a filename from a complete path plus name plus extension...
This base provides a set of functions for maths stuff.
void m_set_led(float value)
Sets DUO3D camera LED setting
void * m_get_duo_frame()
Gets a stereo frame from the DUO3D Camera (void* to be reinterpreted as PDUOFrame)
EIGEN_STRONG_INLINE bool empty() const
GLsizei const GLchar ** string
void startCapture()
Start the actual data capture of the camera.
CDUO3DCamera()
Default Constructor (does not open the camera)
TCamera leftCamera
Intrinsic and distortion parameters of the left and right cameras.
std::map< const mrpt::hwdrivers::TCaptureOptions_DUO3D *, TDUOParams > duo_params
bool m_capture_rectified
(Default = true) Rectify images.
void open(const TCaptureOptions_DUO3D &options, const bool startCapture=true)
Tries to open the camera with the given options, and starts capturing.
void * m_evFrame
DUO's HANDLE.
void getObservations(mrpt::obs::CObservationStereoImages &outObservation_img, mrpt::obs::CObservationIMU &outObservation_imu, bool &there_is_img, bool &there_is_imu)
Specific laser scanner "software drivers" must process here new data from the I/O stream,...
cv::Mat m_rectify_map_left_y
Observation class for either a pair of left+right or left+disparity images from a stereo camera.
mrpt::vision::CStereoRectifyMap m_rectify_map
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at mié 12 jul 2023 10:03:34 CEST | |