Main MRPT website > C++ reference
MRPT logo
CPRRTNavigator.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-2014, 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 #ifndef CPRRTNavigator_H
10 #define CPRRTNavigator_H
11 
12 #include <mrpt/system/threads.h>
17 #include <list>
18 
19 namespace mrpt
20 {
21  namespace slam { class CPointsMap; }
22  namespace reactivenav
23  {
24  using namespace mrpt;
25  using namespace mrpt::slam;
26  using namespace mrpt::math;
27  using namespace mrpt::synch;
28  using namespace mrpt::poses;
30 
31  /** This class is a multi-threaded mobile robot navigator, implementing an (anytime) PTG-based Rapidly-exploring Random Tree (PRRT) search algorithm.
32  *
33  * <b>Usage:</b><br>
34  * - Create an instance of the CPRRTNavigator class (an object on the heap, i.e. no 'new', is preferred, but just for the convenience of the user).
35  * - Set all the parameters in CPRRTNavigator::params
36  * - Call CPRRTNavigator::initialize. If all the params are OK, true is returned and you can go on.
37  * - Start a navigation by calling CPRRTNavigator::navigate.
38  * - From your application, you must update all the sensory data (from the real robot or a simulator) on a timely-fashion. The navigator will stop the robot if the last sensory data is too old.
39  *
40  * Note that all the public methods are thread-safe.
41  *
42  * <b>About the algorithm:</b><br>
43  *
44  *
45  *
46  *
47  *
48  * <b>Changes history</b>
49  * - 05/JUL/2009: Creation (JLBC). This is an evolution from leassons learnt from the pure reactive navigator based on PTGs.
50  * \ingroup mrpt_reactivenav_grp
51  */
53  {
54  public:
56 
57  public:
58  CPRRTNavigator(); //!< Constructor
59  virtual ~CPRRTNavigator(); //!< Destructor
60 
61  /** @name Navigation control methods
62  @{*/
63  /** Initialize the navigator using the parameters in "params"; read the usage instructions in CPRRTNavigator.
64  * This method should be called only once at the beginning of the robot operation.
65  * \return true on sucess, false on any error preparing the navigator (and no navigation command will be processed until that's fixed).
66  */
67  bool initialize();
68 
69  /** Starts a navigation to a 2D pose (including a desired heading at the target).
70  * \note CPRRTNavigator::initialize must be called first.
71  */
72  void navigate( const mrpt::math::TPose2D &target_pose);
73 
74  /** Starts a navigation to a given 2D point (any heading at the target).
75  * \note CPRRTNavigator::initialize must be called first.
76  */
77  void navigate( const mrpt::math::TPoint2D &target_point);
78 
79  /** Cancel current navegacion.
80  * \note CPRRTNavigator::initialize must be called first.
81  */
82  void cancel();
83 
84  /** Continues with suspended navigation.
85  * \sa suspend
86  * \note CPRRTNavigator::initialize must be called first.
87  */
88  void resume();
89 
90  /** Suspend current navegation
91  * \sa resume
92  * \note CPRRTNavigator::initialize must be called first.
93  */
94  void suspend();
95 
96  /** @} */
97 
98  /** @name Navigator data structures
99  @{*/
100  /** Each data point in m_planned_path */
102  {
104  p(0,0,0),
105  max_v(0.1),max_w(0.2),
106  trg_v(0.1)
107  {}
108 
109  TPose2D p; //!< Coordinates are "global"
110  double max_v, max_w; //!< Maximum velocities along this path segment.
111  double trg_v; //!< Desired linear velocity at the target point, ie: the robot should program its velocities such as after this arc the speeds are the given ones.
112  };
113 
114  typedef std::list<TPathData> TPlannedPath; //!< An ordered list of path poses.
115 
117  {
118  public:
119  TOptions(); //!< Initial values
120 
121  /** This method load the options from a ".ini"-like file or memory-stored string list.
122  */
123  void loadFromConfigFile(
124  const mrpt::utils::CConfigFileBase &source,
125  const std::string &section);
126 
127  /** This method displays clearly all the contents of the structure in textual form, sending it to a CStream. */
128  void dumpToTextStream( CStream &out) const;
129 
130  // Data:
131  double absolute_max_v; //!< Max linear speed (m/s)
132  double absolute_max_w; //!< Max angular speed (rad/s)
133  double max_accel_v; //!< Max desired linear speed acceleration (m/s^2)
134  double max_accel_w; //!< Max desired angular speed acceleration (rad/s^2)
135 
136  double max_age_observations; //!< Max age (in seconds) for an observation to be considered invalid for navigation purposes.
137 
138  /** The robot shape used when computing collisions; it's loaded from the
139  * config file/text as a single 2xN matrix in MATLAB format, first row are Xs, second are Ys, e.g:
140  * \code
141  * robot_shape = [-0.2 0.2 0.2 -0.2; -0.1 -0.1 0.1 0.1]
142  * \endcode
143  */
145 
147  {
148  double radius_checkpoints; //!< Radius of each checkpoint in the path, ie: when the robot get closer than this distance, the point is considered as visited and the next one is processed.
149  };
151 
153  {
154  double max_time_expend_planning; //!< Maximum time to spend when planning, in seconds.
155  };
157 
158  };
159 
160  TOptions params; //!< Change here all the parameters of the navigator.
161 
162  /** @} */
163 
164  /** @name Debug and logging
165  @{*/
166  /** Manually sets the short-time path to be followed by the robot (use 'navigate' instead, this method is for debugging mainly)
167  */
168  void setPathToFollow(const TPlannedPath &path );
169 
170  /** Returns the current planned path the robot is following */
171  void getCurrentPlannedPath(TPlannedPath &path ) const;
172 
173 
174  /** @} */
175 
176 
177  /** @name Sensory data methods: call them to update the navigator knowledge on the outside world.
178  @{*/
179  /** Updates the navigator with a low or high-rate estimate from a localization (or SLAM) algorithm running somewhere else.
180  * \param new_robot_pose The (global) coordinates of the mean robot pose as estimated by some external module.
181  * \param new_robot_cov The 3x3 covariance matrix of that estimate.
182  * \param timestamp The associated timestamp of the data.
183  */
184  void processNewLocalization(const TPose2D &new_robot_pose, const CMatrixDouble33 &new_robot_cov, TTimeStamp timestamp );
185 
186  /** Updates the navigator with high-rate odometry from the mobile base.
187  * The odometry poses are dealed internally as increments only, so there is no problem is
188  * arbitrary mismatches between localization (from a particle filter or SLAM) and the odometry.
189  * \param newOdoPose The global, cummulative odometry as computed by the robot.
190  * \param timestamp The associated timestamp of the measurement.
191  * \param hasVelocities If false, the next arguments are ignored.
192  * \param v Measured linear speed, in m/s.
193  * \param w Measured angular speed, in rad/s.
194  */
195  void processNewOdometryInfo( const TPose2D &newOdoPose, TTimeStamp timestamp, bool hasVelocities =false, float v =0, float w=0 );
196 
197  /** Must be called in a timely fashion to let the navigator know about the obstacles in the environment.
198  * \param obstacles
199  * \param timestamp The associated timestamp of the sensed points.
200  */
201  void processNewObstaclesData(const mrpt::slam::CPointsMap* obstacles, TTimeStamp timestamp );
202 
203  /** @} */
204 
205  /** @name Virtual methods to be implemented by the user.
206  @{*/
207  /** This is the most important method the user must provide: to send an instantaneous velocity command to the robot.
208  * \param v Desired linear speed, in meters/second.
209  * \param w Desired angular speed, in rads/second.
210  * \return false on any error. In that case, the navigator will immediately stop the navigation and announce the error.
211  */
212  virtual bool onMotionCommand(float v, float w ) = 0;
213 
214  /** Re-implement this method if you want to know when a new navigation has started.
215  */
216  virtual void onNavigationStart( ) { }
217 
218  /** Re-implement this method if you want to know when and why a navigation has ended.
219  * \param targetReachedOK Will be false if the navigation failed.
220  */
221  virtual void onNavigationEnd( bool targetReachedOK ) {
222  MRPT_UNUSED_PARAM(targetReachedOK);
223  }
224 
225  /** Re-implement this method if you want to know when the robot is approaching the target:
226  * this event is raised before onNavigationEnd, when the robot is closer than a certain distance to the target.
227  */
228  virtual void onApproachingTarget( ) { }
229 
230  /** @} */
231 
232  static const double INVALID_HEADING; //!< Used to refer to undefined or "never mind" headings values.
233 
234  private:
235  // ----------- Internal methods & threads -----------
236 
240 
241  void thread_planner(); //!< Thread function
242  void thread_test_collision(); //!< Thread function
243  void thread_path_tracking(); //!< Thread function
244 
245 
246  // ----------- Internal data -----------
247 
248  bool m_initialized; //!< The object is ready to navigate. Users must call "initialize" first.
249  bool m_closingThreads; //!< set to true at destructor.
250 
251  TPose2D m_target_pose; //!< Heading may be INVALID_HEADING to indicate "don't mind"
254 
255  // Instead of a CSimplePointsMap, just store the X & Y vectors, since
256  // this is a temporary variable. We'll let the planning thread to build
257  // a CSimplePointsMap object with these points.
258  //mrpt::slam::CSimplePointsMap m_last_obstacles;
259  std::vector<float> m_last_obstacles_x,m_last_obstacles_y;
262 
263  // The planned path, to be followed:
265  TTimeStamp m_planned_path_time; //!< The last modification time. INVALID_TIMESTAMP means there is no path.
266  TPlannedPath m_planned_path;
267 
268  /** The list of PTGs used by the anytime planner to explore the free-space. */
271 
272  public:
273 
274  mrpt::poses::CRobot2DPoseEstimator m_robotStateFilter; //!< Object maintained by the robot-tracking thread (All methods are thread-safe).
275 
276 
277 
278  };
279  }
280 }
281 
282 
283 #endif
284 
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:30
double absolute_max_v
Max linear speed (m/s)
mrpt::system::TThreadHandle m_thr_testcol
Thread handle.
double max_accel_v
Max desired linear speed acceleration (m/s^2)
This class provides simple critical sections functionality.
bool m_initialized
The object is ready to navigate. Users must call "initialize" first.
double max_w
Maximum velocities along this path segment.
mrpt::system::TThreadHandle m_thr_planner
Thread handle.
virtual void onNavigationStart()
Re-implement this method if you want to know when a new navigation has started.
TPose2D m_target_pose
Heading may be INVALID_HEADING to indicate "don't mind".
#define MRPT_MAKE_ALIGNED_OPERATOR_NEW
Definition: memory.h:112
virtual void onNavigationEnd(bool targetReachedOK)
Re-implement this method if you want to know when and why a navigation has ended. ...
double absolute_max_w
Max angular speed (rad/s)
bool m_closingThreads
set to true at destructor.
A simple filter to estimate and extrapolate the robot 2D (x,y,phi) pose from asynchronous odometry an...
virtual void onApproachingTarget()
Re-implement this method if you want to know when the robot is approaching the target: this event is ...
TPolygon2D robot_shape
The robot shape used when computing collisions; it's loaded from the config file/text as a single 2xN...
double max_accel_w
Max desired angular speed acceleration (rad/s^2)
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
TPose2D p
Coordinates are "global".
This class allows loading and storing values and vectors of different types from a configuration text...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArray.h:18
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
std::vector< mrpt::reactivenav::CParameterizedTrajectoryGenerator * > TListPTGs
A type for lists of PTGs.
static const double INVALID_HEADING
Used to refer to undefined or "never mind" headings values.
std::vector< float > m_last_obstacles_y
double max_time_expend_planning
Maximum time to spend when planning, in seconds.
This namespace provides multitask, synchronization utilities.
Definition: atomic_incr.h:18
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
double radius_checkpoints
Radius of each checkpoint in the path, ie: when the robot get closer than this distance, the point is considered as visited and the next one is processed.
This class is a multi-threaded mobile robot navigator, implementing an (anytime) PTG-based Rapidly-ex...
Each data point in m_planned_path.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
TOptions params
Change here all the parameters of the navigator.
This structure contains the information needed to interface the threads API on each platform: ...
Definition: threads.h:25
mrpt::poses::CRobot2DPoseEstimator m_robotStateFilter
Object maintained by the robot-tracking thread (All methods are thread-safe).
Lightweight 2D pose.
mrpt::system::TThreadHandle m_thr_pathtrack
Thread handle.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:59
double max_age_observations
Max age (in seconds) for an observation to be considered invalid for navigation purposes.
std::list< TPathData > TPlannedPath
An ordered list of path poses.
double trg_v
Desired linear velocity at the target point, ie: the robot should program its velocities such as afte...
Lightweight 2D point.
TTimeStamp m_planned_path_time
The last modification time. INVALID_TIMESTAMP means there is no path.
2D polygon, inheriting from std::vector.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
TListPTGs m_PTGs
The list of PTGs used by the anytime planner to explore the free-space.



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014