MRPT  1.9.9
CAbstractPTGBasedReactive.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
12 #include <mrpt/math/CPolygon.h>
13 #include <mrpt/math/filters.h>
22 #include <mrpt/system/datetime.h>
23 #include <memory> // unique_ptr
24 
25 namespace mrpt::nav
26 {
27 /** Base class for reactive navigator systems based on TP-Space, with an
28  * arbitrary holonomic
29  * reactive method running on it and any number of PTGs for transforming the
30  * navigation space.
31  * Both, the holonomic method and the PTGs can be customized by the apropriate
32  * user derived classes.
33  *
34  * How to use:
35  * - Instantiate a reactive navigation object (one of the derived classes of
36  * this virtual class).
37  * - A class with callbacks must be defined by the user and provided to the
38  * constructor (derived from CRobot2NavInterface)
39  * - loadConfigFile() must be called to set up the bunch of parameters from a
40  * config file (could be a memory-based virtual config file).
41  * - navigationStep() must be called periodically in order to effectively run
42  * the navigation. This method will internally call the callbacks to gather
43  * sensor data and robot positioning data.
44  *
45  * For working examples, refer to the source code of the apps:
46  * -
47  * [ReactiveNavigationDemo](http://www.mrpt.org/list-of-mrpt-apps/application-reactivenavigationdemo/)
48  * -
49  * [ReactiveNav3D-Demo](http://www.mrpt.org/list-of-mrpt-apps/application-reactivenav3d-demo/)
50  *
51  * Publications:
52  * - See derived classes for papers on each specific method.
53  *
54  * Available "variables" or "score names" for each motion candidate (these can
55  * be used in runtime-compiled expressions
56  * in the configuration files of motion deciders):
57  *
58  * - `clearance`: Clearance (larger means larger distances to obstacles) for
59  * the path from "current pose" up to "end of trajectory".
60  * - `collision_free_distance`: Normalized [0,1] collision-free distance in
61  * selected path. For NOP candidates, the traveled distances is substracted.
62  * - `dist_eucl_final`: Euclidean distance (in the real-world WordSpace)
63  * between "end of trajectory" and target.
64  * - `eta`: Estimated Time of Arrival at "end of trajectory".
65  * - `holo_stage_eval`: Final evaluation of the selected direction from inside
66  * of the holonomic algorithm.
67  * - `hysteresis`: Measure of similarity with previous command [0,1]
68  * - `is_PTG_cont`: 1 (is "NOP" motion command), 0 otherwise
69  * - `is_slowdown`: 1 if PTG returns true in
70  * CParameterizedTrajectoryGenerator::supportSpeedAtTarget() for this step.
71  * - `move_cur_d`: Normalized distance already traveled over the selected PTG.
72  * Normally 0, unless in a "NOP motion".
73  * - `move_k`: Motion candidate path 0-based index.
74  * - `num_paths`: Number of paths in the PTG
75  * - `original_col_free_dist`: Only for "NOP motions", the collision-free
76  * distance when the motion command was originally issued.
77  * - `ptg_idx`: PTG index (0-based)
78  * - `ptg_priority`: Product of PTG getScorePriority() times PTG
79  * evalPathRelativePriority()
80  * - `ref_dist`: PTG ref distance [m]
81  * - `robpose_x`, `robpose_y`, `robpose_phi`: Robot pose ([m] and [rad]) at the
82  * "end of trajectory": at collision or at target distance.
83  * - `target_d_norm`: Normalized target distance. Can be >1 if distance is
84  * larger than ref_distance.
85  * - `target_dir`: Angle of target in TP-Space [rad]
86  * - `target_k`: Same as target_dir but in discrete path 0-based indices.
87  * - `WS_target_x`, `WS_target_y`: Target coordinates in realworld [m]
88  *
89  * \sa CReactiveNavigationSystem, CReactiveNavigationSystem3D
90  * \ingroup nav_reactive
91  */
93 {
94  public:
95  /** The struct for configuring navigation requests to
96  * CAbstractPTGBasedReactive and derived classes. */
99  {
100  /** (Default=empty) Optionally, a list of PTG indices can be sent such
101  * that
102  * the navigator will restrict itself to only employ those PTGs. */
103  std::vector<size_t> restrict_PTG_indices;
104 
105  std::string getAsText() const override;
106  std::unique_ptr<TNavigationParams> clone() const override
107  {
108  return std::unique_ptr<TNavigationParams>(
109  new TNavigationParamsPTG(*this));
110  }
111 
112  protected:
113  bool isEqual(
114  const CAbstractNavigator::TNavigationParamsBase& o) const override;
115  };
116 
117  /** Constructor.
118  * \param[in] react_iterf_impl An instance of an object that implement all
119  * the required interfaces to read from and control a robot.
120  * \param[in] enableConsoleOutput Can be set to false to reduce verbosity.
121  * \param[in] enableLogFile Set to true to enable creation of navigation
122  * log files, useful for inspection and debugging.
123  */
125  CRobot2NavInterface& react_iterf_impl, bool enableConsoleOutput = true,
126  bool enableLogFile = false,
127  const std::string& logFileDirectory =
128  std::string("./reactivenav.logs"));
129 
130  ~CAbstractPTGBasedReactive() override;
131 
132  /** Must be called for loading collision grids, or the first navigation
133  * command may last a long time to be executed.
134  * Internally, it just calls STEP1_CollisionGridsBuilder().
135  */
136  void initialize() override;
137 
138  /** Selects which one from the set of available holonomic methods will be
139  * used
140  * into transformed TP-Space, and sets its configuration from a
141  * configuration file.
142  * Available methods: class names of those derived from
143  * CAbstractHolonomicReactiveMethod
144  */
145  void setHolonomicMethod(
146  const std::string& method,
147  const mrpt::config::CConfigFileBase& cfgBase);
148 
149  /** Provides a copy of the last log record with information about execution.
150  * \param o An object where the log will be stored into.
151  * \note Log records are not prepared unless either "enableLogFile" is
152  * enabled in the constructor or "enableLogFile()" has been called.
153  */
155 
156  /** Enables keeping an internal registry of navigation logs that can be
157  * queried with getLastLogRecord() */
158  void enableKeepLogRecords(bool enable = true)
159  {
160  m_enableKeepLogRecords = enable;
161  }
162 
163  /** Enables/disables saving log files. */
164  void enableLogFile(bool enable);
165 
166  /** Changes the prefix for new log files. */
168  {
169  m_navlogfiles_dir = sDir;
170  }
173  {
174  /** C++ class name of the holonomic navigation method to run in the
175  * transformed TP-Space */
177  /** C++ class name of the motion chooser */
179 
180  /** (Default: ".") */
182  /** Maximum distance up to obstacles will be considered (D_{max} in
183  * papers). */
184  double ref_distance{4.0};
185  /** Time constant (in seconds) for the low-pass filter applied to
186  * kinematic velocity commands (default=0: no filtering) */
187  double speedfilter_tau{0.0};
188 
189  /** In normalized distances, the start and end of a ramp function that
190  * scales the velocity
191  * output from the holonomic navigator:
192  *
193  * \code
194  * velocity scale
195  * ^
196  * | _____________
197  * | /
198  * 1 | /
199  * | /
200  * 0 +-------+---|----------------> normalized distance
201  * Start
202  * End
203  * \endcode
204  *
205  */
207  bool use_delays_model{false};
208  /** Max distance [meters] to discard current PTG and issue a new vel cmd
209  * (default= 0.05) */
211  /** Min normalized dist [0,1] after current pose in a PTG continuation
212  * to allow it. */
214 
215  /** Params related to speed limits. */
219  /** Default: false */
220  bool evaluate_clearance{false};
221  /** Max dist [meters] to use time-based path prediction for NOP
222  * evaluation. */
224 
225  void loadFromConfigFile(
227  const std::string& s) override;
228  void saveToConfigFile(
230  const std::string& s) const override;
232  };
233 
235 
237  override; // See base class docs!
239  const override; // See base class docs!
240 
241  /** Enables/disables the detailed time logger (default:disabled upon
242  * construction)
243  * When enabled, a report will be dumped to std::cout upon destruction.
244  * \sa getTimeLogger
245  */
246  void enableTimeLog(bool enable = true) { m_timelogger.enable(enable); }
247  /** Gives access to a const-ref to the internal time logger \sa
248  * enableTimeLog */
250  {
251  return m_timelogger;
252  }
253 
254  /** Returns the number of different PTGs that have been setup */
255  virtual size_t getPTG_count() const = 0;
256  /** Gets the i'th PTG */
257  virtual CParameterizedTrajectoryGenerator* getPTG(size_t i) = 0;
258  /** Gets the i'th PTG */
259  virtual const CParameterizedTrajectoryGenerator* getPTG(size_t i) const = 0;
260 
261  /** Get the current, global (honored for all PTGs) robot speed limits */
264  {
266  }
267 
268  /** Changes the current, global (honored for all PTGs) robot speed limits,
269  * via returning a reference to a structure that holds those limits */
272  {
274  }
275 
276  /** Changes this parameter in all inner holonomic navigator instances [m].
277  */
278  void setTargetApproachSlowDownDistance(const double dist);
279  /** Returns this parameter for the first inner holonomic navigator instances
280  * [m] (should be the same in all of them?) */
281  double getTargetApproachSlowDownDistance() const;
282 
283  protected:
284  /** The main method for the navigator */
285  void performNavigationStep() override;
286 
288 
289  /** The holonomic navigation algorithm (one object per PTG, so internal
290  * states are maintained) */
291  std::vector<CAbstractHolonomicReactiveMethod::Ptr> m_holonomicMethod;
292  std::unique_ptr<mrpt::io::CStream> m_logFile;
293  /** The current log file stream, or nullptr if not being used */
295  /** See enableKeepLogRecords */
297  /** The last log */
299  /** Last velocity commands */
301 
302  /** Critical zones */
303  std::recursive_mutex m_critZoneLastLog;
304 
305  /** Enables / disables the console debug output. */
307  /** Whether \a loadConfigFile() has been called or not. */
310 
311  /** A complete time logger \sa enableTimeLog() */
314 
315  /** @name Variables for CReactiveNavigationSystem::performNavigationStep
316  @{ */
320  /** Runtime estimation of execution period of the method. */
324  /** @} */
325 
327  const mrpt::math::TPoint2D& wp_local_wrt_robot)
328  const override; // See docs in base class
329 
330  // Steps for the reactive navigation sytem.
331  // ----------------------------------------------------------------------------
332  virtual void STEP1_InitPTGs() = 0;
333 
334  /** Return false on any fatal error */
335  virtual bool implementSenseObstacles(
336  mrpt::system::TTimeStamp& obs_timestamp) = 0;
337  bool STEP2_SenseObstacles();
338 
339  /** Builds TP-Obstacles from Workspace obstacles for the given PTG.
340  * "out_TPObstacles" is already initialized to the proper length and
341  * maximum collision-free distance for each "k" trajectory index.
342  * Distances are in "pseudo-meters". They will be normalized automatically
343  * to [0,1] upon return. */
344  virtual void STEP3_WSpaceToTPSpace(
345  const size_t ptg_idx, std::vector<double>& out_TPObstacles,
346  mrpt::nav::ClearanceDiagram& out_clearance,
347  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense,
348  const bool eval_clearance) = 0;
349 
350  /** Generates a pointcloud of obstacles, and the robot shape, to be saved in
351  * the logging record for the current timestep */
352  virtual void loggingGetWSObstaclesAndShape(CLogFileRecord& out_log) = 0;
353 
354  struct PTGTarget
355  {
356  /** For each PTG, whether target falls into the PTG domain. */
357  bool valid_TP{false};
358  /** The Target, in TP-Space (x,y) */
360  /** TP-Target */
362  /** The discrete version of target_alpha */
363  int target_k;
364 
365  PTGTarget() = default;
366  };
367 
368  /** Scores \a holonomicMovement */
370  TCandidateMovementPTG& holonomicMovement,
371  const std::vector<double>& in_TPObstacles,
372  const mrpt::nav::ClearanceDiagram& in_clearance,
373  const std::vector<mrpt::math::TPose2D>& WS_Targets,
374  const std::vector<PTGTarget>& TP_Targets,
376  const bool this_is_PTG_continuation,
377  const mrpt::math::TPose2D& relPoseVelCmd_NOP,
378  const unsigned int ptg_idx4weights,
379  const mrpt::system::TTimeStamp tim_start_iteration,
381 
382  /** Return the [0,1] velocity scale of raw PTG cmd_vel */
383  virtual double generate_vel_cmd(
384  const TCandidateMovementPTG& in_movement,
387  CLogFileRecord& newLogRec,
388  const std::vector<mrpt::math::TPose2D>& relTargets, int nSelectedPTG,
389  const mrpt::kinematics::CVehicleVelCmd::Ptr& new_vel_cmd, int nPTGs,
390  const bool best_is_NOP_cmdvel,
391  const math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP,
392  const math::TPose2D& rel_pose_PTG_origin_wrt_sense_NOP,
393  const double executionTimeValue, const double tim_changeSpeed,
394  const mrpt::system::TTimeStamp& tim_start_iteration);
395 
396  /** To be called during children destructors to assure thread-safe
397  * destruction, and free of shared objects. */
398  void preDestructor();
399  void onStartNewNavigation() override;
400 
401  /** Signal that the destructor has been called, so no more calls are
402  * accepted from other threads */
404 
406  /** Default: none */
408 
410 
411  struct TInfoPerPTG
412  {
413  std::vector<PTGTarget> targets;
414  /** One distance per discretized alpha value, describing the "polar
415  * plot" of TP obstacles. */
416  std::vector<double> TP_Obstacles;
417  /** Clearance for each path */
419  };
420 
421  /** Temporary buffers for working with each PTG during a navigationStep() */
422  std::vector<TInfoPerPTG> m_infoPerPTG;
424 
426  CParameterizedTrajectoryGenerator* ptg, const size_t indexPTG,
427  const std::vector<mrpt::math::TPose2D>& relTargets,
428  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense,
429  TInfoPerPTG& ipf, TCandidateMovementPTG& holonomicMovement,
430  CLogFileRecord& newLogRec, const bool this_is_PTG_continuation,
432  const mrpt::system::TTimeStamp tim_start_iteration,
433  const TNavigationParams& navp = TNavigationParams(),
434  const mrpt::math::TPose2D& relPoseVelCmd_NOP =
435  mrpt::math::TPose2D(0, 0, 0));
436 
437  struct TSentVelCmd
438  {
439  /** 0-based index of used PTG */
441  /** Path index for selected PTG */
443  /** Timestamp of when the cmd was sent */
445  /** Robot pose & velocities and timestamp of when it was queried */
446  TRobotPoseVel poseVel;
447  /** TP-Obstacles in the move direction at the instant of picking this
448  * movement */
451  /** [0,1] scale of the raw cmd_vel as generated by the PTG */
452  double speed_scale;
455 
456  bool isValid() const;
457  void reset();
458  TSentVelCmd();
459  };
460 
462 
463  private:
464  /** Delete m_holonomicMethod */
465  void deleteHolonomicObjects();
466 
467  /** Default: "./reactivenav.logs" */
469 
471  /** A copy of last-iteration navparams, used to detect changes */
472  std::unique_ptr<TNavigationParams> m_copy_prev_navParams;
473 
474 }; // end of CAbstractPTGBasedReactive
475 } // namespace mrpt::nav
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. ...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
std::unique_ptr< mrpt::io::CStream > m_logFile
const mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & getCurrentRobotSpeedLimits() const
Get the current, global (honored for all PTGs) robot speed limits.
void setTargetApproachSlowDownDistance(const double dist)
Changes this parameter in all inner holonomic navigator instances [m].
std::recursive_mutex m_critZoneLastLog
Critical zones.
void getLastLogRecord(CLogFileRecord &o)
Provides a copy of the last log record with information about execution.
TRobotPoseVel poseVel
Robot pose & velocities and timestamp of when it was queried.
void initialize() override
Must be called for loading collision grids, or the first navigation command may last a long time to b...
Base for all high-level navigation commands.
void setLogFileDirectory(const std::string &sDir)
Changes the prefix for new log files.
A high-performance stopwatch, with typical resolution of nanoseconds.
A base class for holonomic reactive navigation methods.
void enableLogFile(bool enable)
Enables/disables saving log files.
std::vector< CAbstractHolonomicReactiveMethod::Ptr > m_holonomicMethod
The holonomic navigation algorithm (one object per PTG, so internal states are maintained) ...
const mrpt::system::CTimeLogger & getTimeLogger() const
Gives access to a const-ref to the internal time logger.
bool m_enableConsoleOutput
Enables / disables the console debug output.
std::string holonomic_method
C++ class name of the holonomic navigation method to run in the transformed TP-Space.
Clearance information for one particular PTG and one set of obstacles.
std::vector< double > TP_Obstacles
One distance per discretized alpha value, describing the "polar plot" of TP obstacles.
int target_k
The discrete version of target_alpha.
mrpt::math::LowPassFilter_IIR1 meanExecutionPeriod
Runtime estimation of execution period of the method.
This class extends CAbstractNavigator with the capability of following a list of waypoints.
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
void setHolonomicMethod(const std::string &method, const mrpt::config::CConfigFileBase &cfgBase)
Selects which one from the set of available holonomic methods will be used into transformed TP-Space...
GLdouble s
Definition: glext.h:3682
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: io/CStream.h:28
mrpt::kinematics::CVehicleVelCmd::Ptr m_last_vel_cmd
Last velocity commands.
std::string getAsText() const override
Gets navigation params as a human-readable format.
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
mrpt::math::TPoint2D TP_Target
The Target, in TP-Space (x,y)
void STEP8_GenerateLogRecord(CLogFileRecord &newLogRec, const std::vector< mrpt::math::TPose2D > &relTargets, int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd, int nPTGs, const bool best_is_NOP_cmdvel, const math::TPose2D &rel_cur_pose_wrt_last_vel_cmd_NOP, const math::TPose2D &rel_pose_PTG_origin_wrt_sense_NOP, const double executionTimeValue, const double tim_changeSpeed, const mrpt::system::TTimeStamp &tim_start_iteration)
The struct for configuring navigation requests.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
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...
double speed_scale
[0,1] scale of the raw cmd_vel as generated by the PTG
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
void performNavigationStep() override
The main method for the navigator.
double min_normalized_free_space_for_ptg_continuation
Min normalized dist [0,1] after current pose in a PTG continuation to allow it.
const GLubyte * c
Definition: glext.h:6406
virtual double generate_vel_cmd(const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd)
Return the [0,1] velocity scale of raw PTG cmd_vel.
mrpt::math::LowPassFilter_IIR1 timoff_sendVelCmd_avr
std::string motion_decider_method
C++ class name of the motion chooser.
mrpt::nav::CMultiObjectiveMotionOptimizerBase::Ptr m_multiobjopt
double max_dist_for_timebased_path_prediction
Max dist [meters] to use time-based path prediction for NOP evaluation.
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
void onStartNewNavigation() override
Called whenever a new navigation has been started.
std::unique_ptr< TNavigationParams > m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes.
1-order low-pass IIR filter.
Definition: filters.h:24
GLsizei const GLchar ** string
Definition: glext.h:4116
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
bool m_closing_navigator
Signal that the destructor has been called, so no more calls are accepted from other threads...
virtual 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)=0
Builds TP-Obstacles from Workspace obstacles for the given PTG.
mrpt::math::LowPassFilter_IIR1 timoff_obstacles_avr
double secure_distance_start
In normalized distances, the start and end of a ramp function that scales the velocity output from th...
virtual bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp)=0
Return false on any fatal error.
double speedfilter_tau
Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0:...
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits.
void enable(bool enabled=true)
ClearanceDiagram clearance
Clearance for each path.
virtual void loggingGetWSObstaclesAndShape(CLogFileRecord &out_log)=0
Generates a pointcloud of obstacles, and the robot shape, to be saved in the logging record for the c...
void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
mrpt::io::CStream * m_prev_logfile
The current log file stream, or nullptr if not being used.
double colfreedist_move_k
TP-Obstacles in the move direction at the instant of picking this movement.
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
std::vector< TInfoPerPTG > m_infoPerPTG
Temporary buffers for working with each PTG during a navigationStep()
TAbstractPTGNavigatorParams params_abstract_ptg_navigator
void deleteHolonomicObjects()
Delete m_holonomicMethod.
void build_movement_candidate(CParameterizedTrajectoryGenerator *ptg, const size_t indexPTG, const std::vector< mrpt::math::TPose2D > &relTargets, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense, TInfoPerPTG &ipf, TCandidateMovementPTG &holonomicMovement, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, mrpt::nav::CAbstractHolonomicReactiveMethod &holoMethod, const mrpt::system::TTimeStamp tim_start_iteration, const TNavigationParams &navp=TNavigationParams(), const mrpt::math::TPose2D &relPoseVelCmd_NOP=mrpt::math::TPose2D(0, 0, 0))
void enableKeepLogRecords(bool enable=true)
Enables keeping an internal registry of navigation logs that can be queried with getLastLogRecord() ...
CAbstractPTGBasedReactive(CRobot2NavInterface &react_iterf_impl, bool enableConsoleOutput=true, bool enableLogFile=false, const std::string &logFileDirectory=std::string("./reactivenav.logs"))
Constructor.
bool m_init_done
Whether loadConfigFile() has been called or not.
mrpt::math::LowPassFilter_IIR1 meanTotalExecutionTime
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.
Lightweight 2D pose.
Definition: TPose2D.h:22
bool impl_waypoint_is_reachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const override
Implements the way to waypoint is free function in children classes: true must be returned if...
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i)=0
Gets the i&#39;th PTG.
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & changeCurrentRobotSpeedLimits()
Changes the current, global (honored for all PTGs) robot speed limits, via returning a reference to a...
void enableTimeLog(bool enable=true)
Enables/disables the detailed time logger (default:disabled upon construction) When enabled...
double ref_distance
Maximum distance up to obstacles will be considered (D_{max} in papers).
bool valid_TP
For each PTG, whether target falls into the PTG domain.
The struct for configuring navigation requests to CAbstractPTGBasedReactive and derived classes...
double max_distance_predicted_actual_path
Max distance [meters] to discard current PTG and issue a new vel cmd (default= 0.05) ...
bool isEqual(const CAbstractNavigator::TNavigationParamsBase &o) const override
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
Lightweight 2D point.
Definition: TPoint2D.h:31
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
Parameters that may be used by cmdVel_limits() in any derived classes.
Dynamic state that may affect the PTG path parameterization.
virtual CAbstractHolonomicReactiveMethod * getHoloMethod(int idx)
void calc_move_candidate_scores(TCandidateMovementPTG &holonomicMovement, const std::vector< double > &in_TPObstacles, const mrpt::nav::ClearanceDiagram &in_clearance, const std::vector< mrpt::math::TPose2D > &WS_Targets, const std::vector< PTGTarget > &TP_Targets, CLogFileRecord::TInfoPerPTG &log, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, const mrpt::math::TPose2D &relPoseVelCmd_NOP, const unsigned int ptg_idx4weights, const mrpt::system::TTimeStamp tim_start_iteration, const mrpt::nav::CHolonomicLogFileRecord::Ptr &hlfr)
Scores holonomicMovement.
mrpt::system::CTimeLogger m_timelogger
A complete time logger.
The structure used to store all relevant information about each transformation into TP-Space...
mrpt::math::LowPassFilter_IIR1 tim_changeSpeed_avr
std::vector< size_t > restrict_PTG_indices
(Default=empty) Optionally, a list of PTG indices can be sent such that the navigator will restrict i...
bool m_enableKeepLogRecords
See enableKeepLogRecords.
mrpt::math::LowPassFilter_IIR1 timoff_curPoseAndSpeed_avr
double getTargetApproachSlowDownDistance() const
Returns this parameter for the first inner holonomic navigator instances [m] (should be the same in a...
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...
Stores a candidate movement in TP-Space-based navigation.
std::unique_ptr< TNavigationParams > clone() const override



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019