class mrpt::nav::CPTG_DiffDrive_alpha

The “a(symptotic)-alpha PTG”, as named in PTG papers.

  • Compatible kinematics : differential-driven / Ackermann steering

  • Compatible robot shape : Arbitrary 2D polygon

  • PTG parameters : Use the app ptg-configurator

This PT generator functions are:

\[v(\alpha) = V_{MAX} e^{ -\left( \dfrac{\alpha-\phi}{cte_{a0v}} \right)^2}\]
\[\omega(\alpha) = W_{MAX} \left( -\dfrac{1}{2} +\dfrac{1}{1+ e^{ - \dfrac{\alpha-\phi}{cte_{a0w}} } } \right)\]

So, the radius of curvature of each trajectory is NOT constant for each “alpha” value in this PTG:

C-PTG path examples

[Before MRPT 1.5.0 this was named CPTG2]

#include <mrpt/nav/tpspace/CPTG_DiffDrive_alpha.h>

class CPTG_DiffDrive_alpha: public mrpt::nav::CPTG_DiffDrive_CollisionGridBased
{
public:
    // construction

    CPTG_DiffDrive_alpha();

    CPTG_DiffDrive_alpha(
        const mrpt::config::CConfigFileBase& cfg,
        const std::string& sSection
        );

    //
methods

    void setRobotShape(const mrpt::math::CPolygon& robotShape);
    virtual double getMaxRobotRadius() const;
    virtual double evalClearanceToRobotShape(const double ox, const double oy) const;

    virtual bool inverseMap_WS2TP(
        double x,
        double y,
        int& out_k,
        double& out_d,
        double tolerance_dist = 0.10
        ) const;

    virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const;
    virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const;
    virtual void setRefDistance(const double refDist);
    virtual size_t getPathStepCount(uint16_t k) const;
    virtual mrpt::math::TPose2D getPathPose(uint16_t k, uint32_t step) const;
    virtual double getPathDist(uint16_t k, uint32_t step) const;
    virtual bool getPathStepForDist(uint16_t k, double dist, uint32_t& out_step) const;
    virtual double getPathStepDuration() const;
    virtual double getMaxLinVel() const;
    virtual double getMaxAngVel() const;
    virtual void updateTPObstacle(double ox, double oy, std::vector<double>& tp_obstacles) const;
    virtual void updateTPObstacleSingle(double ox, double oy, uint16_t k, double& tp_obstacle_k) const;
    virtual void onNewNavDynamicState();
    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& cfg, const std::string& sSection);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    virtual std::string getDescription() const;

    virtual void ptgDiffDriveSteeringFunction(
        float alpha,
        float t,
        float x,
        float y,
        float phi,
        float& v,
        float& w
        ) const;

    virtual void loadDefaultParams();
    virtual bool isPointInsideRobotShape(const double x, const double y) const;
    virtual void add_robotShape_to_setOfLines(mrpt::opengl::CSetOfLines& gl_shape, const mrpt::poses::CPose2D& origin = mrpt::poses::CPose2D()) const;
};

Inherited Members

public:
    // structs

    struct TNavDynamicState;
    struct TCellForLambdaFunction;

    // classes

    class CCollisionGrid;

    //
