00001 /* +---------------------------------------------------------------------------+ 00002 | The Mobile Robot Programming Toolkit (MRPT) C++ library | 00003 | | 00004 | http://mrpt.sourceforge.net/ | 00005 | | 00006 | Copyright (C) 2005-2009 University of Malaga | 00007 | | 00008 | This software was written by the Perception and Robotics | 00009 | research group, University of Malaga (Spain). | 00010 | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> | 00011 | | 00012 | This file is part of the MRPT project. | 00013 | | 00014 | MRPT is free software: you can redistribute it and/or modify | 00015 | it under the terms of the GNU General Public License as published by | 00016 | the Free Software Foundation, either version 3 of the License, or | 00017 | (at your option) any later version. | 00018 | | 00019 | MRPT is distributed in the hope that it will be useful, | 00020 | but WITHOUT ANY WARRANTY; without even the implied warranty of | 00021 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | 00022 | GNU General Public License for more details. | 00023 | | 00024 | You should have received a copy of the GNU General Public License | 00025 | along with MRPT. If not, see <http://www.gnu.org/licenses/>. | 00026 | | 00027 +---------------------------------------------------------------------------+ */ 00028 #ifndef CPRRTNavigator_H 00029 #define CPRRTNavigator_H 00030 00031 #include <mrpt/slam.h> 00032 #include <mrpt/poses.h> 00033 #include <mrpt/synch.h> 00034 #include <mrpt/system/os.h> 00035 #include <mrpt/bayes/CKalmanFilterCapable.h> 00036 #include <mrpt/reactivenav/CParameterizedTrajectoryGenerator.h> 00037 00038 #include <mrpt/reactivenav/link_pragmas.h> 00039 00040 namespace mrpt 00041 { 00042 namespace reactivenav 00043 { 00044 using namespace mrpt; 00045 using namespace mrpt::slam; 00046 using namespace mrpt::math; 00047 using namespace mrpt::synch; 00048 using namespace mrpt::poses; 00049 00050 /** This class is a multi-threaded mobile robot navigator, implementing an (anytime) PTG-based Rapidly-exploring Random Tree (PRRT) search algorithm. 00051 * 00052 * <b>Usage:</b><br> 00053 * - 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). 00054 * - Set all the parameters in CPRRTNavigator::params 00055 * - Call CPRRTNavigator::initialize. If all the params are OK, true is returned and you can go on. 00056 * - Start a navigation by calling CPRRTNavigator::navigate. 00057 * - 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. 00058 * 00059 * Note that all the public methods are thread-safe. 00060 * 00061 * <b>About the algorithm:</b><br> 00062 * 00063 * 00064 * 00065 * 00066 * 00067 * <b>Changes history</b> 00068 * - 05/JUL/2009: Creation (JLBC). This is an evolution from leassons learnt from the pure reactive navigator based on PTGs. 00069 */ 00070 class RNAVDLLIMPEXP CPRRTNavigator 00071 { 00072 public: 00073 CPRRTNavigator(); //!< Constructor 00074 virtual ~CPRRTNavigator(); //!< Destructor 00075 00076 /** @name Navigation control methods 00077 @{*/ 00078 /** Initialize the navigator using the parameters in "params"; read the usage instructions in CPRRTNavigator. 00079 * This method should be called only once at the beginning of the robot operation. 00080 * \return true on sucess, false on any error preparing the navigator (and no navigation command will be processed until that's fixed). 00081 */ 00082 bool initialize(); 00083 00084 /** Starts a navigation to a 2D pose (including a desired heading at the target). 00085 * \note CPRRTNavigator::initialize must be called first. 00086 */ 00087 void navigate( const mrpt::math::TPose2D &target_pose); 00088 00089 /** Starts a navigation to a given 2D point (any heading at the target). 00090 * \note CPRRTNavigator::initialize must be called first. 00091 */ 00092 void navigate( const mrpt::math::TPoint2D &target_point); 00093 00094 /** Cancel current navegacion. 00095 * \note CPRRTNavigator::initialize must be called first. 00096 */ 00097 void cancel(); 00098 00099 /** Continues with suspended navigation. 00100 * \sa suspend 00101 * \note CPRRTNavigator::initialize must be called first. 00102 */ 00103 void resume(); 00104 00105 /** Suspend current navegation 00106 * \sa resume 00107 * \note CPRRTNavigator::initialize must be called first. 00108 */ 00109 void suspend(); 00110 00111 /** @} */ 00112 00113 /** @name Navigator data structures 00114 @{*/ 00115 /** Each data point in m_planned_path */ 00116 struct RNAVDLLIMPEXP TPathData 00117 { 00118 TPathData() : 00119 p(0,0,0), 00120 max_v(0.1),max_w(0.2), 00121 trg_v(0.1) 00122 {} 00123 00124 TPose2D p; //!< Coordinates are "global" 00125 double max_v, max_w; //!< Maximum velocities along this path segment. 00126 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. 00127 }; 00128 00129 typedef std::list<TPathData> TPlannedPath; //!< An ordered list of path poses. 00130 00131 class RNAVDLLIMPEXP TOptions : public mrpt::utils::CLoadableOptions 00132 { 00133 public: 00134 TOptions(); //!< Initial values 00135 00136 /** This method load the options from a ".ini"-like file or memory-stored string list. 00137 */ 00138 void loadFromConfigFile( 00139 const mrpt::utils::CConfigFileBase &source, 00140 const std::string §ion); 00141 00142 /** This method displays clearly all the contents of the structure in textual form, sending it to a CStream. */ 00143 void dumpToTextStream( CStream &out) const; 00144 00145 // Data: 00146 double absolute_max_v; //!< Max linear speed (m/s) 00147 double absolute_max_w; //!< Max angular speed (rad/s) 00148 double max_accel_v; //!< Max desired linear speed acceleration (m/s^2) 00149 double max_accel_w; //!< Max desired angular speed acceleration (rad/s^2) 00150 00151 double max_age_observations; //!< Max age (in seconds) for an observation to be considered invalid for navigation purposes. 00152 00153 /** The robot shape used when computing collisions; it's loaded from the 00154 * config file/text as a single 2xN matrix in MATLAB format, first row are Xs, second are Ys, e.g: 00155 * \code 00156 * robot_shape = [-0.2 0.2 0.2 -0.2; -0.1 -0.1 0.1 0.1] 00157 * \endcode 00158 */ 00159 TPolygon2D robot_shape; 00160 00161 struct RNAVDLLIMPEXP TPathTrackingOpts 00162 { 00163 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. 00164 }; 00165 TPathTrackingOpts pathtrack; 00166 00167 struct RNAVDLLIMPEXP TPlannerOpts 00168 { 00169 double max_time_expend_planning; //!< Maximum time to spend when planning, in seconds. 00170 }; 00171 TPlannerOpts planner; 00172 00173 }; 00174 00175 TOptions params; //!< Change here all the parameters of the navigator. 00176 00177 /** @} */ 00178 00179 /** @name Debug and logging 00180 @{*/ 00181 /** Manually sets the short-time path to be followed by the robot (use 'navigate' instead, this method is for debugging mainly) 00182 */ 00183 void setPathToFollow(const TPlannedPath &path ); 00184 00185 /** Returns the current planned path the robot is following */ 00186 void getCurrentPlannedPath(TPlannedPath &path ) const; 00187 00188 00189 /** @} */ 00190 00191 00192 /** @name Sensory data methods: call them to update the navigator knowledge on the outside world. 00193 @{*/ 00194 /** Updates the navigator with a low or high-rate estimate from a localization (or SLAM) algorithm running somewhere else. 00195 * \param new_robot_pose The (global) coordinates of the mean robot pose as estimated by some external module. 00196 * \param new_robot_cov The 3x3 covariance matrix of that estimate. 00197 * \param timestamp The associated timestamp of the data. 00198 */ 00199 void processNewLocalization(const TPose2D &new_robot_pose, const CMatrixDouble33 &new_robot_cov, TTimeStamp timestamp ); 00200 00201 /** Updates the navigator with high-rate odometry from the mobile base. 00202 * The odometry poses are dealed internally as increments only, so there is no problem is 00203 * arbitrary mismatches between localization (from a particle filter or SLAM) and the odometry. 00204 * \param newOdoPose The global, cummulative odometry as computed by the robot. 00205 * \param timestamp The associated timestamp of the measurement. 00206 * \param hasVelocities If false, the next arguments are ignored. 00207 * \param v Measured linear speed, in m/s. 00208 * \param w Measured angular speed, in rad/s. 00209 */ 00210 void processNewOdometryInfo( const TPose2D &newOdoPose, TTimeStamp timestamp, bool hasVelocities =false, float v =0, float w=0 ); 00211 00212 /** Must be called in a timely fashion to let the navigator know about the obstacles in the environment. 00213 * \param obstacles 00214 * \param timestamp The associated timestamp of the sensed points. 00215 */ 00216 void processNewObstaclesData(const mrpt::slam::CPointsMap* obstacles, TTimeStamp timestamp ); 00217 00218 /** @} */ 00219 00220 /** @name Virtual methods to be implemented by the user. 00221 @{*/ 00222 /** This is the most important method the user must provide: to send an instantaneous velocity command to the robot. 00223 * \param v Desired linear speed, in meters/second. 00224 * \param w Desired angular speed, in rads/second. 00225 * \return false on any error. In that case, the navigator will immediately stop the navigation and announce the error. 00226 */ 00227 virtual bool onMotionCommand(float v, float w ) = 0; 00228 00229 /** Re-implement this method if you want to know when a new navigation has started. 00230 */ 00231 virtual void onNavigationStart( ) { } 00232 00233 /** Re-implement this method if you want to know when and why a navigation has ended. 00234 * \param targetReachedOK Will be false if the navigation failed. 00235 */ 00236 virtual void onNavigationEnd( bool targetReachedOK ) { } 00237 00238 /** Re-implement this method if you want to know when the robot is approaching the target: 00239 * this event is raised before onNavigationEnd, when the robot is closer than a certain distance to the target. 00240 */ 00241 virtual void onApproachingTarget( ) { } 00242 00243 /** @} */ 00244 00245 static const double INVALID_HEADING; //!< Used to refer to undefined or "never mind" headings values. 00246 00247 private: 00248 // ----------- Internal methods & threads ----------- 00249 00250 TThreadHandle m_thr_planner; //!< Thread handle 00251 TThreadHandle m_thr_testcol; //!< Thread handle 00252 TThreadHandle m_thr_pathtrack; //!< Thread handle 00253 00254 static void thread_planner(void *obj); //!< Thread function 00255 static void thread_test_collision(void *obj); //!< Thread function 00256 static void thread_path_tracking(void *obj); //!< Thread function 00257 00258 00259 // ----------- Internal data ----------- 00260 00261 bool m_initialized; //!< The object is ready to navigate. Users must call "initialize" first. 00262 bool m_closingThreads; //!< set to true at destructor. 00263 00264 TPose2D m_target_pose; //!< Heading may be INVALID_HEADING to indicate "don't mind" 00265 TTimeStamp m_target_pose_time; 00266 CCriticalSection m_target_pose_cs; 00267 00268 // Instead of a CSimplePointsMap, just store the X & Y vectors, since 00269 // this is a temporary variable. We'll let the planning thread to build 00270 // a CSimplePointsMap object with these points. 00271 //mrpt::slam::CSimplePointsMap m_last_obstacles; 00272 vector_float m_last_obstacles_x,m_last_obstacles_y; 00273 TTimeStamp m_last_obstacles_time; 00274 CCriticalSection m_last_obstacles_cs; 00275 00276 // The planned path, to be followed: 00277 CCriticalSection m_planned_path_cs; 00278 TTimeStamp m_planned_path_time; //!< The last modification time. INVALID_TIMESTAMP means there is no path. 00279 TPlannedPath m_planned_path; 00280 00281 /** The list of PTGs used by the anytime planner to explore the free-space. */ 00282 TListPTGs m_PTGs; 00283 CCriticalSection m_PTGs_cs; 00284 00285 /** The filter that estimates and extrapolates the robot pose from odometry and localization data 00286 * The implemented model is a state vector: 00287 * - (x,y,phi,v,w) 00288 * for the robot pose (x,y,phi) and velocities (v,w). 00289 * 00290 * The filter can be asked for an extrapolation for some arbitrary time "t'", and it'll do a simple linear prediction. 00291 * All methods are thread-safe. 00292 */ 00293 class RNAVDLLIMPEXP CRobotStateEstimator 00294 { 00295 public: 00296 CRobotStateEstimator( ); //!< Default constructor 00297 virtual ~CRobotStateEstimator(); //!< Destructor 00298 void reset(); 00299 00300 /** Updates the filter so the pose is tracked to the current time */ 00301 void processUpdateNewPoseLocalization( 00302 const TPose2D &newPose, 00303 const CMatrixDouble33 &newPoseCov, 00304 TTimeStamp cur_tim); 00305 00306 /** Updates the filter so the pose is tracked to the current time */ 00307 void processUpdateNewOdometry( 00308 const TPose2D &newGlobalOdometry, 00309 TTimeStamp cur_tim, 00310 bool hasVelocities = false, 00311 float v = 0, 00312 float w = 0); 00313 00314 /** Get the current estimate, obtained as: 00315 * 00316 * last_loc (+) [ last_odo (-) odo_ref ] (+) extrapolation_from_vw 00317 * 00318 * \return true is the estimate can be trusted. False if the real observed data is too old or there is no valid data yet. 00319 */ 00320 bool getCurrentEstimate( TPose2D &pose, float &v, float &w, TTimeStamp tim_query = mrpt::system::now() ); 00321 00322 struct TOptions 00323 { 00324 TOptions() : 00325 max_odometry_age ( 1.0 ), 00326 max_localiz_age ( 4.0 ) 00327 {} 00328 00329 double max_odometry_age; //!< To consider data old, in seconds 00330 double max_localiz_age; //!< To consider data old, in seconds 00331 }; 00332 00333 TOptions params; //!< parameters of the filter. 00334 00335 private: 00336 mrpt::synch::CCriticalSection m_cs; 00337 00338 TTimeStamp m_last_loc_time; 00339 TPose2D m_last_loc; //!< Last pose as estimated by the localization/SLAM subsystem. 00340 CMatrixDouble33 m_last_loc_cov; 00341 00342 TPose2D m_loc_odo_ref; //!< The interpolated odometry position for the last "m_robot_pose" (used as "coordinates base" for subsequent odo readings) 00343 00344 TTimeStamp m_last_odo_time; 00345 TPose2D m_last_odo; 00346 float m_robot_v; 00347 float m_robot_w; 00348 00349 /** An auxiliary method to extrapolate the pose of a robot located at "p" with velocities (v,w) after a time delay "delta_time". 00350 */ 00351 static void extrapolateRobotPose( 00352 const TPose2D &p, 00353 const float v, 00354 const float w, 00355 const double delta_time, 00356 TPose2D &new_p); 00357 00358 }; // end of CRobotStateEstimator 00359 00360 public: 00361 CRobotStateEstimator m_robotStateFilter; //!< Object maintained by the robot-tracking thread (All methods are thread-safe). 00362 00363 00364 00365 }; 00366 } 00367 } 00368 00369 00370 #endif 00371
Page generated by Doxygen 1.6.1 for MRPT 0.7.1 SVN: at Tue Dec 22 08:29:35 CET 2009 |