Main MRPT website > C++ reference for MRPT 1.9.9
CActionRobotMovement3D.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-2018, 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 CActionRobotMovement3D_H
10 #define CActionRobotMovement3D_H
11 
12 #include <mrpt/obs/CAction.h>
14 
15 namespace mrpt
16 {
17 namespace obs
18 {
19 /** Represents a probabilistic 3D (6D) movement.
20 * Currently this can be determined from visual odometry for full 6D, or from
21 * wheel encoders for 2D movements only.
22 * Here implemented the motion model from the next article: A. L. Ballardini, A.
23 * Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective 6DoF
24 * motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on Planning,
25 * Perception and Navigation for Intelligent Vehicles, IROS, 2012
26 * \ingroup mrpt_obs_grp
27 * \sa CAction
28 */
30 {
32 
33  public:
34  /** A list of posible ways for estimating the content of a
35  * CActionRobotMovement3D object.
36  */
38  {
41  };
42 
44 
45  /** The 3D pose change probabilistic estimation. It can be converted to/from
46  * these alternative classes:
47  * - mrpt::poses::CPose3DQuatPDFGaussian
48  */
50 
51  /** This is the raw odometry reading, and only is used when
52  * "estimationMethod" is "TEstimationMethod::emOdometry" */
54  /** This fields indicates the way this estimation was obtained.
55  */
57 
59  {
62  };
63 
64  /** The parameter to be passed to "computeFromOdometry". */
66  {
67  /** Default values loader. */
69 
70  /** The model to be used. */
72 
74  {
75  /** Options for the 6DOFModel model which generates a
76  * CPosePDFParticles object an then create from that
77  * CPosePDFGaussian object in poseChange */
79  float a1, a2, a3, a4, a5, a6, a7, a8, a9, a10;
80  /** An additional noise added to the 6DOF model (std. dev. in meters
81  * and radians). */
83  } mm6DOFModel;
84 
86 
87  /** Computes the PDF of the pose increment from an odometry reading and
88  * according to the given motion model (speed and encoder ticks information
89  * is not modified).
90  * According to the parameters in the passed struct, it will be called one
91  * the private sampling functions (see "see also" next).
92  * \sa computeFromOdometry_model6DOF
93  */
95  const mrpt::poses::CPose3D& odometryIncrement,
96  const TMotionModelOptions& options);
97  /** Computes the PDF of the pose increment from an odometry reading, using
98  * the motion model for 6 DOF.
99  * The source: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F.
100  * Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte
101  * Carlo Localization 4th Workshop on Planning, Perception and Navigation
102  * for Intelligent Vehicles, IROS, 2012
103  * \sa computeFromOdometry
104  */
106  const mrpt::poses::CPose3D& odometryIncrement,
107  const TMotionModelOptions& o);
108 
109  /** Each "true" entry means that the corresponding "velocities" element
110  * contains valid data - There are 6 entries.
111  */
112  std::vector<bool> hasVelocities;
113 
114  /** The velocity of the robot in each of 6D:
115  * v_x,v_y,v_z,v_yaw,v_pitch,v_roll (linear in meters/sec and angular in
116  * rad/sec).
117  */
119 
120 }; // End of class def.
121 
122 } // End of namespace
123 } // End of namespace
124 
125 #endif
struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::TOptions_6DOFModel mm6DOFModel
mrpt::poses::CPose3DPDFGaussian poseChange
The 3D pose change probabilistic estimation.
std::vector< bool > hasVelocities
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6...
void computeFromOdometry_model6DOF(const mrpt::poses::CPose3D &odometryIncrement, const TMotionModelOptions &o)
Computes the PDF of the pose increment from an odometry reading, using the motion model for 6 DOF...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:44
struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motionModelConfiguration
float additional_std_XYZ
An additional noise added to the 6DOF model (std.
void computeFromOdometry(const mrpt::poses::CPose3D &odometryIncrement, const TMotionModelOptions &options)
Computes the PDF of the pose increment from an odometry reading and according to the given motion mod...
TEstimationMethod estimationMethod
This fields indicates the way this estimation was obtained.
The parameter to be passed to "computeFromOdometry".
Represents a probabilistic 3D (6D) movement.
uint32_t nParticlesCount
Options for the 6DOFModel model which generates a CPosePDFParticles object an then create from that C...
TEstimationMethod
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
Declares a class for storing a robot action.
Definition: CAction.h:27
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...
TDrawSampleMotionModel modelSelection
The model to be used.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
mrpt::math::CVectorFloat velocities
The velocity of the robot in each of 6D: v_x,v_y,v_z,v_yaw,v_pitch,v_roll (linear in meters/sec and a...
mrpt::poses::CPose3D rawOdometryIncrementReading
This is the raw odometry reading, and only is used when "estimationMethod" is "TEstimationMethod::emO...
unsigned __int32 uint32_t
Definition: rptypes.h:47



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at lun oct 28 00:14:14 CET 2019