9 #ifndef CPRRTNavigator_H
10 #define CPRRTNavigator_H
21 namespace slam {
class CPointsMap; }
105 max_v(0.1),max_w(0.2),
123 void loadFromConfigFile(
125 const std::string §ion);
128 void dumpToTextStream(
CStream &out)
const;
168 void setPathToFollow(
const TPlannedPath &path );
171 void getCurrentPlannedPath(TPlannedPath &path )
const;
195 void processNewOdometryInfo(
const TPose2D &newOdoPose,
TTimeStamp timestamp,
bool hasVelocities =
false,
float v =0,
float w=0 );
212 virtual bool onMotionCommand(
float v,
float w ) = 0;
241 void thread_planner();
242 void thread_test_collision();
243 void thread_path_tracking();
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
double absolute_max_v
Max linear speed (m/s)
mrpt::system::TThreadHandle m_thr_testcol
Thread handle.
CCriticalSection m_PTGs_cs
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.
TPlannedPath m_planned_path
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.
CCriticalSection m_planned_path_cs
TPose2D m_target_pose
Heading may be INVALID_HEADING to indicate "don't mind".
#define MRPT_MAKE_ALIGNED_OPERATOR_NEW
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...
TPathTrackingOpts pathtrack
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...
TTimeStamp m_last_obstacles_time
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
CCriticalSection m_last_obstacles_cs
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.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
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.
#define REACTIVENAV_IMPEXP
TOptions params
Change here all the parameters of the navigator.
This structure contains the information needed to interface the threads API on each platform: ...
mrpt::poses::CRobot2DPoseEstimator m_robotStateFilter
Object maintained by the robot-tracking thread (All methods are thread-safe).
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...
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...
TTimeStamp m_target_pose_time
TTimeStamp m_planned_path_time
The last modification time. INVALID_TIMESTAMP means there is no path.
CCriticalSection m_target_pose_cs
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.