Main MRPT website > C++ reference
MRPT logo
CObservationStereoImagesFeatures.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef CObservationStereoImagesFeatures_H
10 #define CObservationStereoImagesFeatures_H
11 
13 #include <mrpt/utils/CImage.h>
14 #include <mrpt/utils/TCamera.h>
15 #include <mrpt/slam/CObservation.h>
16 #include <mrpt/poses/CPose3D.h>
17 #include <mrpt/poses/CPose3DQuat.h>
18 #include <mrpt/poses/CPose2D.h>
19 
20 namespace mrpt
21 {
22 namespace slam
23 {
24  using namespace mrpt::utils;
25  using namespace mrpt::slam;
26  using namespace mrpt::math;
27 
29  {
30  std::pair<TPixelCoordf,TPixelCoordf> pixels;
31  unsigned int ID;
32  };
33 
35  /** Declares a class derived from "CObservation" that encapsules a pair of cameras and a set of matched image features extracted from them.
36  *
37  <b>NOTE:</b> The image features stored in this class are NOT supposed to be UNDISTORTED, but the TCamera members must provide their distortion params.
38  A zero-vector of distortion params means a set of UNDISTORTED pixels.<br>
39  * \sa CObservation
40  * \ingroup mrpt_obs_grp
41  */
43  {
44  // This must be added to any CSerializable derived class:
46 
47  public:
48  /** Default Constructor.
49  */
51 
52  /** Other constructor providing members initialization.
53  */
54  CObservationStereoImagesFeatures(
55  const CMatrixDouble33 &iPLeft /*left intrinsic params*/, const CMatrixDouble33 &iPRight /*right intrinsic params*/,
56  const CArrayDouble<5> &dPLeft /*left distortion params*/, const CArrayDouble<5> &dPRight /*right distortion params*/,
57  const CPose3DQuat &rCPose /*rightCameraPose*/, const CPose3DQuat &cPORobot /*cameraPoseOnRobot*/ );
58 
59  /** Other constructor providing members initialization.
60  */
61  CObservationStereoImagesFeatures(
62  const TCamera &cLeft /*left camera*/, const TCamera &cRight /*right camera*/,
63  const CPose3DQuat &rCPose /*rightCameraPose*/, const CPose3DQuat &cPORobot /*cameraPoseOnRobot*/ );
64 
65  /** Destructor
66  */
67  ~CObservationStereoImagesFeatures( );
68 
69  /** A method for storing the set of observed features in a text file in the format: <br>
70  * ID ul vl ur vr <br>
71  * being (ul,vl) and (ur,vr) the "x" and "y" coordinates for the left and right feature, respectively.
72  */
73  void saveFeaturesToTextFile( const std::string &filename );
74 
75  // ------------------
76  // Class Members
77  // ------------------
78  TCamera cameraLeft, cameraRight;
79 
80  /** The pose of the right camera, relative to the left one:
81  * Note that for the Bumblebee stereo camera and using the conventional reference coordinates for the left
82  * camera ("x" points to the right, "y" down), the "right" camera is situated
83  * at position (BL, 0, 0) with q = [1 0 0 0], where BL is the BASELINE.
84  */
85  CPose3DQuat rightCameraPose;
86 
87  /** The pose of the LEFT camera, relative to the robot.
88  */
89  CPose3DQuat cameraPoseOnRobot;
90 
91  /** Vectors of image feature pairs (with ID).
92  */
93  std::vector<TStereoImageFeatures> theFeatures;
94 
95  /** A general method to retrieve the sensor pose on the robot in CPose3D form.
96  * Note that most sensors will return a full (6D) CPose3DQuat, but see the derived classes for more details or special cases.
97  * \sa setSensorPose
98  */
99  inline void getSensorPose( CPose3D &out_sensorPose ) const { out_sensorPose = CPose3D(cameraPoseOnRobot); }
100 
101  /** A general method to retrieve the sensor pose on the robot in CPose3DQuat form.
102  * Note that most sensors will return a full (6D) CPose3DQuat, but see the derived classes for more details or special cases.
103  * \sa setSensorPose
104  */
105  inline void getSensorPose( CPose3DQuat &out_sensorPose ) const { out_sensorPose = cameraPoseOnRobot; }
106 
107  /** A general method to change the sensor pose on the robot in a CPose3D form.
108  * Note that most sensors will use the full (6D) CPose3DQuat, but see the derived classes for more details or special cases.
109  * \sa getSensorPose
110  */
111  inline void setSensorPose( const CPose3D &newSensorPose ) { cameraPoseOnRobot = CPose3DQuat(newSensorPose); }
112 
113  /** A general method to change the sensor pose on the robot in a CPose3DQuat form.
114  * Note that most sensors will use the full (6D) CPose3DQuat, but see the derived classes for more details or special cases.
115  * \sa getSensorPose
116  */
117  inline void setSensorPose( const CPose3DQuat &newSensorPose ) { cameraPoseOnRobot = newSensorPose; }
118  }; // End of class def.
120 
121  } // End of namespace
122 } // End of namespace
123 
124 #endif
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Definition: zip.h:16
void setSensorPose(const CPose3D &newSensorPose)
A general method to change the sensor pose on the robot in a CPose3D form.
void setSensorPose(const CPose3DQuat &newSensorPose)
A general method to change the sensor pose on the robot in a CPose3DQuat form.
STL namespace.
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
Declares a class derived from "CObservation" that encapsules a pair of cameras and a set of matched i...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArray.h:18
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
Declares a class that represents any robot's observation.
Definition: CObservation.h:52
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:41
class BASE_IMPEXP CPose3DQuat
Definition: CPose3D.h:20
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
void getSensorPose(CPose3DQuat &out_sensorPose) const
A general method to retrieve the sensor pose on the robot in CPose3DQuat form.
A partial specialization of CArrayNumeric for double numbers.
Definition: CArrayNumeric.h:74
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
std::pair< TPixelCoordf, TPixelCoordf > pixels
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:31



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014