class mrpt::kinematics::CVehicleVelCmd

Virtual base for velocity commands of different kinematic models of planar mobile robot.

#include <mrpt/kinematics/CVehicleVelCmd.h>

class CVehicleVelCmd: public mrpt::serialization::CSerializable
{
public:
    // structs

    struct TVelCmdParams;

    // construction

    CVehicleVelCmd();
    CVehicleVelCmd(const CVehicleVelCmd& other);

    //
methods

    CVehicleVelCmd& operator = (const CVehicleVelCmd& other);
    virtual size_t getVelCmdLength() const = 0;
    virtual std::string getVelCmdDescription(const int index) const = 0;
    virtual double getVelCmdElement(const int index) const = 0;
    virtual void setVelCmdElement(const int index, const double val) = 0;
    virtual bool isStopCmd() const = 0;
    virtual void setToStop() = 0;
    std::string asString() const;
    virtual void cmdVel_scale(double vel_scale) = 0;

    virtual double cmdVel_limits(
        const mrpt::kinematics::CVehicleVelCmd& prev_vel_cmd,
        const double beta,
        const TVelCmdParams& params
        ) = 0;
};

// direct descendants

class CVehicleVelCmd_DiffDriven;
class CVehicleVelCmd_Holo;

Methods

virtual size_t getVelCmdLength() const = 0

Get number of components in each velocity command.

virtual std::string getVelCmdDescription(const int index) const = 0

Get textual, human-readable description of each velocity command component.

virtual double getVelCmdElement(const int index) const = 0

Get each velocity command component.

virtual void setVelCmdElement(const int index, const double val) = 0

Set each velocity command component.

virtual bool isStopCmd() const = 0

Returns true if the command means “do not move” / “stop”.

See also:

setToStop

virtual void setToStop() = 0

Set to a command that means “do not move” / “stop”.

See also:

isStopCmd

std::string asString() const

Returns a human readable description of the cmd.

virtual void cmdVel_scale(double vel_scale) = 0

Scale the velocity command encoded in this object.

Parameters:

vel_scale

A scale within [0,1] reflecting how much should be the raw velocity command be lessen (e.g. for safety reasons,…).

out_vel_cmd

Users can directly inherit from existing implementations instead of manually redefining this method:

virtual double cmdVel_limits(
    const mrpt::kinematics::CVehicleVelCmd& prev_vel_cmd,
    const double beta,
    const TVelCmdParams& params
    ) = 0

Updates this command, computing a blended version of beta (within [0,1]) of vel_cmd and 1-beta of prev_vel_cmd, simultaneously to honoring any user-side maximum velocities.

Returns:

The [0,1] ratio that the cmdvel had to be scaled down, or 1.0 if none.