MRPT  1.9.9
CActionRobotMovement3D.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/obs/CAction.h>
13 
14 namespace mrpt::obs
15 {
16 /** Represents a probabilistic 3D (6D) movement.
17  * Currently this can be determined from visual odometry for full 6D, or from
18  * wheel encoders for 2D movements only.
19  * Here implemented the motion model from the next article: A. L. Ballardini,
20  * A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective
21  * 6DoF motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on
22  * Planning, Perception and Navigation for Intelligent Vehicles, IROS, 2012
23  * \ingroup mrpt_obs_grp
24  * \sa CAction
25  */
27 {
29 
30  public:
31  /** A list of posible ways for estimating the content of a
32  * CActionRobotMovement3D object.
33  */
35  {
38  };
39 
40  CActionRobotMovement3D() = default;
41 
42  /** The 3D pose change probabilistic estimation. It can be converted to/from
43  * these alternative classes:
44  * - mrpt::poses::CPose3DQuatPDFGaussian
45  */
47 
48  /** This is the raw odometry reading, and only is used when
49  * "estimationMethod" is "TEstimationMethod::emOdometry" */
51 
52  /** This fields indicates the way this estimation was obtained */
54 
56  {
59  };
60 
61  /** The parameter to be passed to "computeFromOdometry".
62  * Based ont he motion model:
63  * A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D.
64  * G. Sorrenti, "An effective 6DoF motion model for 3D-6DoF Monte Carlo
65  * Localization", 4th Workshop on Planning, Perception and Navigation for
66  * Intelligent Vehicles, IROS, 2012
67  */
69  {
70  TMotionModelOptions() = default;
71 
72  /** The model to be used. */
74 
76  {
77  /** Options for the 6DOFModel model which generates a
78  * CPosePDFParticles object an then create from that
79  * CPosePDFGaussian object in poseChange */
80  uint32_t nParticlesCount{300};
81  float a1{0}, a2{0}, a3{0}, a4{0}, a5{0}, a6{0}, a7{0}, a8{0}, a9{0},
82  a10{0};
83 
84  /** An additional noise added to the 6DOF model (std. dev. in meters
85  * and radians). */
86  float additional_std_XYZ{0.001f},
88  };
89 
91 
93 
94  /** Computes the PDF of the pose increment from an odometry reading and
95  * according to the given motion model (speed and encoder ticks information
96  * is not modified).
97  * According to the parameters in the passed struct, it will be called one
98  * the private sampling functions (see "see also" next).
99  * \sa computeFromOdometry_model6DOF
100  */
101  void computeFromOdometry(
102  const mrpt::poses::CPose3D& odometryIncrement,
103  const TMotionModelOptions& options);
104  /** Computes the PDF of the pose increment from an odometry reading, using
105  * the motion model for 6 DOF.
106  * The source: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F.
107  * Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte
108  * Carlo Localization 4th Workshop on Planning, Perception and Navigation
109  * for Intelligent Vehicles, IROS, 2012
110  * \sa computeFromOdometry
111  */
113  const mrpt::poses::CPose3D& odometryIncrement,
114  const TMotionModelOptions& o);
115 
116  virtual void getDescriptionAsText(std::ostream& o) const override;
117 
118  /** Each "true" entry means that the corresponding "velocities" element
119  * contains valid data - There are 6 entries.
120  */
121  std::vector<bool> hasVelocities{false, false, false, false, false, false};
122 
123  /** The velocity of the robot in each of 6D:
124  * v_x,v_y,v_z,v_yaw,v_pitch,v_roll (linear in meters/sec and angular in
125  * rad/sec).
126  */
128 
129 }; // End of class def.
130 
131 } // namespace mrpt::obs
mrpt::poses::CPose3DPDFGaussian poseChange
The 3D pose change probabilistic estimation.
Template for column vectors of dynamic size, compatible with Eigen.
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...
struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motionModelConfiguration
float additional_std_XYZ
An additional noise added to the 6DOF model (std.
virtual void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the action contents and dump it to the output str...
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...
constexpr double DEG2RAD(const double x)
Degrees to radians.
TEstimationMethod
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
This namespace contains representation of robot actions and observations.
Declares a class for storing a robot action.
Definition: CAction.h:24
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:85
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...
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
mrpt::poses::CPose3D rawOdometryIncrementReading
This is the raw odometry reading, and only is used when "estimationMethod" is "TEstimationMethod::emO...



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020