Go to the documentation of this file.
9 #ifndef CReactiveNavigationSystem_H
10 #define CReactiveNavigationSystem_H
92 size_t i)
const override
124 std::vector<CParameterizedTrajectoryGenerator*>
PTGs;
154 const size_t ptg_idx, std::vector<double>& out_TPObstacles,
157 const bool eval_clearance)
override;
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i) override
Gets the i'th PTG.
virtual ~CReactiveNavigationSystem()
Destructor.
std::vector< CParameterizedTrajectoryGenerator * > PTGs
The list of PTGs to use for navigation.
void enableLogFile(bool enable)
Enables/disables saving log files.
virtual void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
TReactiveNavigatorParams params_reactive_nav
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::math::CPolygon m_robotShape
The robot 2D shape model.
double max_obstacles_height
mrpt::maps::CSimplePointsMap m_WS_Obstacles_original
Obstacle points, before filtering (if filtering is enabled).
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
#define ASSERT_(f)
Defines an assertion mechanism.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
void STEP3_WSpaceToTPSpace(const size_t ptg_idx, std::vector< double > &out_TPObstacles, mrpt::nav::ClearanceDiagram &out_clearance, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense, const bool eval_clearance) override
Builds TP-Obstacles from Workspace obstacles for the given PTG.
void changeRobotCircularShapeRadius(const double R)
Defines the 2D circular robot shape radius, used for some PTGs for collision checking.
double m_robotShapeCircularRadius
Radius of the robot if approximated as a circle.
virtual void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
TReactiveNavigatorParams()
This class allows loading and storing values and vectors of different types from a configuration text...
virtual void saveToConfigFile(mrpt::config::CConfigFileBase &c, const std::string &s) const override
This method saves the options to a ".ini"-like file or memory-stored string list.
Clearance information for one particular PTG and one set of obstacles.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.
virtual void loggingGetWSObstaclesAndShape(CLogFileRecord &out_log) override
Generates a pointcloud of obstacles, and the robot shape, to be saved in the logging record for the c...
CReactiveNavigationSystem(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.
virtual bool checkCollisionWithLatestObstacles(const mrpt::math::TPose2D &relative_robot_pose) const override
Checks whether the robot shape, when placed at the given pose (relative to the current pose),...
virtual void STEP1_InitPTGs() override
virtual const CParameterizedTrajectoryGenerator * getPTG(size_t i) const override
Gets the i'th PTG.
A wrapper of a TPolygon2D class, implementing CSerializable.
bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp) override
Return false on any fatal error.
See base class CAbstractPTGBasedReactive for a description and instructions of use.
virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase &c, const std::string &s) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::maps::CSimplePointsMap m_WS_Obstacles
The obstacle points, as seen from the local robot frame.
#define MRPT_MAKE_ALIGNED_OPERATOR_NEW
Put this macro inside any class with members that require {16,32,64}-byte memory alignment (e....
GLsizei const GLchar ** string
virtual size_t getPTG_count() const override
Returns the number of different PTGs that have been setup.
double min_obstacles_height
This is the base class for any user-defined PTG.
void changeRobotShape(const mrpt::math::CPolygon &shape)
Defines the 2D polygonal robot shape, used for some PTGs for collision checking.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |