MRPT  1.9.9
CAbstractNavigator.cpp
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 
10 #include "nav-precomp.h" // Precomp header
11 
13 #include <mrpt/math/TSegment2D.h>
15 #include <limits>
16 #include <typeinfo>
17 
18 using namespace mrpt::nav;
19 using namespace std;
20 
21 const double PREVIOUS_POSES_MAX_AGE = 20; // seconds
22 
23 // Ctor: CAbstractNavigator::TargetInfo
25  : target_coords(0, 0, 0), target_frame_id("map")
26 
27 {
28 }
29 
30 // Gets navigation params as a human-readable format:
32 {
33  string s;
34  s += mrpt::format(
35  "target_coords = (%.03f,%.03f,%.03f deg)\n", target_coords.x,
36  target_coords.y, target_coords.phi);
37  s += mrpt::format("target_frame_id = \"%s\"\n", target_frame_id.c_str());
38  s += mrpt::format("targetAllowedDistance = %.03f\n", targetAllowedDistance);
39  s += mrpt::format(
40  "targetIsRelative = %s\n", targetIsRelative ? "YES" : "NO");
41  s += mrpt::format(
42  "targetIsIntermediaryWaypoint = %s\n",
43  targetIsIntermediaryWaypoint ? "YES" : "NO");
44  s += mrpt::format("targetDesiredRelSpeed = %.02f\n", targetDesiredRelSpeed);
45  return s;
46 }
47 
49  const TargetInfo& o) const
50 {
51  return target_coords == o.target_coords &&
52  target_frame_id == o.target_frame_id &&
53  targetAllowedDistance == o.targetAllowedDistance &&
54  targetIsRelative == o.targetIsRelative &&
55  targetDesiredRelSpeed == o.targetDesiredRelSpeed &&
56  targetIsIntermediaryWaypoint == o.targetIsIntermediaryWaypoint;
57 }
58 
59 // Gets navigation params as a human-readable format:
61 {
62  string s;
63  s += "navparams. Single target:\n";
64  s += target.getAsText();
65  return s;
66 }
67 
70 {
71  auto* rhs = dynamic_cast<const CAbstractNavigator::TNavigationParams*>(&o);
72  return (rhs != nullptr) && (this->target == rhs->target);
73 }
74 
76  : pose(0, 0, 0),
77  velGlobal(0, 0, 0),
78  velLocal(0, 0, 0),
79  rawOdometry(0, 0, 0),
80  timestamp(INVALID_TIMESTAMP),
81  pose_frame_id()
82 {
83 }
84 
85 /*---------------------------------------------------------------
86  Constructor
87  ---------------------------------------------------------------*/
89  : mrpt::system::COutputLogger("MRPT_navigator"),
94  m_robot(react_iterf_impl),
95  m_curPoseVel(),
97  m_latestPoses(),
99  m_timlog_delays(true, "CAbstractNavigator::m_timlog_delays")
100 {
104 }
105 
106 // Dtor:
108 /** \callergraph */
110 {
111  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
112  MRPT_LOG_DEBUG("CAbstractNavigator::cancel() called.");
114  this->stop(false /*not emergency*/);
115 }
116 
117 /** \callergraph */
119 {
120  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
121 
122  MRPT_LOG_DEBUG("[CAbstractNavigator::resume() called.");
124 }
125 
126 /** \callergraph */
128 {
129  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
130 
131  // Issue an "stop" if we are moving:
132  // Update: do it *always*, even if the current velocity is zero, since
133  // we may be in the middle of a multi-part motion command. It's safer.
134  this->stop(false /*not an emergency stop*/);
135 
136  MRPT_LOG_DEBUG("CAbstractNavigator::suspend() called.");
138 }
139 
140 /** \callergraph */
142 {
143  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
144 
145  MRPT_LOG_DEBUG("CAbstractNavigator::resetNavError() called.");
147  {
150  }
151 }
152 
154  const std::weak_ptr<mrpt::poses::FrameTransformer<2>>& frame_tf)
155 {
156  m_frame_tf = frame_tf;
157 }
158 
160 {
161  MRPT_START
162 
163  params_abstract_navigator.loadFromConfigFile(c, "CAbstractNavigator");
164 
165  // At this point, all derived classes have already loaded their parameters.
166  // Dump them to debug output:
167  {
169  this->saveConfigFile(cfg_mem);
170  MRPT_LOG_INFO(cfg_mem.getContent());
171  }
172 
173  MRPT_END
174 }
175 
177 {
178  params_abstract_navigator.saveToConfigFile(c, "CAbstractNavigator");
179 }
180 
181 /** \callergraph */
183 {
184  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
186  m_timlog_delays, "CAbstractNavigator::navigationStep()");
187 
188  const TState prevState = m_navigationState;
189  switch (m_navigationState)
190  {
191  case IDLE:
192  case SUSPENDED:
193  try
194  {
195  // If we just arrived at this state, stop robot:
197  {
199  "[CAbstractNavigator::navigationStep()] Navigation "
200  "stopped.");
201  // this->stop(); stop() is called by the method switching
202  // the "state", so we have more flexibility
204  }
205  }
206  catch (...)
207  {
208  }
209  break;
210 
211  case NAV_ERROR:
212  try
213  {
214  // Send end-of-navigation event:
217  {
218  m_pending_events.emplace_back(std::bind(
220  std::ref(m_robot)));
221  }
222 
223  // If we just arrived at this state, stop the robot:
225  {
227  "[CAbstractNavigator::navigationStep()] Stopping "
228  "Navigation due to a NAV_ERROR state!");
229  this->stop(false /*not emergency*/);
231  }
232  }
233  catch (...)
234  {
235  }
236  break;
237 
238  case NAVIGATING:
240  true /* do call virtual method nav implementation*/);
241  break; // End case NAVIGATING
242  };
243  m_lastNavigationState = prevState;
244 
246 }
247 
248 /** \callergraph */
250 {
251  // Invoke pending events:
252  for (auto& ev : m_pending_events)
253  {
254  ev();
255  }
256  m_pending_events.clear();
257 }
258 
259 /** \callergraph */
261 {
262  try
263  {
264  this->stop(true /* emergency*/);
265  }
266  catch (...)
267  {
268  }
270  // don't overwrite an error msg from a caller:
272  {
275  std::string("doEmergencyStop called for: ") + msg;
276  }
277  MRPT_LOG_ERROR(msg);
278 }
279 
281 {
282  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
283 
284  m_navigationEndEventSent = false;
285  m_navigationParams.reset();
286 }
287 
289 {
290  MRPT_START;
291  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
292 
293  ASSERT_(params != nullptr);
294  ASSERT_(
295  params->target.targetDesiredRelSpeed >= .0 &&
296  params->target.targetDesiredRelSpeed <= 1.0);
297 
298  // Copy data:
299  m_navigationParams = params->clone();
300 
301  // Transform: relative -> absolute, if needed.
302  if (m_navigationParams->target.targetIsRelative)
303  {
305  m_navigationParams->target.target_coords =
306  m_curPoseVel.pose + m_navigationParams->target.target_coords;
307  m_navigationParams->target.targetIsRelative =
308  false; // Now it's not relative
309  }
310 
311  // new state:
314 
315  // Reset the bad navigation alarm:
316  m_badNavAlarm_minDistTarget = std::numeric_limits<double>::max();
318 
319  MRPT_END;
320 }
321 
324 {
325  MRPT_START;
327  this->processNavigateCommand(params);
328  MRPT_END;
329 }
330 
332 {
333  // Ignore calls too-close in time, e.g. from the navigationStep() methods of
334  // AbstractNavigator and a derived, overriding class.
335  const double robot_time_secs =
336  m_robot.getNavigationTime(); // this is clockwall time for real robots,
337  // simulated time in simulators.
338 
339  const double MIN_TIME_BETWEEN_POSE_UPDATES = 20e-3;
341  {
342  const double last_call_age =
343  robot_time_secs - m_last_curPoseVelUpdate_robot_time;
344  if (last_call_age < MIN_TIME_BETWEEN_POSE_UPDATES)
345  {
347  5.0,
348  "updateCurrentPoseAndSpeeds: ignoring call, since last call "
349  "was only %f ms ago.",
350  last_call_age * 1e3);
351  return; // previous data is still valid: don't query the robot
352  // again
353  }
354  }
355 
356  {
358  m_timlog_delays, "getCurrentPoseAndSpeeds()");
359  m_curPoseVel.pose_frame_id = std::string("map"); // default
364  {
368  "ERROR calling m_robot.getCurrentPoseAndSpeeds, stopping robot "
369  "and finishing navigation");
370  try
371  {
372  this->stop(true /*emergency*/);
373  }
374  catch (...)
375  {
376  }
378  "ERROR calling m_robot.getCurrentPoseAndSpeeds, stopping robot "
379  "and finishing navigation");
380  throw std::runtime_error(
381  "ERROR calling m_robot.getCurrentPoseAndSpeeds, stopping robot "
382  "and finishing navigation");
383  }
384  }
387 
388  m_last_curPoseVelUpdate_robot_time = robot_time_secs;
389  const bool changed_frame_id =
392 
393  if (changed_frame_id)
394  {
395  // If frame changed, clear past poses. This could be improved by
396  // requesting
397  // the transf between the two frames, but it's probably not worth.
400  }
401 
402  // Append to list of past poses:
405 
406  // Purge old ones:
407  while (m_latestPoses.size() > 1 &&
409  m_latestPoses.begin()->first, m_latestPoses.rbegin()->first) >
411  {
413  }
414  while (m_latestOdomPoses.size() > 1 &&
416  m_latestOdomPoses.begin()->first,
418  {
420  }
421 }
422 
423 /** \callergraph */
425  const mrpt::kinematics::CVehicleVelCmd& vel_cmd)
426 {
427  return m_robot.changeSpeeds(vel_cmd);
428 }
429 /** \callergraph */
431 /** \callergraph */
432 bool CAbstractNavigator::stop(bool isEmergencyStop)
433 {
434  return m_robot.stop(isEmergencyStop);
435 }
436 
438 
439  = default;
442 {
447 }
450 {
452  dist_to_target_for_sending_event,
453  "Default value=0, means use the `targetAllowedDistance` passed by the "
454  "user in the navigation request.");
456  alarm_seems_not_approaching_target_timeout,
457  "navigator timeout (seconds) [Default=30 sec]");
459  dist_check_target_is_blocked,
460  "When closer than this distance, check if the target is blocked to "
461  "abort navigation with an error. [Default=0.6 m]");
463  dist_to_target_for_sending_event,
464  "Default value=0, means use the `targetAllowedDistance` passed by the"
465  " user in the navigation request.");
467  alarm_seems_not_approaching_target_timeout,
468  "navigator timeout (seconds) [Default=30 sec]");
470  dist_check_target_is_blocked,
471  "When closer than this distance, check if the target is blocked to "
472  "abort navigation with an error. [Default=0.6 m]");
474  hysteresis_check_target_is_blocked,
475  "How many steps should the condition for dist_check_target_is_blocked "
476  "be fulfilled to raise an event");
477 }
478 
482 {
483  return typeid(a) == typeid(b) && a.isEqual(b);
484 }
485 
486 /** \callergraph */
487 bool CAbstractNavigator::checkHasReachedTarget(const double targetDist) const
488 {
489  return (targetDist < m_navigationParams->target.targetAllowedDistance);
490 }
491 
492 /** \callergraph */
494 {
495  m_robot.startWatchdog(1000); // Watchdog = 1 seg
496  m_latestPoses.clear(); // Clear cache of last poses.
499 }
500 
501 /** \callergraph */
503  bool call_virtual_nav_method)
504 {
505  const TState prevState = m_navigationState;
506  try
507  {
509  {
511  "[CAbstractNavigator::navigationStep()] Starting Navigation. "
512  "Watchdog initiated...\n");
513  if (m_navigationParams)
515  "[CAbstractNavigator::navigationStep()] Navigation "
516  "Params:\n%s\n",
517  m_navigationParams->getAsText().c_str()));
518 
520  }
521 
522  // Have we just started the navigation?
524  {
525  m_pending_events.emplace_back(std::bind(
527  std::ref(m_robot)));
528  }
529 
530  /* ----------------------------------------------------------------
531  Get current robot dyn state:
532  ---------------------------------------------------------------- */
534 
535  /* ----------------------------------------------------------------
536  Have we reached the target location?
537  ---------------------------------------------------------------- */
538  // Build a 2D segment from the current robot pose to the previous one:
540  const mrpt::math::TSegment2D seg_robot_mov = mrpt::math::TSegment2D(
542  m_latestPoses.size() > 1
543  ? mrpt::math::TPoint2D((++m_latestPoses.rbegin())->second)
544  : mrpt::math::TPoint2D((m_latestPoses.rbegin())->second));
545 
546  if (m_navigationParams)
547  {
548  const double targetDist = seg_robot_mov.distance(
549  mrpt::math::TPoint2D(m_navigationParams->target.target_coords));
550 
551  // Should "End of navigation" event be sent??
552  if (!m_navigationParams->target.targetIsIntermediaryWaypoint &&
554  targetDist <
556  {
558  m_pending_events.emplace_back(std::bind(
560  std::ref(m_robot)));
561  }
562 
563  // Have we really reached the target?
564  if (checkHasReachedTarget(targetDist))
565  {
567  logFmt(
569  "Navigation target (%.03f,%.03f) was reached\n",
570  m_navigationParams->target.target_coords.x,
571  m_navigationParams->target.target_coords.y);
572 
573  if (!m_navigationParams->target.targetIsIntermediaryWaypoint)
574  {
575  this->stop(false /*not emergency*/);
577  {
579  m_pending_events.emplace_back(std::bind(
581  std::ref(m_robot)));
582  }
583  }
584  return;
585  }
586 
587  // Check the "no approaching the target"-alarm:
588  // -----------------------------------------------------------
589  if (targetDist < m_badNavAlarm_minDistTarget)
590  {
591  m_badNavAlarm_minDistTarget = targetDist;
593  }
594  else
595  {
596  // Too much time have passed?
601  .alarm_seems_not_approaching_target_timeout)
602  {
604  "Timeout approaching the target. Aborting navigation.");
605 
609  "Timeout approaching the target. Aborting navigation.");
610 
611  m_pending_events.emplace_back(std::bind(
613  std::ref(m_robot)));
614  return;
615  }
616  }
617 
618  // Check if the target seems to be at reach, but it's clearly
619  // occupied by obstacles:
620  if (targetDist <
622  {
623  const auto rel_trg = m_navigationParams->target.target_coords -
625  const bool is_col = checkCollisionWithLatestObstacles(rel_trg);
626  if (is_col)
627  {
628  const bool send_event =
632 
633  if (send_event)
634  {
636  5.0,
637  "Target seems to be blocked by obstacles. Invoking"
638  " sendCannotGetCloserToBlockedTargetEvent().");
639 
640  m_pending_events.emplace_back(std::bind(
642  sendCannotGetCloserToBlockedTargetEvent,
643  std::ref(m_robot)));
644 
646  }
647  }
648  else
649  {
651  }
652  }
653  }
654 
655  // The normal execution of the navigation: Execute one step:
656  if (call_virtual_nav_method)
657  {
659  }
660  }
661  catch (const std::exception& e)
662  {
665  {
668  std::string("Exception: ") + std::string(e.what());
669  }
670 
672  "[CAbstractNavigator::navigationStep] Exception:\n %s", e.what());
673  if (m_rethrow_exceptions) throw;
674  }
675  catch (...)
676  {
679  {
681  m_navErrorReason.error_msg = "Untyped exception";
682  }
683 
685  "[CAbstractNavigator::navigationStep] Untyped exception!");
686  if (m_rethrow_exceptions) throw;
687  }
688  m_navigationState = prevState;
689 }
690 
692  const mrpt::math::TPose2D& relative_robot_pose) const
693 {
694  // Default impl:
695  return false;
696 }
double m_badNavAlarm_minDistTarget
For sending an alarm (error event) when it seems that we are not approaching toward the target in a w...
virtual bool stop(bool isEmergencyStop=true)=0
Stop the robot right now.
std::recursive_mutex m_nav_cs
mutex for all navigation methods
TRobotPoseVel m_curPoseVel
Current robot pose (updated in CAbstractNavigator::navigationStep() )
std::list< std::function< void(void)> > m_pending_events
Events generated during navigationStep(), enqueued to be called at the end of the method execution to...
This class implements a config file-like interface over a memory-stored string list.
virtual bool startWatchdog(float T_ms)
Start the watchdog timer of the robot platform, if any, for maximum expected delay between consecutiv...
void rotate(const double ang)
Transform the (vx,vy) components for a counterclockwise rotation of ang radians.
virtual void loadConfigFile(const mrpt::config::CConfigFileBase &c)
Loads all params from a file.
#define MRPT_START
Definition: exceptions.h:241
#define MRPT_LOG_DEBUG(_STRING)
Use: MRPT_LOG_DEBUG("message");
mrpt::system::CTimeLogger m_timlog_delays
Time logger to collect delay-related stats.
#define MRPT_LOG_ERROR_FMT(_FMT_STRING,...)
virtual bool stopWatchdog()
Stop the watchdog timer.
void setFrameTF(const std::weak_ptr< mrpt::poses::FrameTransformer< 2 >> &frame_tf)
Sets a user-provided frame transformer object; used only if providing targets in a frame ID different...
void logFmt(const VerbosityLevel level, const char *fmt,...) const MRPT_printf_format_check(3
Alternative logging method, which mimics the printf behavior.
A safe way to call enter() and leave() of a mrpt::system::CTimeLogger upon construction and destructi...
mrpt::system::TTimeStamp getCurrentTime()
Returns the current (UTC) system time.
Definition: datetime.h:82
GLenum GLint ref
Definition: glext.h:4062
#define MRPT_LOAD_CONFIG_VAR_CS(variableName, variableType)
Shortcut for MRPT_LOAD_CONFIG_VAR() for config file object named c and section string named s ...
~CAbstractNavigator() override
dtor
double distance(const TPoint2D &point) const
Distance to point.
Base for all high-level navigation commands.
float targetAllowedDistance
(Default=0.5 meters) Allowed distance to target in order to end the navigation.
#define MRPT_LOG_THROTTLE_DEBUG_FMT(_PERIOD_SECONDS, _FMT_STRING,...)
Usage: MRPT_LOG_THROTTLE_DEBUG_FMT(5.0, "i=%u", i);
virtual void sendNavigationEndEvent()
Callback: End of navigation command (reach of single goal, or final waypoint of waypoint list) ...
STL namespace.
virtual void updateCurrentPoseAndSpeeds()
Call to the robot getCurrentPoseAndSpeeds() and updates members m_curPoseVel accordingly.
bool targetIsRelative
(Default=false) Whether the target coordinates are in global coordinates (false) or are relative to t...
virtual double getNavigationTime()
Returns the number of seconds ellapsed since the constructor of this class was invoked, or since the last call of resetNavigationTimer().
double dist_check_target_is_blocked
(Default value=0.6) When closer than this distance, check if the target is blocked to abort navigatio...
GLdouble s
Definition: glext.h:3682
void setInterpolationMethod(TInterpolatorMethod method)
Change the method used to interpolate the robot path.
virtual void navigationStep()
This method must be called periodically in order to effectively run the navigation.
std::string pose_frame_id
map frame ID for pose
virtual bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd)
Default: forward call to m_robot.changeSpeed().
virtual bool changeSpeedsNOP()
Default: forward call to m_robot.changeSpeedsNOP().
TState m_navigationState
Current internal state of navigator:
Virtual base for velocity commands of different kinematic models of planar mobile robot...
virtual void performNavigationStep()=0
To be implemented in derived classes.
bool operator==(const CAbstractNavigator::TNavigationParamsBase &, const CAbstractNavigator::TNavigationParamsBase &)
The struct for configuring navigation requests.
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
CAbstractNavigator(CRobot2NavInterface &robot_interface_impl)
ctor
This class allows loading and storing values and vectors of different types from a configuration text...
TState
The different states for the navigation system.
2D segment, consisting of two points.
Definition: TSegment2D.h:20
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.
double dist_to_target_for_sending_event
Default value=0, means use the "targetAllowedDistance" passed by the user in the navigation request...
double targetDesiredRelSpeed
(Default=.05) Desired relative speed (wrt maximum speed), in range [0,1], of the vehicle at target...
virtual void onNavigateCommandReceived()
Called after each call to CAbstractNavigator::navigate()
virtual void sendNavigationStartEvent()
Callback: Start of navigation command.
virtual void sendNavigationEndDueToErrorEvent()
Callback: Error asking sensory data from robot or sending motor commands.
std::string target_frame_id
(Default="map") Frame ID in which target is given.
const GLubyte * c
Definition: glext.h:6406
virtual void resetNavError()
Resets a NAV_ERROR state back to IDLE
std::unique_ptr< TNavigationParams > m_navigationParams
Current navigation parameters.
void internal_onStartNewNavigation()
Called before starting a new navigation.
GLubyte GLubyte b
Definition: glext.h:6372
Individual target info in CAbstractNavigator::TNavigationParamsBase and derived classes.
virtual void onStartNewNavigation()=0
Called whenever a new navigation has been started.
GLsizei const GLchar ** string
Definition: glext.h:4116
virtual void sendWaySeemsBlockedEvent()
Callback: No progression made towards target for a predefined period of time.
virtual void resume()
Continues with suspended navigation.
mrpt::math::TPose2D target_coords
Coordinates of desired target location.
TState m_lastNavigationState
Last internal state of navigator:
double alarm_seems_not_approaching_target_timeout
navigator timeout (seconds) [Default=30 sec]
void setVerbosityLevel(const VerbosityLevel level)
alias of setMinLoggingLevel()
const double PREVIOUS_POSES_MAX_AGE
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
virtual void performNavigationStepNavigating(bool call_virtual_nav_method=true)
Factorization of the part inside navigationStep(), for the case of state being NAVIGATING.
virtual bool getCurrentPoseAndSpeeds(mrpt::math::TPose2D &curPose, mrpt::math::TTwist2D &curVelGlobal, mrpt::system::TTimeStamp &timestamp, mrpt::math::TPose2D &curOdometry, std::string &frame_id)=0
Get the current pose and velocity of the robot.
virtual void saveConfigFile(mrpt::config::CConfigFileBase &c) const
Saves all current options to a config file.
virtual bool changeSpeedsNOP()
Just like changeSpeeds(), but will be called when the last velocity command is still the preferred so...
std::string getAsText() const
Gets navigation params as a human-readable format.
void clear()
Clears the current sequence of poses.
virtual void doEmergencyStop(const std::string &msg)
Stops the robot and set navigation state to error.
virtual void processNavigateCommand(const TNavigationParams *params)
Does the job of navigate(), except the call to onNavigateCommandReceived()
#define MRPT_LOG_ERROR(_STRING)
TAbstractNavigatorParams params_abstract_navigator
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. ...
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
CRobot2NavInterface & m_robot
The navigator-robot interface.
COutputLogger()
Default class constructor.
#define MRPT_END
Definition: exceptions.h:245
bool isEqual(const TNavigationParamsBase &o) const override
virtual bool checkCollisionWithLatestObstacles(const mrpt::math::TPose2D &relative_robot_pose) const
Checks whether the robot shape, when placed at the given pose (relative to the current pose)...
void getContent(std::string &str) const
Return the current contents of the virtual "config file".
Lightweight 2D pose.
Definition: TPose2D.h:22
virtual bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd)=0
Sends a velocity command to the robot.
iterator erase(iterator element_to_erase)
virtual void cancel()
Cancel current navegation.
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
std::string error_msg
Human friendly description of the error.
bool operator==(const TargetInfo &o) const
#define MRPT_LOG_WARN(_STRING)
virtual void suspend()
Suspend current navegation.
std::weak_ptr< mrpt::poses::FrameTransformer< 2 > > m_frame_tf
Optional, user-provided frame transformer.
void insert(const mrpt::Clock::time_point &t, const pose_t &p)
Inserts a new pose in the sequence.
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
Definition: datetime.h:123
int hysteresis_check_target_is_blocked
(Default=3) How many steps should the condition for dist_check_target_is_blocked be fulfilled to rais...
virtual bool checkHasReachedTarget(const double targetDist) const
Default implementation: check if target_dist is below the accepted distance.
mrpt::poses::CPose2DInterpolator m_latestOdomPoses
bool m_navigationEndEventSent
Will be false until the navigation end is sent, and it is reset with each new command.
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
mrpt::system::TTimeStamp m_badNavAlarm_lastMinDistTime
Lightweight 2D point.
Definition: TPoint2D.h:31
GLubyte GLubyte GLubyte a
Definition: glext.h:6372
GLenum const GLfloat * params
Definition: glext.h:3538
mrpt::poses::CPose2DInterpolator m_latestPoses
Latest robot poses (updated in CAbstractNavigator::navigationStep() )
double phi
Orientation (rads)
Definition: TPose2D.h:32
std::string getAsText() const override
Gets navigation params as a human-readable format.
#define MRPT_LOG_THROTTLE_WARN(_PERIOD_SECONDS, _STRING)
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
mrpt::math::TPose2D rawOdometry
raw odometry (frame does not match to "pose", but is expected to be smoother in the short term)...
virtual bool stop(bool isEmergencyStop)
Default: forward call to m_robot.stop().
#define MRPT_LOG_INFO(_STRING)
virtual void navigate(const TNavigationParams *params)
Navigation request to a single target location.



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