9 #ifndef CActionRobotMovement3D_H
10 #define CActionRobotMovement3D_H
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
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.
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.
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_)