Main MRPT website > C++ reference for MRPT 1.5.9
obs/CActionRobotMovement2D.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-2017, 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 CActionRobotMovement2D_H
10 #define CActionRobotMovement2D_H
11 
12 #include <mrpt/obs/CAction.h>
13 #include <mrpt/poses/CPose2D.h>
14 #include <mrpt/poses/CPosePDF.h>
17 
18 namespace mrpt
19 {
20  namespace obs
21  {
22  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CActionRobotMovement2D, CAction, OBS_IMPEXP )
23 
24  /** Represents a probabilistic 2D movement of the robot mobile base
25  *
26  * See the tutorial on <a href="http://www.mrpt.org/Probabilistic_Motion_Models" >probabilistic motion models</a>.
27  *
28  * \note [New in MRPT 1.5.0] Velocity is now encoded as mrpt::math::TTwist2D as a more general version of the old (linVel, angVel).
29  * \sa CAction
30  * \ingroup mrpt_obs_grp
31  */
33  {
34  // This must be added to any CSerializable derived class:
36 
37  public:
38  /** A list of posible ways for estimating the content of a CActionRobotMovement2D object.
39  */
41  {
42  emOdometry = 0,
43  emScan2DMatching
44  };
45 
46  CActionRobotMovement2D(); //!< Constructor
47 
48  mrpt::utils::poly_ptr_ptr<mrpt::poses::CPosePDFPtr> poseChange; //!< The 2D pose change probabilistic estimation.
49  /** This is the raw odometry reading, and only is used when "estimationMethod" is "TEstimationMethod::emOdometry" */
51  TEstimationMethod estimationMethod; //!< This fields indicates the way in which this estimation was obtained.
52 
53  bool hasEncodersInfo; //!< If "true" means that "encoderLeftTicks" and "encoderRightTicks" contain valid values.
54  /** For odometry only: the ticks count for each wheel FROM the last reading (positive means FORWARD, for both wheels);
55  * \sa hasEncodersInfo
56  */
57  int32_t encoderLeftTicks,encoderRightTicks;
58 
59  bool hasVelocities; //!< If "true" means that "velocityLin" and "velocityAng" contain valid values.
60  mrpt::math::TTwist2D velocityLocal; //!< If "hasVelocities"=true, the robot velocity in local (robot frame, +X forward) coordinates.
61 
62  double velocityLin() const { return velocityLocal.vx; }
63  double velocityAng() const { return velocityLocal.omega; }
64 
66  {
67  mmGaussian = 0,
68  mmThrun
69  };
70  /** The parameter to be passed to "computeFromOdometry". */
72  {
73  TMotionModelOptions(); //!< Default values loader.
74 
75  TDrawSampleMotionModel modelSelection; //!< The model to be used.
76 
77  /** Options for the gaussian model, which generates a CPosePDFGaussian object in poseChange
78  * See docs in : http://www.mrpt.org/tutorials/programming/odometry-and-motion-models/probabilistic_motion_models/
79  */
81  {
82  float a1,a2,a3,a4,minStdXY,minStdPHI;
83  } gaussianModel;
84 
85  /** Options for the Thrun's model, which generates a CPosePDFParticles object in poseChange
86  * See docs in : http://www.mrpt.org/tutorials/programming/odometry-and-motion-models/probabilistic_motion_models/
87  */
89  {
90  /** The default number of particles to generate in a internal representation (anyway you can draw as many samples as you want through CActionRobotMovement2D::drawSingleSample) */
96 
97  /** An additional noise added to the thrun model (std. dev. in meters and radians). */
98  float additional_std_XY, additional_std_phi;
99  } thrunModel;
100 
101  } motionModelConfiguration;
102 
103  /** Computes the PDF of the pose increment from an odometry reading and according to the given motion model (speed and encoder ticks information is not modified).
104  * According to the parameters in the passed struct, it will be called one the private sampling functions (see "see also" next).
105  * \sa computeFromOdometry_modelGaussian, computeFromOdometry_modelThrun
106  */
107  void computeFromOdometry(
108  const mrpt::poses::CPose2D &odometryIncrement,
109  const TMotionModelOptions &options);
110 
111  /** If "hasEncodersInfo"=true, this method updates the pose estimation according to the ticks from both encoders and the passed parameters, which is passed internally to the method "computeFromOdometry" with the last used PDF options (or the defualt ones if not explicitly called by the user).
112  *
113  * \param K_left The meters / tick ratio for the left encoder.
114  * \param K_right The meters / tick ratio for the right encoder.
115  * \param D The distance between both wheels, in meters.
116  */
117  void computeFromEncoders(
118  double K_left,
119  double K_right,
120  double D );
121 
122  /** Using this method instead of "poseChange->drawSingleSample()" may be more efficient in most situations.
123  * \sa CPosePDF::drawSingleSample
124  */
125  void drawSingleSample( mrpt::poses::CPose2D &outSample ) const;
126 
127  /** Call this before calling a high number of times "fastDrawSingleSample", which is much faster than "drawSingleSample"
128  */
129  void prepareFastDrawSingleSamples() const;
130 
131  /** Faster version than "drawSingleSample", but requires a previous call to "prepareFastDrawSingleSamples"
132  */
133  void fastDrawSingleSample( mrpt::poses::CPose2D &outSample ) const;
134 
135  protected:
136  /** Computes the PDF of the pose increment from an odometry reading, using a Gaussian approximation as the motion model.
137  * \sa computeFromOdometry
138  */
139  void computeFromOdometry_modelGaussian(
140  const mrpt::poses::CPose2D &odometryIncrement,
141  const TMotionModelOptions &o
142  );
143 
144  /** Computes the PDF of the pose increment from an odometry reading, using the motion model from Thrun's book.
145  * This model is discussed in "Probabilistic Robotics", Thrun, Burgard, and Fox, 2006, pp.136.
146  * \sa computeFromOdometry
147  */
148  void computeFromOdometry_modelThrun(
149  const mrpt::poses::CPose2D &odometryIncrement,
150  const TMotionModelOptions &o
151  );
152 
153  /** The sample generator for the model "computeFromOdometry_modelGaussian", internally called when the user invokes "drawSingleSample".
154  */
155  void drawSingleSample_modelGaussian( mrpt::poses::CPose2D &outSample ) const;
156 
157  /** The sample generator for the model "computeFromOdometry_modelThrun", internally called when the user invokes "drawSingleSample".
158  */
159  void drawSingleSample_modelThrun( mrpt::poses::CPose2D &outSample ) const;
160 
161  /** Internal use
162  */
163  void prepareFastDrawSingleSample_modelGaussian() const;
164 
165  /** Internal use
166  */
167  void prepareFastDrawSingleSample_modelThrun() const;
168 
169  /** Internal use
170  */
171  void fastDrawSingleSample_modelGaussian( mrpt::poses::CPose2D &outSample ) const;
172 
173  /** Internal use
174  */
175  void fastDrawSingleSample_modelThrun( mrpt::poses::CPose2D &outSample ) const;
176 
177  /** Auxiliary matrix
178  */
181 
182 
183  }; // End of class def.
185 
186 
187  } // End of namespace
188 } // End of namespace
189 
190 #endif
Options for the gaussian model, which generates a CPosePDFGaussian object in poseChange See docs in :...
mrpt::utils::poly_ptr_ptr< mrpt::poses::CPosePDFPtr > poseChange
The 2D pose change probabilistic estimation.
TEstimationMethod estimationMethod
This fields indicates the way in which this estimation was obtained.
The parameter to be passed to "computeFromOdometry".
2D twist: 2D velocity vector (vx,vy) + planar angular velocity (omega)
Represents a probabilistic 2D movement of the robot mobile base.
#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...
mrpt::math::CMatrixDouble33 m_fastDrawGauss_Z
Auxiliary matrix.
float additional_std_XY
An additional noise added to the thrun model (std.
mrpt::math::TTwist2D velocityLocal
If "hasVelocities"=true, the robot velocity in local (robot frame, +X forward) coordinates.
TEstimationMethod
A list of posible ways for estimating the content of a CActionRobotMovement2D object.
bool hasEncodersInfo
If "true" means that "encoderLeftTicks" and "encoderRightTicks" contain valid values.
TDrawSampleMotionModel modelSelection
The model to be used.
Options for the Thrun&#39;s model, which generates a CPosePDFParticles object in poseChange See docs in :...
Declares a class for storing a robot action.
Definition: obs/CAction.h:33
__int32 int32_t
Definition: rptypes.h:48
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 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:36
uint32_t nParticlesCount
The default number of particles to generate in a internal representation (anyway you can draw as many...
unsigned __int32 uint32_t
Definition: rptypes.h:49
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
double omega
Angular velocity (rad/s)
mrpt::poses::CPose2D rawOdometryIncrementReading
This is the raw odometry reading, and only is used when "estimationMethod" is "TEstimationMethod::emO...
bool hasVelocities
If "true" means that "velocityLin" and "velocityAng" contain valid values.



Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020