MRPT  1.9.9
CAbstractPTGBasedReactive.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 
15 #include <mrpt/io/CMemoryStream.h>
17 #include <mrpt/math/geometry.h>
18 #include <mrpt/math/ops_containers.h> // sum()
19 #include <mrpt/math/wrap2pi.h>
22 #include <mrpt/system/filesystem.h>
23 #include <array>
24 #include <iomanip>
25 #include <limits>
26 
27 using namespace mrpt;
28 using namespace mrpt::io;
29 using namespace mrpt::poses;
30 using namespace mrpt::math;
31 using namespace mrpt::system;
32 using namespace mrpt::nav;
33 using namespace mrpt::serialization;
34 using namespace std;
35 
36 // ------ CAbstractPTGBasedReactive::TNavigationParamsPTG -----
37 std::string CAbstractPTGBasedReactive::TNavigationParamsPTG::getAsText() const
38 {
39  std::string s =
40  CWaypointsNavigator::TNavigationParamsWaypoints::getAsText();
41  s += "restrict_PTG_indices: ";
42  s += mrpt::containers::sprintf_vector("%u ", this->restrict_PTG_indices);
43  s += "\n";
44  return s;
45 }
46 
47 bool CAbstractPTGBasedReactive::TNavigationParamsPTG::isEqual(
49 {
50  auto o =
52  &rhs);
53  return o != nullptr &&
54  CWaypointsNavigator::TNavigationParamsWaypoints::isEqual(rhs) &&
55  restrict_PTG_indices == o->restrict_PTG_indices;
56 }
57 
58 const double ESTIM_LOWPASSFILTER_ALPHA = 0.7;
59 
60 // Ctor:
61 CAbstractPTGBasedReactive::CAbstractPTGBasedReactive(
62  CRobot2NavInterface& react_iterf_impl, bool enableConsoleOutput,
63  bool enableLogFile, const std::string& sLogDir)
64  : CWaypointsNavigator(react_iterf_impl),
65  m_holonomicMethod(),
66  m_prev_logfile(nullptr),
67  m_enableKeepLogRecords(false),
68  m_enableConsoleOutput(enableConsoleOutput),
69  m_init_done(false),
70  m_timelogger(false), // default: disabled
71  m_PTGsMustBeReInitialized(true),
72  meanExecutionTime(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
73  meanTotalExecutionTime(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
74  meanExecutionPeriod(ESTIM_LOWPASSFILTER_ALPHA, 0.1),
75  tim_changeSpeed_avr(ESTIM_LOWPASSFILTER_ALPHA),
76  timoff_obstacles_avr(ESTIM_LOWPASSFILTER_ALPHA),
77  timoff_curPoseAndSpeed_avr(ESTIM_LOWPASSFILTER_ALPHA),
78  timoff_sendVelCmd_avr(ESTIM_LOWPASSFILTER_ALPHA),
79  m_closing_navigator(false),
80  m_WS_Obstacles_timestamp(INVALID_TIMESTAMP),
81  m_infoPerPTG_timestamp(INVALID_TIMESTAMP),
82  m_navlogfiles_dir(sLogDir)
83 {
84  this->enableLogFile(enableLogFile);
85 }
86 
88 {
89  m_closing_navigator = true;
90 
91  // Wait to end of navigation (multi-thread...)
92  m_nav_cs.lock();
93  m_nav_cs.unlock();
94 
95  // Just in case.
96  try
97  {
98  // Call base class method, NOT the generic, virtual one,
99  // to avoid problems if we are in the dtor, while the vtable
100  // is being destroyed.
101  CAbstractNavigator::stop(false /*not emergency*/);
102  }
103  catch (...)
104  {
105  }
106 
107  m_logFile.reset();
108 
109  // Free holonomic method:
110  this->deleteHolonomicObjects();
111 }
112 
114 {
115  this->preDestructor(); // ensure the robot is stopped; free dynamic objects
116 }
117 
118 /** \callergraph */
120 {
121  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
122 
124 
126  m_multiobjopt->clear();
127 
128  // Compute collision grids:
129  STEP1_InitPTGs();
130 }
131 
132 /*---------------------------------------------------------------
133  enableLogFile
134  ---------------------------------------------------------------*/
136 {
137  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
138 
139  try
140  {
141  // Disable:
142  // -------------------------------
143  if (!enable)
144  {
145  if (m_logFile)
146  {
148  "[CAbstractPTGBasedReactive::enableLogFile] Stopping "
149  "logging.");
150  m_logFile.reset(); // Close file:
151  }
152  else
153  return; // Already disabled.
154  }
155  else
156  { // Enable
157  // -------------------------------
158  if (m_logFile) return; // Already enabled:
159 
160  // Open file, find the first free file-name.
162  "[CAbstractPTGBasedReactive::enableLogFile] Creating rnav log "
163  "directory: %s",
164  m_navlogfiles_dir.c_str());
167  {
169  "Could not create directory for navigation logs: `%s`",
170  m_navlogfiles_dir.c_str());
171  }
172 
173  std::string filToOpen;
174  for (unsigned int nFile = 0;; nFile++)
175  {
176  filToOpen = mrpt::format(
177  "%s/log_%03u.reactivenavlog", m_navlogfiles_dir.c_str(),
178  nFile);
179  if (!system::fileExists(filToOpen)) break;
180  }
181 
182  // Open log file:
183  {
184  std::unique_ptr<CFileGZOutputStream> fil(
185  new CFileGZOutputStream);
186  bool ok = fil->open(filToOpen, 1 /* compress level */);
187  if (!ok)
188  {
190  "Error opening log file: `%s`", filToOpen.c_str());
191  }
192  else
193  {
194  m_logFile = std::move(fil);
195  }
196  }
197 
199  "[CAbstractPTGBasedReactive::enableLogFile] Logging to "
200  "file `%s`",
201  filToOpen.c_str()));
202  }
203  }
204  catch (const std::exception& e)
205  {
207  "[CAbstractPTGBasedReactive::enableLogFile] Exception: %s",
208  e.what());
209  }
210 }
211 
213 {
214  std::lock_guard<std::recursive_mutex> lock(m_critZoneLastLog);
215  o = lastLogRecord;
216 }
217 
219 {
220  m_holonomicMethod.clear();
221 }
222 
224  const std::string& method, const mrpt::config::CConfigFileBase& ini)
225 {
226  std::lock_guard<std::recursive_mutex> csl(m_nav_cs);
227 
228  this->deleteHolonomicObjects();
229  const size_t nPTGs = this->getPTG_count();
230  ASSERT_(nPTGs != 0);
231  m_holonomicMethod.resize(nPTGs);
232 
233  for (size_t i = 0; i < nPTGs; i++)
234  {
235  m_holonomicMethod[i] =
237  if (!m_holonomicMethod[i])
239  "Non-registered holonomic method className=`%s`",
240  method.c_str());
241 
242  m_holonomicMethod[i]->setAssociatedPTG(this->getPTG(i));
243  m_holonomicMethod[i]->initialize(ini); // load params
244  }
245 }
246 
247 /** The main method: executes one time-iteration of the reactive navigation
248  * algorithm.
249  * \callergraph */
251 {
252  // Security tests:
253  if (m_closing_navigator) return; // Are we closing in the main thread?
254  if (!m_init_done)
255  THROW_EXCEPTION("Have you called loadConfigFile() before?");
257  const size_t nPTGs = this->getPTG_count();
258 
259  // Whether to worry about log files:
260  const bool fill_log_record = (m_logFile || m_enableKeepLogRecords);
261  CLogFileRecord newLogRec;
262  newLogRec.infoPerPTG.resize(nPTGs + 1); /* +1: [N] is the "NOP cmdvel"
263  option; not to be present in all
264  log entries. */
265 
266  // At the beginning of each log file, add an introductory block explaining
267  // which PTGs are we using:
268  {
269  if (m_logFile &&
270  m_logFile.get() != m_prev_logfile) // Only the first time
271  {
272  m_prev_logfile = m_logFile.get();
273  for (size_t i = 0; i < nPTGs; i++)
274  {
275  // If we make a direct copy (=) we will store the entire, heavy,
276  // collision grid.
277  // Let's just store the parameters of each PTG by serializing
278  // it, so paths can be reconstructed
279  // by invoking initialize()
281  auto arch = archiveFrom(buf);
282  arch << *this->getPTG(i);
283  buf.Seek(0);
284  newLogRec.infoPerPTG[i].ptg = std::dynamic_pointer_cast<
286  arch.ReadObject());
287  }
288  }
289  }
290 
291  CTimeLoggerEntry tle1(m_timelogger, "navigationStep");
292 
293  try
294  {
295  totalExecutionTime.Tic(); // Start timer
296 
297  const mrpt::system::TTimeStamp tim_start_iteration =
299 
300  // Compute target location relative to current robot pose:
301  // ---------------------------------------------------------------------
302  // Detect changes in target since last iteration (for NOP):
303  const bool target_changed_since_last_iteration =
306  if (target_changed_since_last_iteration)
308 
309  // Load the list of target(s) from the navigationParam user command.
310  // Semantic is: any of the target is good. If several targets are
311  // reachable, head to latest one.
312  std::vector<CAbstractNavigator::TargetInfo> targets;
313  {
314  auto p = dynamic_cast<
316  m_navigationParams.get());
317  if (p && !p->multiple_targets.empty())
318  {
319  targets = p->multiple_targets;
320  }
321  else
322  {
323  targets.push_back(m_navigationParams->target);
324  }
325  }
326  const size_t nTargets = targets.size(); // Normally = 1, will be >1 if
327  // we want the robot local
328  // planner to be "smarter" in
329  // skipping dynamic obstacles.
330  ASSERT_(nTargets >= 1);
331 
332  STEP1_InitPTGs(); // Will only recompute if
333  // "m_PTGsMustBeReInitialized==true"
334 
335  // STEP2: Load the obstacles and sort them in height bands.
336  // -----------------------------------------------------------------------------
337  if (!STEP2_SenseObstacles())
338  {
340  "Error while loading and sorting the obstacles. Robot will be "
341  "stopped.");
342  if (fill_log_record)
343  {
344  CPose2D rel_cur_pose_wrt_last_vel_cmd_NOP,
345  rel_pose_PTG_origin_wrt_sense_NOP;
347  newLogRec,
348  std::vector<mrpt::math::TPose2D>() /*no targets*/,
349  -1, // best_ptg_idx,
350  m_robot.getEmergencyStopCmd(), nPTGs,
351  false, // best_is_NOP_cmdvel,
352  rel_cur_pose_wrt_last_vel_cmd_NOP.asTPose(),
353  rel_pose_PTG_origin_wrt_sense_NOP.asTPose(),
354  0, // executionTimeValue,
355  0, // tim_changeSpeed,
356  tim_start_iteration);
357  }
358  return;
359  }
360 
361  // ------- start of motion decision zone ---------
362  executionTime.Tic();
363 
364  // Round #1: As usual, pure reactive, evaluate all PTGs and all
365  // directions from scratch.
366  // =========
367 
368  mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense(0, 0, 0),
369  relPoseSense(0, 0, 0), relPoseVelCmd(0, 0, 0);
371  {
372  /*
373  * Delays model
374  *
375  * Event: OBSTACLES_SENSED RNAV_ITERATION_STARTS
376  * GET_ROBOT_POSE_VEL VEL_CMD_SENT_TO_ROBOT
377  * Timestamp: (m_WS_Obstacles_timestamp) (tim_start_iteration)
378  * (m_curPoseVelTimestamp) ("tim_send_cmd_vel")
379  * Delay |
380  * <---+--------------->|<--------------+-------->| |
381  * estimator: | |
382  * | |
383  * timoff_obstacles <-+ |
384  * +--> timoff_curPoseVelAge |
385  * |<---------------------------------+--------------->|
386  * +-->
387  * timoff_sendVelCmd_avr (estimation)
388  *
389  * |<-------------------->|
390  * tim_changeSpeed_avr
391  * (estim)
392  *
393  * |<-----------------------------------------------|-------------------------->|
394  * Relative poses: relPoseSense
395  * relPoseVelCmd
396  * Time offsets (signed): timoff_pose2sense
397  * timoff_pose2VelCmd
398  */
399  const double timoff_obstacles = mrpt::system::timeDifference(
400  tim_start_iteration, m_WS_Obstacles_timestamp);
401  timoff_obstacles_avr.filter(timoff_obstacles);
402  newLogRec.values["timoff_obstacles"] = timoff_obstacles;
403  newLogRec.values["timoff_obstacles_avr"] =
405  newLogRec.timestamps["obstacles"] = m_WS_Obstacles_timestamp;
406 
407  const double timoff_curPoseVelAge = mrpt::system::timeDifference(
408  tim_start_iteration, m_curPoseVel.timestamp);
409  timoff_curPoseAndSpeed_avr.filter(timoff_curPoseVelAge);
410  newLogRec.values["timoff_curPoseVelAge"] = timoff_curPoseVelAge;
411  newLogRec.values["timoff_curPoseVelAge_avr"] =
413 
414  // time offset estimations:
415  const double timoff_pose2sense =
416  timoff_obstacles - timoff_curPoseVelAge;
417 
418  double timoff_pose2VelCmd;
419  timoff_pose2VelCmd = timoff_sendVelCmd_avr.getLastOutput() +
421  timoff_curPoseVelAge;
422  newLogRec.values["timoff_pose2sense"] = timoff_pose2sense;
423  newLogRec.values["timoff_pose2VelCmd"] = timoff_pose2VelCmd;
424 
425  if (std::abs(timoff_pose2sense) > 1.25)
427  "timoff_pose2sense=%e is too large! Path extrapolation may "
428  "be not accurate.",
429  timoff_pose2sense);
430  if (std::abs(timoff_pose2VelCmd) > 1.25)
432  "timoff_pose2VelCmd=%e is too large! Path extrapolation "
433  "may be not accurate.",
434  timoff_pose2VelCmd);
435 
436  // Path extrapolation: robot relative poses along current path
437  // estimation:
438  relPoseSense = m_curPoseVel.velLocal * timoff_pose2sense;
439  relPoseVelCmd = m_curPoseVel.velLocal * timoff_pose2VelCmd;
440 
441  // relative pose for PTGs:
442  rel_pose_PTG_origin_wrt_sense = relPoseVelCmd - relPoseSense;
443 
444  // logging:
445  newLogRec.relPoseSense = relPoseSense;
446  newLogRec.relPoseVelCmd = relPoseVelCmd;
447  }
448  else
449  {
450  // No delays model: poses to their default values.
451  }
452 
453  for (auto& t : targets)
454  {
455  if (t.target_frame_id != m_curPoseVel.pose_frame_id)
456  {
457  auto frame_tf = m_frame_tf.lock();
458  if (!frame_tf)
459  {
461  "Different frame_id's but no frame_tf object "
462  "attached (or it expired)!: target_frame_id=`%s` != "
463  "pose_frame_id=`%s`",
464  t.target_frame_id.c_str(),
465  m_curPoseVel.pose_frame_id.c_str());
466  }
467  mrpt::math::TPose2D robot_frame2map_frame;
468  frame_tf->lookupTransform(
469  t.target_frame_id, m_curPoseVel.pose_frame_id,
470  robot_frame2map_frame);
471 
473  "frame_tf: target_frame_id=`%s` as seen from "
474  "pose_frame_id=`%s` = %s",
475  t.target_frame_id.c_str(),
476  m_curPoseVel.pose_frame_id.c_str(),
477  robot_frame2map_frame.asString().c_str());
478 
479  t.target_coords = robot_frame2map_frame + t.target_coords;
480  t.target_frame_id =
481  m_curPoseVel.pose_frame_id; // Now the coordinates are in
482  // the same frame than robot
483  // pose
484  }
485  }
486 
487  std::vector<TPose2D> relTargets;
488  const auto curPoseExtrapol = (m_curPoseVel.pose + relPoseVelCmd);
490  targets.begin(), targets.end(), // in
491  std::back_inserter(relTargets), // out
492  [curPoseExtrapol](const CAbstractNavigator::TargetInfo& e) {
493  return e.target_coords - curPoseExtrapol;
494  });
495  ASSERT_EQUAL_(relTargets.size(), targets.size());
496 
497  // Use the distance to the first target as reference:
498  const double relTargetDist = relTargets.begin()->norm();
499 
500  // PTG dynamic state
501  /** Allow PTGs to be responsive to target location, dynamics, etc. */
503 
504  ptg_dynState.curVelLocal = m_curPoseVel.velLocal;
505  ptg_dynState.relTarget = relTargets[0];
506  ptg_dynState.targetRelSpeed =
507  m_navigationParams->target.targetDesiredRelSpeed;
508 
509  newLogRec.navDynState = ptg_dynState;
510 
511  for (size_t i = 0; i < nPTGs; i++)
512  {
513  getPTG(i)->updateNavDynamicState(ptg_dynState);
514  }
515 
516  m_infoPerPTG.assign(nPTGs + 1, TInfoPerPTG()); // reset contents
517  m_infoPerPTG_timestamp = tim_start_iteration;
518  vector<TCandidateMovementPTG> candidate_movs(
519  nPTGs + 1); // the last extra one is for the evaluation of "NOP
520  // motion command" choice.
521 
522  for (size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
523  {
524  CParameterizedTrajectoryGenerator* ptg = getPTG(indexPTG);
525  TInfoPerPTG& ipf = m_infoPerPTG[indexPTG];
526 
527  // Ensure the method knows about its associated PTG:
528  auto holoMethod = this->getHoloMethod(indexPTG);
529  ASSERT_(holoMethod);
530  holoMethod->setAssociatedPTG(this->getPTG(indexPTG));
531 
532  // The picked movement in TP-Space (to be determined by holonomic
533  // method below)
534  TCandidateMovementPTG& cm = candidate_movs[indexPTG];
535 
538  ptg, indexPTG, relTargets, rel_pose_PTG_origin_wrt_sense, ipf,
539  cm, newLogRec, false /* this is a regular PTG reactive case */,
540  *holoMethod, tim_start_iteration, *m_navigationParams);
541  } // end for each PTG
542 
543  // check for collision, which is reflected by ALL TP-Obstacles being
544  // zero:
545  bool is_all_ptg_collision = true;
546  for (size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
547  {
548  bool is_collision = true;
549  const auto& obs = m_infoPerPTG[indexPTG].TP_Obstacles;
550  for (const auto o : obs)
551  {
552  if (o != 0)
553  {
554  is_collision = false;
555  break;
556  }
557  }
558  if (!is_collision)
559  {
560  is_all_ptg_collision = false;
561  break;
562  }
563  }
564  if (is_all_ptg_collision)
565  {
566  m_pending_events.emplace_back(std::bind(
568  std::ref(m_robot)));
569  }
570 
571  // Round #2: Evaluate dont sending any new velocity command ("NOP"
572  // motion)
573  // =========
574  bool NOP_not_too_old = true;
575  bool NOP_not_too_close_and_have_to_slowdown = true;
576  double NOP_max_time = -1.0, NOP_At = -1.0;
577  double slowdowndist = .0;
578  CParameterizedTrajectoryGenerator* last_sent_ptg =
581  : nullptr;
582  if (last_sent_ptg)
583  {
584  // So supportSpeedAtTarget() below is evaluated in the correct
585  // context:
587  }
588 
589  // This approach is only possible if:
590  const bool can_do_nop_motion =
592  !target_changed_since_last_iteration && last_sent_ptg &&
593  last_sent_ptg->supportVelCmdNOP()) &&
594  (NOP_not_too_old =
596  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration)) <
597  (NOP_max_time =
598  last_sent_ptg->maxTimeInVelCmdNOP(
600  std::max(0.1, m_lastSentVelCmd.speed_scale))) &&
601  (NOP_not_too_close_and_have_to_slowdown =
602  (last_sent_ptg->supportSpeedAtTarget() ||
603  (relTargetDist >
605  ->getTargetApproachSlowDownDistance())
606  // slowdowndist is assigned here, inside the if()
607  // to be sure the index in m_lastSentVelCmd is valid!
608  )));
609 
610  if (!NOP_not_too_old)
611  {
612  newLogRec.additional_debug_msgs["PTG_cont"] = mrpt::format(
613  "PTG-continuation not allowed: previous command timed-out "
614  "(At=%.03f > Max_At=%.03f)",
615  NOP_At, NOP_max_time);
616  }
617  if (!NOP_not_too_close_and_have_to_slowdown)
618  {
619  newLogRec.additional_debug_msgs["PTG_cont_trgdst"] = mrpt::format(
620  "PTG-continuation not allowed: target too close and must start "
621  "slow-down (trgDist=%.03f < SlowDownDist=%.03f)",
622  relTargetDist, slowdowndist);
623  }
624 
625  mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP(0, 0, 0),
626  rel_pose_PTG_origin_wrt_sense_NOP(0, 0, 0);
627 
628  if (can_do_nop_motion)
629  {
630  // Add the estimation of how long it takes to run the changeSpeeds()
631  // callback (usually a tiny period):
632  const mrpt::system::TTimeStamp tim_send_cmd_vel_corrected =
636 
637  // Note: we use (uncorrected) raw odometry as basis to the following
638  // calculation since it's normally
639  // smoother than particle filter-based localization data, more
640  // accurate in the middle/long term,
641  // but not in the short term:
642  mrpt::math::TPose2D robot_pose_at_send_cmd, robot_odom_at_send_cmd;
643  bool valid_odom, valid_pose;
644 
646  tim_send_cmd_vel_corrected, robot_odom_at_send_cmd, valid_odom);
648  tim_send_cmd_vel_corrected, robot_pose_at_send_cmd, valid_pose);
649 
650  if (valid_odom && valid_pose)
651  {
652  ASSERT_(last_sent_ptg != nullptr);
653 
654  std::vector<TPose2D> relTargets_NOPs;
656  targets.begin(), targets.end(), // in
657  std::back_inserter(relTargets_NOPs), // out
658  [robot_pose_at_send_cmd](
660  return e.target_coords - robot_pose_at_send_cmd;
661  });
662  ASSERT_EQUAL_(relTargets_NOPs.size(), targets.size());
663 
664  rel_pose_PTG_origin_wrt_sense_NOP =
665  robot_odom_at_send_cmd -
666  (m_curPoseVel.rawOdometry + relPoseSense);
667  rel_cur_pose_wrt_last_vel_cmd_NOP =
668  m_curPoseVel.rawOdometry - robot_odom_at_send_cmd;
669 
670  // Update PTG response to dynamic params:
671  last_sent_ptg->updateNavDynamicState(
673 
674  if (fill_log_record)
675  {
676  newLogRec.additional_debug_msgs
677  ["rel_cur_pose_wrt_last_vel_cmd_NOP(interp)"] =
678  rel_cur_pose_wrt_last_vel_cmd_NOP.asString();
679  newLogRec.additional_debug_msgs
680  ["robot_odom_at_send_cmd(interp)"] =
681  robot_odom_at_send_cmd.asString();
682  }
683 
684  // No need to call setAssociatedPTG(), already correctly
685  // associated above.
686 
689  last_sent_ptg, m_lastSentVelCmd.ptg_index, relTargets_NOPs,
690  rel_pose_PTG_origin_wrt_sense_NOP, m_infoPerPTG[nPTGs],
691  candidate_movs[nPTGs], newLogRec,
692  true /* this is the PTG continuation (NOP) choice */,
694  tim_start_iteration, *m_navigationParams,
695  rel_cur_pose_wrt_last_vel_cmd_NOP);
696 
697  } // end valid interpolated origin pose
698  else
699  {
700  // Can't interpolate pose, hence can't evaluate NOP:
701  candidate_movs[nPTGs].speed =
702  -0.01; // <0 means inviable movement
703  }
704  } // end can_do_NOP_motion
705 
706  // Evaluate all the candidates and pick the "best" one, using
707  // the user-defined multiobjective optimizer
708  // --------------------------------------------------------------
711  int best_ptg_idx = m_multiobjopt->decide(candidate_movs, mo_info);
712 
713  if (fill_log_record)
714  {
715  if (mo_info.final_evaluation.size() == newLogRec.infoPerPTG.size())
716  {
717  for (unsigned int i = 0; i < newLogRec.infoPerPTG.size(); i++)
718  {
719  newLogRec.infoPerPTG[i].evaluation =
720  mo_info.final_evaluation[i];
721  }
722  }
723  int idx = 0;
724  for (const auto& le : mo_info.log_entries)
725  {
727  "MultiObjMotOptmzr_msg%03i", idx++)] = le;
728  }
729  }
730 
731  // Pick best movement (or null if none is good)
732  const TCandidateMovementPTG* selectedHolonomicMovement = nullptr;
733  if (best_ptg_idx >= 0)
734  {
735  selectedHolonomicMovement = &candidate_movs[best_ptg_idx];
736  }
737 
738  // If the selected PTG is (N+1), it means the NOP cmd. vel is selected
739  // as the best alternative, i.e. do NOT send any new motion command.
740  const bool best_is_NOP_cmdvel = (best_ptg_idx == int(nPTGs));
741 
742  // ---------------------------------------------------------------------
743  // SEND MOVEMENT COMMAND TO THE ROBOT
744  // ---------------------------------------------------------------------
746  if (best_is_NOP_cmdvel)
747  {
748  // Notify the robot that we want it to keep executing the last
749  // cmdvel:
750  if (!this->changeSpeedsNOP())
751  {
753  "\nERROR calling changeSpeedsNOP()!! Stopping robot and "
754  "finishing navigation\n");
755  if (fill_log_record)
756  {
758  newLogRec, relTargets, best_ptg_idx,
759  m_robot.getEmergencyStopCmd(), nPTGs,
760  best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
761  rel_pose_PTG_origin_wrt_sense_NOP,
762  0, // executionTimeValue,
763  0, // tim_changeSpeed,
764  tim_start_iteration);
765  }
766  return;
767  }
768  }
769  else
770  {
771  // Make sure the dynamic state of a NOP cmd has not overwritten the
772  // state for a "regular" PTG choice:
773  for (size_t i = 0; i < nPTGs; i++)
774  {
775  getPTG(i)->updateNavDynamicState(ptg_dynState);
776  }
777 
778  // STEP7: Get the non-holonomic movement command.
779  // ---------------------------------------------------------------------
780  double cmd_vel_speed_ratio = 1.0;
781  if (selectedHolonomicMovement)
782  {
783  CTimeLoggerEntry tle(
784  m_timelogger, "navigationStep.selectedHolonomicMovement");
785  cmd_vel_speed_ratio =
786  generate_vel_cmd(*selectedHolonomicMovement, new_vel_cmd);
787  ASSERT_(new_vel_cmd);
788  }
789 
790  if (!new_vel_cmd /* which means best_PTG_eval==.0*/ ||
791  new_vel_cmd->isStopCmd())
792  {
794  "Best velocity command is STOP (no way found), calling "
795  "robot.stop()");
796  this->stop(true /* emergency */); // don't call
797  // doEmergencyStop() here
798  // since that will stop
799  // navigation completely
800  new_vel_cmd = m_robot.getEmergencyStopCmd();
802  }
803  else
804  {
805  mrpt::system::TTimeStamp tim_send_cmd_vel;
806  {
808  m_timlog_delays, "changeSpeeds()");
809  tim_send_cmd_vel = mrpt::system::now();
810  newLogRec.timestamps["tim_send_cmd_vel"] = tim_send_cmd_vel;
811  if (!this->changeSpeeds(*new_vel_cmd))
812  {
814  "\nERROR calling changeSpeeds()!! Stopping robot "
815  "and finishing navigation\n");
816  if (fill_log_record)
817  {
818  new_vel_cmd = m_robot.getEmergencyStopCmd();
820  newLogRec, relTargets, best_ptg_idx,
821  new_vel_cmd, nPTGs, best_is_NOP_cmdvel,
822  rel_cur_pose_wrt_last_vel_cmd_NOP,
823  rel_pose_PTG_origin_wrt_sense_NOP,
824  0, // executionTimeValue,
825  0, // tim_changeSpeed,
826  tim_start_iteration);
827  }
828  return;
829  }
830  }
831  // Save last sent cmd:
832  m_lastSentVelCmd.speed_scale = cmd_vel_speed_ratio;
833  m_lastSentVelCmd.ptg_index = best_ptg_idx;
835  selectedHolonomicMovement
836  ? selectedHolonomicMovement->PTG->alpha2index(
837  selectedHolonomicMovement->direction)
838  : 0;
840  selectedHolonomicMovement->props["holo_stage_eval"];
841 
843  best_ptg_idx >= 0
844  ? m_infoPerPTG[best_ptg_idx]
845  .TP_Obstacles[m_lastSentVelCmd.ptg_alpha_index]
846  : .0;
848  (selectedHolonomicMovement->props["is_slowdown"] != 0.0);
849 
851  m_lastSentVelCmd.tim_send_cmd_vel = tim_send_cmd_vel;
852  m_lastSentVelCmd.ptg_dynState = ptg_dynState;
853 
854  // Update delay model:
855  const double timoff_sendVelCmd = mrpt::system::timeDifference(
856  tim_start_iteration, tim_send_cmd_vel);
857  timoff_sendVelCmd_avr.filter(timoff_sendVelCmd);
858  newLogRec.values["timoff_sendVelCmd"] = timoff_sendVelCmd;
859  newLogRec.values["timoff_sendVelCmd_avr"] =
861  }
862  }
863 
864  // ------- end of motion decision zone ---------
865 
866  // Statistics:
867  // ----------------------------------------------------
868  const double executionTimeValue = executionTime.Tac();
869  meanExecutionTime.filter(executionTimeValue);
871 
872  const double tim_changeSpeed =
873  m_timlog_delays.getLastTime("changeSpeeds()");
874  tim_changeSpeed_avr.filter(tim_changeSpeed);
875 
876  // Running period estim:
877  const double period_tim = timerForExecutionPeriod.Tac();
878  if (period_tim > 1.5 * meanExecutionPeriod.getLastOutput())
879  {
881  "Timing warning: Suspicious executionPeriod=%.03f ms is far "
882  "above the average of %.03f ms",
883  1e3 * period_tim, meanExecutionPeriod.getLastOutput() * 1e3);
884  }
885  meanExecutionPeriod.filter(period_tim);
887 
889  {
891  "CMD: %s "
892  "speedScale=%.04f "
893  "T=%.01lfms Exec:%.01lfms|%.01lfms "
894  "PTG#%i\n",
895  new_vel_cmd ? new_vel_cmd->asString().c_str() : "NOP",
896  selectedHolonomicMovement ? selectedHolonomicMovement->speed
897  : .0,
899  1000.0 * meanExecutionTime.getLastOutput(),
900  1000.0 * meanTotalExecutionTime.getLastOutput(), best_ptg_idx));
901  }
902  if (fill_log_record)
903  {
905  newLogRec, relTargets, best_ptg_idx, new_vel_cmd, nPTGs,
906  best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
907  rel_pose_PTG_origin_wrt_sense_NOP, executionTimeValue,
908  tim_changeSpeed, tim_start_iteration);
909  }
910  }
911  catch (const std::exception& e)
912  {
914  std::string("[CAbstractPTGBasedReactive::performNavigationStep] "
915  "Stopping robot and finishing navigation due to "
916  "exception:\n") +
917  std::string(e.what()));
918  }
919  catch (...)
920  {
922  "[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot "
923  "and finishing navigation due to untyped exception.");
924  }
925 }
926 
927 /** \callergraph */
929  CLogFileRecord& newLogRec, const std::vector<TPose2D>& relTargets,
930  int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmd::Ptr& new_vel_cmd,
931  const int nPTGs, const bool best_is_NOP_cmdvel,
932  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP,
933  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense_NOP,
934  const double executionTimeValue, const double tim_changeSpeed,
935  const mrpt::system::TTimeStamp& tim_start_iteration)
936 {
937  // ---------------------------------------
938  // STEP8: Generate log record
939  // ---------------------------------------
940  m_timelogger.enter("navigationStep.populate_log_info");
941 
942  this->loggingGetWSObstaclesAndShape(newLogRec);
943 
946  newLogRec.WS_targets_relative = relTargets;
947  newLogRec.nSelectedPTG = nSelectedPTG;
948  newLogRec.cur_vel = m_curPoseVel.velGlobal;
949  newLogRec.cur_vel_local = m_curPoseVel.velLocal;
950  newLogRec.cmd_vel = new_vel_cmd;
951  newLogRec.values["estimatedExecutionPeriod"] =
953  newLogRec.values["executionTime"] = executionTimeValue;
954  newLogRec.values["executionTime_avr"] = meanExecutionTime.getLastOutput();
955  newLogRec.values["time_changeSpeeds()"] = tim_changeSpeed;
956  newLogRec.values["time_changeSpeeds()_avr"] =
958  newLogRec.values["CWaypointsNavigator::navigationStep()"] =
959  m_timlog_delays.getLastTime("CWaypointsNavigator::navigationStep()");
960  newLogRec.values["CAbstractNavigator::navigationStep()"] =
961  m_timlog_delays.getLastTime("CAbstractNavigator::navigationStep()");
962  newLogRec.timestamps["tim_start_iteration"] = tim_start_iteration;
963  newLogRec.timestamps["curPoseAndVel"] = m_curPoseVel.timestamp;
964  newLogRec.nPTGs = nPTGs;
965 
966  // NOP mode stuff:
968  rel_cur_pose_wrt_last_vel_cmd_NOP;
970  rel_pose_PTG_origin_wrt_sense_NOP;
971  newLogRec.ptg_index_NOP =
972  best_is_NOP_cmdvel ? m_lastSentVelCmd.ptg_index : -1;
975 
976  m_timelogger.leave("navigationStep.populate_log_info");
977 
978  // Save to log file:
979  // --------------------------------------
980  {
982  m_timelogger, "navigationStep.write_log_file");
983  if (m_logFile) archiveFrom(*m_logFile) << newLogRec;
984  }
985  // Set as last log record
986  {
987  std::lock_guard<std::recursive_mutex> lock_log(
988  m_critZoneLastLog); // Lock
989  lastLogRecord = newLogRec; // COPY
990  }
991 }
992 
993 /** \callergraph */
995  TCandidateMovementPTG& cm, const std::vector<double>& in_TPObstacles,
996  const mrpt::nav::ClearanceDiagram& in_clearance,
997  const std::vector<mrpt::math::TPose2D>& WS_Targets,
998  const std::vector<CAbstractPTGBasedReactive::PTGTarget>& TP_Targets,
1000  const bool this_is_PTG_continuation,
1001  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP,
1002  const unsigned int ptg_idx4weights,
1003  const mrpt::system::TTimeStamp tim_start_iteration,
1005 {
1006  MRPT_START;
1007 
1008  const double ref_dist = cm.PTG->getRefDistance();
1009 
1010  // Replaced by: TP_Targets[i].*
1011  // const double target_dir = (TP_Target.x!=0 || TP_Target.y!=0) ?
1012  // atan2( TP_Target.y, TP_Target.x) : 0.0;
1013  // const int target_k = static_cast<int>( cm.PTG->alpha2index(
1014  // target_dir ) );
1015  // const double target_d_norm = TP_Target.norm();
1016 
1017  // We need to evaluate the movement wrt to ONE target of the possibly many
1018  // input ones.
1019  // Policy: use the target whose TP-Space direction is closer to this
1020  // candidate direction:
1021  size_t selected_trg_idx = 0;
1022  {
1023  double best_trg_angdist = std::numeric_limits<double>::max();
1024  for (size_t i = 0; i < TP_Targets.size(); i++)
1025  {
1026  const double angdist = std::abs(mrpt::math::angDistance(
1027  TP_Targets[i].target_alpha, cm.direction));
1028  if (angdist < best_trg_angdist)
1029  {
1030  best_trg_angdist = angdist;
1031  selected_trg_idx = i;
1032  }
1033  }
1034  }
1035  ASSERT_(selected_trg_idx < WS_Targets.size());
1036  const auto WS_Target = WS_Targets[selected_trg_idx];
1037  const auto TP_Target = TP_Targets[selected_trg_idx];
1038 
1039  const double target_d_norm = TP_Target.target_dist;
1040 
1041  // Picked movement direction:
1042  const int move_k = static_cast<int>(cm.PTG->alpha2index(cm.direction));
1043  const double target_WS_d = WS_Target.norm();
1044 
1045  // Coordinates of the trajectory end for the given PTG and "alpha":
1046  const double d = std::min(in_TPObstacles[move_k], 0.99 * target_d_norm);
1047  uint32_t nStep;
1048  bool pt_in_range = cm.PTG->getPathStepForDist(move_k, d, nStep);
1049  ASSERT_(pt_in_range);
1050  mrpt::math::TPose2D pose;
1051  cm.PTG->getPathPose(move_k, nStep, pose);
1052 
1053  // Make sure that the target slow-down is honored, as seen in real-world
1054  // Euclidean space
1055  // (as opposed to TP-Space, where the holo methods are evaluated)
1056  if (m_navigationParams &&
1057  m_navigationParams->target.targetDesiredRelSpeed < 1.0 &&
1058  !m_holonomicMethod.empty() && getHoloMethod(0) != nullptr &&
1059  !cm.PTG->supportSpeedAtTarget() // If the PTG is able to handle the
1060  // slow-down on its own, dont change
1061  // speed here
1062  )
1063  {
1064  const double TARGET_SLOW_APPROACHING_DISTANCE =
1066 
1067  const double Vf =
1068  m_navigationParams->target.targetDesiredRelSpeed; // [0,1]
1069 
1070  const double f = std::min(
1071  1.0,
1072  Vf + target_WS_d * (1.0 - Vf) / TARGET_SLOW_APPROACHING_DISTANCE);
1073  if (f < cm.speed)
1074  {
1075  newLogRec.additional_debug_msgs["PTG_eval.speed"] = mrpt::format(
1076  "Relative speed reduced %.03f->%.03f based on Euclidean "
1077  "nearness to target.",
1078  cm.speed, f);
1079  cm.speed = f;
1080  }
1081  }
1082 
1083  // Start storing params in the candidate move structure:
1084  cm.props["ptg_idx"] = ptg_idx4weights;
1085  cm.props["ref_dist"] = ref_dist;
1086  cm.props["target_dir"] = TP_Target.target_alpha;
1087  cm.props["target_k"] = TP_Target.target_k;
1088  cm.props["target_d_norm"] = target_d_norm;
1089  cm.props["move_k"] = move_k;
1090  double& move_cur_d = cm.props["move_cur_d"] =
1091  0; // current robot path normalized distance over path (0 unless in a
1092  // NOP cmd)
1093  cm.props["is_PTG_cont"] = this_is_PTG_continuation ? 1 : 0;
1094  cm.props["num_paths"] = in_TPObstacles.size();
1095  cm.props["WS_target_x"] = WS_Target.x;
1096  cm.props["WS_target_y"] = WS_Target.y;
1097  cm.props["robpose_x"] = pose.x;
1098  cm.props["robpose_y"] = pose.y;
1099  cm.props["robpose_phi"] = pose.phi;
1100  cm.props["ptg_priority"] =
1101  cm.PTG->getScorePriority() *
1102  cm.PTG->evalPathRelativePriority(TP_Target.target_k, target_d_norm);
1103  const bool is_slowdown =
1104  this_is_PTG_continuation
1106  : (cm.PTG->supportSpeedAtTarget() && TP_Target.target_k == move_k &&
1107  target_d_norm < 0.99 * in_TPObstacles[move_k]);
1108  cm.props["is_slowdown"] = is_slowdown ? 1 : 0;
1109  cm.props["holo_stage_eval"] =
1110  this_is_PTG_continuation
1112  : (hlfr && !hlfr->dirs_eval.empty() &&
1113  hlfr->dirs_eval.rbegin()->size() == in_TPObstacles.size())
1114  ? hlfr->dirs_eval.rbegin()->at(move_k)
1115  : .0;
1116  // Factor 1: Free distance for the chosen PTG and "alpha" in the TP-Space:
1117  // ----------------------------------------------------------------------
1118  double& colfree = cm.props["collision_free_distance"];
1119 
1120  // distance to collision:
1121  colfree = in_TPObstacles[move_k]; // we'll next substract here the
1122  // already-traveled distance, for NOP
1123  // motion candidates.
1124 
1125  // Special case for NOP motion cmd:
1126  // consider only the empty space *after* the current robot pose, which is
1127  // not at the origin.
1128 
1129  if (this_is_PTG_continuation)
1130  {
1131  int cur_k = 0;
1132  double cur_norm_d = .0;
1133  bool is_exact, is_time_based = false;
1134  uint32_t cur_ptg_step = 0;
1135 
1136  // Use: time-based prediction for shorter distances, PTG inverse
1137  // mapping-based for longer ranges:
1138  const double maxD = params_abstract_ptg_navigator
1140  if (std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.x) > maxD ||
1141  std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.y) > maxD)
1142  {
1143  is_exact = cm.PTG->inverseMap_WS2TP(
1144  rel_cur_pose_wrt_last_vel_cmd_NOP.x,
1145  rel_cur_pose_wrt_last_vel_cmd_NOP.y, cur_k, cur_norm_d);
1146  }
1147  else
1148  {
1149  // Use time:
1150  is_time_based = true;
1151  is_exact = true; // well, sort of...
1152  const double NOP_At =
1155  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
1156  newLogRec.additional_debug_msgs["PTG_eval.NOP_At"] =
1157  mrpt::format("%.06f s", NOP_At);
1158  cur_k = move_k;
1159  cur_ptg_step = mrpt::round(NOP_At / cm.PTG->getPathStepDuration());
1160  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step) /
1161  cm.PTG->getRefDistance();
1162  {
1163  const double cur_a = cm.PTG->index2alpha(cur_k);
1164  log.TP_Robot.x = cos(cur_a) * cur_norm_d;
1165  log.TP_Robot.y = sin(cur_a) * cur_norm_d;
1166  cm.starting_robot_dir = cur_a;
1167  cm.starting_robot_dist = cur_norm_d;
1168  }
1169  }
1170 
1171  if (!is_exact)
1172  {
1173  // Don't trust this step: we are not 100% sure of the robot pose in
1174  // TP-Space for this "PTG continuation" step:
1175  cm.speed = -0.01; // this enforces a 0 global evaluation score
1176  newLogRec.additional_debug_msgs["PTG_eval"] =
1177  "PTG-continuation not allowed, cur. pose out of PTG domain.";
1178  return;
1179  }
1180  bool WS_point_is_unique = true;
1181  if (!is_time_based)
1182  {
1183  bool ok1 = cm.PTG->getPathStepForDist(
1185  cur_norm_d * cm.PTG->getRefDistance(), cur_ptg_step);
1186  if (ok1)
1187  {
1188  // Check bijective:
1189  WS_point_is_unique = cm.PTG->isBijectiveAt(cur_k, cur_ptg_step);
1190  const uint32_t predicted_step =
1193  mrpt::system::now()) /
1194  cm.PTG->getPathStepDuration();
1195  WS_point_is_unique =
1196  WS_point_is_unique &&
1197  cm.PTG->isBijectiveAt(move_k, predicted_step);
1198  newLogRec.additional_debug_msgs["PTG_eval.bijective"] =
1199  mrpt::format(
1200  "isBijectiveAt(): k=%i step=%i -> %s", (int)cur_k,
1201  (int)cur_ptg_step, WS_point_is_unique ? "yes" : "no");
1202 
1203  if (!WS_point_is_unique)
1204  {
1205  // Don't trust direction:
1206  cur_k = move_k;
1207  cur_ptg_step = predicted_step;
1208  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step);
1209  }
1210  {
1211  const double cur_a = cm.PTG->index2alpha(cur_k);
1212  log.TP_Robot.x = cos(cur_a) * cur_norm_d;
1213  log.TP_Robot.y = sin(cur_a) * cur_norm_d;
1214  cm.starting_robot_dir = cur_a;
1215  cm.starting_robot_dist = cur_norm_d;
1216  }
1217 
1218  mrpt::math::TPose2D predicted_rel_pose;
1219  cm.PTG->getPathPose(
1220  m_lastSentVelCmd.ptg_alpha_index, cur_ptg_step,
1221  predicted_rel_pose);
1222  const auto predicted_pose_global =
1223  m_lastSentVelCmd.poseVel.rawOdometry + predicted_rel_pose;
1224  const double predicted2real_dist = mrpt::hypot_fast(
1225  predicted_pose_global.x - m_curPoseVel.rawOdometry.x,
1226  predicted_pose_global.y - m_curPoseVel.rawOdometry.y);
1227  newLogRec.additional_debug_msgs["PTG_eval.lastCmdPose(raw)"] =
1229  newLogRec.additional_debug_msgs["PTG_eval.PTGcont"] =
1230  mrpt::format(
1231  "mismatchDistance=%.03f cm", 1e2 * predicted2real_dist);
1232 
1233  if (predicted2real_dist >
1235  .max_distance_predicted_actual_path &&
1236  (!is_slowdown ||
1237  (target_d_norm - cur_norm_d) * ref_dist > 2.0 /*meters*/))
1238  {
1239  cm.speed =
1240  -0.01; // this enforces a 0 global evaluation score
1241  newLogRec.additional_debug_msgs["PTG_eval"] =
1242  "PTG-continuation not allowed, mismatchDistance above "
1243  "threshold.";
1244  return;
1245  }
1246  }
1247  else
1248  {
1249  cm.speed = -0.01; // this enforces a 0 global evaluation score
1250  newLogRec.additional_debug_msgs["PTG_eval"] =
1251  "PTG-continuation not allowed, couldn't get PTG step for "
1252  "cur. robot pose.";
1253  return;
1254  }
1255  }
1256 
1257  // Path following isn't perfect: we can't be 100% sure of whether the
1258  // robot followed exactly
1259  // the intended path (`kDirection`), or if it's actually a bit shifted,
1260  // as reported in `cur_k`.
1261  // Take the least favorable case.
1262  // [Update] Do this only when the PTG gave us a unique-mapped WS<->TPS
1263  // point:
1264 
1265  colfree = WS_point_is_unique
1266  ? std::min(in_TPObstacles[move_k], in_TPObstacles[cur_k])
1267  : in_TPObstacles[move_k];
1268 
1269  // Only discount free space if there was a real obstacle, not the "end
1270  // of path" due to limited refDistance.
1271  if (colfree < 0.99)
1272  {
1273  colfree -= cur_norm_d;
1274  }
1275 
1276  // Save estimated robot pose over path as a parameter for scores:
1277  move_cur_d = cur_norm_d;
1278  }
1279 
1280  // Factor4: Decrease in euclidean distance between (x,y) and the target:
1281  // Moving away of the target is negatively valued.
1282  cm.props["dist_eucl_final"] =
1283  mrpt::hypot_fast(WS_Target.x - pose.x, WS_Target.y - pose.y);
1284 
1285  // dist_eucl_min: Use PTG clearance methods to evaluate the real-world
1286  // (WorkSpace) minimum distance to target:
1287  {
1288  using map_d2d_t = std::map<double, double>;
1289  map_d2d_t pathDists;
1290  const double D = cm.PTG->getRefDistance();
1291  const int num_steps = ceil(D * 2.0);
1292  for (int i = 0; i < num_steps; i++)
1293  {
1294  pathDists[i / double(num_steps)] =
1295  100.0; // default normalized distance to target (a huge value)
1296  }
1297 
1299  WS_Target.x, WS_Target.y, move_k, pathDists,
1300  false /*treat point as target, not obstacle*/);
1301 
1302  const auto it = std::min_element(
1303  pathDists.begin(), pathDists.end(),
1304  [colfree](map_d2d_t::value_type& l, map_d2d_t::value_type& r)
1305  -> bool { return (l.second < r.second) && l.first < colfree; });
1306  cm.props["dist_eucl_min"] = (it != pathDists.end())
1307  ? it->second * cm.PTG->getRefDistance()
1308  : 100.0;
1309  }
1310 
1311  // Factor5: Hysteresis:
1312  // -----------------------------------------------------
1313  double& hysteresis = cm.props["hysteresis"];
1314  hysteresis = .0;
1315 
1316  if (cm.PTG->supportVelCmdNOP())
1317  {
1318  hysteresis = this_is_PTG_continuation ? 1.0 : 0.;
1319  }
1320  else if (m_last_vel_cmd)
1321  {
1323  desired_cmd = cm.PTG->directionToMotionCommand(move_k);
1325  const mrpt::kinematics::CVehicleVelCmd* ptr2 = desired_cmd.get();
1326  if (typeid(*ptr1) == typeid(*ptr2))
1327  {
1328  ASSERT_EQUAL_(
1329  m_last_vel_cmd->getVelCmdLength(),
1330  desired_cmd->getVelCmdLength());
1331 
1332  double simil_score = 0.5;
1333  for (size_t i = 0; i < desired_cmd->getVelCmdLength(); i++)
1334  {
1335  const double scr =
1336  exp(-std::abs(
1337  desired_cmd->getVelCmdElement(i) -
1338  m_last_vel_cmd->getVelCmdElement(i)) /
1339  0.20);
1340  mrpt::keep_min(simil_score, scr);
1341  }
1342  hysteresis = simil_score;
1343  }
1344  }
1345 
1346  // Factor6: clearance
1347  // -----------------------------------------------------
1348  // clearance indicators that may be useful in deciding the best motion:
1349  double& clearance = cm.props["clearance"];
1350  clearance = in_clearance.getClearance(
1351  move_k, target_d_norm * 1.01, false /* spot, dont interpolate */);
1352  cm.props["clearance_50p"] = in_clearance.getClearance(
1353  move_k, target_d_norm * 0.5, false /* spot, dont interpolate */);
1354  cm.props["clearance_path"] = in_clearance.getClearance(
1355  move_k, target_d_norm * 0.9, true /* average */);
1356  cm.props["clearance_path_50p"] = in_clearance.getClearance(
1357  move_k, target_d_norm * 0.5, true /* average */);
1358 
1359  // Factor: ETA (Estimated Time of Arrival to target or to closest obstacle,
1360  // whatever it's first)
1361  // -----------------------------------------------------
1362  double& eta = cm.props["eta"];
1363  eta = .0;
1364  if (cm.PTG && cm.speed > .0) // for valid cases only
1365  {
1366  // OK, we have a direct path to target without collisions.
1367  const double path_len_meters = d * ref_dist;
1368 
1369  // Calculate their ETA
1370  uint32_t target_step;
1371  bool valid_step =
1372  cm.PTG->getPathStepForDist(move_k, path_len_meters, target_step);
1373  if (valid_step)
1374  {
1375  eta = cm.PTG->getPathStepDuration() *
1376  target_step /* PTG original time to get to target point */
1377  * cm.speed /* times the speed scale factor*/;
1378 
1379  double discount_time = .0;
1380  if (this_is_PTG_continuation)
1381  {
1382  // Heuristic: discount the time already executed.
1383  // Note that hm.speed above scales the overall path time using
1384  // the current speed scale, not the exact
1385  // integration over the past timesteps. It's an approximation,
1386  // probably good enough...
1387  discount_time = mrpt::system::timeDifference(
1388  m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
1389  }
1390  eta -= discount_time; // This could even become negative if the
1391  // approximation is poor...
1392  }
1393  }
1394 
1395  MRPT_END;
1396 }
1397 
1399  const TCandidateMovementPTG& in_movement,
1401 {
1402  mrpt::system::CTimeLoggerEntry tle(m_timelogger, "generate_vel_cmd");
1403  double cmdvel_speed_scale = 1.0;
1404  try
1405  {
1406  if (in_movement.speed == 0)
1407  {
1408  // The robot will stop:
1409  new_vel_cmd =
1411  new_vel_cmd->setToStop();
1412  }
1413  else
1414  {
1415  // Take the normalized movement command:
1416  new_vel_cmd = in_movement.PTG->directionToMotionCommand(
1417  in_movement.PTG->alpha2index(in_movement.direction));
1418 
1419  // Scale holonomic speeds to real-world one:
1420  new_vel_cmd->cmdVel_scale(in_movement.speed);
1421  cmdvel_speed_scale *= in_movement.speed;
1422 
1423  if (!m_last_vel_cmd) // first iteration? Use default values:
1424  m_last_vel_cmd =
1426 
1427  // Honor user speed limits & "blending":
1428  const double beta = meanExecutionPeriod.getLastOutput() /
1431  cmdvel_speed_scale *= new_vel_cmd->cmdVel_limits(
1432  *m_last_vel_cmd, beta,
1434  }
1435 
1436  m_last_vel_cmd = new_vel_cmd; // Save for filtering in next step
1437  }
1438  catch (const std::exception& e)
1439  {
1441  "[CAbstractPTGBasedReactive::generate_vel_cmd] Exception: "
1442  << e.what());
1443  }
1444  return cmdvel_speed_scale;
1445 }
1446 
1447 /** \callergraph */
1449  const mrpt::math::TPoint2D& wp) const
1450 {
1451  MRPT_START;
1452 
1453  const size_t N = this->getPTG_count();
1454  if (m_infoPerPTG.size() < N ||
1458  return false; // We didn't run yet or obstacle info is old
1459 
1460  for (size_t i = 0; i < N; i++)
1461  {
1462  const CParameterizedTrajectoryGenerator* ptg = getPTG(i);
1463 
1464  const std::vector<double>& tp_obs =
1465  m_infoPerPTG[i].TP_Obstacles; // normalized distances
1466  if (tp_obs.size() != ptg->getPathCount())
1467  continue; // May be this PTG has not been used so far? (Target out
1468  // of domain,...)
1469 
1470  int wp_k;
1471  double wp_norm_d;
1472  bool is_into_domain =
1473  ptg->inverseMap_WS2TP(wp.x, wp.y, wp_k, wp_norm_d);
1474  if (!is_into_domain) continue;
1475 
1476  ASSERT_(wp_k < int(tp_obs.size()));
1477 
1478  const double collision_free_dist = tp_obs[wp_k];
1479  if (collision_free_dist > 1.01 * wp_norm_d)
1480  return true; // free path found to target
1481  }
1482 
1483  return false; // no way found
1484  MRPT_END;
1485 }
1486 
1487 /** \callergraph */
1489 {
1491 }
1492 
1493 /** \callergraph */
1495 {
1498 
1499  CWaypointsNavigator::onStartNewNavigation(); // Call base method we
1500  // override
1501 }
1502 
1505 {
1506  ptg_index = -1;
1507  ptg_alpha_index = -1;
1508  tim_send_cmd_vel = INVALID_TIMESTAMP;
1509  poseVel = TRobotPoseVel();
1510  colfreedist_move_k = .0;
1511  was_slowdown = false;
1512  speed_scale = 1.0;
1513  original_holo_eval = .0;
1515 }
1517 {
1518  return this->poseVel.timestamp != INVALID_TIMESTAMP;
1519 }
1520 
1521 /** \callergraph */
1523  CParameterizedTrajectoryGenerator* ptg, const size_t indexPTG,
1524  const std::vector<mrpt::math::TPose2D>& relTargets,
1525  const mrpt::math::TPose2D& rel_pose_PTG_origin_wrt_sense, TInfoPerPTG& ipf,
1526  TCandidateMovementPTG& cm, CLogFileRecord& newLogRec,
1527  const bool this_is_PTG_continuation,
1529  const mrpt::system::TTimeStamp tim_start_iteration,
1530  const TNavigationParams& navp,
1531  const mrpt::math::TPose2D& rel_cur_pose_wrt_last_vel_cmd_NOP)
1532 {
1533  ASSERT_(ptg);
1534 
1535  const size_t idx_in_log_infoPerPTGs =
1536  this_is_PTG_continuation ? getPTG_count() : indexPTG;
1537 
1539  cm.PTG = ptg;
1540 
1541  // If the user doesn't want to use this PTG, just mark it as invalid:
1542  ipf.targets.clear();
1543  bool use_this_ptg = true;
1544  {
1545  const auto* navpPTG = dynamic_cast<const TNavigationParamsPTG*>(&navp);
1546  if (navpPTG && !navpPTG->restrict_PTG_indices.empty())
1547  {
1548  use_this_ptg = false;
1549  for (size_t i = 0;
1550  i < navpPTG->restrict_PTG_indices.size() && !use_this_ptg; i++)
1551  {
1552  if (navpPTG->restrict_PTG_indices[i] == indexPTG)
1553  use_this_ptg = true;
1554  }
1555  }
1556  }
1557 
1558  double timeForTPObsTransformation = .0, timeForHolonomicMethod = .0;
1559 
1560  // Normal PTG validity filter: check if target falls into the PTG domain:
1561  bool any_TPTarget_is_valid = false;
1562  if (use_this_ptg)
1563  {
1564  for (const auto& trg : relTargets)
1565  {
1566  PTGTarget ptg_target;
1567 
1568  ptg_target.valid_TP = ptg->inverseMap_WS2TP(
1569  trg.x, trg.y, ptg_target.target_k, ptg_target.target_dist);
1570  if (!ptg_target.valid_TP) continue;
1571 
1572  any_TPTarget_is_valid = true;
1573  ptg_target.target_alpha = ptg->index2alpha(ptg_target.target_k);
1574  ptg_target.TP_Target.x =
1575  cos(ptg_target.target_alpha) * ptg_target.target_dist;
1576  ptg_target.TP_Target.y =
1577  sin(ptg_target.target_alpha) * ptg_target.target_dist;
1578 
1579  ipf.targets.emplace_back(ptg_target);
1580  }
1581  }
1582 
1583  if (!any_TPTarget_is_valid)
1584  {
1586  "mov_candidate_%u", static_cast<unsigned int>(indexPTG))] =
1587  "PTG discarded since target(s) is(are) out of domain.";
1588  }
1589  else
1590  {
1591  // STEP3(b): Build TP-Obstacles
1592  // -----------------------------------------------------------------------------
1593  {
1594  tictac.Tic();
1595 
1596  // Initialize TP-Obstacles:
1597  const size_t Ki = ptg->getAlphaValuesCount();
1598  ptg->initTPObstacles(ipf.TP_Obstacles);
1600  {
1601  ptg->initClearanceDiagram(ipf.clearance);
1602  }
1603 
1604  // Implementation-dependent conversion:
1606  indexPTG, ipf.TP_Obstacles, ipf.clearance,
1607  mrpt::math::TPose2D(0, 0, 0) - rel_pose_PTG_origin_wrt_sense,
1609 
1611  {
1613  }
1614 
1615  // Distances in TP-Space are normalized to [0,1]:
1616  const double _refD = 1.0 / ptg->getRefDistance();
1617  for (size_t i = 0; i < Ki; i++) ipf.TP_Obstacles[i] *= _refD;
1618 
1619  timeForTPObsTransformation = tictac.Tac();
1620  if (m_timelogger.isEnabled())
1622  "navigationStep.STEP3_WSpaceToTPSpace",
1623  timeForTPObsTransformation);
1624  }
1625 
1626  // STEP4: Holonomic navigation method
1627  // -----------------------------------------------------------------------------
1628  if (!this_is_PTG_continuation)
1629  {
1630  tictac.Tic();
1631 
1632  // Slow down if we are approaching the final target, etc.
1633  holoMethod.enableApproachTargetSlowDown(
1634  navp.target.targetDesiredRelSpeed < .11);
1635 
1636  // Prepare holonomic algorithm call:
1638  ni.clearance = &ipf.clearance;
1639  ni.maxObstacleDist = 1.0;
1640  ni.maxRobotSpeed = 1.0; // So, we use a normalized max speed here.
1641  ni.obstacles = ipf.TP_Obstacles; // Normalized [0,1]
1642 
1643  ni.targets.clear(); // Normalized [0,1]
1644  for (const auto& t : ipf.targets)
1645  {
1646  ni.targets.push_back(t.TP_Target);
1647  }
1648 
1650 
1651  holoMethod.navigate(ni, no);
1652 
1653  // Extract resuls:
1654  cm.direction = no.desiredDirection;
1655  cm.speed = no.desiredSpeed;
1656  HLFR = no.logRecord;
1657 
1658  // Security: Scale down the velocity when heading towards obstacles,
1659  // such that it's assured that we never go thru an obstacle!
1660  const int kDirection =
1661  static_cast<int>(cm.PTG->alpha2index(cm.direction));
1662  double obsFreeNormalizedDistance = ipf.TP_Obstacles[kDirection];
1663 
1664  // Take into account the future robot pose after NOP motion
1665  // iterations to slow down accordingly *now*
1666  if (ptg->supportVelCmdNOP())
1667  {
1668  const double v = mrpt::hypot_fast(
1670  const double d = v * ptg->maxTimeInVelCmdNOP(kDirection);
1671  obsFreeNormalizedDistance = std::min(
1672  obsFreeNormalizedDistance,
1673  std::max(0.90, obsFreeNormalizedDistance - d));
1674  }
1675 
1676  double velScale = 1.0;
1677  ASSERT_(
1680  if (obsFreeNormalizedDistance <
1682  {
1683  if (obsFreeNormalizedDistance <=
1685  velScale = 0.0; // security stop
1686  else
1687  velScale =
1688  (obsFreeNormalizedDistance -
1692  }
1693 
1694  // Scale:
1695  cm.speed *= velScale;
1696 
1697  timeForHolonomicMethod = tictac.Tac();
1698  if (m_timelogger.isEnabled())
1700  "navigationStep.STEP4_HolonomicMethod",
1701  timeForHolonomicMethod);
1702  }
1703  else
1704  {
1705  // "NOP cmdvel" case: don't need to re-run holo algorithm, just keep
1706  // the last selection:
1708  cm.speed = 1.0; // Not used.
1709  }
1710 
1711  // STEP5: Evaluate each movement to assign them a "evaluation" value.
1712  // ---------------------------------------------------------------------
1713  {
1714  CTimeLoggerEntry tle(
1715  m_timelogger, "navigationStep.calc_move_candidate_scores");
1716 
1718  cm, ipf.TP_Obstacles, ipf.clearance, relTargets, ipf.targets,
1719  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs], newLogRec,
1720  this_is_PTG_continuation, rel_cur_pose_wrt_last_vel_cmd_NOP,
1721  indexPTG, tim_start_iteration, HLFR);
1722 
1723  // Store NOP related extra vars:
1724  cm.props["original_col_free_dist"] =
1725  this_is_PTG_continuation ? m_lastSentVelCmd.colfreedist_move_k
1726  : .0;
1727 
1728  // SAVE LOG
1729  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs].evalFactors = cm.props;
1730  }
1731 
1732  } // end "valid_TP"
1733 
1734  // Logging:
1735  const bool fill_log_record =
1736  (m_logFile != nullptr || m_enableKeepLogRecords);
1737  if (fill_log_record)
1738  {
1740  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs];
1741  if (!this_is_PTG_continuation)
1742  ipp.PTG_desc = ptg->getDescription();
1743  else
1744  ipp.PTG_desc = mrpt::format(
1745  "NOP cmdvel (prev PTG idx=%u)",
1746  static_cast<unsigned int>(m_lastSentVelCmd.ptg_index));
1747 
1749  ipf.TP_Obstacles, ipp.TP_Obstacles);
1750  ipp.clearance = ipf.clearance;
1751  ipp.TP_Targets.clear();
1752  for (const auto& t : ipf.targets)
1753  {
1754  ipp.TP_Targets.push_back(t.TP_Target);
1755  }
1756  ipp.HLFR = HLFR;
1757  ipp.desiredDirection = cm.direction;
1758  ipp.desiredSpeed = cm.speed;
1759  ipp.timeForTPObsTransformation = timeForTPObsTransformation;
1760  ipp.timeForHolonomicMethod = timeForHolonomicMethod;
1761  }
1762 }
1763 
1766 {
1767  MRPT_START;
1768 
1769  robot_absolute_speed_limits.loadConfigFile(c, s);
1770 
1771  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(holonomic_method, string);
1772  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(motion_decider_method, string);
1773  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(ref_distance, double);
1774  MRPT_LOAD_CONFIG_VAR_CS(speedfilter_tau, double);
1775  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_start, double);
1776  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_end, double);
1777  MRPT_LOAD_CONFIG_VAR_CS(use_delays_model, bool);
1778  MRPT_LOAD_CONFIG_VAR_CS(max_distance_predicted_actual_path, double);
1780  min_normalized_free_space_for_ptg_continuation, double);
1781  MRPT_LOAD_CONFIG_VAR_CS(enable_obstacle_filtering, bool);
1782  MRPT_LOAD_CONFIG_VAR_CS(evaluate_clearance, bool);
1783  MRPT_LOAD_CONFIG_VAR_CS(max_dist_for_timebased_path_prediction, double);
1784 
1785  MRPT_END;
1786 }
1787 
1790 {
1791  robot_absolute_speed_limits.saveToConfigFile(c, s);
1792 
1793  // Build list of known holo methods:
1794  string lstHoloStr = "# List of known classes:\n";
1795  {
1798  for (const auto& cl : lst)
1799  lstHoloStr +=
1800  string("# - `") + string(cl->className) + string("`\n");
1801  }
1803  holonomic_method,
1804  string("C++ class name of the holonomic navigation method to run in "
1805  "the transformed TP-Space.\n") +
1806  lstHoloStr);
1807 
1808  // Build list of known decider methods:
1809  string lstDecidersStr = "# List of known classes:\n";
1810  {
1813  for (const auto& cl : lst)
1814  lstDecidersStr +=
1815  string("# - `") + string(cl->className) + string("`\n");
1816  }
1818  motion_decider_method,
1819  string("C++ class name of the motion decider method.\n") +
1820  lstDecidersStr);
1821 
1823  ref_distance,
1824  "Maximum distance up to obstacles will be considered (D_{max} in "
1825  "papers).");
1827  speedfilter_tau,
1828  "Time constant (in seconds) for the low-pass filter applied to "
1829  "kinematic velocity commands (default=0: no filtering)");
1831  secure_distance_start,
1832  "In normalized distance [0,1], start/end of a ramp function that "
1833  "scales the holonomic navigator output velocity.");
1835  secure_distance_end,
1836  "In normalized distance [0,1], start/end of a ramp function that "
1837  "scales the holonomic navigator output velocity.");
1839  use_delays_model,
1840  "Whether to use robot pose inter/extrapolation to improve accuracy "
1841  "(Default:false)");
1843  max_distance_predicted_actual_path,
1844  "Max distance [meters] to discard current PTG and issue a new vel cmd "
1845  "(default= 0.05)");
1847  min_normalized_free_space_for_ptg_continuation,
1848  "Min normalized dist [0,1] after current pose in a PTG continuation to "
1849  "allow it.");
1851  enable_obstacle_filtering,
1852  "Enabled obstacle filtering (params in its own section)");
1854  evaluate_clearance,
1855  "Enable exact computation of clearance (default=false)");
1857  max_dist_for_timebased_path_prediction,
1858  "Max dist [meters] to use time-based path prediction for NOP "
1859  "evaluation");
1860 }
1861 
1864  : holonomic_method(),
1865  ptg_cache_files_directory("."),
1866 
1867  robot_absolute_speed_limits()
1868 
1869 {
1870 }
1871 
1874 {
1875  MRPT_START;
1877 
1878  // At this point, we have been called from the derived class, who must be
1879  // already loaded all its specific params, including PTGs.
1880 
1881  // Load my params:
1883  c, "CAbstractPTGBasedReactive");
1884 
1885  // Filtering:
1887  {
1890  filter->options.loadFromConfigFile(c, "CPointCloudFilterByDistance");
1891  }
1892  else
1893  {
1894  m_WS_filter.reset();
1895  }
1896 
1897  // Movement chooser:
1900  if (!m_multiobjopt)
1902  "Non-registered CMultiObjectiveMotionOptimizerBase className=`%s`",
1904 
1905  m_multiobjopt->loadConfigFile(c);
1906 
1907  // Holo method:
1909  ASSERT_(!m_holonomicMethod.empty());
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::rtti::CObject::Ptr(cl->createObject());
1945  auto* holo =
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::rtti::CObject::Ptr(cl->createObject());
1969  auto* momo =
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 }
1993 
1995  int idx)
1996 {
1997  return m_holonomicMethod[idx].get();
1998 }
double index2alpha(uint16_t k) const
Alpha value for the discrete corresponding value.
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
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:86
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() )
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...
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 < ...
double x
X,Y coordinates.
Definition: TPoint2D.h:23
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:161
#define MRPT_START
Definition: exceptions.h:241
#define MRPT_LOG_DEBUG(_STRING)
Use: MRPT_LOG_DEBUG("message");
GLdouble GLdouble t
Definition: glext.h:3695
mrpt::system::CTimeLogger m_timlog_delays
Time logger to collect delay-related stats.
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_LOG_ERROR_FMT(_FMT_STRING,...)
std::vector< mrpt::math::TPose2D > WS_targets_relative
Relative poses (wrt to robotPoseLocalization) for.
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. ...
mrpt::system::TParameters< double > props
List of properties.
std::unique_ptr< mrpt::io::CStream > m_logFile
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.
Definition: TPose2D.h:30
void onStartNewNavigation() override
Called whenever a new navigation has been started.
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
A safe way to call enter() and leave() of a mrpt::system::CTimeLogger upon construction and destructi...
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...
std::vector< double > final_evaluation
The final evaluation score for each candidate.
bool open(const std::string &fileName, int compress_level=1, mrpt::optional_ref< std::string > error_msg=std::nullopt)
Open a file for write, choosing the compression level.
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
std::recursive_mutex m_critZoneLastLog
Critical zones.
std::vector< const TRuntimeClassId * > getAllRegisteredClassesChildrenOf(const TRuntimeClassId *parent_id)
Like getAllRegisteredClasses(), but filters the list to only include children clases of a given base ...
mrpt::nav::ClearanceDiagram clearance
Clearance for each path.
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...
GLenum GLint ref
Definition: glext.h:4062
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.
#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 ...
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.
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...
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:128
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:95
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:86
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) ...
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.
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...
int target_k
The discrete version of target_alpha.
mrpt::math::LowPassFilter_IIR1 meanExecutionPeriod
Runtime estimation of execution period of the method.
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...
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...
void setHolonomicMethod(const std::string &method, const mrpt::config::CConfigFileBase &cfgBase)
Selects which one from the set of available holonomic methods will be used into transformed TP-Space...
GLdouble s
Definition: glext.h:3682
#define MRPT_LOG_WARN_FMT(_FMT_STRING,...)
GLsizei GLsizei GLuint * obj
Definition: glext.h:4085
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
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.
mrpt::kinematics::CVehicleVelCmd::Ptr m_last_vel_cmd
Last velocity commands.
mrpt::math::TPose2D asTPose() const
Definition: CPose2D.cpp:468
virtual bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd)
Default: forward call to m_robot.changeSpeed().
void registerUserMeasure(const std::string_view &event_name, const double value, const bool is_time=false)
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().
mrpt::math::TPoint2D TP_Target
The Target, in TP-Space (x,y)
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)
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT&#39;s CStream, std::istream, std::ostream, std::stringstream.
Definition: CArchive.h:586
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.
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
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
This is the base class for any user-defined PTG.
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
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:89
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
static CMultiObjectiveMotionOptimizerBase::Ptr Factory(const std::string &className) noexcept
Class factory from C++ class name.
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_LOG_DEBUG_FMT(_FMT_STRING,...)
Use: MRPT_LOG_DEBUG_FMT("i=%u", i);
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
Definition: exceptions.h:137
double speed
TP-Space movement speed, normalized to [0,1].
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.
const GLubyte * c
Definition: glext.h:6406
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)
Definition: TTwist2D.h:26
This CStream derived class allow using a memory buffer as a CStream.
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
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::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.
void onStartNewNavigation() override
Called whenever a new navigation has been started.
uint64_t Seek(int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) override
Introduces a pure virtual method for moving to a specified position in the streamed resource...
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.
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.
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:4116
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd()=0
Gets the emergency stop command for the current robot.
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
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...
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.
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.
ClearanceDiagram clearance
Clearance for each path.
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:3684
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
pose_t & interpolate(const mrpt::Clock::time_point &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...
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...
void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
mrpt::math::CVectorFloat TP_Obstacles
Distances until obstacles, in "pseudometers", first index for -PI direction, last one for PI directio...
mrpt::io::CStream * m_prev_logfile
The current log file stream, or nullptr if not being used.
GLdouble GLdouble GLdouble r
Definition: glext.h:3711
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()
void loadConfigFile(const mrpt::config::CConfigFileBase &c) override
Loads all params from a file.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
virtual 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.
std::vector< TInfoPerPTG > infoPerPTG
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
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::math::TPose2D(0, 0, 0))
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
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.
#define MRPT_END
Definition: exceptions.h:245
mrpt::math::LowPassFilter_IIR1 meanTotalExecutionTime
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.
static CAbstractHolonomicReactiveMethod::Ptr Factory(const std::string &className) noexcept
#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 ...
Lightweight 2D pose.
Definition: TPose2D.h:22
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...
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i)=0
Gets the i&#39;th PTG.
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
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 double getTargetApproachSlowDownDistance() const =0
Returns the actual value of this parameter [m], as set via the children class options structure...
std::weak_ptr< mrpt::poses::FrameTransformer< 2 > > m_frame_tf
Optional, user-provided frame transformer.
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.h:146
virtual void navigate(const NavInput &ni, NavOutput &no)=0
Invokes the holonomic navigation algorithm itself.
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) ...
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:137
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
Saves data to a file and transparently compress the data using the given compression level...
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:75
mrpt::poses::CPose2DInterpolator m_latestOdomPoses
GLuint GLenum GLenum transform
Definition: glext.h:7089
std::string sprintf_vector(const char *fmt, const VEC &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:24
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
Definition: exceptions.h:69
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
unsigned __int32 uint32_t
Definition: rptypes.h:50
Lightweight 2D point.
Definition: TPoint2D.h:31
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
Dynamic state that may affect the PTG path parameterization.
Output for CAbstractHolonomicReactiveMethod::navigate()
mrpt::math::TPose2D relPoseVelCmd
GLfloat GLfloat p
Definition: glext.h:6398
virtual CAbstractHolonomicReactiveMethod * getHoloMethod(int idx)
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, const mrpt::nav::CHolonomicLogFileRecord::Ptr &hlfr)
Scores holonomicMovement.
mrpt::poses::CPose2DInterpolator m_latestPoses
Latest robot poses (updated in CAbstractNavigator::navigationStep() )
double phi
Orientation (rads)
Definition: TPose2D.h:32
void enter(const std::string_view &func_name)
Start of a named section.
std::shared_ptr< CObject > Ptr
Definition: CObject.h:180
mrpt::system::CTimeLogger m_timelogger
A complete time logger.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
double getLastOutput() const
Definition: filters.cpp:29
The structure used to store all relevant information about each transformation into TP-Space...
double leave(const std::string_view &func_name)
End of a named section.
mrpt::math::LowPassFilter_IIR1 tim_changeSpeed_avr
GLenum filter
Definition: glext.h:5134
mrpt::math::TPose2D rawOdometry
raw odometry (frame does not match to "pose", but is expected to be smoother in the short term)...
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.
void saveConfigFile(mrpt::config::CConfigFileBase &c) const override
Saves all current options to a config file.
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:23



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