class mrpt::obs::CActionRobotMovement3D

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. Here implemented the motion model from the next article: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on Planning, Perception and Navigation for Intelligent Vehicles, IROS, 2012

See also:

CAction

#include <mrpt/obs/CActionRobotMovement3D.h>

class CActionRobotMovement3D: public mrpt::obs::CAction
{
public:
    // enums

    enum TDrawSampleMotionModel;
    enum TEstimationMethod;

    // structs

    struct TMotionModelOptions;

    //
fields

    mrpt::poses::CPose3DPDFGaussian poseChange {};
    mrpt::poses::CPose3D rawOdometryIncrementReading {};
    TEstimationMethod estimationMethod {emOdometry};
    struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motionModelConfiguration;
    std::vector<bool> hasVelocities {false, false, false, false, false, false};
    mrpt::math::CVectorFloat velocities {6};

    // construction

    CActionRobotMovement3D();

    //
methods

    void computeFromOdometry(const mrpt::poses::CPose3D& odometryIncrement, const TMotionModelOptions& options);
    void computeFromOdometry_model6DOF(const mrpt::poses::CPose3D& odometryIncrement, const TMotionModelOptions& o);
    virtual void getDescriptionAsText(std::ostream& o) const;
};

Inherited Members

public:
    //
fields

    mrpt::system::TTimeStamp timestamp {INVALID_TIMESTAMP};

    //
methods

    virtual void getDescriptionAsText(std::ostream& o) const;
    std::string getDescriptionAsTextValue() const;

Fields

mrpt::poses::CPose3DPDFGaussian poseChange {}

The 3D pose change probabilistic estimation.

It can be converted to/from these alternative classes:

mrpt::poses::CPose3D rawOdometryIncrementReading {}

This is the raw odometry reading, and only is used when “estimationMethod” is “TEstimationMethod::emOdometry”.

TEstimationMethod estimationMethod {emOdometry}

This fields indicates the way this estimation was obtained.

std::vector<bool> hasVelocities {false, false, false, false, false, false}

Each “true” entry means that the corresponding “velocities” element contains valid data - There are 6 entries.

mrpt::math::CVectorFloat velocities {6}

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).

Methods

void computeFromOdometry(const mrpt::poses::CPose3D& odometryIncrement, const TMotionModelOptions& options)

Computes the PDF of the pose increment from an odometry reading and according to the given motion model (speed and encoder ticks information is not modified).

According to the parameters in the passed struct, it will be called one the private sampling functions (see “see also” next).

See also:

computeFromOdometry_model6DOF

void computeFromOdometry_model6DOF(const mrpt::poses::CPose3D& odometryIncrement, const TMotionModelOptions& o)

Computes the PDF of the pose increment from an odometry reading, using the motion model for 6 DOF.

The source: A. L. Ballardini, A. Furlan, A. Galbiati, M. Matteucci, F. Sacchi, D. G. Sorrenti An effective 6DoF motion model for 3D-6DoF Monte Carlo Localization 4th Workshop on Planning, Perception and Navigation for Intelligent Vehicles, IROS, 2012

See also:

computeFromOdometry

virtual void getDescriptionAsText(std::ostream& o) const

Build a detailed, multi-line textual description of the action contents and dump it to the output stream.

If overried by derived classes, call base CAction::getDescriptionAsText() first to show common information.