#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. | |
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). |
Currently this can be determined from visual odometry for full 6D, or from wheel encoders for 2D movements only.
Definition at line 44 of file CActionRobotMovement3D.h.
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
Definition at line 52 of file CActionRobotMovement3D.h.
mrpt::slam::CActionRobotMovement3D::CActionRobotMovement3D | ( | ) |
Constructor.
virtual mrpt::slam::CActionRobotMovement3D::~CActionRobotMovement3D | ( | ) | [virtual] |
Destructor.
This fields indicates the way this estimation was obtained.
Definition at line 72 of file CActionRobotMovement3D.h.
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries.
Definition at line 76 of file CActionRobotMovement3D.h.
The 3D pose change probabilistic estimation.
Definition at line 68 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 80 of file CActionRobotMovement3D.h.
Page generated by Doxygen 1.5.7.1 for MRPT 0.6.5 SVN: at Mon Feb 23 13:35:09 EST 2009 |