Class CActionRobotMovement3D

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class CActionRobotMovement3D : public mrpt::obs::CAction

Represents a probabilistic motion increment in SE(3).

Odometry increments might be determined from visual odometry for full 3D, or from wheel encoders for 2D movements only.

The implemented model for creating a SE(3) Gaussian from an odometry increment is based on ballardini2012effective

Public Types

enum TEstimationMethod

A list of possible ways for estimating the content of a CActionRobotMovement3D object.

Values:

enumerator emOdometry
enumerator emVisualOdometry
enum TDrawSampleMotionModel

Values:

enumerator mmGaussian
enumerator mm6DOF

Public Functions

CActionRobotMovement3D() = default
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).

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.

Based on: ballardini2012effective

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

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

Note

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

Public Members

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

struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motionModelConfiguration
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).

struct TMotionModelOptions

The parameter to be passed to “computeFromOdometry”. See: ballardini2012effective

Public Functions

TMotionModelOptions() = default

Public Members

TDrawSampleMotionModel modelSelection = {mm6DOF}

The model to be used.

TOptions_6DOFModel mm6DOFModel
struct TOptions_6DOFModel

Public Members

uint32_t nParticlesCount = {300}

Options for the 6DOFModel model which generates a CPosePDFParticles object an then create from that CPosePDFGaussian object in poseChange

float a1 = {0}
float a2 = {0}
float a3 = {0}
float a4 = {0}
float a5 = {0}
float a6 = {0}
float a7 = {0}
float a8 = {0}
float a9 = {0}
float a10 = {0}
float additional_std_XYZ = {0.001f}

An additional noise added to the 6DOF model (std. dev. in meters and radians).

float additional_std_angle = {mrpt::DEG2RAD(0.05f)}