Go to the documentation of this file.
9 #ifndef CReactiveNavigationSystem3D_H
10 #define CReactiveNavigationSystem3D_H
118 size_t i)
const override
138 std::vector<CParameterizedTrajectoryGenerator*>
PTGs;
172 const size_t ptg_idx, std::vector<double>& out_TPObstacles,
175 const bool eval_clearance)
override;
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
See base class CAbstractPTGBasedReactive for a description and instructions of use.
const double & getRadius(size_t level) const
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
void enableLogFile(bool enable)
Enables/disables saving log files.
virtual size_t getPTG_count() const override
Returns the number of different PTGs that have been setup.
const std::vector< double > & getHeights() const
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
virtual void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
#define ASSERT_(f)
Defines an assertion mechanism.
void resize(size_t num_levels)
void changeRobotShape(TRobotShape robotShape)
Change the robot shape, which is taken into account for collision grid building.
A set of PTGs of the same type, one per "height level".
mrpt::math::CPolygon & polygon(size_t level)
std::vector< double > heights
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
GLdouble GLdouble GLdouble r
virtual ~CReactiveNavigationSystem3D()
Destructor.
mrpt::math::TPoint2D TP_Target
This class allows loading and storing values and vectors of different types from a configuration text...
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...
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i) override
Gets the i'th PTG.
Clearance information for one particular PTG and one set of obstacles.
Stores a candidate movement in TP-Space-based navigation.
const mrpt::math::CPolygon & polygon(size_t level) const
std::vector< mrpt::maps::CSimplePointsMap > m_WS_Obstacles_inlevels
One point cloud per 2.5D robot-shape-slice, coordinates relative to the robot local frame.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.
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
Transform the obstacle into TP-Obstacles in TP-Spaces.
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),...
std::vector< TPTGmultilevel > m_ptgmultilevel
The set of PTG-transformations to be used: indices are [ptg_index][height_index].
TCandidateMovementPTG holonomicmov
TRobotShape m_robotShape
The robot 3D shape model.
const double & getHeight(size_t level) const
A wrapper of a TPolygon2D class, implementing CSerializable.
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.
bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp) override
Return false on any fatal error.
void setHeight(size_t level, double h)
mrpt::maps::CSimplePointsMap m_WS_Obstacles_unsorted
The unsorted set of obstacles from the sensors.
#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 void STEP1_InitPTGs() override
virtual void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
void setRadius(size_t level, double r)
std::vector< CParameterizedTrajectoryGenerator * > PTGs
std::vector< double > radius
virtual const CParameterizedTrajectoryGenerator * getPTG(size_t i) const override
Gets the i'th PTG.
This is the base class for any user-defined PTG.
std::vector< mrpt::math::CPolygon > polygons
A 3D robot shape stored as a "sliced" stack of 2D polygons, used for CReactiveNavigationSystem3D Depe...
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 | |