Main MRPT website > C++ reference for MRPT 1.5.7
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/nav/holonomic/CHolonomicVFF.h> // TODO: Remove for MRPT 2.0
14 #include <mrpt/nav/holonomic/CHolonomicND.h> // TODO: Remove for MRPT 2.0
15 #include <mrpt/nav/holonomic/CHolonomicFullEval.h> // TODO: Remove for MRPT 2.0
16 #include <mrpt/system/filesystem.h>
17 #include <mrpt/math/wrap2pi.h>
18 #include <mrpt/math/geometry.h>
19 #include <mrpt/math/ops_containers.h> // sum()
25 #include <limits>
26 #include <iomanip>
27 #include <array>
28 
29 using namespace mrpt;
30 using namespace mrpt::poses;
31 using namespace mrpt::math;
32 using namespace mrpt::utils;
33 using namespace mrpt::nav;
34 using namespace std;
35 
36 // ------ CAbstractPTGBasedReactive::TNavigationParamsPTG -----
37 std::string CAbstractPTGBasedReactive::TNavigationParamsPTG::getAsText() const
38 {
39  std::string s = CWaypointsNavigator::TNavigationParamsWaypoints::getAsText();
40  s += "restrict_PTG_indices: ";
41  s += mrpt::utils::sprintf_vector("%u ",this->restrict_PTG_indices);
42  s += "\n";
43  return s;
44 }
45 
46 bool CAbstractPTGBasedReactive::TNavigationParamsPTG::isEqual(const CAbstractNavigator::TNavigationParamsBase& rhs) const
47 {
48  auto o = dynamic_cast<const CAbstractPTGBasedReactive::TNavigationParamsPTG*>(&rhs);
49  return o!=nullptr &&
50  CWaypointsNavigator::TNavigationParamsWaypoints::isEqual(rhs) &&
51  restrict_PTG_indices == o->restrict_PTG_indices;
52 }
53 
54 const double ESTIM_LOWPASSFILTER_ALPHA = 0.7;
55 
56 // Ctor:
57 CAbstractPTGBasedReactive::CAbstractPTGBasedReactive(CRobot2NavInterface &react_iterf_impl, bool enableConsoleOutput, bool enableLogFile, const std::string &sLogDir):
58  CWaypointsNavigator(react_iterf_impl),
59  m_holonomicMethod (),
60  m_logFile (nullptr),
61  m_prev_logfile (nullptr),
62  m_enableKeepLogRecords (false),
63  m_enableConsoleOutput (enableConsoleOutput),
64  m_init_done (false),
65  m_timelogger (false), // default: disabled
66  m_PTGsMustBeReInitialized (true),
67  meanExecutionTime (ESTIM_LOWPASSFILTER_ALPHA, 0.1),
68  meanTotalExecutionTime (ESTIM_LOWPASSFILTER_ALPHA, 0.1),
69  meanExecutionPeriod (ESTIM_LOWPASSFILTER_ALPHA, 0.1),
70  tim_changeSpeed_avr (ESTIM_LOWPASSFILTER_ALPHA),
71  timoff_obstacles_avr (ESTIM_LOWPASSFILTER_ALPHA),
72  timoff_curPoseAndSpeed_avr (ESTIM_LOWPASSFILTER_ALPHA),
73  timoff_sendVelCmd_avr (ESTIM_LOWPASSFILTER_ALPHA),
74  m_closing_navigator (false),
75  m_WS_Obstacles_timestamp (INVALID_TIMESTAMP),
76  m_infoPerPTG_timestamp (INVALID_TIMESTAMP),
77  m_navlogfiles_dir (sLogDir),
78  m_copy_prev_navParams (nullptr)
79 {
80  this->enableLogFile( enableLogFile );
81 }
82 
84 {
85  m_closing_navigator = true;
86 
87  // Wait to end of navigation (multi-thread...)
88  m_nav_cs.enter();
89  m_nav_cs.leave();
90 
91  // Just in case.
92  try {
93  // Call base class method, NOT the generic, virtual one,
94  // to avoid problems if we are in the dtor, while the vtable
95  // is being destroyed.
96  CAbstractNavigator::stop(false /*not emergency*/);
97  } catch (...) { }
98 
100 
101  // Free holonomic method:
102  this->deleteHolonomicObjects();
103 }
104 
106 {
107  this->preDestructor(); // ensure the robot is stopped; free dynamic objects
108 
110 }
111 
113 {
115 
117 
119  m_multiobjopt->clear();
120 
121  // Compute collision grids:
122  STEP1_InitPTGs();
123 }
124 
125 /*---------------------------------------------------------------
126  enableLogFile
127  ---------------------------------------------------------------*/
129 {
131 
132  try
133  {
134  // Disable:
135  // -------------------------------
136  if (!enable)
137  {
138  if (m_logFile)
139  {
140  MRPT_LOG_DEBUG("[CAbstractPTGBasedReactive::enableLogFile] Stopping logging.");
141  // Close file:
142  delete m_logFile;
143  m_logFile = NULL;
144  }
145  else return; // Already disabled.
146  }
147  else
148  { // Enable
149  // -------------------------------
150  if (m_logFile) return; // Already enabled:
151 
152  // Open file, find the first free file-name.
153  char aux[300];
154  unsigned int nFile = 0;
155  bool free_name = false;
156 
159  THROW_EXCEPTION_FMT("Could not create directory for navigation logs: `%s`", m_navlogfiles_dir.c_str());
160  }
161 
162  while (!free_name)
163  {
164  nFile++;
165  sprintf(aux, "%s/log_%03u.reactivenavlog", m_navlogfiles_dir.c_str(), nFile );
166  free_name = !system::fileExists(aux);
167  }
168 
169  // Open log file:
170  {
172  bool ok = fil->open(aux, 1 /* compress level */);
173  if (!ok) {
174  delete fil;
175  THROW_EXCEPTION_FMT("Error opening log file: `%s`",aux);
176  }
177  else {
178  m_logFile = fil;
179  }
180  }
181 
182  MRPT_LOG_DEBUG(mrpt::format("[CAbstractPTGBasedReactive::enableLogFile] Logging to file `%s`\n",aux));
183 
184  }
185  } catch (std::exception &e) {
186  MRPT_LOG_ERROR_FMT("[CAbstractPTGBasedReactive::enableLogFile] Exception: %s",e.what());
187  }
188 
189 }
190 
192 {
194  o = lastLogRecord;
195 }
196 
197 // TODO: Remove for MRPT 2.0
199 {
200  std::string className;
201  switch (method)
202  {
203  case hmSEARCH_FOR_BEST_GAP: className = "CHolonomicND"; break;
204  case hmVIRTUAL_FORCE_FIELDS: className = "CHolonomicVFF"; break;
205  case hmFULL_EVAL: className = "CHolonomicFullEval"; break;
206  default: THROW_EXCEPTION_FMT("Unknown Holonomic method: %u", static_cast<unsigned int>(method))
207  };
208  return className;
209 }
210 
212 {
213  for (size_t i=0;i<m_holonomicMethod.size();i++)
214  delete m_holonomicMethod[i];
215  m_holonomicMethod.clear();
216 }
217 
219 {
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  {
230  if (!m_holonomicMethod[i])
231  THROW_EXCEPTION_FMT("Non-registered holonomic method className=`%s`", method.c_str());
232 
233  m_holonomicMethod[i]->setAssociatedPTG(this->getPTG(i));
234  m_holonomicMethod[i]->initialize(ini); // load params
235  }
236 }
237 
239 {
241 }
242 
243 // The main method: executes one time-iteration of the reactive navigation algorithm.
245 {
246  // Security tests:
247  if (m_closing_navigator) return; // Are we closing in the main thread?
248  if (!m_init_done) THROW_EXCEPTION("Have you called loadConfigFile() before?")
250 
251  const size_t nPTGs = this->getPTG_count();
252 
253  // Whether to worry about log files:
254  const bool fill_log_record = (m_logFile!=NULL || m_enableKeepLogRecords);
255  CLogFileRecord newLogRec;
256  newLogRec.infoPerPTG.resize(nPTGs+1); /* +1: [N] is the "NOP cmdvel" option; not to be present in all log entries. */
257 
258  // At the beginning of each log file, add an introductory block explaining which PTGs are we using:
259  {
260  if (m_logFile && m_logFile!= m_prev_logfile) // Only the first time
261  {
263  for (size_t i=0;i<nPTGs;i++)
264  {
265  // If we make a direct copy (=) we will store the entire, heavy, collision grid.
266  // Let's just store the parameters of each PTG by serializing it, so paths can be reconstructed
267  // by invoking initialize()
269  buf << *this->getPTG(i);
270  buf.Seek(0);
271  newLogRec.infoPerPTG[i].ptg = mrpt::nav::CParameterizedTrajectoryGeneratorPtr ( buf.ReadObject() );
272  }
273  }
274  }
275 
276  CTimeLoggerEntry tle1(m_timelogger,"navigationStep");
277 
278  try
279  {
280  totalExecutionTime.Tic(); // Start timer
281 
282  const mrpt::system::TTimeStamp tim_start_iteration = mrpt::system::now();
283 
284  // Compute target location relative to current robot pose:
285  // ---------------------------------------------------------------------
286  // Detect changes in target since last iteration (for NOP):
287  const bool target_changed_since_last_iteration = (m_copy_prev_navParams == nullptr) || !(*m_copy_prev_navParams==*m_navigationParams);
288  if (target_changed_since_last_iteration) {
291  }
292 
293  // Load the list of target(s) from the navigationParam user command.
294  // Semantic is: any of the target is good. If several targets are reachable, head to latest one.
295  std::vector<CAbstractNavigator::TargetInfo> targets;
296  {
298  if (p && !p->multiple_targets.empty())
299  {
300  targets = p->multiple_targets;
301  }
302  else
303  {
304  targets.push_back(m_navigationParams->target);
305  }
306  }
307  const size_t nTargets = targets.size(); // Normally = 1, will be >1 if we want the robot local planner to be "smarter" in skipping dynamic obstacles.
308  ASSERT_(nTargets>=1);
309 
310  STEP1_InitPTGs(); // Will only recompute if "m_PTGsMustBeReInitialized==true"
311 
312  // STEP2: Load the obstacles and sort them in height bands.
313  // -----------------------------------------------------------------------------
314  if (! STEP2_SenseObstacles() )
315  {
316  doEmergencyStop("Error while loading and sorting the obstacles. Robot will be stopped.");
317  if (fill_log_record)
318  {
319  CPose2D rel_cur_pose_wrt_last_vel_cmd_NOP, rel_pose_PTG_origin_wrt_sense_NOP;
320  STEP8_GenerateLogRecord(newLogRec,
321  std::vector<mrpt::math::TPose2D>() /*no targets*/,
322  -1, // best_ptg_idx,
324  nPTGs,
325  false, //best_is_NOP_cmdvel,
326  rel_cur_pose_wrt_last_vel_cmd_NOP,
327  rel_pose_PTG_origin_wrt_sense_NOP,
328  0, //executionTimeValue,
329  0, //tim_changeSpeed,
330  tim_start_iteration);
331  }
332  return;
333  }
334 
335  // ------- start of motion decision zone ---------
336  executionTime.Tic();
337 
338  // Round #1: As usual, pure reactive, evaluate all PTGs and all directions from scratch.
339  // =========
340 
341  mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense(0,0,0),relPoseSense(0,0,0), relPoseVelCmd(0,0,0);
343  {
344  /*
345  * Delays model
346  *
347  * Event: OBSTACLES_SENSED RNAV_ITERATION_STARTS GET_ROBOT_POSE_VEL VEL_CMD_SENT_TO_ROBOT
348  * Timestamp: (m_WS_Obstacles_timestamp) (tim_start_iteration) (m_curPoseVelTimestamp) ("tim_send_cmd_vel")
349  * Delay | <---+--------------->|<--------------+-------->| |
350  * estimator: | | | |
351  * timoff_obstacles <-+ | +--> timoff_curPoseVelAge |
352  * |<---------------------------------+--------------->|
353  * +--> timoff_sendVelCmd_avr (estimation)
354  *
355  * |<-------------------->|
356  * tim_changeSpeed_avr (estim)
357  *
358  * |<-----------------------------------------------|-------------------------->|
359  * Relative poses: relPoseSense relPoseVelCmd
360  * Time offsets (signed): timoff_pose2sense timoff_pose2VelCmd
361  */
362  const double timoff_obstacles = mrpt::system::timeDifference(tim_start_iteration, m_WS_Obstacles_timestamp);
363  timoff_obstacles_avr.filter(timoff_obstacles);
364  newLogRec.values["timoff_obstacles"] = timoff_obstacles;
365  newLogRec.values["timoff_obstacles_avr"] = timoff_obstacles_avr.getLastOutput();
366  newLogRec.timestamps["obstacles"] = m_WS_Obstacles_timestamp;
367 
368  const double timoff_curPoseVelAge = mrpt::system::timeDifference(tim_start_iteration, m_curPoseVel.timestamp);
369  timoff_curPoseAndSpeed_avr.filter(timoff_curPoseVelAge);
370  newLogRec.values["timoff_curPoseVelAge"] = timoff_curPoseVelAge;
371  newLogRec.values["timoff_curPoseVelAge_avr"] = timoff_curPoseAndSpeed_avr.getLastOutput();
372 
373  // time offset estimations:
374  const double timoff_pose2sense = timoff_obstacles - timoff_curPoseVelAge;
375 
376  double timoff_pose2VelCmd;
377  timoff_pose2VelCmd = timoff_sendVelCmd_avr.getLastOutput() + 0.5*tim_changeSpeed_avr.getLastOutput() - timoff_curPoseVelAge;
378  newLogRec.values["timoff_pose2sense"] = timoff_pose2sense;
379  newLogRec.values["timoff_pose2VelCmd"] = timoff_pose2VelCmd;
380 
381  if (std::abs(timoff_pose2sense) > 1.25) MRPT_LOG_WARN_FMT("timoff_pose2sense=%e is too large! Path extrapolation may be not accurate.", timoff_pose2sense);
382  if (std::abs(timoff_pose2VelCmd) > 1.25) MRPT_LOG_WARN_FMT("timoff_pose2VelCmd=%e is too large! Path extrapolation may be not accurate.", timoff_pose2VelCmd);
383 
384  // Path extrapolation: robot relative poses along current path estimation:
385  relPoseSense = m_curPoseVel.velLocal * timoff_pose2sense;
386  relPoseVelCmd = m_curPoseVel.velLocal * timoff_pose2VelCmd;
387 
388  // relative pose for PTGs:
389  rel_pose_PTG_origin_wrt_sense = relPoseVelCmd - relPoseSense;
390 
391  // logging:
392  newLogRec.relPoseSense = relPoseSense;
393  newLogRec.relPoseVelCmd = relPoseVelCmd;
394  }
395  else {
396  // No delays model: poses to their default values.
397  }
398 
399 
400  for (auto &t : targets)
401  {
402  if ( t.target_frame_id != m_curPoseVel.pose_frame_id)
403  {
404  if (m_frame_tf == nullptr) {
405  THROW_EXCEPTION_FMT("Different frame_id's but no frame_tf object attached!: target_frame_id=`%s` != pose_frame_id=`%s`", t.target_frame_id.c_str(), m_curPoseVel.pose_frame_id.c_str());
406  }
407  mrpt::math::TPose2D robot_frame2map_frame;
408  m_frame_tf->lookupTransform(t.target_frame_id, m_curPoseVel.pose_frame_id, robot_frame2map_frame);
409 
410  MRPT_LOG_DEBUG_FMT("frame_tf: target_frame_id=`%s` as seen from pose_frame_id=`%s` = %s", t.target_frame_id.c_str(), m_curPoseVel.pose_frame_id.c_str(), robot_frame2map_frame.asString().c_str());
411 
412  t.target_coords = robot_frame2map_frame + t.target_coords;
413  t.target_frame_id = m_curPoseVel.pose_frame_id; // Now the coordinates are in the same frame than robot pose
414  }
415  }
416 
417  std::vector<TPose2D> relTargets;
418  const auto curPoseExtrapol = (m_curPoseVel.pose + relPoseVelCmd);
420  targets.begin(), targets.end(), // in
421  std::back_inserter(relTargets), // out
422  [curPoseExtrapol](const CAbstractNavigator::TargetInfo &e) { return e.target_coords - curPoseExtrapol; }
423  );
424  ASSERT_EQUAL_(relTargets.size(),targets.size());
425 
426  // Use the distance to the first target as reference:
427  const double relTargetDist = relTargets.begin()->norm();
428 
429  // PTG dynamic state
430  CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState; //!< Allow PTGs to be responsive to target location, dynamics, etc.
431 
432  ptg_dynState.curVelLocal = m_curPoseVel.velLocal;
433  ptg_dynState.relTarget = relTargets[0];
435 
436  newLogRec.navDynState = ptg_dynState;
437 
438  for (size_t i = 0; i < nPTGs; i++) {
439  getPTG(i)->updateNavDynamicState(ptg_dynState);
440  }
441 
442  m_infoPerPTG.assign(nPTGs+1, TInfoPerPTG()); // reset contents
443  m_infoPerPTG_timestamp = tim_start_iteration;
444  vector<TCandidateMovementPTG> candidate_movs(nPTGs+1); // the last extra one is for the evaluation of "NOP motion command" choice.
445 
446  for (size_t indexPTG=0;indexPTG<nPTGs;indexPTG++)
447  {
448  CParameterizedTrajectoryGenerator * ptg = getPTG(indexPTG);
449 
450  // Ensure the method knows about its associated PTG:
451  auto holoMethod = this->getHoloMethod(indexPTG);
452  ASSERT_(holoMethod);
453  holoMethod->setAssociatedPTG(this->getPTG(indexPTG));
454 
455  TInfoPerPTG &ipf = m_infoPerPTG[indexPTG];
456 
457  // The picked movement in TP-Space (to be determined by holonomic method below)
458  TCandidateMovementPTG &cm = candidate_movs[indexPTG];
459 
462  ptg, indexPTG,
463  relTargets, rel_pose_PTG_origin_wrt_sense,
464  ipf, cm,
465  newLogRec, false /* this is a regular PTG reactive case */,
466  holoMethod,
467  tim_start_iteration,
469  );
470  } // end for each PTG
471 
472  // check for collision, which is reflected by ALL TP-Obstacles being zero:
473  bool is_all_ptg_collision = true;
474  for (size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
475  {
476  bool is_collision = true;
477  const auto & obs = m_infoPerPTG[indexPTG].TP_Obstacles;
478  for (const auto o : obs) {
479  if (o != 0) {
480  is_collision = false;
481  break;
482  }
483  }
484  if (!is_collision) {
485  is_all_ptg_collision = false;
486  break;
487  }
488  }
489  if (is_all_ptg_collision) {
490  TPendingEvent ev;
492  m_pending_events.push_back(ev);
493  }
494 
495  // Round #2: Evaluate dont sending any new velocity command ("NOP" motion)
496  // =========
497  bool NOP_not_too_old = true;
498  bool NOP_not_too_close_and_have_to_slowdown = true;
499  double NOP_max_time = -1.0, NOP_At = -1.0;
500  double slowdowndist = .0;
501  CParameterizedTrajectoryGenerator * last_sent_ptg =
503  getPTG(m_lastSentVelCmd.ptg_index) : nullptr;
504  if (last_sent_ptg) {
505  // So supportSpeedAtTarget() below is evaluated in the correct context:
507  }
508 
509  // This approach is only possible if:
510  const bool can_do_nop_motion =
511  (
513  !target_changed_since_last_iteration &&
514  last_sent_ptg &&
515  last_sent_ptg->supportVelCmdNOP()
516  )
517  &&
518  (
519  NOP_not_too_old =
520  (NOP_At=mrpt::system::timeDifference(m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration))
521  <
522  (NOP_max_time= last_sent_ptg->maxTimeInVelCmdNOP(m_lastSentVelCmd.ptg_alpha_index)/ std::max(0.1,m_lastSentVelCmd.speed_scale))
523  )
524  &&
525  (NOP_not_too_close_and_have_to_slowdown =
526  (last_sent_ptg->supportSpeedAtTarget() ||
527  ( relTargetDist
528  >
529  (slowdowndist = m_holonomicMethod[m_lastSentVelCmd.ptg_index]->getTargetApproachSlowDownDistance()) // slowdowndist is assigned here, inside the if() to be sure the index in m_lastSentVelCmd is valid!
530  )
531  )
532  )
533  ;
534 
535  if (!NOP_not_too_old) {
536  newLogRec.additional_debug_msgs["PTG_cont"] = mrpt::format("PTG-continuation not allowed: previous command timed-out (At=%.03f > Max_At=%.03f)", NOP_At, NOP_max_time);
537  }
538  if (!NOP_not_too_close_and_have_to_slowdown) {
539  newLogRec.additional_debug_msgs["PTG_cont_trgdst"] = mrpt::format("PTG-continuation not allowed: target too close and must start slow-down (trgDist=%.03f < SlowDownDist=%.03f)", relTargetDist, slowdowndist);
540  }
541 
542  mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP(0,0,0), rel_pose_PTG_origin_wrt_sense_NOP(0,0,0);
543 
544  if (can_do_nop_motion)
545  {
546  // Add the estimation of how long it takes to run the changeSpeeds() callback (usually a tiny period):
547  const mrpt::system::TTimeStamp tim_send_cmd_vel_corrected =
551 
552  // Note: we use (uncorrected) raw odometry as basis to the following calculation since it's normally
553  // smoother than particle filter-based localization data, more accurate in the middle/long term,
554  // but not in the short term:
555  mrpt::math::TPose2D robot_pose_at_send_cmd, robot_odom_at_send_cmd;
556  bool valid_odom, valid_pose;
557 
558  m_latestOdomPoses.interpolate(tim_send_cmd_vel_corrected, robot_odom_at_send_cmd, valid_odom);
559  m_latestPoses.interpolate(tim_send_cmd_vel_corrected, robot_pose_at_send_cmd, valid_pose);
560 
561  if (valid_odom && valid_pose)
562  {
563  ASSERT_(last_sent_ptg!=nullptr);
564 
565  std::vector<TPose2D> relTargets_NOPs;
567  targets.begin(), targets.end(), // in
568  std::back_inserter(relTargets_NOPs), // out
569  [robot_pose_at_send_cmd](const CAbstractNavigator::TargetInfo &e) { return e.target_coords - robot_pose_at_send_cmd; }
570  );
571  ASSERT_EQUAL_(relTargets_NOPs.size(), targets.size());
572 
573  rel_pose_PTG_origin_wrt_sense_NOP = robot_odom_at_send_cmd - (m_curPoseVel.rawOdometry + relPoseSense);
574  rel_cur_pose_wrt_last_vel_cmd_NOP = m_curPoseVel.rawOdometry - robot_odom_at_send_cmd;
575 
576  // Update PTG response to dynamic params:
578 
579  if (fill_log_record)
580  {
581  newLogRec.additional_debug_msgs["rel_cur_pose_wrt_last_vel_cmd_NOP(interp)"] = rel_cur_pose_wrt_last_vel_cmd_NOP.asString();
582  newLogRec.additional_debug_msgs["robot_odom_at_send_cmd(interp)"] = robot_odom_at_send_cmd.asString();
583  }
584 
585  // No need to call setAssociatedPTG(), already correctly associated above.
586 
589  last_sent_ptg, m_lastSentVelCmd.ptg_index,
590  relTargets_NOPs, rel_pose_PTG_origin_wrt_sense_NOP,
591  m_infoPerPTG[nPTGs], candidate_movs[nPTGs],
592  newLogRec, true /* this is the PTG continuation (NOP) choice */,
594  tim_start_iteration,
596  rel_cur_pose_wrt_last_vel_cmd_NOP);
597 
598  } // end valid interpolated origin pose
599  else
600  {
601  // Can't interpolate pose, hence can't evaluate NOP:
602  candidate_movs[nPTGs].speed = -0.01; // <0 means inviable movement
603  }
604  } //end can_do_NOP_motion
605 
606  // Evaluate all the candidates and pick the "best" one, using
607  // the user-defined multiobjective optimizer
608  // --------------------------------------------------------------
611  int best_ptg_idx = m_multiobjopt->decide(candidate_movs, mo_info);
612 
613  if (fill_log_record)
614  {
615  if (mo_info.final_evaluation.size() == newLogRec.infoPerPTG.size())
616  {
617  for (unsigned int i = 0; i < newLogRec.infoPerPTG.size(); i++) {
618  newLogRec.infoPerPTG[i].evaluation = mo_info.final_evaluation[i];
619  }
620  }
621  int idx = 0;
622  for (const auto &le : mo_info.log_entries) {
623  newLogRec.additional_debug_msgs[mrpt::format("MultiObjMotOptmzr_msg%03i",idx++)] = le;
624  }
625  }
626 
627  // Pick best movement (or null if none is good)
628  const TCandidateMovementPTG * selectedHolonomicMovement = nullptr;
629  if (best_ptg_idx >= 0) {
630  selectedHolonomicMovement = &candidate_movs[best_ptg_idx];
631  }
632 
633  // If the selected PTG is (N+1), it means the NOP cmd. vel is selected as the best alternative, i.e. do NOT send any new motion command.
634  const bool best_is_NOP_cmdvel = (best_ptg_idx==int(nPTGs));
635 
636  // ---------------------------------------------------------------------
637  // SEND MOVEMENT COMMAND TO THE ROBOT
638  // ---------------------------------------------------------------------
639  mrpt::kinematics::CVehicleVelCmdPtr new_vel_cmd;
640  if (best_is_NOP_cmdvel)
641  {
642  // Notify the robot that we want it to keep executing the last cmdvel:
643  if (!this->changeSpeedsNOP())
644  {
645  doEmergencyStop("\nERROR calling changeSpeedsNOP()!! Stopping robot and finishing navigation\n");
646  if(fill_log_record)
647  {
648  STEP8_GenerateLogRecord(newLogRec,
649  relTargets,
650  best_ptg_idx,
652  nPTGs,
653  best_is_NOP_cmdvel,
654  rel_cur_pose_wrt_last_vel_cmd_NOP,
655  rel_pose_PTG_origin_wrt_sense_NOP,
656  0, //executionTimeValue,
657  0, //tim_changeSpeed,
658  tim_start_iteration);
659  }
660  return;
661  }
662  }
663  else
664  {
665  // Make sure the dynamic state of a NOP cmd has not overwritten the state for a "regular" PTG choice:
666  for (size_t i = 0; i < nPTGs; i++) {
667  getPTG(i)->updateNavDynamicState(ptg_dynState);
668  }
669 
670  // STEP7: Get the non-holonomic movement command.
671  // ---------------------------------------------------------------------
672  double cmd_vel_speed_ratio = 1.0;
673  if (selectedHolonomicMovement)
674  {
675  CTimeLoggerEntry tle(m_timelogger, "navigationStep.selectedHolonomicMovement");
676  cmd_vel_speed_ratio = generate_vel_cmd(*selectedHolonomicMovement, new_vel_cmd);
677  ASSERT_(new_vel_cmd);
678  }
679 
680  if (!new_vel_cmd /* which means best_PTG_eval==.0*/ || new_vel_cmd->isStopCmd()) {
681  MRPT_LOG_DEBUG("Best velocity command is STOP (no way found), calling robot.stop()");
682  this->stop(true /* emergency */); // don't call doEmergencyStop() here since that will stop navigation completely
683  new_vel_cmd = m_robot.getEmergencyStopCmd();
685  }
686  else
687  {
688  mrpt::system::TTimeStamp tim_send_cmd_vel;
689  {
690  mrpt::utils::CTimeLoggerEntry tle(m_timlog_delays, "changeSpeeds()");
691  tim_send_cmd_vel = mrpt::system::now();
692  newLogRec.timestamps["tim_send_cmd_vel"] = tim_send_cmd_vel;
693  if (!this->changeSpeeds(*new_vel_cmd))
694  {
695  doEmergencyStop("\nERROR calling changeSpeeds()!! Stopping robot and finishing navigation\n");
696  if (fill_log_record)
697  {
698  new_vel_cmd = m_robot.getEmergencyStopCmd();
699  STEP8_GenerateLogRecord(newLogRec,
700  relTargets,
701  best_ptg_idx,
702  new_vel_cmd,
703  nPTGs,
704  best_is_NOP_cmdvel,
705  rel_cur_pose_wrt_last_vel_cmd_NOP,
706  rel_pose_PTG_origin_wrt_sense_NOP,
707  0, //executionTimeValue,
708  0, //tim_changeSpeed,
709  tim_start_iteration);
710  }
711  return;
712  }
713  }
714  // Save last sent cmd:
715  m_lastSentVelCmd.speed_scale = cmd_vel_speed_ratio;
716  m_lastSentVelCmd.ptg_index = best_ptg_idx;
717  m_lastSentVelCmd.ptg_alpha_index = selectedHolonomicMovement ?
718  selectedHolonomicMovement->PTG->alpha2index(selectedHolonomicMovement->direction)
719  :
720  0;
721  m_lastSentVelCmd.original_holo_eval = selectedHolonomicMovement->props["holo_stage_eval"];
722 
723  m_lastSentVelCmd.colfreedist_move_k = best_ptg_idx >= 0 ?
724  m_infoPerPTG[best_ptg_idx].TP_Obstacles[m_lastSentVelCmd.ptg_alpha_index]
725  :
726  .0;
727  m_lastSentVelCmd.was_slowdown = (selectedHolonomicMovement->props["is_slowdown"]!=0.0);
728 
730  m_lastSentVelCmd.tim_send_cmd_vel = tim_send_cmd_vel;
731  m_lastSentVelCmd.ptg_dynState = ptg_dynState;
732 
733  // Update delay model:
734  const double timoff_sendVelCmd = mrpt::system::timeDifference(tim_start_iteration, tim_send_cmd_vel);
735  timoff_sendVelCmd_avr.filter(timoff_sendVelCmd);
736  newLogRec.values["timoff_sendVelCmd"] = timoff_sendVelCmd;
737  newLogRec.values["timoff_sendVelCmd_avr"] = timoff_sendVelCmd_avr.getLastOutput();
738  }
739  }
740 
741  // ------- end of motion decision zone ---------
742 
743 
744  // Statistics:
745  // ----------------------------------------------------
746  const double executionTimeValue = executionTime.Tac();
747  meanExecutionTime.filter(executionTimeValue);
749 
750  const double tim_changeSpeed = m_timlog_delays.getLastTime("changeSpeeds()");
751  tim_changeSpeed_avr.filter(tim_changeSpeed);
752 
753  // Running period estim:
754  const double period_tim= timerForExecutionPeriod.Tac();
755  if (period_tim > 1.5* meanExecutionPeriod.getLastOutput()) {
756  MRPT_LOG_WARN_FMT("Timing warning: Suspicious executionPeriod=%.03f ms is far above the average of %.03f ms", 1e3*period_tim, meanExecutionPeriod.getLastOutput()*1e3);
757  }
758  meanExecutionPeriod.filter(period_tim);
760 
761 
763  {
765  "CMD: %s "
766  "speedScale=%.04f "
767  "T=%.01lfms Exec:%.01lfms|%.01lfms "
768  "PTG#%i\n",
769  new_vel_cmd ? new_vel_cmd->asString().c_str() : "NOP",
770  selectedHolonomicMovement ? selectedHolonomicMovement->speed : .0,
774  best_ptg_idx
775  ) );
776  }
777  if (fill_log_record)
778  {
779  STEP8_GenerateLogRecord(newLogRec,
780  relTargets,
781  best_ptg_idx,
782  new_vel_cmd,
783  nPTGs,
784  best_is_NOP_cmdvel,
785  rel_cur_pose_wrt_last_vel_cmd_NOP,
786  rel_pose_PTG_origin_wrt_sense_NOP,
787  executionTimeValue,
788  tim_changeSpeed,
789  tim_start_iteration);
790  }
791  }
792  catch (std::exception &e) {
793  doEmergencyStop(std::string("[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot and finishing navigation due to exception:\n") + std::string(e.what()));
794  }
795  catch (...) {
796  doEmergencyStop("[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot and finishing navigation due to untyped exception." );
797  }
798 }
799 
800 
801 void CAbstractPTGBasedReactive::STEP8_GenerateLogRecord(CLogFileRecord &newLogRec,const std::vector<TPose2D>& relTargets,int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmdPtr &new_vel_cmd, const int nPTGs, const bool best_is_NOP_cmdvel, const mrpt::math::TPose2D &rel_cur_pose_wrt_last_vel_cmd_NOP, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense_NOP, const double executionTimeValue, const double tim_changeSpeed, const mrpt::system::TTimeStamp &tim_start_iteration)
802 {
803  // ---------------------------------------
804  // STEP8: Generate log record
805  // ---------------------------------------
806  m_timelogger.enter("navigationStep.populate_log_info");
807 
808  this->loggingGetWSObstaclesAndShape(newLogRec);
809 
812  newLogRec.WS_targets_relative = relTargets;
813  newLogRec.nSelectedPTG = nSelectedPTG;
814  newLogRec.cur_vel = m_curPoseVel.velGlobal;
815  newLogRec.cur_vel_local = m_curPoseVel.velLocal;
816  newLogRec.cmd_vel = new_vel_cmd;
817  newLogRec.values["estimatedExecutionPeriod"] = meanExecutionPeriod.getLastOutput();
818  newLogRec.values["executionTime"] = executionTimeValue;
819  newLogRec.values["executionTime_avr"] = meanExecutionTime.getLastOutput();
820  newLogRec.values["time_changeSpeeds()"] = tim_changeSpeed;
821  newLogRec.values["time_changeSpeeds()_avr"] = tim_changeSpeed_avr.getLastOutput();
822  newLogRec.values["CWaypointsNavigator::navigationStep()"] = m_timlog_delays.getLastTime("CWaypointsNavigator::navigationStep()");
823  newLogRec.values["CAbstractNavigator::navigationStep()"] = m_timlog_delays.getLastTime("CAbstractNavigator::navigationStep()");
824  newLogRec.timestamps["tim_start_iteration"] = tim_start_iteration;
825  newLogRec.timestamps["curPoseAndVel"] = m_curPoseVel.timestamp;
826  newLogRec.nPTGs = nPTGs;
827 
828  // NOP mode stuff:
829  newLogRec.rel_cur_pose_wrt_last_vel_cmd_NOP = rel_cur_pose_wrt_last_vel_cmd_NOP;
830  newLogRec.rel_pose_PTG_origin_wrt_sense_NOP = rel_pose_PTG_origin_wrt_sense_NOP;
831  newLogRec.ptg_index_NOP = best_is_NOP_cmdvel ? m_lastSentVelCmd.ptg_index : -1;
834 
835  // Last entry in info-per-PTG:
836  {
837  CLogFileRecord::TInfoPerPTG &ipp = *newLogRec.infoPerPTG.rbegin();
838  if (!ipp.HLFR) ipp.HLFR = CLogFileRecord_VFF::Create();
839  }
840 
841  m_timelogger.leave("navigationStep.populate_log_info");
842 
843  // Save to log file:
844  // --------------------------------------
845  {
846  mrpt::utils::CTimeLoggerEntry tle(m_timelogger,"navigationStep.write_log_file");
847  if (m_logFile) (*m_logFile) << newLogRec;
848  }
849  // Set as last log record
850  {
852  lastLogRecord = newLogRec; // COPY
853  }
854 }
855 
858  const std::vector<double> & in_TPObstacles,
859  const mrpt::nav::ClearanceDiagram & in_clearance,
860  const std::vector<mrpt::math::TPose2D> & WS_Targets,
861  const std::vector<CAbstractPTGBasedReactive::PTGTarget> & TP_Targets,
863  CLogFileRecord & newLogRec,
864  const bool this_is_PTG_continuation,
865  const mrpt::math::TPose2D & rel_cur_pose_wrt_last_vel_cmd_NOP,
866  const unsigned int ptg_idx4weights,
867  const mrpt::system::TTimeStamp tim_start_iteration,
868  const mrpt::nav::CHolonomicLogFileRecordPtr &hlfr)
869 {
870  MRPT_START;
871 
872  const double ref_dist = cm.PTG->getRefDistance();
873 
874  // Replaced by: TP_Targets[i].*
875  //const double target_dir = (TP_Target.x!=0 || TP_Target.y!=0) ? atan2( TP_Target.y, TP_Target.x) : 0.0;
876  //const int target_k = static_cast<int>( cm.PTG->alpha2index( target_dir ) );
877  //const double target_d_norm = TP_Target.norm();
878 
879  // We need to evaluate the movement wrt to ONE target of the possibly many input ones.
880  // Policy: use the target whose TP-Space direction is closer to this candidate direction:
881  size_t selected_trg_idx = 0;
882  {
883  double best_trg_angdist = std::numeric_limits<double>::max();
884  for (size_t i = 0; i < TP_Targets.size(); i++)
885  {
886  const double angdist = std::abs(mrpt::math::angDistance(TP_Targets[i].target_alpha, cm.direction));
887  if (angdist < best_trg_angdist) {
888  best_trg_angdist = angdist;
889  selected_trg_idx = i;
890  }
891  }
892  }
893  ASSERT_(selected_trg_idx<WS_Targets.size());
894  const auto WS_Target = WS_Targets[selected_trg_idx];
895  const auto TP_Target = TP_Targets[selected_trg_idx];
896 
897  const double target_d_norm = TP_Target.target_dist;
898 
899  // Picked movement direction:
900  const int move_k = static_cast<int>( cm.PTG->alpha2index( cm.direction ) );
901  const double target_WS_d = WS_Target.norm();
902 
903  // Coordinates of the trajectory end for the given PTG and "alpha":
904  const double d = std::min( in_TPObstacles[ move_k ], 0.99*target_d_norm);
905  uint32_t nStep;
906  bool pt_in_range = cm.PTG->getPathStepForDist(move_k, d, nStep);
907  ASSERT_(pt_in_range)
908 
909  mrpt::math::TPose2D pose;
910  cm.PTG->getPathPose(move_k, nStep,pose);
911 
912  // Make sure that the target slow-down is honored, as seen in real-world Euclidean space
913  // (as opposed to TP-Space, where the holo methods are evaluated)
915  && !cm.PTG->supportSpeedAtTarget() // If the PTG is able to handle the slow-down on its own, dont change speed here
916  )
917  {
918  const double TARGET_SLOW_APPROACHING_DISTANCE = getHoloMethod(0)->getTargetApproachSlowDownDistance();
919 
920  const double Vf = m_navigationParams->target.targetDesiredRelSpeed; // [0,1]
921 
922  const double f = std::min(1.0,Vf + target_WS_d*(1.0-Vf)/TARGET_SLOW_APPROACHING_DISTANCE);
923  if (f < cm.speed) {
924  newLogRec.additional_debug_msgs["PTG_eval.speed"] = mrpt::format("Relative speed reduced %.03f->%.03f based on Euclidean nearness to target.", cm.speed,f);
925  cm.speed = f;
926  }
927  }
928 
929  // Start storing params in the candidate move structure:
930  cm.props["ptg_idx"] = ptg_idx4weights;
931  cm.props["ref_dist"] = ref_dist;
932  cm.props["target_dir"] = TP_Target.target_alpha;
933  cm.props["target_k"] = TP_Target.target_k;
934  cm.props["target_d_norm"] = target_d_norm;
935  cm.props["move_k"] = move_k;
936  double & move_cur_d = cm.props["move_cur_d"] = 0; // current robot path normalized distance over path (0 unless in a NOP cmd)
937  cm.props["is_PTG_cont"] = this_is_PTG_continuation ? 1 : 0;
938  cm.props["num_paths"] = in_TPObstacles.size();
939  cm.props["WS_target_x"] = WS_Target.x;
940  cm.props["WS_target_y"] = WS_Target.y;
941  cm.props["robpose_x"] = pose.x;
942  cm.props["robpose_y"] = pose.y;
943  cm.props["robpose_phi"] = pose.phi;
944  cm.props["ptg_priority"] = cm.PTG->getScorePriority() * cm.PTG->evalPathRelativePriority(TP_Target.target_k, target_d_norm);
945  const bool is_slowdown =
946  this_is_PTG_continuation ?
948  :
949  (cm.PTG->supportSpeedAtTarget() && TP_Target.target_k == move_k);
950  cm.props["is_slowdown"] = is_slowdown ? 1:0;
951  cm.props["holo_stage_eval"] =
952  this_is_PTG_continuation ?
954  :
955  (hlfr && !hlfr->dirs_eval.empty() && hlfr->dirs_eval.rbegin()->size() == in_TPObstacles.size()) ? hlfr->dirs_eval.rbegin()->at(move_k) : .0
956  ;
957 
958  // Factor 1: Free distance for the chosen PTG and "alpha" in the TP-Space:
959  // ----------------------------------------------------------------------
960  double & colfree = cm.props["collision_free_distance"];
961 
962  // distance to collision:
963  colfree = in_TPObstacles[move_k]; // we'll next substract here the already-traveled distance, for NOP motion candidates.
964 
965  // Special case for NOP motion cmd:
966  // consider only the empty space *after* the current robot pose, which is not at the origin.
967 
968  if (this_is_PTG_continuation)
969  {
970  int cur_k=0;
971  double cur_norm_d=.0;
972  bool is_exact, is_time_based = false;
973  uint32_t cur_ptg_step = 0;
974 
975  // Use: time-based prediction for shorter distances, PTG inverse mapping-based for longer ranges:
977  if (std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.x) > maxD || std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.y) > maxD) {
978  is_exact = cm.PTG->inverseMap_WS2TP(rel_cur_pose_wrt_last_vel_cmd_NOP.x, rel_cur_pose_wrt_last_vel_cmd_NOP.y, cur_k, cur_norm_d);
979  }
980  else {
981  // Use time:
982  is_time_based = true;
983  is_exact = true; // well, sort of...
984  const double NOP_At = m_lastSentVelCmd.speed_scale * mrpt::system::timeDifference(m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
985  newLogRec.additional_debug_msgs["PTG_eval.NOP_At"] = mrpt::format("%.06f s",NOP_At);
986  cur_k = move_k;
987  cur_ptg_step = mrpt::utils::round(NOP_At / cm.PTG->getPathStepDuration());
988  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step) / cm.PTG->getRefDistance();
989  {
990  const double cur_a = cm.PTG->index2alpha(cur_k);
991  log.TP_Robot.x = cos(cur_a)*cur_norm_d;
992  log.TP_Robot.y = sin(cur_a)*cur_norm_d;
993  cm.starting_robot_dir = cur_a;
994  cm.starting_robot_dist = cur_norm_d;
995  }
996  }
997 
998  if (!is_exact)
999  {
1000  // Don't trust this step: we are not 100% sure of the robot pose in TP-Space for this "PTG continuation" step:
1001  cm.speed = -0.01; // this enforces a 0 global evaluation score
1002  newLogRec.additional_debug_msgs["PTG_eval"] = "PTG-continuation not allowed, cur. pose out of PTG domain.";
1003  return;
1004  }
1005  bool WS_point_is_unique = true;
1006  if (!is_time_based)
1007  {
1008  bool ok1 = cm.PTG->getPathStepForDist(m_lastSentVelCmd.ptg_alpha_index, cur_norm_d * cm.PTG->getRefDistance(), cur_ptg_step);
1009  if (ok1) {
1010  // Check bijective:
1011  WS_point_is_unique = cm.PTG->isBijectiveAt(cur_k, cur_ptg_step);
1013  WS_point_is_unique = WS_point_is_unique && cm.PTG->isBijectiveAt(move_k, predicted_step);
1014  newLogRec.additional_debug_msgs["PTG_eval.bijective"] = mrpt::format("isBijectiveAt(): k=%i step=%i -> %s", (int)cur_k, (int)cur_ptg_step, WS_point_is_unique ? "yes" : "no");
1015 
1016  if (!WS_point_is_unique)
1017  {
1018  // Don't trust direction:
1019  cur_k = move_k;
1020  cur_ptg_step = predicted_step;
1021  cur_norm_d = cm.PTG->getPathDist(cur_k, cur_ptg_step);
1022  }
1023  {
1024  const double cur_a = cm.PTG->index2alpha(cur_k);
1025  log.TP_Robot.x = cos(cur_a)*cur_norm_d;
1026  log.TP_Robot.y = sin(cur_a)*cur_norm_d;
1027  cm.starting_robot_dir = cur_a;
1028  cm.starting_robot_dist = cur_norm_d;
1029  }
1030 
1031  mrpt::math::TPose2D predicted_rel_pose;
1032  cm.PTG->getPathPose(m_lastSentVelCmd.ptg_alpha_index, cur_ptg_step, predicted_rel_pose);
1033  const auto predicted_pose_global = m_lastSentVelCmd.poseVel.rawOdometry + predicted_rel_pose;
1034  const double predicted2real_dist = mrpt::math::hypot_fast(predicted_pose_global.x - m_curPoseVel.rawOdometry.x, predicted_pose_global.y - m_curPoseVel.rawOdometry.y);
1035  newLogRec.additional_debug_msgs["PTG_eval.lastCmdPose(raw)"] = m_lastSentVelCmd.poseVel.pose.asString();
1036  newLogRec.additional_debug_msgs["PTG_eval.PTGcont"] = mrpt::format("mismatchDistance=%.03f cm", 1e2*predicted2real_dist);
1037 
1039  (!is_slowdown || (target_d_norm - cur_norm_d)*ref_dist>2.0 /*meters*/)
1040  )
1041  {
1042  cm.speed = -0.01; // this enforces a 0 global evaluation score
1043  newLogRec.additional_debug_msgs["PTG_eval"] = "PTG-continuation not allowed, mismatchDistance above threshold.";
1044  return;
1045  }
1046  }
1047  else {
1048  cm.speed = -0.01; // this enforces a 0 global evaluation score
1049  newLogRec.additional_debug_msgs["PTG_eval"] = "PTG-continuation not allowed, couldn't get PTG step for cur. robot pose.";
1050  return;
1051  }
1052  }
1053 
1054  // Path following isn't perfect: we can't be 100% sure of whether the robot followed exactly
1055  // the intended path (`kDirection`), or if it's actually a bit shifted, as reported in `cur_k`.
1056  // Take the least favorable case.
1057  // [Update] Do this only when the PTG gave us a unique-mapped WS<->TPS point:
1058 
1059  colfree = WS_point_is_unique ?
1060  std::min(in_TPObstacles[move_k], in_TPObstacles[cur_k])
1061  :
1062  in_TPObstacles[move_k];
1063 
1064  // Only discount free space if there was a real obstacle, not the "end of path" due to limited refDistance.
1065  if (colfree < 0.99) {
1066  colfree -= cur_norm_d;
1067  }
1068 
1069  // Save estimated robot pose over path as a parameter for scores:
1070  move_cur_d = cur_norm_d;
1071  }
1072 
1073  // Factor4: Decrease in euclidean distance between (x,y) and the target:
1074  // Moving away of the target is negatively valued.
1075  cm.props["dist_eucl_final"] = mrpt::math::hypot_fast(WS_Target.x- pose.x, WS_Target.y- pose.y);
1076 
1077 
1078  // dist_eucl_min: Use PTG clearance methods to evaluate the real-world (WorkSpace) minimum distance to target:
1079  {
1080  typedef std::map<double, double> map_d2d_t;
1081  map_d2d_t pathDists;
1082  const double D = cm.PTG->getRefDistance();
1083  const int num_steps = ceil( D * 2.0);
1084  for (int i = 0; i < num_steps; i++) {
1085  pathDists[i / double(num_steps)] = 100.0; // default normalized distance to target (a huge value)
1086  }
1087 
1088  cm.PTG->evalClearanceSingleObstacle(WS_Target.x, WS_Target.y, move_k, pathDists, false /*treat point as target, not obstacle*/ );
1089 
1090  const auto it = std::min_element(
1091  pathDists.begin(), pathDists.end(),
1092  [colfree](map_d2d_t::value_type& l, map_d2d_t::value_type& r) -> bool {
1093  return (l.second < r.second) && l.first<colfree;
1094  }
1095  );
1096  cm.props["dist_eucl_min"] = (it!= pathDists.end()) ? it->second * cm.PTG->getRefDistance() : 100.0;
1097  }
1098 
1099  // Factor5: Hysteresis:
1100  // -----------------------------------------------------
1101  double &hysteresis = cm.props["hysteresis"];
1102  hysteresis = .0;
1103 
1104  if (cm.PTG->supportVelCmdNOP())
1105  {
1106  hysteresis = this_is_PTG_continuation ? 1.0 : 0.;
1107  }
1108  else if (m_last_vel_cmd)
1109  {
1110  mrpt::kinematics::CVehicleVelCmdPtr desired_cmd;
1111  desired_cmd = cm.PTG->directionToMotionCommand(move_k);
1112  const mrpt::kinematics::CVehicleVelCmd *ptr1 = m_last_vel_cmd.pointer();
1113  const mrpt::kinematics::CVehicleVelCmd *ptr2 = desired_cmd.pointer();
1114  if(typeid(*ptr1) == typeid(*ptr2)){
1115  ASSERT_EQUAL_(m_last_vel_cmd->getVelCmdLength(), desired_cmd->getVelCmdLength());
1116 
1117  double simil_score = 0.5;
1118  for (size_t i = 0; i < desired_cmd->getVelCmdLength(); i++)
1119  {
1120  const double scr = exp(-std::abs(desired_cmd->getVelCmdElement(i) - m_last_vel_cmd->getVelCmdElement(i)) / 0.20);
1121  mrpt::utils::keep_min(simil_score, scr);
1122  }
1123  hysteresis = simil_score;
1124  }
1125  }
1126 
1127  // Factor6: clearance
1128  // -----------------------------------------------------
1129  // clearance indicators that may be useful in deciding the best motion:
1130  double &clearance = cm.props["clearance"];
1131  clearance = in_clearance.getClearance(move_k, target_d_norm*1.01, false /* spot, dont interpolate */ );
1132  cm.props["clearance_50p"] = in_clearance.getClearance(move_k, target_d_norm*0.5, false /* spot, dont interpolate */);
1133  cm.props["clearance_path"] = in_clearance.getClearance(move_k, target_d_norm*0.9, true /* average */);
1134  cm.props["clearance_path_50p"] = in_clearance.getClearance(move_k, target_d_norm*0.5, true /* average */);
1135 
1136  // Factor: ETA (Estimated Time of Arrival to target or to closest obstacle, whatever it's first)
1137  // -----------------------------------------------------
1138  double &eta = cm.props["eta"];
1139  eta = .0;
1140  if (cm.PTG && cm.speed>.0) // for valid cases only
1141  {
1142  // OK, we have a direct path to target without collisions.
1143  const double path_len_meters = d * ref_dist;
1144 
1145  // Calculate their ETA
1146  uint32_t target_step;
1147  bool valid_step = cm.PTG->getPathStepForDist(move_k, path_len_meters, target_step);
1148  if (valid_step)
1149  {
1150  eta = cm.PTG->getPathStepDuration() * target_step /* PTG original time to get to target point */
1151  * cm.speed /* times the speed scale factor*/;
1152 
1153  double discount_time = .0;
1154  if (this_is_PTG_continuation)
1155  {
1156  // Heuristic: discount the time already executed.
1157  // Note that hm.speed above scales the overall path time using the current speed scale, not the exact
1158  // integration over the past timesteps. It's an approximation, probably good enough...
1159  discount_time = mrpt::system::timeDifference(m_lastSentVelCmd.tim_send_cmd_vel, tim_start_iteration);
1160  }
1161  eta -= discount_time; // This could even become negative if the approximation is poor...
1162  }
1163  }
1164 
1165  MRPT_END;
1166 }
1167 
1168 double CAbstractPTGBasedReactive::generate_vel_cmd( const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmdPtr &new_vel_cmd )
1169 {
1170  mrpt::utils::CTimeLoggerEntry tle(m_timelogger, "generate_vel_cmd");
1171  double cmdvel_speed_scale = 1.0;
1172  try
1173  {
1174  if (in_movement.speed == 0)
1175  {
1176  // The robot will stop:
1177  new_vel_cmd = in_movement.PTG->getSupportedKinematicVelocityCommand();
1178  new_vel_cmd->setToStop();
1179  }
1180  else
1181  {
1182  // Take the normalized movement command:
1183  new_vel_cmd = in_movement.PTG->directionToMotionCommand( in_movement.PTG->alpha2index( in_movement.direction ) );
1184 
1185  // Scale holonomic speeds to real-world one:
1186  new_vel_cmd->cmdVel_scale(in_movement.speed);
1187  cmdvel_speed_scale *= in_movement.speed;
1188 
1189  if (!m_last_vel_cmd) // first iteration? Use default values:
1191 
1192  // Honor user speed limits & "blending":
1194  cmdvel_speed_scale *= new_vel_cmd->cmdVel_limits(*m_last_vel_cmd, beta, params_abstract_ptg_navigator.robot_absolute_speed_limits);
1195  }
1196 
1197  m_last_vel_cmd = new_vel_cmd; // Save for filtering in next step
1198  }
1199  catch (std::exception &e)
1200  {
1201  MRPT_LOG_ERROR_STREAM( "[CAbstractPTGBasedReactive::generate_vel_cmd] Exception: " << e.what());
1202  }
1203  return cmdvel_speed_scale;
1204 }
1205 
1207 {
1208  MRPT_START;
1209 
1210  const size_t N = this->getPTG_count();
1211  if (m_infoPerPTG.size()<N ||
1214  )
1215  return false; // We didn't run yet or obstacle info is old
1216 
1217  for (size_t i=0;i<N;i++)
1218  {
1219  const CParameterizedTrajectoryGenerator* ptg = getPTG(i);
1220 
1221  const std::vector<double> & tp_obs = m_infoPerPTG[i].TP_Obstacles; // normalized distances
1222  if (tp_obs.size() != ptg->getPathCount() )
1223  continue; // May be this PTG has not been used so far? (Target out of domain,...)
1224 
1225  int wp_k;
1226  double wp_norm_d;
1227  bool is_into_domain = ptg->inverseMap_WS2TP(wp.x,wp.y, wp_k, wp_norm_d);
1228  if (!is_into_domain)
1229  continue;
1230 
1231  ASSERT_(wp_k<int(tp_obs.size()));
1232 
1233  const double collision_free_dist = tp_obs[wp_k];
1234  if (collision_free_dist>1.01*wp_norm_d)
1235  return true; // free path found to target
1236  }
1237 
1238  return false; // no way found
1239  MRPT_END;
1240 }
1241 
1243 {
1245 }
1246 
1248 {
1251 
1252  CWaypointsNavigator::onStartNewNavigation(); // Call base method we override
1253 }
1254 
1256 {
1257  reset();
1258 }
1260 {
1261  ptg_index = -1;
1262  ptg_alpha_index = -1;
1263  tim_send_cmd_vel = INVALID_TIMESTAMP;
1264  poseVel = TRobotPoseVel();
1265  colfreedist_move_k = .0;
1266  was_slowdown = false;
1267  speed_scale = 1.0;
1269  original_holo_eval = .0;
1270 }
1272 {
1273  return this->poseVel.timestamp != INVALID_TIMESTAMP;
1274 }
1275 
1276 
1279  const size_t indexPTG,
1280  const std::vector<mrpt::math::TPose2D> &relTargets,
1281  const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense,
1282  TInfoPerPTG &ipf,
1284  CLogFileRecord &newLogRec,
1285  const bool this_is_PTG_continuation,
1287  const mrpt::system::TTimeStamp tim_start_iteration,
1288  const TNavigationParams &navp,
1289  const mrpt::math::TPose2D &rel_cur_pose_wrt_last_vel_cmd_NOP
1290  )
1291 {
1292  ASSERT_(ptg);
1293 
1294  const size_t idx_in_log_infoPerPTGs = this_is_PTG_continuation ? getPTG_count() : indexPTG;
1295 
1296  CHolonomicLogFileRecordPtr HLFR;
1297  cm.PTG = ptg;
1298 
1299  // If the user doesn't want to use this PTG, just mark it as invalid:
1300  ipf.targets.clear();
1301  bool use_this_ptg = true;
1302  {
1303  const TNavigationParamsPTG * navpPTG = dynamic_cast<const TNavigationParamsPTG*>(&navp);
1304  if (navpPTG && !navpPTG->restrict_PTG_indices.empty())
1305  {
1306  use_this_ptg = false;
1307  for (size_t i = 0; i < navpPTG->restrict_PTG_indices.size() && !use_this_ptg; i++) {
1308  if (navpPTG->restrict_PTG_indices[i] == indexPTG)
1309  use_this_ptg = true;
1310  }
1311  }
1312  }
1313 
1314  double timeForTPObsTransformation = .0, timeForHolonomicMethod = .0;
1315 
1316  // Normal PTG validity filter: check if target falls into the PTG domain:
1317  bool any_TPTarget_is_valid = false;
1318  if (use_this_ptg)
1319  {
1320  for (size_t i=0;i<relTargets.size();i++)
1321  {
1322  const auto & trg = relTargets[i];
1323  PTGTarget ptg_target;
1324 
1325  ptg_target.valid_TP = ptg->inverseMap_WS2TP(trg.x, trg.y, ptg_target.target_k, ptg_target.target_dist);
1326  if (!ptg_target.valid_TP) continue;
1327 
1328  any_TPTarget_is_valid = true;
1329  ptg_target.target_alpha = ptg->index2alpha(ptg_target.target_k);
1330  ptg_target.TP_Target.x = cos(ptg_target.target_alpha) * ptg_target.target_dist;
1331  ptg_target.TP_Target.y = sin(ptg_target.target_alpha) * ptg_target.target_dist;
1332 
1333  ipf.targets.emplace_back(ptg_target);
1334  }
1335  }
1336 
1337  if (!any_TPTarget_is_valid)
1338  {
1339  newLogRec.additional_debug_msgs[mrpt::format("mov_candidate_%u", static_cast<unsigned int>(indexPTG))] = "PTG discarded since target(s) is(are) out of domain.";
1340 
1341  { // Invalid PTG (target out of reachable space):
1342  // - holonomicMovement= Leave default values
1343  HLFR = CLogFileRecord_VFF::Create();
1344  }
1345  }
1346  else
1347  {
1348  // STEP3(b): Build TP-Obstacles
1349  // -----------------------------------------------------------------------------
1350  {
1351  tictac.Tic();
1352 
1353  // Initialize TP-Obstacles:
1354  const size_t Ki = ptg->getAlphaValuesCount();
1355  ptg->initTPObstacles(ipf.TP_Obstacles);
1357  ptg->initClearanceDiagram(ipf.clearance);
1358  }
1359 
1360  // Implementation-dependent conversion:
1361  STEP3_WSpaceToTPSpace(indexPTG, ipf.TP_Obstacles, ipf.clearance, mrpt::math::TPose2D(0,0,0)-rel_pose_PTG_origin_wrt_sense, params_abstract_ptg_navigator.evaluate_clearance);
1362 
1365  }
1366 
1367  // Distances in TP-Space are normalized to [0,1]:
1368  const double _refD = 1.0 / ptg->getRefDistance();
1369  for (size_t i = 0; i < Ki; i++) ipf.TP_Obstacles[i] *= _refD;
1370 
1371  timeForTPObsTransformation = tictac.Tac();
1372  if (m_timelogger.isEnabled())
1373  m_timelogger.registerUserMeasure("navigationStep.STEP3_WSpaceToTPSpace", timeForTPObsTransformation);
1374  }
1375 
1376  // STEP4: Holonomic navigation method
1377  // -----------------------------------------------------------------------------
1378  if (!this_is_PTG_continuation)
1379  {
1380  tictac.Tic();
1381 
1382  ASSERT_(holoMethod);
1383  // Slow down if we are approaching the final target, etc.
1385 
1386  // Prepare holonomic algorithm call:
1388  ni.clearance = &ipf.clearance;
1389  ni.maxObstacleDist = 1.0;
1390  ni.maxRobotSpeed = 1.0; // So, we use a normalized max speed here.
1391  ni.obstacles = ipf.TP_Obstacles; // Normalized [0,1]
1392 
1393  ni.targets.clear(); // Normalized [0,1]
1394  for (const auto &t : ipf.targets) {
1395  ni.targets.push_back( t.TP_Target );
1396  }
1397 
1399 
1400  holoMethod->navigate(ni, no);
1401 
1402  // Extract resuls:
1403  cm.direction = no.desiredDirection;
1404  cm.speed = no.desiredSpeed;
1405  HLFR = no.logRecord;
1406 
1407  // Security: Scale down the velocity when heading towards obstacles,
1408  // such that it's assured that we never go thru an obstacle!
1409  const int kDirection = static_cast<int>(cm.PTG->alpha2index(cm.direction));
1410  double obsFreeNormalizedDistance = ipf.TP_Obstacles[kDirection];
1411 
1412  // Take into account the future robot pose after NOP motion iterations to slow down accordingly *now*
1413  if (ptg->supportVelCmdNOP()) {
1415  const double d = v * ptg->maxTimeInVelCmdNOP(kDirection);
1416  obsFreeNormalizedDistance = std::min(obsFreeNormalizedDistance, std::max(0.90, obsFreeNormalizedDistance - d) );
1417  }
1418 
1419  double velScale = 1.0;
1421  if (obsFreeNormalizedDistance < params_abstract_ptg_navigator.secure_distance_end)
1422  {
1423  if (obsFreeNormalizedDistance <= params_abstract_ptg_navigator.secure_distance_start)
1424  velScale = 0.0; // security stop
1426  }
1427 
1428  // Scale:
1429  cm.speed *= velScale;
1430 
1431  timeForHolonomicMethod = tictac.Tac();
1432  if (m_timelogger.isEnabled())
1433  m_timelogger.registerUserMeasure("navigationStep.STEP4_HolonomicMethod", timeForHolonomicMethod);
1434  }
1435  else
1436  {
1437  // "NOP cmdvel" case: don't need to re-run holo algorithm, just keep the last selection:
1439  cm.speed = 1.0; // Not used.
1440  }
1441 
1442  // STEP5: Evaluate each movement to assign them a "evaluation" value.
1443  // ---------------------------------------------------------------------
1444  {
1445  CTimeLoggerEntry tle(m_timelogger, "navigationStep.calc_move_candidate_scores");
1446 
1448  cm,
1449  ipf.TP_Obstacles,
1450  ipf.clearance,
1451  relTargets,
1452  ipf.targets,
1453  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs], newLogRec,
1454  this_is_PTG_continuation, rel_cur_pose_wrt_last_vel_cmd_NOP,
1455  indexPTG,
1456  tim_start_iteration,
1457  HLFR);
1458 
1459  // Store NOP related extra vars:
1460  cm.props["original_col_free_dist"] =
1461  this_is_PTG_continuation ?
1463  :
1464  .0;
1465 
1466  // SAVE LOG
1467  newLogRec.infoPerPTG[idx_in_log_infoPerPTGs].evalFactors = cm.props;
1468  }
1469 
1470  } // end "valid_TP"
1471 
1472  // Logging:
1473  const bool fill_log_record = (m_logFile != NULL || m_enableKeepLogRecords);
1474  if (fill_log_record)
1475  {
1476  CLogFileRecord::TInfoPerPTG &ipp = newLogRec.infoPerPTG[idx_in_log_infoPerPTGs];
1477  if (!this_is_PTG_continuation)
1478  ipp.PTG_desc = ptg->getDescription();
1479  else ipp.PTG_desc = mrpt::format("NOP cmdvel (prev PTG idx=%u)", static_cast<unsigned int>(m_lastSentVelCmd.ptg_index) );
1480 
1482  ipp.clearance = ipf.clearance;
1483  ipp.TP_Targets.clear();
1484  for (const auto &t : ipf.targets) {
1485  ipp.TP_Targets.push_back(t.TP_Target);
1486  }
1487  ipp.HLFR = HLFR;
1488  ipp.desiredDirection = cm.direction;
1489  ipp.desiredSpeed = cm.speed;
1490  ipp.timeForTPObsTransformation = timeForTPObsTransformation;
1491  ipp.timeForHolonomicMethod = timeForHolonomicMethod;
1492  }
1493 }
1494 
1496 {
1497  MRPT_START;
1498 
1499  robot_absolute_speed_limits.loadConfigFile(c, s);
1500 
1501  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(holonomic_method, string);
1502  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(motion_decider_method, string);
1503  MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(ref_distance, double);
1504  MRPT_LOAD_CONFIG_VAR_CS(speedfilter_tau, double);
1505  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_start, double);
1506  MRPT_LOAD_CONFIG_VAR_CS(secure_distance_end, double);
1507  MRPT_LOAD_CONFIG_VAR_CS(use_delays_model, bool);
1508  MRPT_LOAD_CONFIG_VAR_CS(max_distance_predicted_actual_path, double);
1509  MRPT_LOAD_CONFIG_VAR_CS(min_normalized_free_space_for_ptg_continuation, double);
1510  MRPT_LOAD_CONFIG_VAR_CS(enable_obstacle_filtering, bool);
1511  MRPT_LOAD_CONFIG_VAR_CS(evaluate_clearance, bool);
1512  MRPT_LOAD_CONFIG_VAR_CS(max_dist_for_timebased_path_prediction, double);
1513 
1514  MRPT_END;
1515 }
1516 
1518 {
1519  robot_absolute_speed_limits.saveToConfigFile(c, s);
1520 
1521  // Build list of known holo methods:
1522  string lstHoloStr = "# List of known classes:\n";
1523  {
1525  for (const auto &c : lst)
1526  lstHoloStr += string("# - `") + string(c->className) + string("`\n");
1527  }
1528  MRPT_SAVE_CONFIG_VAR_COMMENT(holonomic_method, string("C++ class name of the holonomic navigation method to run in the transformed TP-Space.\n")+ lstHoloStr);
1529 
1530  // Build list of known decider methods:
1531  string lstDecidersStr = "# List of known classes:\n";
1532  {
1534  for (const auto &c : lst)
1535  lstDecidersStr += string("# - `") + string(c->className) + string("`\n");
1536  }
1537  MRPT_SAVE_CONFIG_VAR_COMMENT(motion_decider_method, string("C++ class name of the motion decider method.\n") + lstDecidersStr);
1538 
1539  MRPT_SAVE_CONFIG_VAR_COMMENT(ref_distance, "Maximum distance up to obstacles will be considered (D_{max} in papers).");
1540  MRPT_SAVE_CONFIG_VAR_COMMENT(speedfilter_tau, "Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0: no filtering)");
1541  MRPT_SAVE_CONFIG_VAR_COMMENT(secure_distance_start, "In normalized distance [0,1], start/end of a ramp function that scales the holonomic navigator output velocity.");
1542  MRPT_SAVE_CONFIG_VAR_COMMENT(secure_distance_end, "In normalized distance [0,1], start/end of a ramp function that scales the holonomic navigator output velocity.");
1543  MRPT_SAVE_CONFIG_VAR_COMMENT(use_delays_model, "Whether to use robot pose inter/extrapolation to improve accuracy (Default:false)");
1544  MRPT_SAVE_CONFIG_VAR_COMMENT(max_distance_predicted_actual_path, "Max distance [meters] to discard current PTG and issue a new vel cmd (default= 0.05)");
1545  MRPT_SAVE_CONFIG_VAR_COMMENT(min_normalized_free_space_for_ptg_continuation, "Min normalized dist [0,1] after current pose in a PTG continuation to allow it.");
1546  MRPT_SAVE_CONFIG_VAR_COMMENT(enable_obstacle_filtering, "Enabled obstacle filtering (params in its own section)");
1547  MRPT_SAVE_CONFIG_VAR_COMMENT(evaluate_clearance, "Enable exact computation of clearance (default=false)");
1548  MRPT_SAVE_CONFIG_VAR_COMMENT(max_dist_for_timebased_path_prediction, "Max dist [meters] to use time-based path prediction for NOP evaluation");
1549 }
1550 
1552  holonomic_method(),
1553  ptg_cache_files_directory("."),
1554  ref_distance(4.0),
1555  speedfilter_tau(0.0),
1556  secure_distance_start(0.05),
1557  secure_distance_end(0.20),
1558  use_delays_model(false),
1559  max_distance_predicted_actual_path(0.15),
1560  min_normalized_free_space_for_ptg_continuation(0.2),
1561  robot_absolute_speed_limits(),
1562  enable_obstacle_filtering(true),
1563  evaluate_clearance(false),
1564  max_dist_for_timebased_path_prediction(2.0)
1565 {
1566 }
1567 
1569 {
1570  MRPT_START;
1572 
1573  // At this point, we have been called from the derived class, who must be already
1574  // loaded all its specific params, including PTGs.
1575 
1576  // Load my params:
1577  params_abstract_ptg_navigator.loadFromConfigFile(c, "CAbstractPTGBasedReactive");
1578 
1579  // Filtering:
1581  {
1584  filter->options.loadFromConfigFile(c,"CPointCloudFilterByDistance");
1585  }
1586  else
1587  {
1588  m_WS_filter.reset();
1589  }
1590 
1591  // Movement chooser:
1593  if (!m_multiobjopt)
1594  THROW_EXCEPTION_FMT("Non-registered CMultiObjectiveMotionOptimizerBase className=`%s`", params_abstract_ptg_navigator.motion_decider_method.c_str());
1595 
1596  m_multiobjopt->loadConfigFile(c);
1597 
1598 
1599  // Holo method:
1601  ASSERT_(!m_holonomicMethod.empty())
1602 
1603  CWaypointsNavigator::loadConfigFile(c); // Load parent params
1604 
1605  m_init_done = true; // If we reached this point without an exception, all is good.
1606  MRPT_END;
1607 }
1608 
1610 {
1612  params_abstract_ptg_navigator.saveToConfigFile(c, "CAbstractPTGBasedReactive");
1613 
1614  // Filtering:
1615  {
1617  filter.options.saveToConfigFile(c, "CPointCloudFilterByDistance");
1618  }
1619 
1620  // Holo method:
1621  if (!m_holonomicMethod.empty() && m_holonomicMethod[0])
1622  {
1623  // Save my current settings:
1624  m_holonomicMethod[0]->saveConfigFile(c);
1625  }
1626  else
1627  {
1628  // save options of ALL known methods:
1630  for (const auto &cl : lst) {
1631  mrpt::utils::CObjectPtr obj = mrpt::utils::CObjectPtr(cl->createObject());
1632  CAbstractHolonomicReactiveMethod * holo = dynamic_cast<CAbstractHolonomicReactiveMethod *>(obj.pointer());
1633  if (holo) {
1634  holo->saveConfigFile(c);
1635  }
1636  }
1637  }
1638 
1639  // Decider method:
1640  if (m_multiobjopt)
1641  {
1642  // Save my current settings:
1643  m_multiobjopt->saveConfigFile(c);
1644  }
1645  else
1646  {
1647  // save options of ALL known methods:
1649  for (const auto &cl : lst) {
1650  mrpt::utils::CObjectPtr obj = mrpt::utils::CObjectPtr(cl->createObject());
1652  if (momo) {
1653  momo->saveConfigFile(c);
1654  }
1655  }
1656  }
1657 }
1658 
1660 {
1661  for (auto &o : m_holonomicMethod) {
1662  o->setTargetApproachSlowDownDistance(dist);
1663  }
1664 }
1665 
1667 {
1668  ASSERT_(!m_holonomicMethod.empty());
1669  return m_holonomicMethod[0]->getTargetApproachSlowDownDistance();
1670 }
1671 
1673 {
1674  return m_holonomicMethod[idx];
1675 }
mrpt::synch::CCriticalSectionRecursive m_critZoneLastLog
Critical zones.
#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:30
virtual bool supportSpeedAtTarget() const
Returns true if this PTG takes into account the desired velocity at target.
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) MRPT_OVERRIDE
Loads all params from a file.
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).
virtual double generate_vel_cmd(const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmdPtr &new_vel_cmd)
Return the [0,1] velocity scale of raw PTG cmd_vel.
A class acquiring a CCriticalSection at its constructor, and releasing it at destructor.
double targetRelSpeed
Desired relative speed [0,1] at target. Default=0.
CSerializablePtr ReadObject()
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the obje...
Definition: CStream.cpp:486
bool BASE_IMPEXP createDirectory(const std::string &dirName)
Creates a directory.
Definition: filesystem.cpp:154
double y
X,Y coordinates.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Definition: zip.h:16
GLdouble GLdouble t
Definition: glext.h:3610
void enter() const MRPT_OVERRIDE
Enter.
mrpt::utils::CStream * m_prev_logfile
The current log file stream, or NULL if not being used.
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 ...
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())
std::vector< mrpt::math::TPose2D > WS_targets_relative
Relative poses (wrt to robotPoseLocalization) for extrapolated paths at two instants: time of obstacl...
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...
virtual void performNavigationStep() MRPT_OVERRIDE
The main method for the navigator.
void setTargetApproachSlowDownDistance(const double dist)
Changes this parameter in all inner holonomic navigator instances [m].
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::CHolonomicLogFileRecordPtr &hlfr)
Scores holonomicMovement.
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:25
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
virtual bool impl_waypoint_is_reachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const MRPT_OVERRIDE
Implements the way to waypoint is free function in children classes: true must be returned if...
mrpt::nav::ClearanceDiagram clearance
Clearance for each path.
#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. nullptr if not applicable / undefined.
TNavigationParams * m_navigationParams
Current navigation parameters.
#define THROW_EXCEPTION(msg)
mrpt::math::TPose2D robotPoseOdometry
The robot pose (from odometry and from the localization/SLAM system).
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,...)
#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 BASE_IMPEXP fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:124
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:91
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:70
std::vector< mrpt::math::TPoint2D > TP_Targets
Target(s) location in TP-Space.
#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.
functor_event_void_t event_noargs
event w/o arguments
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.
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,...)
GLdouble s
Definition: glext.h:3602
void Tic()
Starts the stopwatch.
Definition: CTicTac.cpp:77
GLsizei GLsizei GLuint * obj
Definition: glext.h:3902
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...
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(). Can be overriden.
std::vector< mrpt::math::TPoint2D > targets
Relative location (x,y) of target point(s). In the same units than obstacles. If many, last targets have higher priority.
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
CHolonomicLogFileRecordPtr HLFR
Other useful info about holonomic method execution.
virtual bool changeSpeedsNOP()
Default: forward call to m_robot.changeSpeedsNOP(). Can be overriden.
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 base for velocity commands of different kinematic models of planar mobile robot...
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: ...
virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &c, const std::string &s) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
The struct for configuring navigation requests.
double maxRobotSpeed
Maximum robot speed, in the same units than obstacles, per second.
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState
This is the base class for any user-defined PTG.
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
virtual mrpt::kinematics::CVehicleVelCmdPtr directionToMotionCommand(uint16_t k) const =0
Converts a discretized "alpha" value into a feasible motion command or action.
std::vector< CAbstractHolonomicReactiveMethod * > m_holonomicMethod
The holonomic navigation algorithm (one object per PTG, so internal states are maintained) ...
double speed_scale
[0,1] scale of the raw cmd_vel as generated by the PTG
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
std::shared_ptr< CPointCloudFilterBase > CPointCloudFilterBasePtr
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
double targetDesiredRelSpeed
(Default=.05) Desired relative speed (wrt maximum speed), in range [0,1], of the vehicle at target...
mrpt::math::TPose2D robotPoseLocalization
static std::string holoMethodEnum2ClassName(const THolonomicMethod method)
#define MRPT_END
TNavigationParams * m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes.
double speed
TP-Space movement speed, normalized to [0,1]. A negative number means this candidate movement is unfe...
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:26
const GLubyte * c
Definition: glext.h:5590
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...
static CLogFileRecord_VFFPtr Create()
mrpt::math::LowPassFilter_IIR1 timoff_sendVelCmd_avr
double desiredDirection
The desired motion direction, in the range [-PI, PI].
std::string motion_decider_method
C++ class name of the motion chooser.
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) MRPT_OVERRIDE
Loads all params from a file.
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.
int16_t ptg_index_NOP
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
double vy
Velocity components: X,Y (m/s)
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::nav::CMultiObjectiveMotionOptimizerBasePtr m_multiobjopt
mrpt::kinematics::CVehicleVelCmdPtr cmd_vel
The final motion command sent to robot, in "m/sec" and "rad/sec".
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...
#define MRPT_LOG_DEBUG(_STRING)
static CAbstractHolonomicReactiveMethod * Create(const std::string &className) MRPT_NO_THROWS
Class factory from class name, e.g.
double direction
TP-Space movement direction. Within [-2*PI,+2*PI].
double maxObstacleDist
Maximum expected value to be found in obstacles. Typically, values in obstacles larger or equal to th...
bool isEnabled() const
Definition: CTimeLogger.h:90
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
const double ESTIM_LOWPASSFILTER_ALPHA
std::map< std::string, double > values
Known values:
GLsizei const GLchar ** string
Definition: glext.h:3919
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:17
THolonomicMethod
The implemented reactive navigation methods.
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:22
double desiredSpeed
The desired motion speed in that direction, from 0 up to NavInput::maxRobotSpeed. ...
std::list< TPendingEvent > m_pending_events
Events generated during navigationStep(), enqueued to be called at the end of the method execution to...
double y
X,Y coordinates.
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits.
#define CLASS_ID(class_name)
Access to runtime class ID for a defined class name.
Definition: CObject.h:82
ClearanceDiagram clearance
Clearance for each path.
#define MRPT_START
const mrpt::nav::ClearanceDiagram * clearance
The computed clearance for each direction (optional in some implementations). Leave to default (NULL)...
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:3603
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void delete_safe(T *&ptr)
Calls "delete" to free an object only if the pointer is not NULL, then set the pointer to NULL...
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::maps::CPointCloudFilterBasePtr m_WS_filter
Default: none.
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:3618
A safe way to call enter() and leave() of a mrpt::utils::CTimeLogger upon construction and destructio...
Definition: CTimeLogger.h:127
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState
static CMultiObjectiveMotionOptimizerBase * Create(const std::string &className) MRPT_NO_THROWS
Class factory from C++ class name.
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:36
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.
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
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...
Lightweight 2D pose.
double Tac()
Stops the stopwatch.
Definition: CTicTac.cpp:92
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
#define ASSERT_(f)
virtual mrpt::kinematics::CVehicleVelCmdPtr getSupportedKinematicVelocityCommand() const =0
Returns an empty kinematic velocity command object of the type supported by this PTG.
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:102
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:26
bool valid_TP
For each PTG, whether target falls into the PTG domain.
uint64_t Seek(int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) MRPT_OVERRIDE
Introduces a pure virtual method for moving to a specified position in the streamed resource...
void initialize() MRPT_OVERRIDE
Must be called for loading collision grids, or the first navigation command may last a long time to b...
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...
int BASE_IMPEXP sprintf(char *buf, size_t bufSize, const char *format,...) MRPT_NO_THROWS 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:191
double max_distance_predicted_actual_path
Max distance [meters] to discard current PTG and issue a new vel cmd (default= 0.05) ...
void STEP8_GenerateLogRecord(CLogFileRecord &newLogRec, const std::vector< mrpt::math::TPose2D > &relTargets, int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmdPtr &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)
mrpt::system::TTimeStamp BASE_IMPEXP 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:197
virtual TNavigationParams * clone() const
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()
mrpt::kinematics::CVehicleVelCmdPtr m_last_vel_cmd
Last velocity commands.
virtual void onStartNewNavigation() MRPT_OVERRIDE
Called whenever a new navigation has been started.
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: "[x y yaw]", yaw in degrees) ...
bool BASE_IMPEXP 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:132
double BASE_IMPEXP 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:205
struct BASE_IMPEXP CObjectPtr
A smart pointer to a CObject object.
Definition: CObject.h:31
mrpt::synch::CCriticalSectionRecursive m_nav_cs
mutex for all navigation methods
mrpt::poses::CPose2DInterpolator m_latestOdomPoses
Latest robot poses (updated in CAbstractNavigator::navigationStep() )
GLuint GLenum GLenum transform
Definition: glext.h:6092
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const MRPT_OVERRIDE
Saves all current options to a config file.
double starting_robot_dist
Default to 0, they can be used to reflect a robot starting at a position not at (0,0). Used in "PTG continuation".
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const MRPT_OVERRIDE
Saves all current options to a config file.
virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &c, const std::string &s) const MRPT_OVERRIDE
This method saves the options to a ".ini"-like file or memory-stored string list. ...
unsigned __int32 uint32_t
Definition: rptypes.h:49
void enter(const char *func_name)
Start of a named section.
Definition: CTimeLogger.h:97
Lightweight 2D point.
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
virtual mrpt::kinematics::CVehicleVelCmdPtr getEmergencyStopCmd()=0
Gets the emergency stop command for the current robot.
Dynamic state that may affect the PTG path parameterization.
Output for CAbstractHolonomicReactiveMethod::navigate()
mrpt::math::TPose2D relPoseVelCmd
GLfloat GLfloat p
Definition: glext.h:5587
void leave() const MRPT_OVERRIDE
Leave.
virtual void onStartNewNavigation() MRPT_OVERRIDE
Called whenever a new navigation has been started.
virtual CAbstractHolonomicReactiveMethod * getHoloMethod(int idx)
mrpt::poses::CPose2DInterpolator m_latestPoses
std::vector< const TRuntimeClassId * > BASE_IMPEXP getAllRegisteredClassesChildrenOf(const TRuntimeClassId *parent_id)
Like getAllRegisteredClasses(), but filters the list to only include children clases of a given base ...
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:30
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:4617
mrpt::math::TPose2D rawOdometry
raw odometry (frame does not match to "pose", but is expected to be smoother in the short term)...
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) MRPT_OVERRIDE
Queries the current pose of target_frame wrt ("as seen from") source_frame.
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(). Can be overriden.
uint16_t alpha2index(double alpha) const
Discrete index value for the corresponding alpha value.
mrpt::math::LowPassFilter_IIR1 timoff_curPoseAndSpeed_avr
double timeForHolonomicMethod
Time, in seconds.
double getTargetApproachSlowDownDistance() const
Returns this parameter for the first inner holonomic navigator instances [m] (should be the same in a...
CHolonomicLogFileRecordPtr logRecord
The navigation method will create a log record and store it here via a smart pointer.
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.
double desiredSpeed
The results from the holonomic method.



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019