Represents a probabilistic 3D (6D) movement.
Currently this can be determined from visual odometry for full 6D, or from wheel encoders for 2D movements only.
Definition at line 46 of file CActionRobotMovement3D.h.
#include <mrpt/slam/CActionRobotMovement3D.h>
Public Types | |
enum | TEstimationMethod { emOdometry = 0, emVisualOdometry } |
A list of posible ways for estimating the content of a CActionRobotMovement3D object. More... | |
Public Member Functions | |
CActionRobotMovement3D () | |
Constructor. | |
virtual | ~CActionRobotMovement3D () |
Destructor. | |
Public Attributes | |
poses::CPose3DPDFGaussian | poseChange |
The 3D pose change probabilistic estimation. | |
poses::CPose3DQuatPDFGaussian | poseChangeQuat |
TEstimationMethod | estimationMethod |
This fields indicates the way this estimation was obtained. | |
vector_bool | hasVelocities |
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries. | |
vector_float | 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 angular in rad/sec). | |
RTTI stuff | |
typedef CActionRobotMovement3DPtr | SmartPtr |
static mrpt::utils::CLASSINIT | _init_CActionRobotMovement3D |
static mrpt::utils::TRuntimeClassId | classCActionRobotMovement3D |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. | |
static mrpt::utils::CObject * | CreateObject () |
static CActionRobotMovement3DPtr | Create () |
A typedef for the associated smart pointer
Definition at line 49 of file CActionRobotMovement3D.h.
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
Definition at line 54 of file CActionRobotMovement3D.h.
mrpt::slam::CActionRobotMovement3D::CActionRobotMovement3D | ( | ) |
Constructor.
virtual mrpt::slam::CActionRobotMovement3D::~CActionRobotMovement3D | ( | ) | [virtual] |
Destructor.
static const mrpt::utils::TRuntimeClassId* mrpt::slam::CActionRobotMovement3D::_GetBaseClass | ( | ) | [static, protected] |
Reimplemented from mrpt::slam::CAction.
static CActionRobotMovement3DPtr mrpt::slam::CActionRobotMovement3D::Create | ( | ) | [static] |
static mrpt::utils::CObject* mrpt::slam::CActionRobotMovement3D::CreateObject | ( | ) | [static] |
virtual mrpt::utils::CObject* mrpt::slam::CActionRobotMovement3D::duplicate | ( | ) | const [virtual] |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
virtual const mrpt::utils::TRuntimeClassId* mrpt::slam::CActionRobotMovement3D::GetRuntimeClass | ( | ) | const [virtual] |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::slam::CAction.
mrpt::utils::CLASSINIT mrpt::slam::CActionRobotMovement3D::_init_CActionRobotMovement3D [static, protected] |
Definition at line 49 of file CActionRobotMovement3D.h.
mrpt::utils::TRuntimeClassId mrpt::slam::CActionRobotMovement3D::classCActionRobotMovement3D [static] |
Definition at line 49 of file CActionRobotMovement3D.h.
Definition at line 49 of file CActionRobotMovement3D.h.
This fields indicates the way this estimation was obtained.
Definition at line 76 of file CActionRobotMovement3D.h.
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries.
Definition at line 80 of file CActionRobotMovement3D.h.
The 3D pose change probabilistic estimation.
Definition at line 70 of file CActionRobotMovement3D.h.
Definition at line 71 of file CActionRobotMovement3D.h.
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).
Definition at line 84 of file CActionRobotMovement3D.h.
Page generated by Doxygen 1.7.2 for MRPT 0.9.4 SVN: at Mon Jan 10 22:46:17 UTC 2011 |