Main MRPT website > C++ reference for MRPT 1.3.2
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-2015, 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>
15 
16 namespace mrpt
17 {
18 namespace obs
19 {
20  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CActionRobotMovement3D, CAction, OBS_IMPEXP )
21 
22  /** Represents a probabilistic 3D (6D) movement.
23  * Currently this can be determined from visual odometry for full 6D, or from wheel encoders for 2D movements only.
24  *
25  * \ingroup mrpt_obs_grp
26  * \sa CAction
27  */
29  {
30  // This must be added to any CSerializable derived class:
32 
33  public:
34  /** A list of posible ways for estimating the content of a CActionRobotMovement3D object.
35  */
37  {
38  emOdometry = 0,
39  emVisualOdometry
40  };
41 
42  /** Constructor
43  */
45 
46  /** Destructor
47  */
48  virtual ~CActionRobotMovement3D();
49 
50  /** The 3D pose change probabilistic estimation.
51  */
54 
55 
56  /** This fields indicates the way this estimation was obtained.
57  */
59 
60  /** Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries.
61  */
63 
64  /** 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).
65  */
67 
68  }; // End of class def.
70 
71 
72  } // End of namespace
73 } // End of namespace
74 
75 #endif
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:35
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
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.
Represents a probabilistic 3D (6D) movement.
#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...
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...
poses::CPose3DQuatPDFGaussian poseChangeQuat
poses::CPose3DPDFGaussian poseChange
The 3D pose change probabilistic estimation.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)



Page generated by Doxygen 1.8.12 for MRPT 1.3.2 SVN: at Mon Oct 3 19:22:36 UTC 2016