Main MRPT website > C++ reference for MRPT 1.5.9
obs/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-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 CActionRobotMovement3D_H
10 #define CActionRobotMovement3D_H
11 
12 #include <mrpt/obs/CAction.h>
14 
15 namespace mrpt
16 {
17 namespace obs
18 {
19  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CActionRobotMovement3D, CAction, OBS_IMPEXP )
20 
21  /** Represents a probabilistic 3D (6D) movement.
22  * Currently this can be determined from visual odometry for full 6D, or from wheel encoders for 2D movements only.
23  * Here implemented the motion model from the next article: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on Planning, Perception and Navigation for Intelligent Vehicles, IROS, 2012
24  * \ingroup mrpt_obs_grp
25  * \sa CAction
26  */
28  {
29  // This must be added to any CSerializable derived class:
31 
32  public:
33  /** A list of posible ways for estimating the content of a CActionRobotMovement3D object.
34  */
36  {
37  emOdometry = 0,
38  emVisualOdometry
39  };
40 
42 
43  /** The 3D pose change probabilistic estimation. It can be converted to/from these alternative classes:
44  * - mrpt::poses::CPose3DQuatPDFGaussian
45  */
47 
48  /** This is the raw odometry reading, and only is used when "estimationMethod" is "TEstimationMethod::emOdometry" */
50  /** This fields indicates the way this estimation was obtained.
51  */
53 
55  {
56  mmGaussian = 0,
57  mm6DOF
58  };
59 
60 
61  /** The parameter to be passed to "computeFromOdometry". */
63  {
64  TMotionModelOptions(); //!< Default values loader.
65 
66  TDrawSampleMotionModel modelSelection; //!< The model to be used.
67 
68 
70  {
71 
72  /** Options for the 6DOFModel model which generates a CPosePDFParticles object an then create from that CPosePDFGaussian object in poseChange */
74  float a1,a2,a3,a4,a5,a6,a7,a8,a9,a10;
75  /** An additional noise added to the 6DOF model (std. dev. in meters and radians). */
76  float additional_std_XYZ, additional_std_angle;
77  }mm6DOFModel;
78 
79  } motionModelConfiguration;
80 
81  /** 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).
82  * According to the parameters in the passed struct, it will be called one the private sampling functions (see "see also" next).
83  * \sa computeFromOdometry_model6DOF
84  */
85  void computeFromOdometry(
86  const mrpt::poses::CPose3D &odometryIncrement,
87  const TMotionModelOptions &options);
88  /** Computes the PDF of the pose increment from an odometry reading, using the motion model for 6 DOF.
89  * The source: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on Planning, Perception and Navigation for Intelligent Vehicles, IROS, 2012
90  * \sa computeFromOdometry
91  */
92  void computeFromOdometry_model6DOF(
93  const mrpt::poses::CPose3D &odometryIncrement,
94  const TMotionModelOptions &o
95  ) ;
96 
97 
98  /** Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries.
99  */
101 
102  /** 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 angular in rad/sec).
103  */
105 
106  }; // End of class def.
108 
109 
110  } // End of namespace
111 } // End of namespace
112 
113 #endif
mrpt::poses::CPose3DPDFGaussian poseChange
The 3D pose change probabilistic estimation.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:35
float additional_std_XYZ
An additional noise added to the 6DOF model (std.
std::vector< bool > vector_bool
A type for passing a vector of bools.
Definition: types_simple.h:29
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...
#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...
TEstimationMethod
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
Declares a class for storing a robot action.
Definition: obs/CAction.h:33
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...
vector_bool hasVelocities
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6...
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:72
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:49
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)



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