Main MRPT website > C++ reference for MRPT 1.5.6
CWaypointsNavigator.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #pragma once
10 
13 
14 namespace mrpt
15 {
16  namespace nav
17  {
18  /** This class extends `CAbstractNavigator` with the capability of following a list of waypoints. By default, waypoints are followed one by one,
19  * but, if they are tagged with `allow_skip=true` **and** the derived navigator class supports it, the navigator may choose to skip some to
20  * make a smoother, safer and shorter navigation.
21  *
22  * Waypoints have an optional `target_heading` field, which will be honored only for waypoints that are skipped, and if the underlying robot
23  * interface supports the pure-rotation methods.
24  *
25  * Notes on navigation status and event dispatchment:
26  * - Navigation state may briefly pass by the `IDLE` status between a waypoint is reached and a new navigation command is issued towards the next waypoint.
27  * - `sendNavigationEndEvent()` will be called only when the last waypoint is reached.
28  * - Reaching an intermediary waypoint (or skipping it if considered so by the navigator) generates a call to `sendWaypointReachedEvent()` instead.
29  *
30  * \sa Base class CAbstractNavigator, CWaypointsNavigator::navigateWaypoints(), and derived classes.
31  * \ingroup nav_reactive
32  */
34  {
35  public:
36  /** The struct for configuring navigation requests to CWaypointsNavigator and derived classes. */
38  {
39  /** If not empty, this will prevail over the base class single goal target.
40  * Semantic is: any of these targets will be good for heading the robot towards them,
41  * but the priority is for the latest ones in the sequence. */
42  std::vector<mrpt::nav::CAbstractNavigator::TargetInfo> multiple_targets;
43 
44  virtual std::string getAsText() const MRPT_OVERRIDE;
45  virtual TNavigationParams* clone() const MRPT_OVERRIDE { return new TNavigationParamsWaypoints(*this); }
46  protected:
47  virtual bool isEqual(const CAbstractNavigator::TNavigationParamsBase& o) const MRPT_OVERRIDE;
48  };
49 
50  CWaypointsNavigator( CRobot2NavInterface &robot_interface_impl ); //!< ctor
51  virtual ~CWaypointsNavigator(); //!< dtor
52 
53  // Overriden to call the general navigationStep(), plus waypoint selection logic.
54  virtual void navigationStep() MRPT_OVERRIDE;
55  virtual void cancel() MRPT_OVERRIDE; //!< Cancel current navegation.
56 
57  /** \name Waypoint navigation control API
58  * @{ */
59 
60  /** Waypoint navigation request. This immediately cancels any other previous on-going navigation.
61  * \sa CAbstractNavigator::navigate() for single waypoint navigation requests.
62  */
63  virtual void navigateWaypoints( const TWaypointSequence & nav_request );
64 
65  /** Get a copy of the control structure which describes the progress status of the waypoint navigation. */
66  virtual void getWaypointNavStatus(TWaypointStatusSequence & out_nav_status) const;
67 
68  /** Get a copy of the control structure which describes the progress status of the waypoint navigation. */
69  TWaypointStatusSequence getWaypointNavStatus() const {
70  TWaypointStatusSequence nav_status;
71  this->getWaypointNavStatus(nav_status);
72  return nav_status;
73  }
74  /** @}*/
75 
76  /** Returns `true` if, according to the information gathered at the last navigation step,
77  * there is a free path to the given point; `false` otherwise: if way is blocked or there is missing information,
78  * the point is out of range for the existing PTGs, etc. */
79  bool isRelativePointReachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const;
80 
82  {
83  double max_distance_to_allow_skip_waypoint; //!< In meters. <0: unlimited
84  int min_timesteps_confirm_skip_waypoints; //!< How many times shall a future waypoint be seen as reachable to skip to it (Default: 1)
85  double waypoint_angle_tolerance; //!< [rad] Angular error tolerance for waypoints with an assigned heading (Default: 5 deg)
86  double rel_speed_for_stop_waypoints; //!< [0,1] Relative speed when aiming at a stop-point waypoint (Default=0.10)
87  int multitarget_look_ahead; //!< >=0 number of waypoints to forward to the underlying navigation engine, to ease obstacles avoidance when a waypoint is blocked (Default=0 : none).
88 
89  virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &c, const std::string &s) MRPT_OVERRIDE;
90  virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &c, const std::string &s) const MRPT_OVERRIDE;
92  };
93 
95 
96  virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) MRPT_OVERRIDE; // See base class docs!
97  virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const MRPT_OVERRIDE; // See base class docs!
98 
99  protected:
100  TWaypointStatusSequence m_waypoint_nav_status; //!< The latest waypoints navigation command and the up-to-date control status.
102 
103  /** Implements the way to waypoint is free function in children classes: `true` must be returned
104  * if, according to the information gathered at the last navigation step, there is a free path to
105  * the given point; `false` otherwise: if way is blocked or there is missing information, the point is out of range, etc. */
106  virtual bool impl_waypoint_is_reachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const = 0;
107 
108  virtual void onStartNewNavigation() MRPT_OVERRIDE;
109  virtual void onNavigateCommandReceived() MRPT_OVERRIDE;
110 
111  virtual bool checkHasReachedTarget(const double targetDist) const MRPT_OVERRIDE;
112  virtual void waypoints_navigationStep(); //!< The waypoints-specific part of navigationStep()
113 
114  bool waypoints_isAligning() const { return m_is_aligning; }
115 
116  private:
117  bool m_was_aligning; //!< Whether the last timestep was "is_aligning" in a waypoint with heading
120 
121  };
122  }
123 }
Recursive mutex: allow recursive locks by the owner thread.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:30
bool m_was_aligning
Whether the last timestep was "is_aligning" in a waypoint with heading.
TWaypointStatusSequence m_waypoint_nav_status
The latest waypoints navigation command and the up-to-date control status.
std::vector< mrpt::nav::CAbstractNavigator::TargetInfo > multiple_targets
If not empty, this will prevail over the base class single goal target.
double waypoint_angle_tolerance
[rad] Angular error tolerance for waypoints with an assigned heading (Default: 5 deg) ...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Base for all high-level navigation commands.
TWaypointsNavigatorParams params_waypoints_navigator
This class extends CAbstractNavigator with the capability of following a list of waypoints.
The struct for requesting navigation requests for a sequence of waypoints.
Definition: TWaypoint.h:71
GLdouble s
Definition: glext.h:3602
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
This class allows loading and storing values and vectors of different types from a configuration text...
double max_distance_to_allow_skip_waypoint
In meters. <0: unlimited.
The struct for configuring navigation requests.
const GLubyte * c
Definition: glext.h:5590
The struct for querying the status of waypoints navigation.
Definition: TWaypoint.h:103
mrpt::system::TTimeStamp m_last_alignment_cmd
mrpt::synch::CCriticalSectionRecursive m_nav_waypoints_cs
GLsizei const GLchar ** string
Definition: glext.h:3919
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
int min_timesteps_confirm_skip_waypoints
How many times shall a future waypoint be seen as reachable to skip to it (Default: 1) ...
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
double rel_speed_for_stop_waypoints
[0,1] Relative speed when aiming at a stop-point waypoint (Default=0.10)
Lightweight 2D point.
This is the base class for any reactive/planned navigation system.
int multitarget_look_ahead
>=0 number of waypoints to forward to the underlying navigation engine, to ease obstacles avoidance w...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...



Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019