class mrpt::nav::CReactiveNavigationSystem3D

See base class CAbstractPTGBasedReactive for a description and instructions of use.

This particular implementation assumes a 3D (or “2.5D”) robot shape model, build as a vertical stack of “2D slices”.

Paper describing the method:

  • M. Jaimez-Tarifa, J. Gonzalez-Jimenez, J.L. Blanco, “Efficient Reactive Navigation with Exact Collision Determination for 3D Robot Shapes”, International Journal of Advanced Robotic Systems, 2015.

Class history:

  • SEP/2012: First design.

  • JUL/2013: Integrated into MRPT library.

  • DEC/2013: Code refactoring between this class and CAbstractHolonomicReactiveMethod

  • FEB/2017: Refactoring of all parameters for a consistent organization in sections by class names (MRPT 1.5.0)

This class requires a number of parameters which are usually provided via an external config (“.ini”) file. Alternatively, a memory-only object can be used to avoid physical files, see mrpt::config::CConfigFileMemory.

A template config file can be generated at any moment by the user by calling saveConfigFile() with a default-constructed object.

Next we provide a self-documented template config file; or see it online: https://github.com/MRPT/mrpt/blob/master/share/mrpt/config_files/navigation-ptgs/reactive3d_config.ini

See also:

CAbstractNavigator, CParameterizedTrajectoryGenerator, CAbstractHolonomicReactiveMethod

#include <mrpt/nav/reactive/CReactiveNavigationSystem3D.h>

class CReactiveNavigationSystem3D: public mrpt::nav::CAbstractPTGBasedReactive
{
public:
    // structs

    struct TPTGmultilevel;

    //
fields

    TAbstractPTGNavigatorParams params_abstract_ptg_navigator;

    // construction

    CReactiveNavigationSystem3D(
        CRobot2NavInterface& react_iterf_impl,
        bool enableConsoleOutput = true,
        bool enableLogFile = false,
        const std::string& logFileDirectory = std::string("./reactivenav.logs")
        );

    //
methods

    void changeRobotShape(TRobotShape robotShape);
    virtual bool checkCollisionWithLatestObstacles(const mrpt::math::TPose2D& relative_robot_pose) const;
    virtual size_t getPTG_count() const;
    virtual CParameterizedTrajectoryGenerator* getPTG(size_t i);
    virtual const CParameterizedTrajectoryGenerator* getPTG(size_t i) const;
    virtual void loadConfigFile(const mrpt::config::CConfigFileBase& c);
    virtual void saveConfigFile(mrpt::config::CConfigFileBase& c) const;
    std::string getLogFileDirectory() const;
};

Inherited Members

public:
    // enums

    enum TErrorCode;
    enum TState;

    // structs

    struct TMsg;
    struct TAbstractNavigatorParams;
    struct TErrorReason;
    struct TNavigationParams;
    struct TNavigationParamsBase;
    struct TRobotPoseVel;
    struct TargetInfo;
    struct TNavigationParamsWaypoints;
    struct TWaypointsNavigatorParams;
    struct PTGTarget;
    struct TAbstractPTGNavigatorParams;
    struct TInfoPerPTG;
    struct TNavigationParamsPTG;
    struct TSentVelCmd;

    //
fields

    mrpt::system::CTimeLogger m_navProfiler {false,                                          "mrpt::nav::CAbstractNavigator"};
    TWaypointsNavigatorParams params_waypoints_navigator;
    TAbstractNavigatorParams params_abstract_navigator;

    //
methods

    virtual void loadConfigFile(const mrpt::config::CConfigFileBase& c);
    virtual void saveConfigFile(mrpt::config::CConfigFileBase& c) const;
    virtual void initialize() = 0;
    virtual void navigationStep();
    virtual void navigate(const TNavigationParams* params);
    virtual void cancel();
    virtual void resume();
    virtual void suspend();
    virtual void resetNavError();
    TState getCurrentState() const;
    const TErrorReason& getErrorReason() const;
    void setFrameTF(const std::weak_ptr<mrpt::poses::FrameTransformer<2>>& frame_tf);
    std::weak_ptr<mrpt::poses::FrameTransformer<2>> getFrameTF() const;
    void enableRethrowNavExceptions(const bool enable);
    const mrpt::system::CTimeLogger& getDelaysTimeLogger() const;
    bool isRethrowNavExceptionsEnabled() const;
    virtual void loadConfigFile(const mrpt::config::CConfigFileBase& c);
    virtual void saveConfigFile(mrpt::config::CConfigFileBase& c) const;
    virtual void navigateWaypoints(const TWaypointSequence& nav_request);
    virtual void getWaypointNavStatus(TWaypointStatusSequence& out_nav_status) const;
    TWaypointStatusSequence getWaypointNavStatus() const;
    virtual void initialize();
    void setHolonomicMethod(const std::string& method, const mrpt::config::CConfigFileBase& cfgBase);
    void getLastLogRecord(CLogFileRecord& o);
    void enableKeepLogRecords(bool enable = true);
    void enableLogFile(bool enable);
    void setLogFileDirectory(const std::string& sDir);
    virtual void loadConfigFile(const mrpt::config::CConfigFileBase& c);
    virtual void saveConfigFile(mrpt::config::CConfigFileBase& c) const;
    void enableTimeLog(bool enable = true);
    const mrpt::system::CTimeLogger& getTimeLogger() const;
    virtual size_t getPTG_count() const = 0;
    virtual CParameterizedTrajectoryGenerator* getPTG(size_t i) = 0;
    virtual const CParameterizedTrajectoryGenerator* getPTG(size_t i) const = 0;
    const mrpt::kinematics::CVehicleVelCmd::TVelCmdParams& getCurrentRobotSpeedLimits() const;
    mrpt::kinematics::CVehicleVelCmd::TVelCmdParams& changeCurrentRobotSpeedLimits();
    void setTargetApproachSlowDownDistance(const double dist);
    double getTargetApproachSlowDownDistance() const;
    virtual void navigationStep();
    virtual void cancel();
    bool isRelativePointReachable(const mrpt::math::TPoint2D& wp_local_wrt_robot) const;

Construction

CReactiveNavigationSystem3D(
    CRobot2NavInterface& react_iterf_impl,
    bool enableConsoleOutput = true,
    bool enableLogFile = false,
    const std::string& logFileDirectory = std::string("./reactivenav.logs")
    )

See docs in ctor of base class.

Methods

void changeRobotShape(TRobotShape robotShape)

Change the robot shape, which is taken into account for collision grid building.

virtual bool checkCollisionWithLatestObstacles(const mrpt::math::TPose2D& relative_robot_pose) const

Checks whether the robot shape, when placed at the given pose (relative to the current pose), is colliding with any of the latest known obstacles.

Default implementation: always returns false.

virtual size_t getPTG_count() const

Returns the number of different PTGs that have been setup.

virtual CParameterizedTrajectoryGenerator* getPTG(size_t i)

Gets the i’th PTG.

virtual const CParameterizedTrajectoryGenerator* getPTG(size_t i) const

Gets the i’th PTG.

virtual void loadConfigFile(const mrpt::config::CConfigFileBase& c)

Loads all params from a file.

To be called before initialize(). Each derived class MUST load its own parameters, and then call ITS PARENT’S overriden method to ensure all params are loaded.

virtual void saveConfigFile(mrpt::config::CConfigFileBase& c) const

Saves all current options to a config file.

Each derived class MUST save its own parameters, and then call ITS PARENT’S overriden method to ensure all params are saved.