methods

    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section) = 0;
    void loadFromConfigFileName(const std::string& config_file, const std::string& section);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    void saveToConfigFileName(const std::string& config_file, const std::string& section) const;
    void dumpToConsole() const;
    virtual void dumpToTextStream(std::ostream& out) const;
    virtual std::string getDescription() const = 0;

    virtual bool inverseMap_WS2TP(
        double x,
        double y,
        int& out_k,
        double& out_normalized_d,
        double tolerance_dist = 0.10
        ) const = 0;

    virtual bool PTG_IsIntoDomain(double x, double y) const;
    virtual bool isBijectiveAt(] uint16_t k, ] uint32_t step) const;
    virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const = 0;
    virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const = 0;
    virtual size_t getPathStepCount(uint16_t k) const = 0;
    virtual mrpt::math::TPose2D getPathPose(uint16_t k, uint32_t step) const = 0;
    virtual mrpt::math::TTwist2D getPathTwist(uint16_t k, uint32_t step) const;
    virtual double getPathDist(uint16_t k, uint32_t step) const = 0;
    virtual double getPathStepDuration() const = 0;
    virtual double getMaxLinVel() const = 0;
    virtual double getMaxAngVel() const = 0;
    virtual bool getPathStepForDist(uint16_t k, double dist, uint32_t& out_step) const = 0;
    virtual void updateTPObstacle(double ox, double oy, std::vector<double>& tp_obstacles) const = 0;
    virtual void updateTPObstacleSingle(double ox, double oy, uint16_t k, double& tp_obstacle_k) const = 0;
    virtual void loadDefaultParams();
    virtual bool supportVelCmdNOP() const;
    virtual bool supportSpeedAtTarget() const;
    virtual double maxTimeInVelCmdNOP(int path_k) const;
    virtual double getActualUnloopedPathLength(] uint16_t k) const;
    virtual double evalPathRelativePriority(] uint16_t k, ] double target_distance) const;
    virtual double getMaxRobotRadius() const = 0;
    virtual bool isPointInsideRobotShape(const double x, const double y) const = 0;
    virtual double evalClearanceToRobotShape(const double ox, const double oy) const = 0;
    void updateNavDynamicState(const TNavDynamicState& newState, const bool force_update = false);

    void initialize(
        const std::string& cacheFilename = std::string(),
        const bool verbose = true
        );

    void deinitialize();
    bool isInitialized() const;
    uint16_t getAlphaValuesCount() const;
    uint16_t getPathCount() const;
    double index2alpha(uint16_t k) const;
    uint16_t alpha2index(double alpha) const;
    void initTPObstacles(std::vector<double>& TP_Obstacles) const;
    double getScorePriority() const;

    virtual void renderPathAsSimpleLine(
        const uint16_t k,
        mrpt::opengl::CSetOfLines& gl_obj,
        const double decimate_distance = 0.1,
        const double max_path_distance = -1.0
        ) const;

    bool debugDumpInFiles(const std::string& ptg_name) const;
    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& cfg, const std::string& sSection);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    virtual void add_robotShape_to_setOfLines(mrpt::opengl::CSetOfLines& gl_shape, const mrpt::poses::CPose2D& origin = mrpt::poses::CPose2D()) const = 0;
    void initClearanceDiagram(ClearanceDiagram& cd) const;
    void updateClearance(const double ox, const double oy, ClearanceDiagram& cd) const;

    virtual void evalClearanceSingleObstacle(
        const double ox,
        const double oy,
        const uint16_t k,
        ClearanceDiagram::dist2clearance_t& inout_realdist2clearance,
        bool treat_as_obstacle = true
        ) const;

    static CParameterizedTrajectoryGenerator::Ptr CreatePTG(
        const std::string& ptgClassName,
        const mrpt::config::CConfigFileBase& cfg,
        const std::string& sSection,
        const std::string& sKeyPrefix
        );

    static std::string& OUTPUT_DEBUG_PATH_PREFIX();
    static PTG_collision_behavior_t& COLLISION_BEHAVIOR();
    virtual void setRefDistance(const double refDist);
    const mrpt::math::CPolygon& getRobotShape() const;
    const TNavDynamicState& getCurrentNavDynamicState() const;
    double getRefDistance() const;
    void initTPObstacleSingle(uint16_t k, double& TP_Obstacle_k) const;
    void setScorePriorty(double prior);
    unsigned getClearanceStepCount() const;
    void setClearanceStepCount(const unsigned res);
    unsigned getClearanceDecimatedPaths() const;
    void setClearanceDecimatedPaths(const unsigned num);
    void updateClearancePost(ClearanceDiagram& cd, const std::vector<double>& TP_obstacles) const;
    static void static_add_robotShape_to_setOfLines(mrpt::opengl::CSetOfLines& gl_shape, const mrpt::poses::CPose2D& origin, const mrpt::math::CPolygon& robotShape);
    static double index2alpha(uint16_t k, const unsigned int num_paths);
    static uint16_t alpha2index(double alpha, const unsigned int num_paths);

    virtual void ptgDiffDriveSteeringFunction(
        float alpha,
        float t,
        float x,
        float y,
        float phi,
        float& v,
        float& w
        ) const = 0;

Methods

void setRobotShape(const mrpt::math::CPolygon& robotShape)

Robot shape must be set before initialization, either from ctor params or via this method.

virtual double getMaxRobotRadius() const

Returns an approximation of the robot radius.

virtual double evalClearanceToRobotShape(const double ox, const double oy) const

Evals the clearance from an obstacle (ox,oy) in coordinates relative to the robot center.

Zero or negative means collision.

virtual bool inverseMap_WS2TP(
    double x,
    double y,
    int& out_k,
    double& out_d,
    double tolerance_dist = 0.10
    ) const

The default implementation in this class relies on a look-up-table.

