Main MRPT website > C++ reference for MRPT 1.9.9
CAbstractPTGBasedReactive.cpp
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 
10 #include "nav-precomp.h" // Precomp header
11 
13 #include <mrpt/system/filesystem.h>
14 #include <mrpt/math/wrap2pi.h>
15 #include <mrpt/math/geometry.h>
16 #include <mrpt/math/ops_containers.h> // sum()
22 #include <limits>
23 #include <iomanip>
24 #include <array>
25 
26 using namespace mrpt;
27 using namespace mrpt::poses;
28 using namespace mrpt::math;
29 using namespace mrpt::utils;
30 using namespace mrpt::nav;
31 using namespace std;
32 
33 // ------ CAbstractPTGBasedReactive::TNavigationParamsPTG -----
34 std::string CAbstractPTGBasedReactive::TNavigationParamsPTG::getAsText() const
35 {
36  std::string s =
37  CWaypointsNavigator::TNavigationParamsWaypoints::getAsText();
38  s += "restrict_PTG_indices: ";
39  s += mrpt::utils::sprintf_vector("%u ", this->restrict_PTG_indices);
40  s += "\n";
41  return s;
42 }
43 
44 bool CAbstractPTGBasedReactive::TNavigationParamsPTG::isEqual(
46 {
47  auto o =
49  &rhs);
50  return o != nullptr &&
51  CWaypointsNavigator::TNavigationParamsWaypoints::isEqual(rhs) &&
52  restrict_PTG_indices == o->restrict_PTG_indices;
53 }
54 
55 const double ESTIM_LOWPASSFILTER_ALPHA = 0.7;
56 
57 // Ctor:
58 CAbstractPTGBasedReactive::CAbstractPTGBasedReactive(
59  CRobot2NavInterface& react_iterf_impl, bool enableConsoleOutput,
60  bool enableLogFile, const std::string& sLogDir)
61  : CWaypointsNavigator(react_iterf_impl),
62  m_holonomicMethod(),
63  m_prev_logfile(nullptr),
64  m_enableKeepLogRecords(false),
65  m_enableConsoleOutput(enableConsoleOutput),
66  m_init_done(false),
67  m_timelogger(false), // default: disabled
68  m_PTGsMustBeReInitialized(true),
69  meanExecutionTime(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
70  meanTotalExecutionTime(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
71  meanExecutionPeriod(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
72  tim_changeSpeed_avr(ESTIM_LOWPASSFILTER_ALPHA),
73  timoff_obstacles_avr(ESTIM_LOWPASSFILTER_ALPHA),
74  timoff_curPoseAndSpeed_avr(ESTIM_LOWPASSFILTER_ALPHA),
75  timoff_sendVelCmd_avr(ESTIM_LOWPASSFILTER_ALPHA),
76  m_closing_navigator(false),
77  m_WS_Obstacles_timestamp(INVALID_TIMESTAMP),
78  m_infoPerPTG_timestamp(INVALID_TIMESTAMP),
79  m_navlogfiles_dir(sLogDir)
80 {
81  this->enableLogFile(enableLogFile);
82 }
83 
85 {
86  m_closing_navigator = true;
87 
88  // Wait to end of navigation (multi-thread...)
89  m_nav_cs.lock();
90  m_nav_cs.unlock();
91 
92  // Just in case.
93  try
94  {
95  this->stop(false /*not emergency*/);
96  }
97  catch (...)
98  {
99  }
100 
101  m_logFile.reset();
102 
103  // Free holonomic method:
104  this->deleteHolonomicObjects();
105 }
106 
108 {
109  this->preDestructor(); // ensure the robot is stopped; free dynamic objects
110 }
111 
112 /** \callergraph */
114 {
115  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
116 
118 
120  m_multiobjopt->clear();
121 
122  // Compute collision grids:
123  STEP1_InitPTGs();
124 }
125 
126 /*---------------------------------------------------------------
127  enableLogFile
128  ---------------------------------------------------------------*/
130 {
131  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
132 
133  try
134  {
135  // Disable:
136  // -------------------------------
137  if (!enable)
138  {
139  if (m_logFile)
140  {
142  "[CAbstractPTGBasedReactive::enableLogFile] Stopping "
143  "logging.");
144  m_logFile.reset(); // Close file:
145  }
146  else
147  return; // Already disabled.
148  }
149  else
150  { // Enable
151  // -------------------------------
152  if (m_logFile) return; // Already enabled:
153 
154  // Open file, find the first free file-name.
155  char aux[300];
156  unsigned int nFile = 0;
157  bool free_name = false;
158 
161  {
163  "Could not create directory for navigation logs: `%s`",
164  m_navlogfiles_dir.c_str());
165  }
166 
167  while (!free_name)
168  {
169  nFile++;
170  sprintf(
171  aux, "%s/log_%03u.reactivenavlog",
172  m_navlogfiles_dir.c_str(), nFile);
173  free_name = !system::fileExists(aux);
174  }
175 
176  // Open log file:
177  {
178  std::unique_ptr<CFileGZOutputStream> fil(
179  new CFileGZOutputStream);
180  bool ok = fil->open(aux, 1 /* compress level */);
181  if (!ok)
182  {
183  THROW_EXCEPTION_FMT("Error opening log file: `%s`", aux);
184  }
185  else
186  {
187  m_logFile.reset(fil.release());
188  }
189  }
190 
192  mrpt::format(
193  "[CAbstractPTGBasedReactive::enableLogFile] Logging to "
194  "file `%s`\n",
195  aux));
196  }
197  }
198  catch (std::exception& e)
199  {
201  "[CAbstractPTGBasedReactive::enableLogFile] Exception: %s",
202  e.what());
203  }
204 }
205 
207 {
208  std::lock_guard<std::recursive_mutex> lock(m_critZoneLastLog);
209  o = lastLogRecord;
210 }
211 
213 {
214  m_holonomicMethod.clear();
215 }
216 
218  const std::string& method, const mrpt::utils::CConfigFileBase& ini)
219 {
220  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
221 
222  this->deleteHolonomicObjects();
223  const size_t nPTGs = this->getPTG_count();
224  ASSERT_(nPTGs != 0);
225  m_holonomicMethod.resize(nPTGs);
226 
227  for (size_t i = 0; i < nPTGs; i++)
228  {
229  m_holonomicMethod[i] =
231  if (!m_holonomicMethod[i])
233  "Non-registered holonomic method className=`%s`",
234  method.c_str());
235 
236  m_holonomicMethod[i]->setAssociatedPTG(this->getPTG(i));
237  m_holonomicMethod[i]->initialize(ini); // load params
238  }
239 }
240 
241 /** The main method: executes one time-iteration of the reactive navigation
242  * algorithm.
243  * \callergraph */
245 {
246  // Security tests:
247  if (m_closing_navigator) return; // Are we closing in the main thread?
248  if (!m_init_done)
249  THROW_EXCEPTION("Have you called loadConfigFile() before?")
251 
252  const size_t nPTGs = this->getPTG_count();
253 
254  // Whether to worry about log files:
255  const bool fill_log_record = (m_logFile || m_enableKeepLogRecords);
256  CLogFileRecord newLogRec;
257  newLogRec.infoPerPTG.resize(
258  nPTGs + 1); /* +1: [N] is the "NOP cmdvel" option; not to be
259  present in all log entries. */
260 
261  // At the beginning of each log file, add an introductory block explaining
262  // which PTGs are we using:
263  {
264  if (m_logFile &&
265  m_logFile.get() != m_prev_logfile) // Only the first time
266  {
267  m_prev_logfile = m_logFile.get();
268  for (size_t i = 0; i < nPTGs; i++)
269  {
270  // If we make a direct copy (=) we will store the entire, heavy,
271  // collision grid.
272  // Let's just store the parameters of each PTG by serializing
273  // it, so paths can be reconstructed
274  // by invoking initialize()
276  buf << *this->getPTG(i);
277  buf.Seek(0);
278  newLogRec.infoPerPTG[i].ptg = std::dynamic_pointer_cast<
280  buf.ReadObject());
281  }
282  }
283  }
284 
285  CTimeLoggerEntry tle1(m_timelogger, "navigationStep");
286 
287  try
288  {
289  totalExecutionTime.Tic(); // Start timer
290 
291  const mrpt::system::TTimeStamp tim_start_iteration =
293 
294  // Compute target location relative to current robot pose:
295  // ---------------------------------------------------------------------
296  // Detect changes in target since last iteration (for NOP):
297  const bool target_changed_since_last_iteration =
300  if (target_changed_since_last_iteration)
302 
303  // Load the list of target(s) from the navigationParam user command.
304  // Semantic is: any of the target is good. If several targets are
305  // reachable, head to latest one.
306  std::vector<CAbstractNavigator::TargetInfo> targets;
307  {
308  auto p = dynamic_cast<
310  m_navigationParams.get());
311  if (p && !p->multiple_targets.empty())
312  {
313  targets = p->multiple_targets;
314  }
315  else
316  {
317  targets.push_back(m_navigationParams->target);
318  }
319  }
320  const size_t nTargets = targets.size(); // Normally = 1, will be >1 if
321  // we want the robot local
322  // planner to be "smarter" in
323  // skipping dynamic obstacles.
324  ASSERT_(nTargets >= 1);
325 
326  STEP1_InitPTGs(); // Will only recompute if
327  // "m_PTGsMustBeReInitialized==true"
328 
329  // STEP2: Load the obstacles and sort them in height bands.
330  // -----------------------------------------------------------------------------
331  if (!STEP2_SenseObstacles())
332  {
334  "Error while loading and sorting the obstacles. Robot will be "
335  "stopped.");
336  if (fill_log_record)
337  {
338  CPose2D rel_cur_pose_wrt_last_vel_cmd_NOP,
339  rel_pose_PTG_origin_wrt_sense_NOP;
341  newLogRec,
342  std::vector<mrpt::math::TPose2D>() /*no targets*/,
343  -1, // best_ptg_idx,
344  m_robot.getEmergencyStopCmd(), nPTGs,
345  false, // best_is_NOP_cmdvel,
346  rel_cur_pose_wrt_last_vel_cmd_NOP,
347  rel_pose_PTG_origin_wrt_sense_NOP,
348  0, // executionTimeValue,
349  0, // tim_changeSpeed,
350  tim_start_iteration);
351  }
352  return;
353  }
354 
355  // ------- start of motion decision zone ---------
356  executionTime.Tic();
357 
358  // Round #1: As usual, pure reactive, evaluate all PTGs and all
359  // directions from scratch.
360  // =========
361 
362  mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense(0, 0, 0),
363  relPoseSense(0, 0, 0), relPoseVelCmd(0, 0, 0);
365  {
366  /*
367  * Delays model
368  *
369  * Event: OBSTACLES_SENSED RNAV_ITERATION_STARTS
370  * GET_ROBOT_POSE_VEL VEL_CMD_SENT_TO_ROBOT
371  * Timestamp: (m_WS_Obstacles_timestamp) (tim_start_iteration)
372  * (m_curPoseVelTimestamp) ("tim_send_cmd_vel")
373  * Delay |
374  * <---+--------------->|<--------------+-------->| |
375  * estimator: | |
376  * | |
377  * timoff_obstacles <-+ |
378  * +--> timoff_curPoseVelAge |
379  * |<---------------------------------+--------------->|
380  * +-->
381  * timoff_sendVelCmd_avr (estimation)
382  *
383  * |<-------------------->|
384  * tim_changeSpeed_avr
385  * (estim)
386  *
387  * |<-----------------------------------------------|-------------------------->|
388  * Relative poses: relPoseSense
389  * relPoseVelCmd
390  * Time offsets (signed): timoff_pose2sense
391  * timoff_pose2VelCmd
392  */
393  const double timoff_obstacles = mrpt::system::timeDifference(
394  tim_start_iteration, m_WS_Obstacles_timestamp);
395  timoff_obstacles_avr.filter(timoff_obstacles);
396  newLogRec.values["timoff_obstacles"] = timoff_obstacles;
397  newLogRec.values["timoff_obstacles_avr"] =
399  newLogRec.timestamps["obstacles"] = m_WS_Obstacles_timestamp;
400 
401  const double timoff_curPoseVelAge = mrpt::system::timeDifference(
402  tim_start_iteration, m_curPoseVel.timestamp);
403  timoff_curPoseAndSpeed_avr.filter(timoff_curPoseVelAge);
404  newLogRec.values["timoff_curPoseVelAge"] = timoff_curPoseVelAge;
405  newLogRec.values["timoff_curPoseVelAge_avr"] =
407 
408  // time offset estimations:
409  const double timoff_pose2sense =
410  timoff_obstacles - timoff_curPoseVelAge;
411 
412  double timoff_pose2VelCmd;
413  timoff_pose2VelCmd = timoff_sendVelCmd_avr.getLastOutput() +
415  timoff_curPoseVelAge;
416  newLogRec.values["timoff_pose2sense"] = timoff_pose2sense;
417  newLogRec.values["timoff_pose2VelCmd"] = timoff_pose2VelCmd;
418 
419  if (std::abs(timoff_pose2sense) > 1.25)
421  "timoff_pose2sense=%e is too large! Path extrapolation may "
422  "be not accurate.",
423  timoff_pose2sense);
424  if (std::abs(timoff_pose2VelCmd) > 1.25)
426  "timoff_pose2VelCmd=%e is too large! Path extrapolation "
427  "may be not accurate.",
428  timoff_pose2VelCmd);
429 
430  // Path extrapolation: robot relative poses along current path
431  // estimation:
432  relPoseSense = m_curPoseVel.velLocal * timoff_pose2sense;
433  relPoseVelCmd = m_curPoseVel.velLocal * timoff_pose2VelCmd;
434 
435  // relative pose for PTGs:
436  rel_pose_PTG_origin_wrt_sense = relPoseVelCmd - relPoseSense;
437 
438  // logging:
439  newLogRec.relPoseSense = relPoseSense;
440  newLogRec.relPoseVelCmd = relPoseVelCmd;
441  }
442  else
443  {
444  // No delays model: poses to their default values.
445  }
446 
447  for (auto& t : targets)
448  {
449  if (t.target_frame_id != m_curPoseVel.pose_frame_id)
450  {
451  if (m_frame_tf == nullptr)
452  {
454  "Different frame_id's but no frame_tf object "
455  "attached!: target_frame_id=`%s` != pose_frame_id=`%s`",
456  t.target_frame_id.c_str(),
457  m_curPoseVel.pose_frame_id.c_str());
458  }
459  mrpt::math::TPose2D robot_frame2map_frame;
461  t.target_frame_id, m_curPoseVel.pose_frame_id,
462  robot_frame2map_frame);
463 
465  "frame_tf: target_frame_id=`%s` as seen from "
466  "pose_frame_id=`%s` = %s",
467  t.target_frame_id.c_str(),
468  m_curPoseVel.pose_frame_id.c_str(),
469  robot_frame2map_frame.asString().c_str());
470 
471  t.target_coords = robot_frame2map_frame + t.target_coords;
472  t.target_frame_id =
473  m_curPoseVel.pose_frame_id; // Now the coordinates are in
474  // the same frame than robot
475  // pose
476  }
477  }
478 
479  std::vector<TPose2D> relTargets;
480  const auto curPoseExtrapol = (m_curPoseVel.pose + relPoseVelCmd);
482  targets.begin(), targets.end(), // in
483  std::back_inserter(relTargets), // out
484  [curPoseExtrapol](const CAbstractNavigator::TargetInfo& e) {
485  return e.target_coords - curPoseExtrapol;
486  });
487  ASSERT_EQUAL_(relTargets.size(), targets.size());
488 
489  // Use the distance to the first target as reference:
490  const double relTargetDist = relTargets.begin()->norm();
491 
492  // PTG dynamic state
493  /** Allow PTGs to be responsive to target location, dynamics, etc. */
495 
496  ptg_dynState.curVelLocal = m_curPoseVel.velLocal;
497  ptg_dynState.relTarget = relTargets[0];
498  ptg_dynState.targetRelSpeed =
499  m_navigationParams->target.targetDesiredRelSpeed;
500 
501  newLogRec.navDynState = ptg_dynState;
502 
503  for (size_t i = 0; i < nPTGs; i++)
504  {
505  getPTG(i)->updateNavDynamicState(ptg_dynState);
506  }
507 
508  m_infoPerPTG.assign(nPTGs + 1, TInfoPerPTG()); // reset contents
509  m_infoPerPTG_timestamp = tim_start_iteration;
510  vector<TCandidateMovementPTG> candidate_movs(
511  nPTGs + 1); // the last extra one is for the evaluation of "NOP
512  // motion command" choice.
513 
514  for (size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
515  {
516  CParameterizedTrajectoryGenerator* ptg = getPTG(indexPTG);
517  TInfoPerPTG& ipf = m_infoPerPTG[indexPTG];
518 
519  // Ensure the method knows about its associated PTG:
520  m_holonomicMethod[indexPTG]->setAssociatedPTG(
521  this->getPTG(indexPTG));
522 
523  // The picked movement in TP-Space (to be determined by holonomic
524  // method below)
525  TCandidateMovementPTG& cm = candidate_movs[indexPTG];
526 
529  ptg, indexPTG, relTargets, rel_pose_PTG_origin_wrt_sense, ipf,
530  cm, newLogRec, false /* this is a regular PTG reactive case */,
531  *m_holonomicMethod[indexPTG], tim_start_iteration,
533  } // end for each PTG
534 
535  // check for collision, which is reflected by ALL TP-Obstacles being
536  // zero:
537  bool is_all_ptg_collision = true;
538  for (size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
539  {
540  bool is_collision = true;
541  const auto& obs = m_infoPerPTG[indexPTG].TP_Obstacles;
542  for (const auto o : obs)
543  {
544  if (o != 0)
545  {
546  is_collision = false;
547  break;
548  }
549  }
550  if (!is_collision)
551  {
552  is_all_ptg_collision = false;
553  break;
554  }
555  }
556  if (is_all_ptg_collision)
557  {
558  m_pending_events.push_back(
559  std::bind(
561  std::ref(m_robot)));
562  }
563 
564  // Round #2: Evaluate dont sending any new velocity command ("NOP"
565  // motion)
566  // =========
567  bool NOP_not_too_old = true;
568  bool NOP_not_too_close_and_have_to_slowdown = true;
569  double NOP_max_time = -1.0, NOP_At = -1.0;
570  double slowdowndist = .0;
571  CParameterizedTrajectoryGenerator* last_sent_ptg =
573  : nullptr;
574  if (last_sent_ptg)
575  {
576  // So supportSpeedAtTarget() below is evaluated in the correct
577  // context:
579  }
580 
581  // This approach is only possible if:
582  const bool can_do_nop_motion =
584  !target_changed_since_last_iteration && last_sent_ptg &&
585  last_sent_ptg->supportVelCmdNOP()) &&
586  (NOP_not_too_old =
588  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration)) <
589  (NOP_max_time =
590  last_sent_ptg->maxTimeInVelCmdNOP(
592  std::max(0.1, m_lastSentVelCmd.speed_scale))) &&
593  (NOP_not_too_close_and_have_to_slowdown =
594  (last_sent_ptg->supportSpeedAtTarget() ||
595  (relTargetDist >
597  ->getTargetApproachSlowDownDistance())
598  // slowdowndist is assigned here, inside the if()
599  // to be sure the index in m_lastSentVelCmd is valid!
600  )));
601 
602  if (!NOP_not_too_old)
603  {
604  newLogRec.additional_debug_msgs["PTG_cont"] = mrpt::format(
605  "PTG-continuation not allowed: previous command timed-out "
606  "(At=%.03f > Max_At=%.03f)",
607  NOP_At, NOP_max_time);
608  }
609  if (!NOP_not_too_close_and_have_to_slowdown)
610  {
611  newLogRec.additional_debug_msgs["PTG_cont_trgdst"] = mrpt::format(
612  "PTG-continuation not allowed: target too close and must start "
613  "slow-down (trgDist=%.03f < SlowDownDist=%.03f)",
614  relTargetDist, slowdowndist);
615  }
616 
617  mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP(0, 0, 0),
618  rel_pose_PTG_origin_wrt_sense_NOP(0, 0, 0);
619 
620  if (can_do_nop_motion)
621  {
622  // Add the estimation of how long it takes to run the changeSpeeds()
623  // callback (usually a tiny period):
624  const mrpt::system::TTimeStamp tim_send_cmd_vel_corrected =
628 
629  // Note: we use (uncorrected) raw odometry as basis to the following
630  // calculation since it's normally
631  // smoother than particle filter-based localization data, more
632  // accurate in the middle/long term,
633  // but not in the short term:
634  mrpt::math::TPose2D robot_pose_at_send_cmd, robot_odom_at_send_cmd;
635  bool valid_odom, valid_pose;
636 
638  tim_send_cmd_vel_corrected, robot_odom_at_send_cmd, valid_odom);
640  tim_send_cmd_vel_corrected, robot_pose_at_send_cmd, valid_pose);
641 
642  if (valid_odom && valid_pose)
643  {
644  ASSERT_(last_sent_ptg != nullptr);
645 
646  std::vector<TPose2D> relTargets_NOPs;
648  targets.begin(), targets.end(), // in
649  std::back_inserter(relTargets_NOPs), // out
650  [robot_pose_at_send_cmd](
652  return e.target_coords - robot_pose_at_send_cmd;
653  });
654  ASSERT_EQUAL_(relTargets_NOPs.size(), targets.size());
655 
656  rel_pose_PTG_origin_wrt_sense_NOP =
657  robot_odom_at_send_cmd -
658  (m_curPoseVel.rawOdometry + relPoseSense);
659  rel_cur_pose_wrt_last_vel_cmd_NOP =
660  m_curPoseVel.rawOdometry - robot_odom_at_send_cmd;
661 
662  // Update PTG response to dynamic params:
663  last_sent_ptg->updateNavDynamicState(
665 
666  if (fill_log_record)
667  {
668  newLogRec.additional_debug_msgs
669  ["rel_cur_pose_wrt_last_vel_cmd_NOP(interp)"] =
670  rel_cur_pose_wrt_last_vel_cmd_NOP.asString();
671  newLogRec.additional_debug_msgs
672  ["robot_odom_at_send_cmd(interp)"] =
673  robot_odom_at_send_cmd.asString();
674  }
675 
676  // No need to call setAssociatedPTG(), already correctly
677  // associated above.
678 
681  last_sent_ptg, m_lastSentVelCmd.ptg_index, relTargets_NOPs,
682  rel_pose_PTG_origin_wrt_sense_NOP, m_infoPerPTG[nPTGs],
683  candidate_movs[nPTGs], newLogRec,
684  true /* this is the PTG continuation (NOP) choice */,
686  tim_start_iteration, *m_navigationParams,
687  rel_cur_pose_wrt_last_vel_cmd_NOP);
688 
689  } // end valid interpolated origin pose
690  else
691  {
692  // Can't interpolate pose, hence can't evaluate NOP:
693  candidate_movs[nPTGs].speed =
694  -0.01; // <0 means inviable movement
695  }
696  } // end can_do_NOP_motion
697 
698  // Evaluate all the candidates and pick the "best" one, using
699  // the user-defined multiobjective optimizer
700  // --------------------------------------------------------------
703  int best_ptg_idx = m_multiobjopt->decide(candidate_movs, mo_info);
704 
705  if (fill_log_record)
706  {
707  if (mo_info.final_evaluation.size() == newLogRec.infoPerPTG.size())
708  {
709  for (unsigned int i = 0; i < newLogRec.infoPerPTG.size(); i++)
710  {
711  newLogRec.infoPerPTG[i].evaluation =
712  mo_info.final_evaluation[i];
713  }
714  }
715  int idx = 0;
716  for (const auto& le : mo_info.log_entries)
717  {
719  "MultiObjMotOptmzr_msg%03i", idx++)] = le;
720  }
721  }
722 
723  // Pick best movement (or null if none is good)
724  const TCandidateMovementPTG* selectedHolonomicMovement = nullptr;
725  if (best_ptg_idx >= 0)
726  {
727  selectedHolonomicMovement = &candidate_movs[best_ptg_idx];
728  }
729 
730  // If the selected PTG is (N+1), it means the NOP cmd. vel is selected
731  // as the best alternative, i.e. do NOT send any new motion command.
732  const bool best_is_NOP_cmdvel = (best_ptg_idx == int(nPTGs));
733 
734  // ---------------------------------------------------------------------
735  // SEND MOVEMENT COMMAND TO THE ROBOT
736  // ---------------------------------------------------------------------
738  if (best_is_NOP_cmdvel)
739  {
740  // Notify the robot that we want it to keep executing the last
741  // cmdvel:
742  if (!this->changeSpeedsNOP())
743  {
745  "\nERROR calling changeSpeedsNOP()!! Stopping robot and "
746  "finishing navigation\n");
747  if (fill_log_record)
748  {
750  newLogRec, relTargets, best_ptg_idx,
751  m_robot.getEmergencyStopCmd(), nPTGs,
752  best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
753  rel_pose_PTG_origin_wrt_sense_NOP,
754  0, // executionTimeValue,
755  0, // tim_changeSpeed,
756  tim_start_iteration);
757  }
758  return;
759  }
760  }
761  else
762  {
763  // Make sure the dynamic state of a NOP cmd has not overwritten the
764  // state for a "regular" PTG choice:
765  for (size_t i = 0; i < nPTGs; i++)
766  {
767  getPTG(i)->updateNavDynamicState(ptg_dynState);
768  }
769 
770  // STEP7: Get the non-holonomic movement command.
771  // ---------------------------------------------------------------------
772  double cmd_vel_speed_ratio = 1.0;
773  if (selectedHolonomicMovement)
774  {
775  CTimeLoggerEntry tle(
776  m_timelogger, "navigationStep.selectedHolonomicMovement");
777  cmd_vel_speed_ratio =
778  generate_vel_cmd(*selectedHolonomicMovement, new_vel_cmd);
779  ASSERT_(new_vel_cmd);
780  }
781 
782  if (!new_vel_cmd /* which means best_PTG_eval==.0*/ ||
783  new_vel_cmd->isStopCmd())
784  {
786  "Best velocity command is STOP (no way found), calling "
787  "robot.stop()");
788  this->stop(true /* emergency */); // don't call
789  // doEmergencyStop() here
790  // since that will stop
791  // navigation completely
792  new_vel_cmd = m_robot.getEmergencyStopCmd();
794  }
795  else
796  {
797  mrpt::system::TTimeStamp tim_send_cmd_vel;
798  {
800  m_timlog_delays, "changeSpeeds()");
801  tim_send_cmd_vel = mrpt::system::now();
802  newLogRec.timestamps["tim_send_cmd_vel"] = tim_send_cmd_vel;
803  if (!this->changeSpeeds(*new_vel_cmd))
804  {
806  "\nERROR calling changeSpeeds()!! Stopping robot "
807  "and finishing navigation\n");
808  if (fill_log_record)
809  {
810  new_vel_cmd = m_robot.getEmergencyStopCmd();
812  newLogRec, relTargets, best_ptg_idx,
813  new_vel_cmd, nPTGs, best_is_NOP_cmdvel,
814  rel_cur_pose_wrt_last_vel_cmd_NOP,
815  rel_pose_PTG_origin_wrt_sense_NOP,
816  0, // executionTimeValue,
817  0, // tim_changeSpeed,
818  tim_start_iteration);
819  }
820  return;
821  }
822  }
823  // Save last sent cmd:
824  m_lastSentVelCmd.speed_scale = cmd_vel_speed_ratio;
825  m_lastSentVelCmd.ptg_index = best_ptg_idx;
827  selectedHolonomicMovement
828  ? selectedHolonomicMovement->PTG->alpha2index(
829  selectedHolonomicMovement->direction)
830  : 0;
831 
833  best_ptg_idx >= 0
834  ? m_infoPerPTG[best_ptg_idx]
835  .TP_Obstacles[m_lastSentVelCmd.ptg_alpha_index]
836  : .0;
838  (selectedHolonomicMovement->props["is_slowdown"] != 0.0);
839 
841  m_lastSentVelCmd.tim_send_cmd_vel = tim_send_cmd_vel;
842  m_lastSentVelCmd.ptg_dynState = ptg_dynState;
843 
844  // Update delay model:
845  const double timoff_sendVelCmd = mrpt::system::timeDifference(
846  tim_start_iteration, tim_send_cmd_vel);
847  timoff_sendVelCmd_avr.filter(timoff_sendVelCmd);
848  newLogRec.values["timoff_sendVelCmd"] = timoff_sendVelCmd;
849  newLogRec.values["timoff_sendVelCmd_avr"] =
851  }
852  }
853 
854  // ------- end of motion decision zone ---------
855 
856  // Statistics:
857  // ----------------------------------------------------
858  const double executionTimeValue = executionTime.Tac();
859  meanExecutionTime.filter(executionTimeValue);
861 
862  const double tim_changeSpeed =
863  m_timlog_delays.getLastTime("changeSpeeds()");
864  tim_changeSpeed_avr.filter(tim_changeSpeed);
865 
866  // Running period estim:
867  const double period_tim = timerForExecutionPeriod.Tac();
868  if (period_tim > 1.5 * meanExecutionPeriod.getLastOutput())
869  {
871  "Timing warning: Suspicious executionPeriod=%.03f ms is far "
872  "above the average of %.03f ms",
873  1e3 * period_tim, meanExecutionPeriod.getLastOutput() * 1e3);
874  }
875  meanExecutionPeriod.filter(period_tim);
877 
879  {
881  mrpt::format(
882  "CMD: %s "
883  "speedScale=%.04f "
884  "T=%.01lfms Exec:%.01lfms|%.01lfms "
885  "PTG#%i\n",
886  new_vel_cmd ? new_vel_cmd->asString().c_str() : "NOP",
887  selectedHolonomicMovement ? selectedHolonomicMovement->speed
888  : .0,
890  1000.0 * meanExecutionTime.getLastOutput(),
892  best_ptg_idx));
893  }
894  if (fill_log_record)
895  {
897  newLogRec, relTargets, best_ptg_idx, new_vel_cmd, nPTGs,
898  best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
899  rel_pose_PTG_origin_wrt_sense_NOP, executionTimeValue,
900  tim_changeSpeed, tim_start_iteration);
901  }
902  }
903  catch (std::exception& e)
904  {
906  std::string(
907  "[CAbstractPTGBasedReactive::performNavigationStep] "
908  "Stopping robot and finishing navigation due to "
909  "exception:\n") +
910  std::string(e.what()));
911  }
912  catch (...)
913  {
915  "[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot "
916  "and finishing navigation due to untyped exception.");
917  }
918 }
919 
920 /** \callergraph */
922  CLogFileRecord& newLogRec, const std::vector<TPose2D>& relTargets,
923  int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmd::Ptr& new_vel_cmd,
924  const int nPTGs, const bool best_is_NOP_cmdvel,
925  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP,
926  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense_NOP,
927  const double executionTimeValue, const double tim_changeSpeed,
928  const mrpt::system::TTimeStamp& tim_start_iteration)
929 {
930  // ---------------------------------------
931  // STEP8: Generate log record
932  // ---------------------------------------
933  m_timelogger.enter("navigationStep.populate_log_info");
934 
935  this->loggingGetWSObstaclesAndShape(newLogRec);
936 
939  newLogRec.WS_targets_relative = relTargets;
940  newLogRec.nSelectedPTG = nSelectedPTG;
941  newLogRec.cur_vel = m_curPoseVel.velGlobal;
942  newLogRec.cur_vel_local = m_curPoseVel.velLocal;
943  newLogRec.cmd_vel = new_vel_cmd;
944  newLogRec.values["estimatedExecutionPeriod"] =
946  newLogRec.values["executionTime"] = executionTimeValue;
947  newLogRec.values["executionTime_avr"] = meanExecutionTime.getLastOutput();
948  newLogRec.values["time_changeSpeeds()"] = tim_changeSpeed;
949  newLogRec.values["time_changeSpeeds()_avr"] =
951  newLogRec.values["CWaypointsNavigator::navigationStep()"] =
952  m_timlog_delays.getLastTime("CWaypointsNavigator::navigationStep()");
953  newLogRec.values["CAbstractNavigator::navigationStep()"] =
954  m_timlog_delays.getLastTime("CAbstractNavigator::navigationStep()");
955  newLogRec.timestamps["tim_start_iteration"] = tim_start_iteration;
956  newLogRec.timestamps["curPoseAndVel"] = m_curPoseVel.timestamp;
957  newLogRec.nPTGs = nPTGs;
958 
959  // NOP mode stuff:
961  rel_cur_pose_wrt_last_vel_cmd_NOP;
963  rel_pose_PTG_origin_wrt_sense_NOP;
964  newLogRec.ptg_index_NOP =
965  best_is_NOP_cmdvel ? m_lastSentVelCmd.ptg_index : -1;
968 
969  m_timelogger.leave("navigationStep.populate_log_info");
970 
971  // Save to log file:
972  // --------------------------------------
973  {
975  m_timelogger, "navigationStep.write_log_file");
976  if (m_logFile) (*m_logFile) << newLogRec;
977  }
978  // Set as last log record
979  {
980  std::lock_guard<std::recursive_mutex> lock_log(
981  m_critZoneLastLog); // Lock
982  lastLogRecord = newLogRec; // COPY
983  }
984 }
985 
986 /** \callergraph */
988  TCandidateMovementPTG& cm, const std::vector<double>& in_TPObstacles,
989  const mrpt::nav::ClearanceDiagram& in_clearance,
990  const std::vector<mrpt::math::TPose2D>& WS_Targets,
991  const std::vector<CAbstractPTGBasedReactive::PTGTarget>& TP_Targets,
993  const bool this_is_PTG_continuation,
994  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP,
995  const unsigned int ptg_idx4weights,
996  const mrpt::system::TTimeStamp tim_start_iteration)
997 {
998  MRPT_START;
999 
1000  const double ref_dist = cm.PTG->getRefDistance();
1001 
1002  // Replaced by: TP_Targets[i].*
1003  // const double target_dir = (TP_Target.x!=0 || TP_Target.y!=0) ?
1004  // atan2( TP_Target.y, TP_Target.x) : 0.0;
1005  // const int target_k = static_cast<int>( cm.PTG->alpha2index(
1006  // target_dir ) );
1007  // const double target_d_norm = TP_Target.norm();
1008 
1009  // We need to evaluate the movement wrt to ONE target of the possibly many
1010  // input ones.
1011  // Policy: use the target whose TP-Space direction is closer to this
1012  // candidate direction:
1013  size_t selected_trg_idx = 0;
1014  {
1015  double best_trg_angdist = std::numeric_limits<double>::max();
1016  for (size_t i = 0; i < TP_Targets.size(); i++)
1017  {
1018  const double angdist = std::abs(
1020  TP_Targets[i].target_alpha, cm.direction));
1021  if (angdist < best_trg_angdist)
1022  {
1023  best_trg_angdist = angdist;
1024  selected_trg_idx = i;
1025  }
1026  }
1027  }
1028  ASSERT_(selected_trg_idx < WS_Targets.size());
1029  const auto WS_Target = WS_Targets[selected_trg_idx];
1030  const auto TP_Target = TP_Targets[selected_trg_idx];
1031 
1032  const double target_d_norm = TP_Target.target_dist;
1033 
1034  // Picked movement direction:
1035  const int move_k = static_cast<int>(cm.PTG->alpha2index(cm.direction));
1036  const double target_WS_d = WS_Target.norm();
1037 
1038  // Coordinates of the trajectory end for the given PTG and "alpha":
1039  const double d = std::min(in_TPObstacles[move_k], 0.99 * target_d_norm);
1040  uint32_t nStep;
1041  bool pt_in_range = cm.PTG->getPathStepForDist(move_k, d, nStep);
1042  ASSERT_(pt_in_range)
1043 
1044  mrpt::math::TPose2D pose;
1045  cm.PTG->getPathPose(move_k, nStep, pose);
1046 
1047  // Make sure that the target slow-down is honored, as seen in real-world
1048  // Euclidean space
1049  // (as opposed to TP-Space, where the holo methods are evaluated)
1050  if (m_navigationParams &&
1051  m_navigationParams->target.targetDesiredRelSpeed < 1.0 &&
1052  !m_holonomicMethod.empty() && m_holonomicMethod[0] != nullptr &&
1053  !cm.PTG->supportSpeedAtTarget() // If the PTG is able to handle the
1054  // slow-down on its own, dont change
1055  // speed here
1056  )
1057  {
1058  const double TARGET_SLOW_APPROACHING_DISTANCE =
1059  m_holonomicMethod[0]->getTargetApproachSlowDownDistance();
1060 
1061  const double Vf =
1062  m_navigationParams->target.targetDesiredRelSpeed; // [0,1]
1063 
1064  const double f = std::min(
1065  1.0,
1066  Vf + target_WS_d * (1.0 - Vf) / TARGET_SLOW_APPROACHING_DISTANCE);
1067  if (f < cm.speed)
1068  {
1069  newLogRec.additional_debug_msgs["PTG_eval.speed"] = mrpt::format(
1070  "Relative speed reduced %.03f->%.03f based on Euclidean "
1071  "nearness to target.",
1072  cm.speed, f);
1073  cm.speed = f;
1074  }
1075  }
1076 
1077  // Start storing params in the candidate move structure:
1078  cm.props["ptg_idx"] = ptg_idx4weights;
1079  cm.props["ref_dist"] = ref_dist;
1080  cm.props["target_dir"] = TP_Target.target_alpha;
1081  cm.props["target_k"] = TP_Target.target_k;
1082  cm.props["target_d_norm"] = target_d_norm;
1083  cm.props["move_k"] = move_k;
1084  double& move_cur_d = cm.props["move_cur_d"] =
1085  0; // current robot path normalized distance over path (0 unless in a
1086  // NOP cmd)
1087  cm.props["is_PTG_cont"] = this_is_PTG_continuation ? 1 : 0;
1088  cm.props["num_paths"] = in_TPObstacles.size();
1089  cm.props["WS_target_x"] = WS_Target.x;
1090  cm.props["WS_target_y"] = WS_Target.y;
1091  cm.props["robpose_x"] = pose.x;
1092  cm.props["robpose_y"] = pose.y;
1093  cm.props["robpose_phi"] = pose.phi;
1094  cm.props["ptg_priority"] =
1095  cm.PTG->getScorePriority() *
1096  cm.PTG->evalPathRelativePriority(TP_Target.target_k, target_d_norm);
1097  const bool is_slowdown =
1098  this_is_PTG_continuation
1100  : (cm.PTG->supportSpeedAtTarget() && TP_Target.target_k == move_k);
1101  cm.props["is_slowdown"] = is_slowdown ? 1 : 0;
1102 
1103  // Factor 1: Free distance for the chosen PTG and "alpha" in the TP-Space:
1104  // ----------------------------------------------------------------------
1105  double& colfree = cm.props["collision_free_distance"];
1106 
1107  // distance to collision:
1108  colfree = in_TPObstacles[move_k]; // we'll next substract here the
1109  // already-traveled distance, for NOP
1110  // motion candidates.
1111 
1112  // Special case for NOP motion cmd:
1113  // consider only the empty space *after* the current robot pose, which is
1114  // not at the origin.
1115 
1116  if (this_is_PTG_continuation)
1117  {
1118  int cur_k = 0;
1119  double cur_norm_d = .0;
1120  bool is_exact, is_time_based = false;
1121  uint32_t cur_ptg_step = 0;
1122 
1123  // Use: time-based prediction for shorter distances, PTG inverse
1124  // mapping-based for longer ranges:
1125  const double maxD = params_abstract_ptg_navigator
1127  if (std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.x) > maxD ||
1128  std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.y) > maxD)
1129  {
1130  is_exact = cm.PTG->inverseMap_WS2TP(
1131  rel_cur_pose_wrt_last_vel_cmd_NOP.x,
1132  rel_cur_pose_wrt_last_vel_cmd_NOP.y, cur_k, cur_norm_d);
1133  }
1134  else
1135  {
1136  // Use time:
1137  is_time_based = true;
1138  is_exact = true; // well, sort of...
1139  const double NOP_At =
1142  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
1143  newLogRec.additional_debug_msgs["PTG_eval.NOP_At"] =
1144  mrpt::format("%.06f s", NOP_At);
1145  cur_k = move_k;
1146  cur_ptg_step =
1147  mrpt::utils::round(NOP_At / cm.PTG->getPathStepDuration());
1148  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step) /
1149  cm.PTG->getRefDistance();
1150  {
1151  const double cur_a = cm.PTG->index2alpha(cur_k);
1152  log.TP_Robot.x = cos(cur_a) * cur_norm_d;
1153  log.TP_Robot.y = sin(cur_a) * cur_norm_d;
1154  cm.starting_robot_dir = cur_a;
1155  cm.starting_robot_dist = cur_norm_d;
1156  }
1157  }
1158 
1159  if (!is_exact)
1160  {
1161  // Don't trust this step: we are not 100% sure of the robot pose in
1162  // TP-Space for this "PTG continuation" step:
1163  cm.speed = -0.01; // this enforces a 0 global evaluation score
1164  newLogRec.additional_debug_msgs["PTG_eval"] =
1165  "PTG-continuation not allowed, cur. pose out of PTG domain.";
1166  return;
1167  }
1168  bool WS_point_is_unique = true;
1169  if (!is_time_based)
1170  {
1171  bool ok1 = cm.PTG->getPathStepForDist(
1173  cur_norm_d * cm.PTG->getRefDistance(), cur_ptg_step);
1174  if (ok1)
1175  {
1176  // Check bijective:
1177  WS_point_is_unique = cm.PTG->isBijectiveAt(cur_k, cur_ptg_step);
1178  const uint32_t predicted_step =
1181  mrpt::system::now()) /
1182  cm.PTG->getPathStepDuration();
1183  WS_point_is_unique =
1184  WS_point_is_unique &&
1185  cm.PTG->isBijectiveAt(move_k, predicted_step);
1186  newLogRec.additional_debug_msgs["PTG_eval.bijective"] =
1187  mrpt::format(
1188  "isBijectiveAt(): k=%i step=%i -> %s", (int)cur_k,
1189  (int)cur_ptg_step, WS_point_is_unique ? "yes" : "no");
1190 
1191  if (!WS_point_is_unique)
1192  {
1193  // Don't trust direction:
1194  cur_k = move_k;
1195  cur_ptg_step = predicted_step;
1196  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step);
1197  }
1198  {
1199  const double cur_a = cm.PTG->index2alpha(cur_k);
1200  log.TP_Robot.x = cos(cur_a) * cur_norm_d;
1201  log.TP_Robot.y = sin(cur_a) * cur_norm_d;
1202  cm.starting_robot_dir = cur_a;
1203  cm.starting_robot_dist = cur_norm_d;
1204  }
1205 
1206  mrpt::math::TPose2D predicted_rel_pose;
1207  cm.PTG->getPathPose(
1208  m_lastSentVelCmd.ptg_alpha_index, cur_ptg_step,
1209  predicted_rel_pose);
1210  const auto predicted_pose_global =
1211  m_lastSentVelCmd.poseVel.rawOdometry + predicted_rel_pose;
1212  const double predicted2real_dist = mrpt::math::hypot_fast(
1213  predicted_pose_global.x - m_curPoseVel.rawOdometry.x,
1214  predicted_pose_global.y - m_curPoseVel.rawOdometry.y);
1215  newLogRec.additional_debug_msgs["PTG_eval.lastCmdPose(raw)"] =
1217  newLogRec.additional_debug_msgs["PTG_eval.PTGcont"] =
1218  mrpt::format(
1219  "mismatchDistance=%.03f cm", 1e2 * predicted2real_dist);
1220 
1221  if (predicted2real_dist >
1223  .max_distance_predicted_actual_path &&
1224  (!is_slowdown ||
1225  (target_d_norm - cur_norm_d) * ref_dist > 2.0 /*meters*/))
1226  {
1227  cm.speed =
1228  -0.01; // this enforces a 0 global evaluation score
1229  newLogRec.additional_debug_msgs["PTG_eval"] =
1230  "PTG-continuation not allowed, mismatchDistance above "
1231  "threshold.";
1232  return;
1233  }
1234  }
1235  else
1236  {
1237  cm.speed = -0.01; // this enforces a 0 global evaluation score
1238  newLogRec.additional_debug_msgs["PTG_eval"] =
1239  "PTG-continuation not allowed, couldn't get PTG step for "
1240  "cur. robot pose.";
1241  return;
1242  }
1243  }
1244 
1245  // Path following isn't perfect: we can't be 100% sure of whether the
1246  // robot followed exactly
1247  // the intended path (`kDirection`), or if it's actually a bit shifted,
1248  // as reported in `cur_k`.
1249  // Take the least favorable case.
1250  // [Update] Do this only when the PTG gave us a unique-mapped WS<->TPS
1251  // point:
1252 
1253  colfree = WS_point_is_unique
1254  ? std::min(in_TPObstacles[move_k], in_TPObstacles[cur_k])
1255  : in_TPObstacles[move_k];
1256 
1257  // Only discount free space if there was a real obstacle, not the "end
1258  // of path" due to limited refDistance.
1259  if (colfree < 0.99)
1260  {
1261  colfree -= cur_norm_d;
1262  }
1263 
1264  // Save estimated robot pose over path as a parameter for scores:
1265  move_cur_d = cur_norm_d;
1266  }
1267 
1268  // Factor4: Decrease in euclidean distance between (x,y) and the target:
1269  // Moving away of the target is negatively valued.
1270  cm.props["dist_eucl_final"] =
1271  mrpt::math::hypot_fast(WS_Target.x - pose.x, WS_Target.y - pose.y);
1272 
1273  // dist_eucl_min: Use PTG clearance methods to evaluate the real-world
1274  // (WorkSpace) minimum distance to target:
1275  {
1276  typedef std::map<double, double> map_d2d_t;
1277  map_d2d_t pathDists;
1278  const double D = cm.PTG->getRefDistance();
1279  const int num_steps = ceil(D * 2.0);
1280  for (int i = 0; i < num_steps; i++)
1281  {
1282  pathDists[i / double(num_steps)] =
1283  100.0; // default normalized distance to target (a huge value)
1284  }
1285 
1287  WS_Target.x, WS_Target.y, move_k, pathDists,
1288  false /*treat point as target, not obstacle*/);
1289 
1290  const auto it = std::min_element(
1291  pathDists.begin(), pathDists.end(),
1292  [colfree](map_d2d_t::value_type& l, map_d2d_t::value_type& r)
1293  -> bool { return (l.second < r.second) && l.first < colfree; });
1294  cm.props["dist_eucl_min"] = (it != pathDists.end())
1295  ? it->second * cm.PTG->getRefDistance()
1296  : 100.0;
1297  }
1298 
1299  // Factor5: Hysteresis:
1300  // -----------------------------------------------------
1301  double& hysteresis = cm.props["hysteresis"];
1302  hysteresis = .0;
1303 
1304  if (cm.PTG->supportVelCmdNOP())
1305  {
1306  hysteresis = this_is_PTG_continuation ? 1.0 : 0.;
1307  }
1308  else if (m_last_vel_cmd)
1309  {
1311  desired_cmd = cm.PTG->directionToMotionCommand(move_k);
1313  const mrpt::kinematics::CVehicleVelCmd* ptr2 = desired_cmd.get();
1314  if (typeid(*ptr1) == typeid(*ptr2))
1315  {
1316  ASSERT_EQUAL_(
1317  m_last_vel_cmd->getVelCmdLength(),
1318  desired_cmd->getVelCmdLength());
1319 
1320  double simil_score = 0.5;
1321  for (size_t i = 0; i < desired_cmd->getVelCmdLength(); i++)
1322  {
1323  const double scr =
1324  exp(-std::abs(
1325  desired_cmd->getVelCmdElement(i) -
1326  m_last_vel_cmd->getVelCmdElement(i)) /
1327  0.20);
1328  mrpt::utils::keep_min(simil_score, scr);
1329  }
1330  hysteresis = simil_score;
1331  }
1332  }
1333 
1334  // Factor6: clearance
1335  // -----------------------------------------------------
1336  // clearance indicators that may be useful in deciding the best motion:
1337  double& clearance = cm.props["clearance"];
1338  clearance = in_clearance.getClearance(
1339  move_k, target_d_norm * 1.01, false /* spot, dont interpolate */);
1340  cm.props["clearance_50p"] = in_clearance.getClearance(
1341  move_k, target_d_norm * 0.5, false /* spot, dont interpolate */);
1342  cm.props["clearance_path"] = in_clearance.getClearance(
1343  move_k, target_d_norm * 0.9, true /* average */);
1344  cm.props["clearance_path_50p"] = in_clearance.getClearance(
1345  move_k, target_d_norm * 0.5, true /* average */);
1346 
1347  // Factor: ETA (Estimated Time of Arrival to target or to closest obstacle,
1348  // whatever it's first)
1349  // -----------------------------------------------------
1350  double& eta = cm.props["eta"];
1351  eta = .0;
1352  if (cm.PTG && cm.speed > .0) // for valid cases only
1353  {
1354  // OK, we have a direct path to target without collisions.
1355  const double path_len_meters = d * ref_dist;
1356 
1357  // Calculate their ETA
1358  uint32_t target_step;
1359  bool valid_step =
1360  cm.PTG->getPathStepForDist(move_k, path_len_meters, target_step);
1361  if (valid_step)
1362  {
1363  eta = cm.PTG->getPathStepDuration() *
1364  target_step /* PTG original time to get to target point */
1365  * cm.speed /* times the speed scale factor*/;
1366 
1367  double discount_time = .0;
1368  if (this_is_PTG_continuation)
1369  {
1370  // Heuristic: discount the time already executed.
1371  // Note that hm.speed above scales the overall path time using
1372  // the current speed scale, not the exact
1373  // integration over the past timesteps. It's an approximation,
1374  // probably good enough...
1375  discount_time = mrpt::system::timeDifference(
1376  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
1377  }
1378  eta -= discount_time; // This could even become negative if the
1379  // approximation is poor...
1380  }
1381  }
1382 
1383  MRPT_END;
1384 }
1385 
1387  const TCandidateMovementPTG& in_movement,
1389 {
1390  mrpt::utils::CTimeLoggerEntry tle(m_timelogger, "generate_vel_cmd");
1391  double cmdvel_speed_scale = 1.0;
1392  try
1393  {
1394  if (in_movement.speed == 0)
1395  {
1396  // The robot will stop:
1397  new_vel_cmd =
1399  new_vel_cmd->setToStop();
1400  }
1401  else
1402  {
1403  // Take the normalized movement command:
1404  new_vel_cmd = in_movement.PTG->directionToMotionCommand(
1405  in_movement.PTG->alpha2index(in_movement.direction));
1406 
1407  // Scale holonomic speeds to real-world one:
1408  new_vel_cmd->cmdVel_scale(in_movement.speed);
1409  cmdvel_speed_scale *= in_movement.speed;
1410 
1411  if (!m_last_vel_cmd) // first iteration? Use default values:
1412  m_last_vel_cmd =
1414 
1415  // Honor user speed limits & "blending":
1416  const double beta = meanExecutionPeriod.getLastOutput() /
1419  cmdvel_speed_scale *= new_vel_cmd->cmdVel_limits(
1420  *m_last_vel_cmd, beta,
1422  }
1423 
1424  m_last_vel_cmd = new_vel_cmd; // Save for filtering in next step
1425  }
1426  catch (std::exception& e)
1427  {
1429  "[CAbstractPTGBasedReactive::generate_vel_cmd] Exception: "
1430  << e.what());
1431  }
1432  return cmdvel_speed_scale;
1433 }
1434 
1435 /** \callergraph */
1437  const mrpt::math::TPoint2D& wp) const
1438 {
1439  MRPT_START;
1440 
1441  const size_t N = this->getPTG_count();
1442  if (m_infoPerPTG.size() < N ||
1446  return false; // We didn't run yet or obstacle info is old
1447 
1448  for (size_t i = 0; i < N; i++)
1449  {
1450  const CParameterizedTrajectoryGenerator* ptg = getPTG(i);
1451 
1452  const std::vector<double>& tp_obs =
1453  m_infoPerPTG[i].TP_Obstacles; // normalized distances
1454  if (tp_obs.size() != ptg->getPathCount())
1455  continue; // May be this PTG has not been used so far? (Target out
1456  // of domain,...)
1457 
1458  int wp_k;
1459  double wp_norm_d;
1460  bool is_into_domain =
1461  ptg->inverseMap_WS2TP(wp.x, wp.y, wp_k, wp_norm_d);
1462  if (!is_into_domain) continue;
1463 
1464  ASSERT_(wp_k < int(tp_obs.size()));
1465 
1466  const double collision_free_dist = tp_obs[wp_k];
1467  if (collision_free_dist > 1.01 * wp_norm_d)
1468  return true; // free path found to target
1469  }
1470 
1471  return false; // no way found
1472  MRPT_END;
1473 }
1474 
1475 /** \callergraph */
1477 {
1479 }
1480 
1481 /** \callergraph */
1483 {
1486 
1487  CWaypointsNavigator::onStartNewNavigation(); // Call base method we
1488  // override
1489 }
1490 
1493 {
1494  ptg_index = -1;
1495  ptg_alpha_index = -1;
1496  tim_send_cmd_vel = INVALID_TIMESTAMP;
1497  poseVel = TRobotPoseVel();
1498  colfreedist_move_k = .0;
1499  was_slowdown = false;
1500  speed_scale = 1.0;
1502 }
1504 {
1505  return this->poseVel.timestamp != INVALID_TIMESTAMP;
1506 }
1507 
1508 /** \callergraph */
1510  CParameterizedTrajectoryGenerator* ptg, const size_t indexPTG,
1511  const std::vector<mrpt::math::TPose2D>& relTargets,
1512  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense, TInfoPerPTG& ipf,
1513  TCandidateMovementPTG& cm, CLogFileRecord& newLogRec,
1514  const bool this_is_PTG_continuation,
1516  const mrpt::system::TTimeStamp tim_start_iteration,
1517  const TNavigationParams& navp,
1518  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP)
1519 {
1520  ASSERT_(ptg);
1521 
1522  const size_t idx_in_log_infoPerPTGs =
1523  this_is_PTG_continuation ? getPTG_count() : indexPTG;
1524 
1526  cm.PTG = ptg;
1527 
1528  // If the user doesn't want to use this PTG, just mark it as invalid:
1529  ipf.targets.clear();
1530  bool use_this_ptg = true;
1531  {
1532  const TNavigationParamsPTG* navpPTG =
1533  dynamic_cast<const TNavigationParamsPTG*>(&navp);
1534  if (navpPTG && !navpPTG->restrict_PTG_indices.empty())
1535  {
1536  use_this_ptg = false;
1537  for (size_t i = 0;
1538  i < navpPTG->restrict_PTG_indices.size() && !use_this_ptg; i++)
1539  {
1540  if (navpPTG->restrict_PTG_indices[i] == indexPTG)
1541  use_this_ptg = true;
1542  }
1543  }
1544  }
1545 
1546  double timeForTPObsTransformation = .0, timeForHolonomicMethod = .0;
1547 
1548  // Normal PTG validity filter: check if target falls into the PTG domain:
1549  bool any_TPTarget_is_valid = false;
1550  if (use_this_ptg)
1551  {
1552  for (size_t i = 0; i < relTargets.size(); i++)
1553  {
1554  const auto& trg = relTargets[i];
1555  PTGTarget ptg_target;
1556 
1557  ptg_target.valid_TP = ptg->inverseMap_WS2TP(
1558  trg.x, trg.y, ptg_target.target_k, ptg_target.target_dist);
1559  if (!ptg_target.valid_TP) continue;
1560 
1561  any_TPTarget_is_valid = true;
1562  ptg_target.target_alpha = ptg->index2alpha(ptg_target.target_k);
1563  ptg_target.TP_Target.x =
1564  cos(ptg_target.target_alpha) * ptg_target.target_dist;
1565  ptg_target.TP_Target.y =
1566  sin(ptg_target.target_alpha) * ptg_target.target_dist;
1567 
1568  ipf.targets.emplace_back(ptg_target);
1569  }
1570  }
1571 
1572  if (!any_TPTarget_is_valid)
1573  {
1575  "mov_candidate_%u", static_cast<unsigned int>(indexPTG))] =
1576  "PTG discarded since target(s) is(are) out of domain.";
1577  }
1578  else
1579  {
1580  // STEP3(b): Build TP-Obstacles
1581  // -----------------------------------------------------------------------------
1582  {
1583  tictac.Tic();
1584 
1585  // Initialize TP-Obstacles:
1586  const size_t Ki = ptg->getAlphaValuesCount();
1587  ptg->initTPObstacles(ipf.TP_Obstacles);
1589  {
1590  ptg->initClearanceDiagram(ipf.clearance);
1591  }
1592 
1593  // Implementation-dependent conversion:
1595  indexPTG, ipf.TP_Obstacles, ipf.clearance,
1596  mrpt::math::TPose2D(0, 0, 0) - rel_pose_PTG_origin_wrt_sense,
1598 
1600  {
1602  }
1603 
1604  // Distances in TP-Space are normalized to [0,1]:
1605  const double _refD = 1.0 / ptg->getRefDistance();
1606  for (size_t i = 0; i < Ki; i++) ipf.TP_Obstacles[i] *= _refD;
1607 
1608  timeForTPObsTransformation = tictac.Tac();
1609  if (m_timelogger.isEnabled())
1611  "navigationStep.STEP3_WSpaceToTPSpace",
1612  timeForTPObsTransformation);
1613  }
1614 
1615  // STEP4: Holonomic navigation method
1616  // -----------------------------------------------------------------------------
1617  if (!this_is_PTG_continuation)
1618  {
1619  tictac.Tic();
1620 
1621  // Slow down if we are approaching the final target, etc.
1622  holoMethod.enableApproachTargetSlowDown(
1623  navp.target.targetDesiredRelSpeed < .11);
1624 
1625  // Prepare holonomic algorithm call:
1627  ni.clearance = &ipf.clearance;
1628  ni.maxObstacleDist = 1.0;
1629  ni.maxRobotSpeed = 1.0; // So, we use a normalized max speed here.
1630  ni.obstacles = ipf.TP_Obstacles; // Normalized [0,1]
1631 
1632  ni.targets.clear(); // Normalized [0,1]
1633  for (const auto& t : ipf.targets)
1634  {
1635  ni.targets.push_back(t.TP_Target);
1636  }
1637 
1639 
1640  holoMethod.navigate(ni, no);
1641 
1642  // Extract resuls:
1643  cm.direction = no.desiredDirection;
1644  cm.speed = no.desiredSpeed;
1645  HLFR = no.logRecord;
1646 
1647  // Security: Scale down the velocity when heading towards obstacles,
1648  // such that it's assured that we never go thru an obstacle!
1649  const int kDirection =
1650  static_cast<int>(cm.PTG->alpha2index(cm.direction));
1651  double obsFreeNormalizedDistance = ipf.TP_Obstacles[kDirection];
1652 
1653  // Take into account the future robot pose after NOP motion
1654  // iterations to slow down accordingly *now*
1655  if (ptg->supportVelCmdNOP())
1656  {
1657  const double v = mrpt::math::hypot_fast(
1659  const double d = v * ptg->maxTimeInVelCmdNOP(kDirection);
1660  obsFreeNormalizedDistance = std::min(
1661  obsFreeNormalizedDistance,
1662  std::max(0.90, obsFreeNormalizedDistance - d));
1663  }
1664 
1665  double velScale = 1.0;
1666  ASSERT_(
1669  if (obsFreeNormalizedDistance <
1671  {
1672  if (obsFreeNormalizedDistance <=
1674  velScale = 0.0; // security stop
1675  else
1676  velScale =
1677  (obsFreeNormalizedDistance -
1681  }
1682 
1683  // Scale:
1684  cm.speed *= velScale;
1685 
1686  timeForHolonomicMethod = tictac.Tac();
1687  if (m_timelogger.isEnabled())
1689  "navigationStep.STEP4_HolonomicMethod",
1690  timeForHolonomicMethod);
1691  }
1692  else
1693  {
1694  // "NOP cmdvel" case: don't need to re-run holo algorithm, just keep
1695  // the last selection:
1697  cm.speed = 1.0; // Not used.
1698  }
1699 
1700  // STEP5: Evaluate each movement to assign them a "evaluation" value.
1701  // ---------------------------------------------------------------------
1702  {
1703  CTimeLoggerEntry tle(
1704  m_timelogger, "navigationStep.calc_move_candidate_scores");
1705 
1707  cm, ipf.TP_Obstacles, ipf.clearance, relTargets, ipf.targets,
1708  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs], newLogRec,
1709  this_is_PTG_continuation, rel_cur_pose_wrt_last_vel_cmd_NOP,
1710  indexPTG, tim_start_iteration);
1711 
1712  // Store NOP related extra vars:
1713  cm.props["original_col_free_dist"] =
1714  this_is_PTG_continuation ? m_lastSentVelCmd.colfreedist_move_k
1715  : .0;
1716 
1717  // SAVE LOG
1718  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs].evalFactors = cm.props;
1719  }
1720 
1721  } // end "valid_TP"
1722 
1723  // Logging:
1724  const bool fill_log_record =
1725  (m_logFile != nullptr || m_enableKeepLogRecords);
1726  if (fill_log_record)
1727  {
1729  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs];
1730  if (!this_is_PTG_continuation)
1731  ipp.PTG_desc = ptg->getDescription();
1732  else
1733  ipp.PTG_desc = mrpt::format(
1734  "NOP cmdvel (prev PTG idx=%u)",
1735  static_cast<unsigned int>(m_lastSentVelCmd.ptg_index));
1736 
1738  ipf.TP_Obstacles, ipp.TP_Obstacles);
1739  ipp.clearance = ipf.clearance;
1740  ipp.TP_Targets.clear();
1741  for (const auto& t : ipf.targets)
1742  {
1743  ipp.TP_Targets.push_back(t.TP_Target);
1744  }
1745  ipp.HLFR = HLFR;
1746  ipp.desiredDirection = cm.direction;
1747  ipp.desiredSpeed = cm.speed;
1748  ipp.timeForTPObsTransformation = timeForTPObsTransformation;
1749  ipp.timeForHolonomicMethod = timeForHolonomicMethod;
1750  }
1751 }
1752 
1755 {
1756  MRPT_START;
1757 
1758  robot_absolute_speed_limits.loadConfigFile(c, s);
1759 
1760  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(holonomic_method, string);
1761  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(motion_decider_method, string);
1762  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(ref_distance, double);
1763  MRPT_LOAD_CONFIG_VAR_CS(speedfilter_tau, double);
1764  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_start, double);
1765  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_end, double);
1766  MRPT_LOAD_CONFIG_VAR_CS(use_delays_model, bool);
1767  MRPT_LOAD_CONFIG_VAR_CS(max_distance_predicted_actual_path, double);
1769  min_normalized_free_space_for_ptg_continuation, double);
1770  MRPT_LOAD_CONFIG_VAR_CS(enable_obstacle_filtering, bool);
1771  MRPT_LOAD_CONFIG_VAR_CS(evaluate_clearance, bool);
1772  MRPT_LOAD_CONFIG_VAR_CS(max_dist_for_timebased_path_prediction, double);
1773 
1774  MRPT_END;
1775 }
1776 
1779 {
1780  robot_absolute_speed_limits.saveToConfigFile(c, s);
1781 
1782  // Build list of known holo methods:
1783  string lstHoloStr = "# List of known classes:\n";
1784  {
1787  for (const auto& c : lst)
1788  lstHoloStr +=
1789  string("# - `") + string(c->className) + string("`\n");
1790  }
1792  holonomic_method,
1793  string(
1794  "C++ class name of the holonomic navigation method to run in "
1795  "the transformed TP-Space.\n") +
1796  lstHoloStr);
1797 
1798  // Build list of known decider methods:
1799  string lstDecidersStr = "# List of known classes:\n";
1800  {
1803  for (const auto& c : lst)
1804  lstDecidersStr +=
1805  string("# - `") + string(c->className) + string("`\n");
1806  }
1808  motion_decider_method,
1809  string("C++ class name of the motion decider method.\n") +
1810  lstDecidersStr);
1811 
1813  ref_distance,
1814  "Maximum distance up to obstacles will be considered (D_{max} in "
1815  "papers).");
1817  speedfilter_tau,
1818  "Time constant (in seconds) for the low-pass filter applied to "
1819  "kinematic velocity commands (default=0: no filtering)");
1821  secure_distance_start,
1822  "In normalized distance [0,1], start/end of a ramp function that "
1823  "scales the holonomic navigator output velocity.");
1825  secure_distance_end,
1826  "In normalized distance [0,1], start/end of a ramp function that "
1827  "scales the holonomic navigator output velocity.");
1829  use_delays_model,
1830  "Whether to use robot pose inter/extrapolation to improve accuracy "
1831  "(Default:false)");
1833  max_distance_predicted_actual_path,
1834  "Max distance [meters] to discard current PTG and issue a new vel cmd "
1835  "(default= 0.05)");
1837  min_normalized_free_space_for_ptg_continuation,
1838  "Min normalized dist [0,1] after current pose in a PTG continuation to "
1839  "allow it.");
1841  enable_obstacle_filtering,
1842  "Enabled obstacle filtering (params in its own section)");
1844  evaluate_clearance,
1845  "Enable exact computation of clearance (default=false)");
1847  max_dist_for_timebased_path_prediction,
1848  "Max dist [meters] to use time-based path prediction for NOP "
1849  "evaluation");
1850 }
1851 
1854  : holonomic_method(),
1855  ptg_cache_files_directory("."),
1856  ref_distance(4.0),
1857  speedfilter_tau(0.0),
1858  secure_distance_start(0.05),
1859  secure_distance_end(0.20),
1860  use_delays_model(false),
1861  max_distance_predicted_actual_path(0.15),
1862  min_normalized_free_space_for_ptg_continuation(0.2),
1863  robot_absolute_speed_limits(),
1864  enable_obstacle_filtering(true),
1865  evaluate_clearance(false),
1866  max_dist_for_timebased_path_prediction(2.0)
1867 {
1868 }
1869 
1872 {
1873  MRPT_START;
1875 
1876  // At this point, we have been called from the derived class, who must be
1877  // already loaded all its specific params, including PTGs.
1878 
1879  // Load my params:
1881  c, "CAbstractPTGBasedReactive");
1882 
1883  // Filtering:
1885  {
1889  filter->options.loadFromConfigFile(c, "CPointCloudFilterByDistance");
1890  }
1891  else
1892  {
1893  m_WS_filter.reset();
1894  }
1895 
1896  // Movement chooser:
1899  if (!m_multiobjopt)
1901  "Non-registered CMultiObjectiveMotionOptimizerBase className=`%s`",
1903 
1904  m_multiobjopt->loadConfigFile(c);
1905 
1906  // Holo method:
1908  ASSERT_(!m_holonomicMethod.empty())
1909 
1910  CWaypointsNavigator::loadConfigFile(c); // Load parent params
1911 
1912  m_init_done =
1913  true; // If we reached this point without an exception, all is good.
1914  MRPT_END;
1915 }
1916 
1919 {
1922  c, "CAbstractPTGBasedReactive");
1923 
1924  // Filtering:
1925  {
1927  filter.options.saveToConfigFile(c, "CPointCloudFilterByDistance");
1928  }
1929 
1930  // Holo method:
1931  if (!m_holonomicMethod.empty() && m_holonomicMethod[0])
1932  {
1933  // Save my current settings:
1934  m_holonomicMethod[0]->saveConfigFile(c);
1935  }
1936  else
1937  {
1938  // save options of ALL known methods:
1941  for (const auto& cl : lst)
1942  {
1944  mrpt::utils::CObject::Ptr(cl->createObject());
1946  dynamic_cast<CAbstractHolonomicReactiveMethod*>(obj.get());
1947  if (holo)
1948  {
1949  holo->saveConfigFile(c);
1950  }
1951  }
1952  }
1953 
1954  // Decider method:
1955  if (m_multiobjopt)
1956  {
1957  // Save my current settings:
1958  m_multiobjopt->saveConfigFile(c);
1959  }
1960  else
1961  {
1962  // save options of ALL known methods:
1965  for (const auto& cl : lst)
1966  {
1968  mrpt::utils::CObject::Ptr(cl->createObject());
1970  dynamic_cast<CMultiObjectiveMotionOptimizerBase*>(obj.get());
1971  if (momo)
1972  {
1973  momo->saveConfigFile(c);
1974  }
1975  }
1976  }
1977 }
1978 
1980  const double dist)
1981 {
1982  for (auto& o : m_holonomicMethod)
1983  {
1984  o->setTargetApproachSlowDownDistance(dist);
1985  }
1986 }
1987 
1989 {
1990  ASSERT_(!m_holonomicMethod.empty());
1991  return m_holonomicMethod[0]->getTargetApproachSlowDownDistance();
1992 }
#define ASSERT_EQUAL_(__A, __B)
double index2alpha(uint16_t k) const
Alpha value for the discrete corresponding value.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:32
virtual bool supportSpeedAtTarget() const
Returns true if this PTG takes into account the desired velocity at target.
std::recursive_mutex m_nav_cs
mutex for all navigation methods
CHolonomicLogFileRecord::Ptr HLFR
Other useful info about holonomic method execution.
mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP
TRobotPoseVel m_curPoseVel
Current robot pose (updated in CAbstractNavigator::navigationStep() )
virtual bool getPathStepForDist(uint16_t k, double dist, uint32_t &out_step) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < ...
virtual bool supportVelCmdNOP() const
Returns true if it is possible to stop sending velocity commands to the robot and, still, the robot controller will be able to keep following the last sent trajectory ("NOP" velocity commands).
bool createDirectory(const std::string &dirName)
Creates a directory.
Definition: filesystem.cpp:158
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
GLdouble GLdouble t
Definition: glext.h:3689
std::vector< std::string > log_entries
Optionally, debug logging info will be stored here by the implementor classes.
int32_t nSelectedPTG
The selected PTG.
#define min(a, b)
#define MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(variableName, variableType)
Shortcut for MRPT_LOAD_CONFIG_VAR_NO_DEFAULT() for REQUIRED variables config file object named c and ...
std::vector< mrpt::math::TPose2D > WS_targets_relative
Relative poses (wrt to robotPoseLocalization) for.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
double x
X,Y coordinates.
virtual double getPathStepDuration() const =0
Returns the duration (in seconds) of each "step".
mrpt::math::TTwist2D cur_vel_local
The actual robot velocities in local (robot) coordinates, as read from sensors, in "m/sec" and "rad/s...
void setTargetApproachSlowDownDistance(const double dist)
Changes this parameter in all inner holonomic navigator instances [m].
double x
X,Y coordinates.
virtual void onStartNewNavigation() override
Called whenever a new navigation has been started.
std::vector< double > final_evaluation
The final evaluation score for each candidate.
mrpt::poses::FrameTransformer< 2 > * m_frame_tf
Optional, user-provided frame transformer.
std::string sprintf_vector(const char *fmt, const std::vector< T > &V)
Generates a string for a vector in the format [A,B,C,...] to std::cout, and the fmt string for each v...
Definition: printf_vector.h:26
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
std::recursive_mutex m_critZoneLastLog
Critical zones.
mrpt::nav::ClearanceDiagram clearance
Clearance for each path.
GLenum GLint ref
Definition: glext.h:4050
#define MRPT_LOG_WARN_FMT(_FMT_STRING,...)
virtual bool isBijectiveAt(uint16_t k, uint32_t step) const
Returns true if a given TP-Space point maps to a unique point in Workspace, and viceversa.
std::vector< double > obstacles
Distance to obstacles in polar coordinates, relative to the robot.
mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense_NOP
CParameterizedTrajectoryGenerator * PTG
The associated PTG.
uint64_t Seek(uint64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) override
Introduces a pure virtual method for moving to a specified position in the streamed resource...
#define THROW_EXCEPTION(msg)
mrpt::math::TPose2D robotPoseOdometry
void getLastLogRecord(CLogFileRecord &o)
Provides a copy of the last log record with information about execution.
TRobotPoseVel poseVel
Robot pose & velocities and timestamp of when it was queried.
#define MRPT_LOG_DEBUG_FMT(_FMT_STRING,...)
std::shared_ptr< CPointCloudFilterBase > Ptr
void initialize() override
Must be called for loading collision grids, or the first navigation command may last a long time to b...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
This file implements several operations that operate element-wise on individual or pairs of container...
Base for all high-level navigation commands.
void initTPObstacles(std::vector< double > &TP_Obstacles) const
Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ra...
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:127
mrpt::utils::CTimeLogger m_timelogger
A complete time logger.
A base class for holonomic reactive navigation methods.
T angDistance(T from, T to)
Computes the shortest angular increment (or distance) between two planar orientations, such that it is constrained to [-pi,pi] and is correct for any combination of angles (e.g.
Definition: wrap2pi.h:98
mrpt::math::TPose2D relPoseSense
void enableLogFile(bool enable)
Enables/disables saving log files.
virtual double maxTimeInVelCmdNOP(int path_k) const
Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path...
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:76
std::vector< mrpt::math::TPoint2D > TP_Targets
Target(s) location in TP-Space.
std::vector< CAbstractHolonomicReactiveMethod::Ptr > m_holonomicMethod
The holonomic navigation algorithm (one object per PTG, so internal states are maintained) ...
#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 ...
bool m_enableConsoleOutput
Enables / disables the console debug output.
std::string holonomic_method
C++ class name of the holonomic navigation method to run in the transformed TP-Space.
void updateClearancePost(ClearanceDiagram &cd, const std::vector< double > &TP_obstacles) const
void updateNavDynamicState(const TNavDynamicState &newState, const bool force_update=false)
To be invoked by the navigator before each navigation step, to let the PTG to react to changing dynam...
uint32_t nPTGs
The number of PTGS:
Clearance information for one particular PTG and one set of obstacles.
STL namespace.
uint16_t getPathCount() const
Get the number of different, discrete paths in this family.
std::vector< double > TP_Obstacles
One distance per discretized alpha value, describing the "polar plot" of TP obstacles.
int target_k
The discrete version of target_alpha.
mrpt::math::LowPassFilter_IIR1 meanExecutionPeriod
Runtime estimation of execution period of the method.
std::shared_ptr< CObject > Ptr
Definition: CObject.h:154
This class extends CAbstractNavigator with the capability of following a list of waypoints.
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
#define MRPT_LOG_ERROR_FMT(_FMT_STRING,...)
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) override
Loads all params from a file.
GLdouble s
Definition: glext.h:3676
void Tic()
Starts the stopwatch.
Definition: CTicTac.cpp:82
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const =0
saves all available parameters, in a forma loadable by initialize()
virtual double getPathDist(uint16_t k, uint32_t step) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step.
std::string pose_frame_id
map frame ID for pose
mrpt::utils::CTimeLogger m_timlog_delays
Time logger to collect delay-related stats.
virtual void getPathPose(uint16_t k, uint32_t step, mrpt::math::TPose2D &p) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step.
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
mrpt::kinematics::CVehicleVelCmd::Ptr m_last_vel_cmd
Last velocity commands.
virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &c, const std::string &s) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
pose_t & interpolate(mrpt::system::TTimeStamp t, pose_t &out_interp, bool &out_valid_interp) const
Returns the pose at a given time, or interpolates using splines if there is not an exact match...
virtual bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd)
Default: forward call to m_robot.changeSpeed().
std::vector< mrpt::math::TPoint2D > targets
Relative location (x,y) of target point(s).
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
virtual bool changeSpeedsNOP()
Default: forward call to m_robot.changeSpeedsNOP().
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::math::TPoint2D TP_Target
The Target, in TP-Space (x,y)
virtual FrameLookUpStatus lookupTransform(const std::string &target_frame, const std::string &source_frame, typename base_t::lightweight_pose_t &child_wrt_parent, const mrpt::system::TTimeStamp query_time=INVALID_TIMESTAMP, const double timeout_secs=.0) override
Queries the current pose of target_frame wrt ("as seen from") source_frame.
Virtual base for velocity commands of different kinematic models of planar mobile robot...
void STEP8_GenerateLogRecord(CLogFileRecord &newLogRec, const std::vector< mrpt::math::TPose2D > &relTargets, int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd, int nPTGs, const bool best_is_NOP_cmdvel, const math::TPose2D &rel_cur_pose_wrt_last_vel_cmd_NOP, const math::TPose2D &rel_pose_PTG_origin_wrt_sense_NOP, const double executionTimeValue, const double tim_changeSpeed, const mrpt::system::TTimeStamp &tim_start_iteration)
double getClearance(uint16_t k, double TPS_query_distance, bool integrate_over_path) const
Gets the clearance for path k and distance TPS_query_distance in one of two modes: ...
The struct for configuring navigation requests.
double maxRobotSpeed
Maximum robot speed, in the same units than obstacles, per second.
virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const =0
Converts a discretized "alpha" value into a feasible motion command or action.
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState
CSerializable::Ptr ReadObject()
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the obje...
Definition: CStream.h:207
This is the base class for any user-defined PTG.
void calc_move_candidate_scores(TCandidateMovementPTG &holonomicMovement, const std::vector< double > &in_TPObstacles, const mrpt::nav::ClearanceDiagram &in_clearance, const std::vector< mrpt::math::TPose2D > &WS_Targets, const std::vector< PTGTarget > &TP_Targets, CLogFileRecord::TInfoPerPTG &log, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, const mrpt::math::TPose2D &relPoseVelCmd_NOP, const unsigned int ptg_idx4weights, const mrpt::system::TTimeStamp tim_start_iteration)
Scores holonomicMovement.
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
double speed_scale
[0,1] scale of the raw cmd_vel as generated by the PTG
double desiredDirection
The results from the holonomic method.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:85
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
static CMultiObjectiveMotionOptimizerBase::Ptr Factory(const std::string &className) noexcept
Class factory from C++ class name.
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
std::shared_ptr< CHolonomicLogFileRecord > Ptr
double targetDesiredRelSpeed
(Default=.05) Desired relative speed (wrt maximum speed), in range [0,1], of the vehicle at target...
mrpt::math::TPose2D robotPoseLocalization
The robot pose (from odometry and from the localization/SLAM system).
mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel
The final motion command sent to robot, in "m/sec" and "rad/sec".
#define MRPT_END
double speed
TP-Space movement speed, normalized to [0,1].
virtual void performNavigationStep() override
The main method for the navigator.
mrpt::math::TPoint2D TP_Robot
Robot location in TP-Space: normally (0,0), except during "NOP cmd vel" steps.
This CStream derived class allow using a memory buffer as a CStream.
Definition: CMemoryStream.h:27
const GLubyte * c
Definition: glext.h:6313
virtual double generate_vel_cmd(const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd)
Return the [0,1] velocity scale of raw PTG cmd_vel.
double vx
Velocity components: X,Y (m/s)
virtual double evalPathRelativePriority(uint16_t k, double target_distance) const
Query the PTG for the relative priority factor (0,1) of this PTG, in comparison to others...
mrpt::math::LowPassFilter_IIR1 timoff_sendVelCmd_avr
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) override
Loads all params from a file.
double desiredDirection
The desired motion direction, in the range [-PI, PI].
double timeForTPObsTransformation
Time, in seconds.
std::string motion_decider_method
C++ class name of the motion chooser.
mrpt::utils::CStream * m_prev_logfile
The current log file stream, or nullptr if not being used.
mrpt::nav::CMultiObjectiveMotionOptimizerBase::Ptr m_multiobjopt
mrpt::math::TTwist2D curVelLocal
Current vehicle velocity (local frame of reference)
double max_dist_for_timebased_path_prediction
Max dist [meters] to use time-based path prediction for NOP evaluation.
std::unique_ptr< TNavigationParams > m_navigationParams
Current navigation parameters.
virtual void onStartNewNavigation() override
Called whenever a new navigation has been started.
int16_t ptg_index_NOP
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
void initClearanceDiagram(ClearanceDiagram &cd) const
Must be called to resize a CD to its correct size, before calling updateClearance() ...
mrpt::math::TPose2D relTarget
Current relative target location.
Individual target info in CAbstractNavigator::TNavigationParamsBase and derived classes.
virtual void sendApparentCollisionEvent()
Callback: Apparent collision event (i.e.
mrpt::aligned_containers< TInfoPerPTG >::vector_t infoPerPTG
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
double getLastTime(const std::string &name) const
Return the last execution time of the given "section", or 0 if it hasn&#39;t ever been called "enter" wit...
std::unique_ptr< TNavigationParams > m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes.
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const =0
Returns an empty kinematic velocity command object of the type supported by this PTG.
CHolonomicLogFileRecord::Ptr logRecord
The navigation method will create a log record and store it here via a smart pointer.
#define MRPT_LOG_DEBUG(_STRING)
double direction
TP-Space movement direction.
double maxObstacleDist
Maximum expected value to be found in obstacles.
double starting_robot_dir
Default to 0, they can be used to reflect a robot starting at a position not at (0,0).
const double ESTIM_LOWPASSFILTER_ALPHA
std::map< std::string, double > values
Known values:
GLsizei const GLchar ** string
Definition: glext.h:4101
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd()=0
Gets the emergency stop command for the current robot.
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const =0
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
void setHolonomicMethod(const std::string &method, const mrpt::utils::CConfigFileBase &cfgBase)
Selects which one from the set of available holonomic methods will be used into transformed TP-Space...
bool m_closing_navigator
Signal that the destructor has been called, so no more calls are accepted from other threads...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
virtual void STEP3_WSpaceToTPSpace(const size_t ptg_idx, std::vector< double > &out_TPObstacles, mrpt::nav::ClearanceDiagram &out_clearance, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense, const bool eval_clearance)=0
Builds TP-Obstacles from Workspace obstacles for the given PTG.
mrpt::math::LowPassFilter_IIR1 timoff_obstacles_avr
double secure_distance_start
In normalized distances, the start and end of a ramp function that scales the velocity output from th...
virtual bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp)=0
Return false on any fatal error.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:16
std::vector< std::function< void(void)> > m_pending_events
Events generated during navigationStep(), enqueued to be called at the end of the method execution to...
std::string PTG_desc
A short description for the applied PTG.
double speedfilter_tau
Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0:...
uint16_t getAlphaValuesCount() const
Get the number of different, discrete paths in this family.
double filter(double x)
Processes one input sample, updates the filter state and return the filtered value.
Definition: filters.cpp:21
double desiredSpeed
The desired motion speed in that direction, from 0 up to NavInput::maxRobotSpeed. ...
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits.
virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &c, const std::string &s) override
This method load the options from a ".ini"-like file or memory-stored string list.
ClearanceDiagram clearance
Clearance for each path.
std::unique_ptr< mrpt::utils::CStream > m_logFile
#define MRPT_START
const mrpt::nav::ClearanceDiagram * clearance
The computed clearance for each direction (optional in some implementations).
virtual void loggingGetWSObstaclesAndShape(CLogFileRecord &out_log)=0
Generates a pointcloud of obstacles, and the robot shape, to be saved in the logging record for the c...
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double getScorePriority() const
When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG...
Virtual base class for multi-objective motion choosers, as used for reactive navigation engines...
mrpt::utils::TParameters< double > props
List of properties.
mrpt::math::CVectorFloat TP_Obstacles
Distances until obstacles, in "pseudometers", first index for -PI direction, last one for PI directio...
#define CFileGZOutputStream
Saves data to a file and transparently compress the data using the given compression level...
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
A safe way to call enter() and leave() of a mrpt::utils::CTimeLogger upon construction and destructio...
Definition: CTimeLogger.h:152
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState
double colfreedist_move_k
TP-Obstacles in the move direction at the instant of picking this movement.
std::vector< TInfoPerPTG > m_infoPerPTG
Temporary buffers for working with each PTG during a navigationStep()
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
void doEmergencyStop(const std::string &msg)
Stops the robot and set navigation state to error.
TAbstractPTGNavigatorParams params_abstract_ptg_navigator
void deleteHolonomicObjects()
Delete m_holonomicMethod.
virtual void evalClearanceSingleObstacle(const double ox, const double oy, const uint16_t k, ClearanceDiagram::dist2clearance_t &inout_realdist2clearance, bool treat_as_obstacle=true) const
Evals the robot clearance for each robot pose along path k, for the real distances in the key of the ...
Implementation of pointcloud filtering based on requisities for minimum neigbouring points in both...
CRobot2NavInterface & m_robot
The navigator-robot interface.
mrpt::math::TTwist2D cur_vel
The actual robot velocities in global (map) coordinates, as read from sensors, in "m/sec" and "rad/se...
bool m_init_done
Whether loadConfigFile() has been called or not.
mrpt::math::LowPassFilter_IIR1 meanTotalExecutionTime
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const override
Saves all current options to a config file.
T hypot_fast(const T x, const T y)
Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code...
static CAbstractHolonomicReactiveMethod::Ptr Factory(const std::string &className) noexcept
Lightweight 2D pose.
virtual bool impl_waypoint_is_reachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const override
Implements the way to waypoint is free function in children classes: true must be returned if...
double Tac()
Stops the stopwatch.
Definition: CTicTac.cpp:97
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
#define ASSERT_(f)
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i)=0
Gets the i&#39;th PTG.
double leave(const char *func_name)
End of a named section.
Definition: CTimeLogger.h:123
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
void build_movement_candidate(CParameterizedTrajectoryGenerator *ptg, const size_t indexPTG, const std::vector< mrpt::math::TPose2D > &relTargets, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense, TInfoPerPTG &ipf, TCandidateMovementPTG &holonomicMovement, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, mrpt::nav::CAbstractHolonomicReactiveMethod &holoMethod, const mrpt::system::TTimeStamp tim_start_iteration, const TNavigationParams &navp=TNavigationParams(), const mrpt::math::TPose2D &relPoseVelCmd_NOP=mrpt::poses::CPose2D())
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:25
bool valid_TP
For each PTG, whether target falls into the PTG domain.
The struct for configuring navigation requests to CAbstractPTGBasedReactive and derived classes...
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const override
Saves all current options to a config file.
mrpt::system::TTimeStamp timestampAdd(const mrpt::system::TTimeStamp tim, const double num_seconds)
Shifts a timestamp the given amount of seconds (>0: forwards in time, <0: backwards) ...
Definition: datetime.cpp:198
virtual void navigate(const NavInput &ni, NavOutput &no)=0
Invokes the holonomic navigation algorithm itself.
void registerUserMeasure(const char *event_name, const double value)
Input parameters for CAbstractHolonomicReactiveMethod::navigate()
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: "[x y yaw]", yaw in degrees) ...
std::vector< const TRuntimeClassId * > getAllRegisteredClassesChildrenOf(const TRuntimeClassId *parent_id)
Like getAllRegisteredClasses(), but filters the list to only include children clases of a given base ...
bool directoryExists(const std::string &fileName)
Test if a given directory exists (it fails if the given path refers to an existing file)...
Definition: filesystem.cpp:136
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.cpp:208
std::shared_ptr< CVehicleVelCmd > Ptr
mrpt::poses::CPose2DInterpolator m_latestOdomPoses
GLuint GLenum GLenum transform
Definition: glext.h:6975
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
unsigned __int32 uint32_t
Definition: rptypes.h:47
void enter(const char *func_name)
Start of a named section.
Definition: CTimeLogger.h:117
Lightweight 2D point.
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
Dynamic state that may affect the PTG path parameterization.
Output for CAbstractHolonomicReactiveMethod::navigate()
mrpt::math::TPose2D relPoseVelCmd
GLfloat GLfloat p
Definition: glext.h:6305
mrpt::poses::CPose2DInterpolator m_latestPoses
Latest robot poses (updated in CAbstractNavigator::navigationStep() )
double phi
Orientation (rads)
void copy_container_typecasting(const src_container &src, dst_container &trg)
Copy all the elements in a container (vector, deque, list) into a different one performing the approp...
double getLastOutput() const
Definition: filters.cpp:29
The structure used to store all relevant information about each transformation into TP-Space...
mrpt::math::LowPassFilter_IIR1 tim_changeSpeed_avr
GLenum filter
Definition: glext.h:5072
mrpt::math::TPose2D rawOdometry
raw odometry (frame does not match to "pose", but is expected to be smoother in the short term)...
int sprintf(char *buf, size_t bufSize, const char *format,...) noexcept MRPT_printf_format_check(3
An OS-independent version of sprintf (Notice the bufSize param, which may be ignored in some compiler...
Definition: os.cpp:188
virtual bool inverseMap_WS2TP(double x, double y, int &out_k, double &out_normalized_d, double tolerance_dist=0.10) const =0
Computes the closest (alpha,d) TP coordinates of the trajectory point closest to the Workspace (WS) C...
std::vector< size_t > restrict_PTG_indices
(Default=empty) Optionally, a list of PTG indices can be sent such that the navigator will restrict i...
bool m_enableKeepLogRecords
See enableKeepLogRecords.
virtual bool stop(bool isEmergencyStop)
Default: forward call to m_robot.stop().
uint16_t alpha2index(double alpha) const
Discrete index value for the corresponding alpha value.
mrpt::math::LowPassFilter_IIR1 timoff_curPoseAndSpeed_avr
double getTargetApproachSlowDownDistance() const
Returns this parameter for the first inner holonomic navigator instances [m] (should be the same in a...
mrpt::maps::CPointCloudFilterBase::Ptr m_WS_filter
Default: none.
void preDestructor()
To be called during children destructors to assure thread-safe destruction, and free of shared object...
Stores a candidate movement in TP-Space-based navigation.
virtual std::string getDescription() const =0
Gets a short textual description of the PTG and its parameters.
std::map< std::string, std::string > additional_debug_msgs
Additional debug traces.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019