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 28 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. More... | |
virtual | ~CActionRobotMovement3D () |
Destructor. More... | |
mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
CObject * | clone () const |
Cloning interface for smart pointers. More... | |
Public Attributes | |
poses::CPose3DPDFGaussian | poseChange |
The 3D pose change probabilistic estimation. More... | |
poses::CPose3DQuatPDFGaussian | poseChangeQuat |
TEstimationMethod | estimationMethod |
This fields indicates the way this estimation was obtained. More... | |
vector_bool | hasVelocities |
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries. More... | |
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). More... | |
mrpt::system::TTimeStamp | timestamp |
The associated time-stamp. More... | |
Static Public Attributes | |
static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCAction |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
CSerializable virtual methods | |
void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
Introduces a pure virtual method responsible for writing to a CStream. More... | |
void | readFromStream (mrpt::utils::CStream &in, int version) |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
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. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
static CActionRobotMovement3DPtr | Create () |
A typedef for the associated smart pointer
Definition at line 31 of file CActionRobotMovement3D.h.
A list of posible ways for estimating the content of a CActionRobotMovement3D object.
Enumerator | |
---|---|
emOdometry | |
emVisualOdometry |
Definition at line 36 of file CActionRobotMovement3D.h.
mrpt::slam::CActionRobotMovement3D::CActionRobotMovement3D | ( | ) |
Constructor.
|
virtual |
Destructor.
|
staticprotected |
|
inlineinherited |
|
static |
|
static |
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
inlineinherited |
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::slam::CAction.
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
out | The output binary stream where object must be dumped. |
getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
|
staticprotected |
Definition at line 31 of file CActionRobotMovement3D.h.
|
staticinherited |
|
static |
Definition at line 31 of file CActionRobotMovement3D.h.
|
staticinherited |
|
staticinherited |
Definition at line 35 of file CSerializable.h.
|
static |
Definition at line 31 of file CActionRobotMovement3D.h.
TEstimationMethod mrpt::slam::CActionRobotMovement3D::estimationMethod |
This fields indicates the way this estimation was obtained.
Definition at line 58 of file CActionRobotMovement3D.h.
vector_bool mrpt::slam::CActionRobotMovement3D::hasVelocities |
Each "true" entry means that the corresponding "velocities" element contains valid data - There are 6 entries.
Definition at line 62 of file CActionRobotMovement3D.h.
poses::CPose3DPDFGaussian mrpt::slam::CActionRobotMovement3D::poseChange |
The 3D pose change probabilistic estimation.
Definition at line 52 of file CActionRobotMovement3D.h.
Referenced by mrpt::slam::PF_implementation< CPose2D, CMonteCarloLocalization2D >::PF_SLAM_implementation_gatherActionsCheckBothActObs(), and mrpt::slam::PF_implementation< CPose2D, CMonteCarloLocalization2D >::PF_SLAM_implementation_pfStandardProposal().
poses::CPose3DQuatPDFGaussian mrpt::slam::CActionRobotMovement3D::poseChangeQuat |
Definition at line 53 of file CActionRobotMovement3D.h.
|
inherited |
vector_float mrpt::slam::CActionRobotMovement3D::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).
Definition at line 66 of file CActionRobotMovement3D.h.
Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 | Hosted on: |