Derived classes may redefine this to closed-form expressions, when they exist. See full docs in base class CParameterizedTrajectoryGenerator::inverseMap_WS2TP()

virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const

In this class, out_action_cmd contains: [0]: linear velocity (m/s), [1]: angular velocity (rad/s).

In this class, out_action_cmd contains: [0]: linear velocity (m/s), [1]: angular velocity (rad/s)

See more docs in CParameterizedTrajectoryGenerator::directionToMotionCommand()

virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const

Returns an empty kinematic velocity command object of the type supported by this PTG.

Can be queried to determine the expected kinematic interface of the PTG.

virtual void setRefDistance(const double refDist)

Launches an exception in this class: it is not allowed in numerical integration-based PTGs to change the reference distance after initialization.

virtual size_t getPathStepCount(uint16_t k) const

Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete “steps” along the trajectory.

May be actual steps from a numerical integration or an arbitrary small length for analytical PTGs.

See also:

getAlphaValuesCount()

virtual mrpt::math::TPose2D getPathPose(uint16_t k, uint32_t step) const

Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step.

See also:

getPathStepCount(), getAlphaValuesCount(), getPathTwist()

virtual double getPathDist(uint16_t k, uint32_t step) const

Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step.

Returns:

Distance in pseudometers (real distance, NOT normalized to [0,1] for [0,refDist])

See also:

getPathStepCount(), getAlphaValuesCount()

virtual bool getPathStepForDist(uint16_t k, double dist, uint32_t& out_step) const

Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is <dist

Parameters:

dist

Distance in pseudometers (real distance, NOT normalized to [0,1] for [0,refDist])

Returns:

false if no step fulfills the condition for the given trajectory k (e.g. out of reference distance). Note that, anyway, the maximum distance (closest point) is returned in out_step.

See also:

getPathStepCount(), getAlphaValuesCount()

virtual double getPathStepDuration() const

Returns the duration (in seconds) of each “step”.

See also:

getPathStepCount()

virtual double getMaxLinVel() const

Returns the maximum linear velocity expected from this PTG [m/s].

virtual double getMaxAngVel() const

Returns the maximum angular velocity expected from this PTG [rad/s].

virtual void updateTPObstacle(
    double ox,
    double oy,
    std::vector<double>& tp_obstacles
    ) const

Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy)

The length of tp_obstacles is not checked for efficiency since this method is potentially called thousands of times per navigation timestap, so it is left to the user responsibility to provide a valid buffer.

tp_obstacles must be initialized with initTPObstacle() before call.

Parameters:

tp_obstacles

A vector of length getAlphaValuesCount(), initialized with initTPObstacles() (collision-free ranges, in “pseudometers”, un-normalized).

ox

Obstacle point (X), relative coordinates wrt origin of the PTG.

oy

Obstacle point (Y), relative coordinates wrt origin of the PTG.

virtual void updateTPObstacleSingle(
    double ox,
    double oy,
    uint16_t k,
    double& tp_obstacle_k
    ) const

Like updateTPObstacle() but for one direction only (k) in TP-Space.

tp_obstacle_k must be initialized with initTPObstacleSingle() before call (collision-free ranges, in “pseudometers”, un-normalized).

virtual void onNewNavDynamicState()

This family of PTGs ignores the dynamic states.

virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& cfg, const std::string& sSection)

Parameters accepted by this base class:

  • ${sKeyPrefix}num_paths : The number of different paths in this family (number of discrete alpha values).

  • ${sKeyPrefix}ref_distance : The maximum distance in PTGs [meters]

  • ${sKeyPrefix}score_priority : When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG. Assign values <1 to PTGs with low priority.

virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const

This method saves the options to a “.ini”-like file or memory-stored string list.

See also:

loadFromConfigFile, saveToConfigFileName

virtual std::string getDescription() const

Gets a short textual description of the PTG and its parameters.

virtual void ptgDiffDriveSteeringFunction(
    float alpha,
    float t,
    float x,
    float y,
    float phi,
    float& v,
    float& w
    ) const

The main method to be implemented in derived classes: it defines the differential-driven differential equation.

virtual void loadDefaultParams()

Loads a set of default parameters; provided exclusively for the PTG-configurator tool.

virtual bool isPointInsideRobotShape(const double x, const double y) const

Returns true if the point lies within the robot shape.

virtual void add_robotShape_to_setOfLines(mrpt::opengl::CSetOfLines& gl_shape, const mrpt::poses::CPose2D& origin = mrpt::poses::CPose2D()) const

Auxiliary function for rendering.