26 CReactiveNavigationSystem::CReactiveNavigationSystem(
28 bool enableLogToFile,
const std::string& logFileDirectory)
30 react_iterf_impl, enableConsoleOutput, enableLogToFile,
65 const std::string s =
"CReactiveNavigationSystem";
68 unsigned int PTG_COUNT =
PTGs.size();
78 const std::string sectCfg =
"CReactiveNavigationSystem";
81 unsigned int PTG_COUNT = c.
read_int(sectCfg,
"PTG_COUNT", 0,
true);
87 sectCfg,
"RobotModel_shape2D_xs", vector<float>(0), xs,
false);
89 sectCfg,
"RobotModel_shape2D_ys", vector<float>(0), ys,
false);
91 xs.size() == ys.size(),
92 "Config parameters `RobotModel_shape2D_xs` and `RobotModel_shape2D_ys` " 93 "must have the same length!");
97 for (
size_t i = 0; i < xs.size(); i++) shape.
AddVertex(xs[i], ys[i]);
103 const double robot_shape_radius =
104 c.
read_double(sectCfg,
"RobotModel_circular_shape_radius", .0,
false);
105 ASSERT_(robot_shape_radius >= .0);
106 if (robot_shape_radius != .0)
115 PTGs.resize(PTG_COUNT);
117 for (
unsigned int n = 0; n < PTG_COUNT; n++)
120 const std::string sPTGName =
123 sPTGName, c, sectCfg,
format(
"PTG%u_", n));
141 for (
unsigned int i = 0; i <
PTGs.size(); i++)
143 PTGs[i]->deinitialize();
147 "[CReactiveNavigationSystem::STEP1_InitPTGs] Initializing " 149 i,
PTGs[i]->getDescription().c_str());
167 "%s/ReacNavGrid_%03u.dat.gz",
204 catch (
const std::exception& e)
207 "[CReactiveNavigationSystem::STEP2_Sense] Exception:" << e.what());
213 "[CReactiveNavigationSystem::STEP2_Sense] Unexpected exception!");
220 const size_t ptg_idx, std::vector<double>& out_TPObstacles,
223 const bool eval_clearance)
226 m_navProfiler,
"CReactiveNavigationSystem::STEP3_WSpaceToTPSpace()");
232 rel_pose_PTG_origin_wrt_sense_);
239 const float *xs, *ys, *zs;
242 for (
size_t obs = 0; obs < nObs; obs++)
244 double ox, oy, oz = zs[obs];
245 rel_pose_PTG_origin_wrt_sense.
composePoint(xs[obs], ys[obs], ox, oy);
247 if (ox > -OBS_MAX_XY && ox < OBS_MAX_XY && oy > -OBS_MAX_XY &&
274 for (
size_t i = 0; i < nVerts; i++)
292 min_obstacles_height,
293 "Minimum `z` coordinate of obstacles to be considered fo collision " 296 max_obstacles_height,
297 "Maximum `z` coordinate of obstacles to be considered fo collision " 310 const float *xs, *ys, *zs;
313 for (
size_t i = 0; i < 1 ;
316 const auto ptg =
PTGs[i];
318 const double R = ptg->getMaxRobotRadius();
319 for (
size_t obs = 0; obs < nObs; obs++)
321 const double gox = xs[obs], goy = ys[obs], oz = zs[obs];
330 if (lo.
x >= -
R && lo.
x <=
R && lo.
y >= -
R && lo.
y <=
R &&
331 ptg->isPointInsideRobotShape(lo.
x, lo.
y))
double GetVertex_x(size_t i) const
Methods for accessing the vertices.
TRobotPoseVel m_curPoseVel
Current robot pose (updated in CAbstractNavigator::navigationStep() )
virtual bool senseObstacles(mrpt::maps::CSimplePointsMap &obstacles, mrpt::system::TTimeStamp ×tamp)=0
Return the current set of obstacle points, as seen from the local coordinate frame of the robot...
mrpt::system::CTimeLogger m_timlog_delays
Time logger to collect delay-related stats.
size_t verticesCount() const
Returns the vertices count in the polygon:
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
mrpt::math::CVectorFloat robotShape_y
void logFmt(const VerbosityLevel level, const char *fmt,...) const MRPT_printf_format_check(3
Alternative logging method, which mimics the printf behavior.
mrpt::maps::CSimplePointsMap m_WS_Obstacles
The obstacle points, as seen from the local robot frame.
#define THROW_EXCEPTION(msg)
A safe way to call enter() and leave() of a mrpt::system::CTimeLogger upon construction and destructi...
std::string std::string format(std::string_view fmt, ARGS &&... args)
void STEP1_InitPTGs() override
Base class for all PTGs using a 2D circular robot shape model.
#define ASSERT_BELOW_(__A, __B)
void changeRobotCircularShapeRadius(const double R)
Defines the 2D circular robot shape radius, used for some PTGs for collision checking.
double max_obstacles_height
TReactiveNavigatorParams params_reactive_nav
mrpt::maps::CSimplePointsMap m_WS_Obstacles_original
Obstacle points, before filtering (if filtering is enabled).
size_t getPTG_count() const override
Returns the number of different PTGs that have been setup.
A wrapper of a TPolygon2D class, implementing CSerializable.
bool m_enableConsoleOutput
Enables / disables the console debug output.
std::vector< CParameterizedTrajectoryGenerator::Ptr > PTGs
The list of PTGs to use for navigation.
Clearance information for one particular PTG and one set of obstacles.
static CParameterizedTrajectoryGenerator::Ptr CreatePTG(const std::string &ptgClassName, const mrpt::config::CConfigFileBase &cfg, const std::string &sSection, const std::string &sKeyPrefix)
The class factory for creating a PTG from a list of parameters in a section of a given config file (p...
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
void composePoint(double lx, double ly, double &gx, double &gy) const
An alternative, slightly more efficient way of doing with G and L being 2D points and P this 2D pose...
mrpt::math::CVectorFloat robotShape_x
The robot shape in WS.
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
#define ASSERT_(f)
Defines an assertion mechanism.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
This is the base class for any user-defined PTG.
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
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...
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. ...
Base class for all PTGs using a 2D polygonal robot shape model.
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
void setRobotShapeRadius(const double robot_radius)
Robot shape must be set before initialization, either from ctor params or via this method...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
mrpt::maps::CSimplePointsMap WS_Obstacles_original
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
~CReactiveNavigationSystem() override
Destructor.
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.
std::string ptg_cache_files_directory
(Default: ".")
mrpt::system::CTimeLogger m_navProfiler
Publicly available time profiling object.
void updateClearance(const double ox, const double oy, ClearanceDiagram &cd) const
Updates the clearance diagram given one (ox,oy) obstacle point, in coordinates relative to the PTG pa...
void setRobotShape(const mrpt::math::CPolygon &robotShape)
Robot shape must be set before initialization, either from ctor params or via this method...
virtual void updateTPObstacle(double ox, double oy, std::vector< double > &tp_obstacles) const =0
Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double min_obstacles_height
void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
void changeRobotShape(const mrpt::math::CPolygon &shape)
Defines the 2D polygonal robot shape, used for some PTGs for collision checking.
CParameterizedTrajectoryGenerator * getPTG(size_t i) override
Gets the i'th PTG.
void getPointsBuffer(size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs) const
Provides a direct access to points buffer, or nullptr if there is no points in the map...
void logStr(const VerbosityLevel level, std::string_view msg_str) const
Main method to add the specified message string to the logger.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
TAbstractPTGNavigatorParams params_abstract_ptg_navigator
CRobot2NavInterface & m_robot
The navigator-robot interface.
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.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
#define MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(variableName, variableType)
Shortcut for MRPT_LOAD_CONFIG_VAR_NO_DEFAULT() for REQUIRED variables config file object named c and ...
TReactiveNavigatorParams()
double ref_distance
Maximum distance up to obstacles will be considered (D_{max} in papers).
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
double m_robotShapeCircularRadius
Radius of the robot if approximated as a circle.
mrpt::math::TPoint2D inverseComposePoint(const TPoint2D g) const
void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
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)...
double GetVertex_y(size_t i) const
void resize(std::size_t N, bool zeroNewElements=false)
mrpt::maps::CSimplePointsMap WS_Obstacles
The WS-Obstacles.
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
mrpt::math::CPolygon m_robotShape
The robot 2D shape model.
void AddVertex(double x, double y)
Add a new vertex to polygon.
bool m_PTGsMustBeReInitialized
mrpt::system::CTimeLogger m_timelogger
A complete time logger.
bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp) override
Return false on any fatal error.
void read_vector(const std::string §ion, const std::string &name, const VECTOR_TYPE &defaultValue, VECTOR_TYPE &outValues, bool failIfNotFound=false) const
Reads a configuration parameter of type vector, stored in the file as a string: "[v1 v2 v3 ...
mrpt::maps::CPointCloudFilterBase::Ptr m_WS_filter
Default: none.
void preDestructor()
To be called during children destructors to assure thread-safe destruction, and free of shared object...
double robotShape_radius
The circular robot radius.