Class CVehicleVelCmd
Defined in File CVehicleVelCmd.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Types
public mrpt::serialization::CSerializablepublic mrpt::Stringifyable
Derived Types
public mrpt::kinematics::CVehicleVelCmd_DiffDriven(Class CVehicleVelCmd_DiffDriven)public mrpt::kinematics::CVehicleVelCmd_Holo(Class CVehicleVelCmd_Holo)
Class Documentation
-
class CVehicleVelCmd : public mrpt::serialization::CSerializable, public mrpt::Stringifyable
Virtual base for velocity commands of different kinematic models of planar mobile robot.
Subclassed by mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo
Public Functions
-
CVehicleVelCmd()
-
CVehicleVelCmd(const CVehicleVelCmd &other)
-
~CVehicleVelCmd() override
-
CVehicleVelCmd &operator=(const CVehicleVelCmd &other)
-
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
-
virtual void setToStop() = 0
Set to a command that means “do not move” / “stop”.
See also
-
virtual std::string asString() const override
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 – [in] A scale within [0,1] reflecting how much should be the raw velocity command be lessen (e.g. for safety reasons,…).
out_vel_cmd – [out] 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 ¶ms) = 0
Updates this command, computing a blended version of
beta(within [0,1]) ofvel_cmdand1-betaofprev_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.
-
struct TVelCmdParams
Parameters that may be used by cmdVel_limits() in any derived classes.
Public Functions
-
TVelCmdParams()
-
void loadConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string §ion)
Load any parameter required by a CVehicleVelCmd derived class.
-
void saveToConfigFile(mrpt::config::CConfigFileBase &c, const std::string &s) const
Public Members
-
double robotMax_V_mps = {-1.}
Max. linear speed (m/s) [Default=-1 (not set), will raise exception if needed and not set]
-
double robotMax_W_radps = {-1.}
Max. angular speed (rad/s) [Default=-1 (not set), will raise exception if needed and not set]
-
double robotMinCurvRadius = {-1.}
Min. radius of curvature of paths (m) [Default=-1 (not set), will raise exception if needed and not set]
-
TVelCmdParams()
-
CVehicleVelCmd()