34 std::string CAbstractPTGBasedReactive::TNavigationParamsPTG::getAsText()
const 37 CWaypointsNavigator::TNavigationParamsWaypoints::getAsText();
38 s +=
"restrict_PTG_indices: ";
44 bool CAbstractPTGBasedReactive::TNavigationParamsPTG::isEqual(
50 return o !=
nullptr &&
51 CWaypointsNavigator::TNavigationParamsWaypoints::isEqual(rhs) &&
58 CAbstractPTGBasedReactive::CAbstractPTGBasedReactive(
63 m_prev_logfile(nullptr),
64 m_enableKeepLogRecords(false),
65 m_enableConsoleOutput(enableConsoleOutput),
68 m_PTGsMustBeReInitialized(true),
76 m_closing_navigator(false),
79 m_navlogfiles_dir(sLogDir)
115 std::lock_guard<std::recursive_mutex> csl(
m_nav_cs);
131 std::lock_guard<std::recursive_mutex> csl(
m_nav_cs);
142 "[CAbstractPTGBasedReactive::enableLogFile] Stopping " 156 unsigned int nFile = 0;
157 bool free_name =
false;
163 "Could not create directory for navigation logs: `%s`",
171 aux,
"%s/log_%03u.reactivenavlog",
178 std::unique_ptr<CFileGZOutputStream> fil(
180 bool ok = fil->open(aux, 1 );
193 "[CAbstractPTGBasedReactive::enableLogFile] Logging to " 198 catch (std::exception& e)
201 "[CAbstractPTGBasedReactive::enableLogFile] Exception: %s",
220 std::lock_guard<std::recursive_mutex> csl(
m_nav_cs);
227 for (
size_t i = 0; i < nPTGs; i++)
233 "Non-registered holonomic method className=`%s`",
268 for (
size_t i = 0; i < nPTGs; i++)
278 newLogRec.
infoPerPTG[i].ptg = std::dynamic_pointer_cast<
297 const bool target_changed_since_last_iteration =
300 if (target_changed_since_last_iteration)
306 std::vector<CAbstractNavigator::TargetInfo> targets;
308 auto p =
dynamic_cast< 311 if (
p && !
p->multiple_targets.empty())
313 targets =
p->multiple_targets;
320 const size_t nTargets = targets.size();
334 "Error while loading and sorting the obstacles. Robot will be " 338 CPose2D rel_cur_pose_wrt_last_vel_cmd_NOP,
339 rel_pose_PTG_origin_wrt_sense_NOP;
342 std::vector<mrpt::math::TPose2D>() ,
346 rel_cur_pose_wrt_last_vel_cmd_NOP,
347 rel_pose_PTG_origin_wrt_sense_NOP,
350 tim_start_iteration);
363 relPoseSense(0, 0, 0), relPoseVelCmd(0, 0, 0);
396 newLogRec.
values[
"timoff_obstacles"] = timoff_obstacles;
397 newLogRec.
values[
"timoff_obstacles_avr"] =
404 newLogRec.
values[
"timoff_curPoseVelAge"] = timoff_curPoseVelAge;
405 newLogRec.
values[
"timoff_curPoseVelAge_avr"] =
409 const double timoff_pose2sense =
410 timoff_obstacles - timoff_curPoseVelAge;
412 double timoff_pose2VelCmd;
415 timoff_curPoseVelAge;
416 newLogRec.
values[
"timoff_pose2sense"] = timoff_pose2sense;
417 newLogRec.
values[
"timoff_pose2VelCmd"] = timoff_pose2VelCmd;
419 if (std::abs(timoff_pose2sense) > 1.25)
421 "timoff_pose2sense=%e is too large! Path extrapolation may " 424 if (std::abs(timoff_pose2VelCmd) > 1.25)
426 "timoff_pose2VelCmd=%e is too large! Path extrapolation " 427 "may be not accurate.",
436 rel_pose_PTG_origin_wrt_sense = relPoseVelCmd - relPoseSense;
447 for (
auto&
t : targets)
454 "Different frame_id's but no frame_tf object " 455 "attached!: target_frame_id=`%s` != pose_frame_id=`%s`",
456 t.target_frame_id.c_str(),
462 robot_frame2map_frame);
465 "frame_tf: target_frame_id=`%s` as seen from " 466 "pose_frame_id=`%s` = %s",
467 t.target_frame_id.c_str(),
469 robot_frame2map_frame.
asString().c_str());
471 t.target_coords = robot_frame2map_frame +
t.target_coords;
479 std::vector<TPose2D> relTargets;
482 targets.begin(), targets.end(),
483 std::back_inserter(relTargets),
485 return e.target_coords - curPoseExtrapol;
490 const double relTargetDist = relTargets.begin()->norm();
503 for (
size_t i = 0; i < nPTGs; i++)
510 vector<TCandidateMovementPTG> candidate_movs(
514 for (
size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
529 ptg, indexPTG, relTargets, rel_pose_PTG_origin_wrt_sense, ipf,
530 cm, newLogRec,
false ,
537 bool is_all_ptg_collision =
true;
538 for (
size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
540 bool is_collision =
true;
542 for (
const auto o : obs)
546 is_collision =
false;
552 is_all_ptg_collision =
false;
556 if (is_all_ptg_collision)
567 bool NOP_not_too_old =
true;
568 bool NOP_not_too_close_and_have_to_slowdown =
true;
569 double NOP_max_time = -1.0, NOP_At = -1.0;
570 double slowdowndist = .0;
582 const bool can_do_nop_motion =
584 !target_changed_since_last_iteration && last_sent_ptg &&
593 (NOP_not_too_close_and_have_to_slowdown =
597 ->getTargetApproachSlowDownDistance())
602 if (!NOP_not_too_old)
605 "PTG-continuation not allowed: previous command timed-out " 606 "(At=%.03f > Max_At=%.03f)",
607 NOP_At, NOP_max_time);
609 if (!NOP_not_too_close_and_have_to_slowdown)
612 "PTG-continuation not allowed: target too close and must start " 613 "slow-down (trgDist=%.03f < SlowDownDist=%.03f)",
614 relTargetDist, slowdowndist);
618 rel_pose_PTG_origin_wrt_sense_NOP(0, 0, 0);
620 if (can_do_nop_motion)
635 bool valid_odom, valid_pose;
638 tim_send_cmd_vel_corrected, robot_odom_at_send_cmd, valid_odom);
640 tim_send_cmd_vel_corrected, robot_pose_at_send_cmd, valid_pose);
642 if (valid_odom && valid_pose)
644 ASSERT_(last_sent_ptg !=
nullptr);
646 std::vector<TPose2D> relTargets_NOPs;
648 targets.begin(), targets.end(),
649 std::back_inserter(relTargets_NOPs),
650 [robot_pose_at_send_cmd](
652 return e.target_coords - robot_pose_at_send_cmd;
656 rel_pose_PTG_origin_wrt_sense_NOP =
657 robot_odom_at_send_cmd -
659 rel_cur_pose_wrt_last_vel_cmd_NOP =
669 [
"rel_cur_pose_wrt_last_vel_cmd_NOP(interp)"] =
670 rel_cur_pose_wrt_last_vel_cmd_NOP.asString();
672 [
"robot_odom_at_send_cmd(interp)"] =
673 robot_odom_at_send_cmd.asString();
683 candidate_movs[nPTGs], newLogRec,
687 rel_cur_pose_wrt_last_vel_cmd_NOP);
693 candidate_movs[nPTGs].speed =
703 int best_ptg_idx =
m_multiobjopt->decide(candidate_movs, mo_info);
709 for (
unsigned int i = 0; i < newLogRec.
infoPerPTG.size(); i++)
719 "MultiObjMotOptmzr_msg%03i", idx++)] = le;
725 if (best_ptg_idx >= 0)
727 selectedHolonomicMovement = &candidate_movs[best_ptg_idx];
732 const bool best_is_NOP_cmdvel = (best_ptg_idx == int(nPTGs));
738 if (best_is_NOP_cmdvel)
745 "\nERROR calling changeSpeedsNOP()!! Stopping robot and " 746 "finishing navigation\n");
750 newLogRec, relTargets, best_ptg_idx,
752 best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
753 rel_pose_PTG_origin_wrt_sense_NOP,
756 tim_start_iteration);
765 for (
size_t i = 0; i < nPTGs; i++)
772 double cmd_vel_speed_ratio = 1.0;
773 if (selectedHolonomicMovement)
776 m_timelogger,
"navigationStep.selectedHolonomicMovement");
777 cmd_vel_speed_ratio =
783 new_vel_cmd->isStopCmd())
786 "Best velocity command is STOP (no way found), calling " 802 newLogRec.
timestamps[
"tim_send_cmd_vel"] = tim_send_cmd_vel;
806 "\nERROR calling changeSpeeds()!! Stopping robot " 807 "and finishing navigation\n");
812 newLogRec, relTargets, best_ptg_idx,
813 new_vel_cmd, nPTGs, best_is_NOP_cmdvel,
814 rel_cur_pose_wrt_last_vel_cmd_NOP,
815 rel_pose_PTG_origin_wrt_sense_NOP,
818 tim_start_iteration);
827 selectedHolonomicMovement
838 (selectedHolonomicMovement->
props[
"is_slowdown"] != 0.0);
846 tim_start_iteration, tim_send_cmd_vel);
848 newLogRec.
values[
"timoff_sendVelCmd"] = timoff_sendVelCmd;
849 newLogRec.
values[
"timoff_sendVelCmd_avr"] =
862 const double tim_changeSpeed =
871 "Timing warning: Suspicious executionPeriod=%.03f ms is far " 872 "above the average of %.03f ms",
884 "T=%.01lfms Exec:%.01lfms|%.01lfms " 886 new_vel_cmd ? new_vel_cmd->asString().c_str() :
"NOP",
887 selectedHolonomicMovement ? selectedHolonomicMovement->
speed 897 newLogRec, relTargets, best_ptg_idx, new_vel_cmd, nPTGs,
898 best_is_NOP_cmdvel, rel_cur_pose_wrt_last_vel_cmd_NOP,
899 rel_pose_PTG_origin_wrt_sense_NOP, executionTimeValue,
900 tim_changeSpeed, tim_start_iteration);
903 catch (std::exception& e)
907 "[CAbstractPTGBasedReactive::performNavigationStep] " 908 "Stopping robot and finishing navigation due to " 915 "[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot " 916 "and finishing navigation due to untyped exception.");
922 CLogFileRecord& newLogRec,
const std::vector<TPose2D>& relTargets,
924 const int nPTGs,
const bool best_is_NOP_cmdvel,
927 const double executionTimeValue,
const double tim_changeSpeed,
943 newLogRec.
cmd_vel = new_vel_cmd;
944 newLogRec.
values[
"estimatedExecutionPeriod"] =
946 newLogRec.
values[
"executionTime"] = executionTimeValue;
948 newLogRec.
values[
"time_changeSpeeds()"] = tim_changeSpeed;
949 newLogRec.
values[
"time_changeSpeeds()_avr"] =
951 newLogRec.
values[
"CWaypointsNavigator::navigationStep()"] =
953 newLogRec.
values[
"CAbstractNavigator::navigationStep()"] =
955 newLogRec.
timestamps[
"tim_start_iteration"] = tim_start_iteration;
957 newLogRec.
nPTGs = nPTGs;
961 rel_cur_pose_wrt_last_vel_cmd_NOP;
963 rel_pose_PTG_origin_wrt_sense_NOP;
976 if (
m_logFile) (*m_logFile) << newLogRec;
980 std::lock_guard<std::recursive_mutex> lock_log(
990 const std::vector<mrpt::math::TPose2D>& WS_Targets,
991 const std::vector<CAbstractPTGBasedReactive::PTGTarget>& TP_Targets,
993 const bool this_is_PTG_continuation,
995 const unsigned int ptg_idx4weights,
1013 size_t selected_trg_idx = 0;
1015 double best_trg_angdist = std::numeric_limits<double>::max();
1016 for (
size_t i = 0; i < TP_Targets.size(); i++)
1018 const double angdist = std::abs(
1020 TP_Targets[i].target_alpha, cm.
direction));
1021 if (angdist < best_trg_angdist)
1023 best_trg_angdist = angdist;
1024 selected_trg_idx = i;
1028 ASSERT_(selected_trg_idx < WS_Targets.size());
1029 const auto WS_Target = WS_Targets[selected_trg_idx];
1030 const auto TP_Target = TP_Targets[selected_trg_idx];
1032 const double target_d_norm = TP_Target.target_dist;
1036 const double target_WS_d = WS_Target.norm();
1039 const double d =
std::min(in_TPObstacles[move_k], 0.99 * target_d_norm);
1058 const double TARGET_SLOW_APPROACHING_DISTANCE =
1066 Vf + target_WS_d * (1.0 - Vf) / TARGET_SLOW_APPROACHING_DISTANCE);
1070 "Relative speed reduced %.03f->%.03f based on Euclidean " 1071 "nearness to target.",
1078 cm.
props[
"ptg_idx"] = ptg_idx4weights;
1079 cm.
props[
"ref_dist"] = ref_dist;
1080 cm.
props[
"target_dir"] = TP_Target.target_alpha;
1081 cm.
props[
"target_k"] = TP_Target.target_k;
1082 cm.
props[
"target_d_norm"] = target_d_norm;
1083 cm.
props[
"move_k"] = move_k;
1084 double& move_cur_d = cm.
props[
"move_cur_d"] =
1087 cm.
props[
"is_PTG_cont"] = this_is_PTG_continuation ? 1 : 0;
1088 cm.
props[
"num_paths"] = in_TPObstacles.size();
1089 cm.
props[
"WS_target_x"] = WS_Target.x;
1090 cm.
props[
"WS_target_y"] = WS_Target.y;
1091 cm.
props[
"robpose_x"] = pose.
x;
1092 cm.
props[
"robpose_y"] = pose.
y;
1093 cm.
props[
"robpose_phi"] = pose.
phi;
1094 cm.
props[
"ptg_priority"] =
1097 const bool is_slowdown =
1098 this_is_PTG_continuation
1101 cm.
props[
"is_slowdown"] = is_slowdown ? 1 : 0;
1105 double& colfree = cm.
props[
"collision_free_distance"];
1108 colfree = in_TPObstacles[move_k];
1116 if (this_is_PTG_continuation)
1119 double cur_norm_d = .0;
1120 bool is_exact, is_time_based =
false;
1127 if (std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.
x) > maxD ||
1128 std::abs(rel_cur_pose_wrt_last_vel_cmd_NOP.
y) > maxD)
1131 rel_cur_pose_wrt_last_vel_cmd_NOP.
x,
1132 rel_cur_pose_wrt_last_vel_cmd_NOP.
y, cur_k, cur_norm_d);
1137 is_time_based =
true;
1139 const double NOP_At =
1152 log.
TP_Robot.
x = cos(cur_a) * cur_norm_d;
1153 log.
TP_Robot.
y = sin(cur_a) * cur_norm_d;
1165 "PTG-continuation not allowed, cur. pose out of PTG domain.";
1168 bool WS_point_is_unique =
true;
1183 WS_point_is_unique =
1184 WS_point_is_unique &&
1188 "isBijectiveAt(): k=%i step=%i -> %s", (
int)cur_k,
1189 (
int)cur_ptg_step, WS_point_is_unique ?
"yes" :
"no");
1191 if (!WS_point_is_unique)
1195 cur_ptg_step = predicted_step;
1200 log.
TP_Robot.
x = cos(cur_a) * cur_norm_d;
1201 log.
TP_Robot.
y = sin(cur_a) * cur_norm_d;
1209 predicted_rel_pose);
1210 const auto predicted_pose_global =
1219 "mismatchDistance=%.03f cm", 1e2 * predicted2real_dist);
1221 if (predicted2real_dist >
1223 .max_distance_predicted_actual_path &&
1225 (target_d_norm - cur_norm_d) * ref_dist > 2.0 ))
1230 "PTG-continuation not allowed, mismatchDistance above " 1239 "PTG-continuation not allowed, couldn't get PTG step for " 1253 colfree = WS_point_is_unique
1254 ?
std::min(in_TPObstacles[move_k], in_TPObstacles[cur_k])
1255 : in_TPObstacles[move_k];
1261 colfree -= cur_norm_d;
1265 move_cur_d = cur_norm_d;
1270 cm.
props[
"dist_eucl_final"] =
1276 typedef std::map<double, double> map_d2d_t;
1277 map_d2d_t pathDists;
1279 const int num_steps = ceil(D * 2.0);
1280 for (
int i = 0; i < num_steps; i++)
1282 pathDists[i / double(num_steps)] =
1287 WS_Target.x, WS_Target.y, move_k, pathDists,
1290 const auto it = std::min_element(
1291 pathDists.begin(), pathDists.end(),
1292 [colfree](map_d2d_t::value_type& l, map_d2d_t::value_type&
r)
1293 ->
bool {
return (l.second <
r.second) && l.first < colfree; });
1294 cm.
props[
"dist_eucl_min"] = (it != pathDists.end())
1301 double& hysteresis = cm.
props[
"hysteresis"];
1306 hysteresis = this_is_PTG_continuation ? 1.0 : 0.;
1314 if (
typeid(*ptr1) ==
typeid(*ptr2))
1318 desired_cmd->getVelCmdLength());
1320 double simil_score = 0.5;
1321 for (
size_t i = 0; i < desired_cmd->getVelCmdLength(); i++)
1325 desired_cmd->getVelCmdElement(i) -
1330 hysteresis = simil_score;
1337 double& clearance = cm.
props[
"clearance"];
1339 move_k, target_d_norm * 1.01,
false );
1341 move_k, target_d_norm * 0.5,
false );
1343 move_k, target_d_norm * 0.9,
true );
1345 move_k, target_d_norm * 0.5,
true );
1350 double& eta = cm.
props[
"eta"];
1355 const double path_len_meters = d * ref_dist;
1367 double discount_time = .0;
1368 if (this_is_PTG_continuation)
1378 eta -= discount_time;
1391 double cmdvel_speed_scale = 1.0;
1394 if (in_movement.
speed == 0)
1399 new_vel_cmd->setToStop();
1408 new_vel_cmd->cmdVel_scale(in_movement.
speed);
1409 cmdvel_speed_scale *= in_movement.
speed;
1419 cmdvel_speed_scale *= new_vel_cmd->cmdVel_limits(
1426 catch (std::exception& e)
1429 "[CAbstractPTGBasedReactive::generate_vel_cmd] Exception: " 1432 return cmdvel_speed_scale;
1448 for (
size_t i = 0; i < N; i++)
1452 const std::vector<double>& tp_obs =
1460 bool is_into_domain =
1462 if (!is_into_domain)
continue;
1464 ASSERT_(wp_k <
int(tp_obs.size()));
1466 const double collision_free_dist = tp_obs[wp_k];
1467 if (collision_free_dist > 1.01 * wp_norm_d)
1495 ptg_alpha_index = -1;
1498 colfreedist_move_k = .0;
1499 was_slowdown =
false;
1511 const std::vector<mrpt::math::TPose2D>& relTargets,
1514 const bool this_is_PTG_continuation,
1522 const size_t idx_in_log_infoPerPTGs =
1530 bool use_this_ptg =
true;
1536 use_this_ptg =
false;
1541 use_this_ptg =
true;
1546 double timeForTPObsTransformation = .0, timeForHolonomicMethod = .0;
1549 bool any_TPTarget_is_valid =
false;
1552 for (
size_t i = 0; i < relTargets.size(); i++)
1554 const auto& trg = relTargets[i];
1559 if (!ptg_target.
valid_TP)
continue;
1561 any_TPTarget_is_valid =
true;
1568 ipf.
targets.emplace_back(ptg_target);
1572 if (!any_TPTarget_is_valid)
1575 "mov_candidate_%u", static_cast<unsigned int>(indexPTG))] =
1576 "PTG discarded since target(s) is(are) out of domain.";
1606 for (
size_t i = 0; i < Ki; i++) ipf.
TP_Obstacles[i] *= _refD;
1608 timeForTPObsTransformation =
tictac.
Tac();
1611 "navigationStep.STEP3_WSpaceToTPSpace",
1612 timeForTPObsTransformation);
1617 if (!this_is_PTG_continuation)
1649 const int kDirection =
1651 double obsFreeNormalizedDistance = ipf.
TP_Obstacles[kDirection];
1660 obsFreeNormalizedDistance =
std::min(
1661 obsFreeNormalizedDistance,
1662 std::max(0.90, obsFreeNormalizedDistance - d));
1665 double velScale = 1.0;
1669 if (obsFreeNormalizedDistance <
1672 if (obsFreeNormalizedDistance <=
1677 (obsFreeNormalizedDistance -
1684 cm.
speed *= velScale;
1689 "navigationStep.STEP4_HolonomicMethod",
1690 timeForHolonomicMethod);
1704 m_timelogger,
"navigationStep.calc_move_candidate_scores");
1708 newLogRec.
infoPerPTG[idx_in_log_infoPerPTGs], newLogRec,
1709 this_is_PTG_continuation, rel_cur_pose_wrt_last_vel_cmd_NOP,
1710 indexPTG, tim_start_iteration);
1713 cm.
props[
"original_col_free_dist"] =
1724 const bool fill_log_record =
1726 if (fill_log_record)
1729 newLogRec.
infoPerPTG[idx_in_log_infoPerPTGs];
1730 if (!this_is_PTG_continuation)
1734 "NOP cmdvel (prev PTG idx=%u)",
1758 robot_absolute_speed_limits.loadConfigFile(
c,
s);
1769 min_normalized_free_space_for_ptg_continuation,
double);
1780 robot_absolute_speed_limits.saveToConfigFile(
c,
s);
1783 string lstHoloStr =
"# List of known classes:\n";
1787 for (
const auto&
c : lst)
1794 "C++ class name of the holonomic navigation method to run in " 1795 "the transformed TP-Space.\n") +
1799 string lstDecidersStr =
"# List of known classes:\n";
1803 for (
const auto&
c : lst)
1808 motion_decider_method,
1809 string(
"C++ class name of the motion decider method.\n") +
1814 "Maximum distance up to obstacles will be considered (D_{max} in " 1818 "Time constant (in seconds) for the low-pass filter applied to " 1819 "kinematic velocity commands (default=0: no filtering)");
1821 secure_distance_start,
1822 "In normalized distance [0,1], start/end of a ramp function that " 1823 "scales the holonomic navigator output velocity.");
1825 secure_distance_end,
1826 "In normalized distance [0,1], start/end of a ramp function that " 1827 "scales the holonomic navigator output velocity.");
1830 "Whether to use robot pose inter/extrapolation to improve accuracy " 1833 max_distance_predicted_actual_path,
1834 "Max distance [meters] to discard current PTG and issue a new vel cmd " 1837 min_normalized_free_space_for_ptg_continuation,
1838 "Min normalized dist [0,1] after current pose in a PTG continuation to " 1841 enable_obstacle_filtering,
1842 "Enabled obstacle filtering (params in its own section)");
1845 "Enable exact computation of clearance (default=false)");
1847 max_dist_for_timebased_path_prediction,
1848 "Max dist [meters] to use time-based path prediction for NOP " 1854 : holonomic_method(),
1855 ptg_cache_files_directory(
"."),
1857 speedfilter_tau(0.0),
1858 secure_distance_start(0.05),
1859 secure_distance_end(0.20),
1860 use_delays_model(false),
1861 max_distance_predicted_actual_path(0.15),
1862 min_normalized_free_space_for_ptg_continuation(0.2),
1863 robot_absolute_speed_limits(),
1864 enable_obstacle_filtering(true),
1865 evaluate_clearance(false),
1866 max_dist_for_timebased_path_prediction(2.0)
1881 c,
"CAbstractPTGBasedReactive");
1889 filter->options.loadFromConfigFile(
c,
"CPointCloudFilterByDistance");
1901 "Non-registered CMultiObjectiveMotionOptimizerBase className=`%s`",
1922 c,
"CAbstractPTGBasedReactive");
1927 filter.options.saveToConfigFile(
c,
"CPointCloudFilterByDistance");
1941 for (
const auto& cl : lst)
1965 for (
const auto& cl : lst)
1984 o->setTargetApproachSlowDownDistance(dist);
#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...
virtual bool supportSpeedAtTarget() const
Returns true if this PTG takes into account the desired velocity at target.
std::recursive_mutex m_nav_cs
mutex for all navigation methods
CHolonomicLogFileRecord::Ptr HLFR
Other useful info about holonomic method execution.
mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP
TRobotPoseVel m_curPoseVel
Current robot pose (updated in CAbstractNavigator::navigationStep() )
virtual bool getPathStepForDist(uint16_t k, double dist, uint32_t &out_step) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < ...
virtual bool supportVelCmdNOP() const
Returns true if it is possible to stop sending velocity commands to the robot and, still, the robot controller will be able to keep following the last sent trajectory ("NOP" velocity commands).
double targetRelSpeed
Desired relative speed [0,1] at target.
bool createDirectory(const std::string &dirName)
Creates a directory.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
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 MRPT_LOAD_CONFIG_VAR_REQUIRED_CS(variableName, variableType)
Shortcut for MRPT_LOAD_CONFIG_VAR_NO_DEFAULT() for REQUIRED variables config file object named c and ...
std::vector< mrpt::math::TPose2D > WS_targets_relative
Relative poses (wrt to robotPoseLocalization) for.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
mrpt::utils::CTicTac totalExecutionTime
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].
virtual void onStartNewNavigation() override
Called whenever a new navigation has been started.
double getRefDistance() const
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...
std::map< std::string, mrpt::system::TTimeStamp > timestamps
Known values:
std::recursive_mutex m_critZoneLastLog
Critical zones.
mrpt::nav::ClearanceDiagram clearance
Clearance for each path.
#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.
mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense_NOP
CParameterizedTrajectoryGenerator * PTG
The associated PTG.
uint64_t Seek(uint64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) override
Introduces a pure virtual method for moving to a specified position in the streamed resource...
#define THROW_EXCEPTION(msg)
mrpt::math::TPose2D robotPoseOdometry
void getLastLogRecord(CLogFileRecord &o)
Provides a copy of the last log record with information about execution.
TRobotPoseVel poseVel
Robot pose & velocities and timestamp of when it was queried.
#define MRPT_LOG_DEBUG_FMT(_FMT_STRING,...)
std::shared_ptr< CPointCloudFilterBase > Ptr
void initialize() override
Must be called for loading collision grids, or the first navigation command may last a long time to b...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
This file implements several operations that operate element-wise on individual or pairs of container...
Base for all high-level navigation commands.
void initTPObstacles(std::vector< double > &TP_Obstacles) const
Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ra...
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
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.
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.
std::vector< mrpt::math::TPoint2D > TP_Targets
Target(s) location in TP-Space.
std::vector< CAbstractHolonomicReactiveMethod::Ptr > m_holonomicMethod
The holonomic navigation algorithm (one object per PTG, so internal states are maintained) ...
#define MRPT_LOAD_CONFIG_VAR_CS(variableName, variableType)
Shortcut for MRPT_LOAD_CONFIG_VAR() for config file object named c and section string named s ...
bool m_enableConsoleOutput
Enables / disables the console debug output.
std::string holonomic_method
C++ class name of the holonomic navigation method to run in the transformed TP-Space.
void updateClearancePost(ClearanceDiagram &cd, const std::vector< double > &TP_obstacles) const
void updateNavDynamicState(const TNavDynamicState &newState, const bool force_update=false)
To be invoked by the navigator before each navigation step, to let the PTG to react to changing dynam...
uint32_t nPTGs
The number of PTGS:
Clearance information for one particular PTG and one set of obstacles.
mrpt::utils::CTicTac executionTime
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.
mrpt::system::TTimeStamp m_WS_Obstacles_timestamp
std::shared_ptr< CObject > Ptr
This class extends CAbstractNavigator with the capability of following a list of waypoints.
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
#define MRPT_LOG_ERROR_FMT(_FMT_STRING,...)
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) override
Loads all params from a file.
void Tic()
Starts the stopwatch.
GLsizei GLsizei GLuint * obj
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const =0
saves all available parameters, in a forma loadable by initialize()
double target_alpha
TP-Target.
virtual double getPathDist(uint16_t k, uint32_t step) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step.
std::string pose_frame_id
map frame ID for pose
mrpt::utils::CTimeLogger m_timlog_delays
Time logger to collect delay-related stats.
virtual void getPathPose(uint16_t k, uint32_t step, mrpt::math::TPose2D &p) const =0
Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step.
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
mrpt::kinematics::CVehicleVelCmd::Ptr m_last_vel_cmd
Last velocity commands.
bool STEP2_SenseObstacles()
virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &c, const std::string &s) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
pose_t & interpolate(mrpt::system::TTimeStamp t, pose_t &out_interp, bool &out_valid_interp) const
Returns the pose at a given time, or interpolates using splines if there is not an exact match...
virtual bool changeSpeeds(const mrpt::kinematics::CVehicleVelCmd &vel_cmd)
Default: forward call to m_robot.changeSpeed().
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
virtual bool changeSpeedsNOP()
Default: forward call to m_robot.changeSpeedsNOP().
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::math::TPoint2D TP_Target
The Target, in TP-Space (x,y)
Virtual base for velocity commands of different kinematic models of planar mobile robot...
void STEP8_GenerateLogRecord(CLogFileRecord &newLogRec, const std::vector< mrpt::math::TPose2D > &relTargets, int nSelectedPTG, const mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd, int nPTGs, const bool best_is_NOP_cmdvel, const math::TPose2D &rel_cur_pose_wrt_last_vel_cmd_NOP, const math::TPose2D &rel_pose_PTG_origin_wrt_sense_NOP, const double executionTimeValue, const double tim_changeSpeed, const mrpt::system::TTimeStamp &tim_start_iteration)
double getClearance(uint16_t k, double TPS_query_distance, bool integrate_over_path) const
Gets the clearance for path k and distance TPS_query_distance in one of two modes: ...
The struct for configuring navigation requests.
virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const =0
Converts a discretized "alpha" value into a feasible motion command or action.
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState ptg_last_navDynState
CSerializable::Ptr ReadObject()
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the obje...
This is the base class for any user-defined PTG.
void calc_move_candidate_scores(TCandidateMovementPTG &holonomicMovement, const std::vector< double > &in_TPObstacles, const mrpt::nav::ClearanceDiagram &in_clearance, const std::vector< mrpt::math::TPose2D > &WS_Targets, const std::vector< PTGTarget > &TP_Targets, CLogFileRecord::TInfoPerPTG &log, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, const mrpt::math::TPose2D &relPoseVelCmd_NOP, const unsigned int ptg_idx4weights, const mrpt::system::TTimeStamp tim_start_iteration)
Scores holonomicMovement.
This base provides a set of functions for maths stuff.
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.
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
static CMultiObjectiveMotionOptimizerBase::Ptr Factory(const std::string &className) noexcept
Class factory from C++ class name.
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
std::shared_ptr< CHolonomicLogFileRecord > Ptr
double targetDesiredRelSpeed
(Default=.05) Desired relative speed (wrt maximum speed), in range [0,1], of the vehicle at target...
mrpt::math::TPose2D robotPoseLocalization
The robot pose (from odometry and from the localization/SLAM system).
mrpt::kinematics::CVehicleVelCmd::Ptr cmd_vel
The final motion command sent to robot, in "m/sec" and "rad/sec".
double speed
TP-Space movement speed, normalized to [0,1].
virtual void performNavigationStep() override
The main method for the navigator.
mrpt::math::TPoint2D TP_Robot
Robot location in TP-Space: normally (0,0), except during "NOP cmd vel" steps.
This CStream derived class allow using a memory buffer as a CStream.
virtual double generate_vel_cmd(const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmd::Ptr &new_vel_cmd)
Return the [0,1] velocity scale of raw PTG cmd_vel.
double vx
Velocity components: X,Y (m/s)
virtual double evalPathRelativePriority(uint16_t k, double target_distance) const
Query the PTG for the relative priority factor (0,1) of this PTG, in comparison to others...
mrpt::math::LowPassFilter_IIR1 timoff_sendVelCmd_avr
virtual void loadConfigFile(const mrpt::utils::CConfigFileBase &c) override
Loads all params from a file.
double desiredDirection
The desired motion direction, in the range [-PI, PI].
double timeForTPObsTransformation
Time, in seconds.
std::string motion_decider_method
C++ class name of the motion chooser.
mrpt::utils::CStream * m_prev_logfile
The current log file stream, or nullptr if not being used.
mrpt::nav::CMultiObjectiveMotionOptimizerBase::Ptr m_multiobjopt
mrpt::math::TTwist2D curVelLocal
Current vehicle velocity (local frame of reference)
double max_dist_for_timebased_path_prediction
Max dist [meters] to use time-based path prediction for NOP evaluation.
std::unique_ptr< TNavigationParams > m_navigationParams
Current navigation parameters.
virtual void onStartNewNavigation() override
Called whenever a new navigation has been started.
int16_t ptg_index_NOP
Negative means no NOP mode evaluation, so the rest of "NOP variables" should be ignored.
mrpt::system::TTimeStamp timestamp
void initClearanceDiagram(ClearanceDiagram &cd) const
Must be called to resize a CD to its correct size, before calling updateClearance() ...
mrpt::math::TPose2D relTarget
Current relative target location.
Individual target info in CAbstractNavigator::TNavigationParamsBase and derived classes.
virtual void sendApparentCollisionEvent()
Callback: Apparent collision event (i.e.
mrpt::aligned_containers< TInfoPerPTG >::vector_t infoPerPTG
The info for each applied PTG: must contain "nPTGs * nSecDistances" elements.
double getLastTime(const std::string &name) const
Return the last execution time of the given "section", or 0 if it hasn't ever been called "enter" wit...
std::unique_ptr< TNavigationParams > m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes.
mrpt::system::TTimeStamp m_infoPerPTG_timestamp
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const =0
Returns an empty kinematic velocity command object of the type supported by this PTG.
CHolonomicLogFileRecord::Ptr logRecord
The navigation method will create a log record and store it here via a smart pointer.
#define MRPT_LOG_DEBUG(_STRING)
void enableApproachTargetSlowDown(bool enable)
double direction
TP-Space movement direction.
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
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd()=0
Gets the emergency stop command for the current robot.
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const =0
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
void setHolonomicMethod(const std::string &method, const mrpt::utils::CConfigFileBase &cfgBase)
Selects which one from the set of available holonomic methods will be used into transformed TP-Space...
bool m_closing_navigator
Signal that the destructor has been called, so no more calls are accepted from other threads...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
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...
bool enable_obstacle_filtering
virtual bool implementSenseObstacles(mrpt::system::TTimeStamp &obs_timestamp)=0
Return false on any fatal error.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
std::vector< std::function< void(void)> > m_pending_events
Events generated during navigationStep(), enqueued to be called at the end of the method execution to...
std::string PTG_desc
A short description for the applied PTG.
double speedfilter_tau
Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0:...
uint16_t getAlphaValuesCount() const
Get the number of different, discrete paths in this family.
double filter(double x)
Processes one input sample, updates the filter state and return the filtered value.
double desiredSpeed
The desired motion speed in that direction, from 0 up to NavInput::maxRobotSpeed. ...
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits.
virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &c, const std::string &s) override
This method load the options from a ".ini"-like file or memory-stored string list.
ClearanceDiagram clearance
Clearance for each path.
std::unique_ptr< mrpt::utils::CStream > m_logFile
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...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double getScorePriority() const
When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG...
Virtual base class for multi-objective motion choosers, as used for reactive navigation engines...
mrpt::utils::TParameters< double > props
List of properties.
mrpt::utils::CTicTac timerForExecutionPeriod
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
A safe way to call enter() and leave() of a mrpt::utils::CTimeLogger upon construction and destructio...
mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState navDynState
int ptg_index
0-based index of used PTG
double colfreedist_move_k
TP-Obstacles in the move direction at the instant of picking this movement.
std::vector< PTGTarget > targets
std::vector< TInfoPerPTG > m_infoPerPTG
Temporary buffers for working with each PTG during a navigationStep()
virtual ~CAbstractPTGBasedReactive()
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
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.
CLogFileRecord lastLogRecord
The last log.
mrpt::math::TTwist2D velLocal
virtual void evalClearanceSingleObstacle(const double ox, const double oy, const uint16_t k, ClearanceDiagram::dist2clearance_t &inout_realdist2clearance, bool treat_as_obstacle=true) const
Evals the robot clearance for each robot pose along path k, for the real distances in the key of the ...
Implementation of pointcloud filtering based on requisities for minimum neigbouring points in both...
CRobot2NavInterface & m_robot
The navigator-robot interface.
mrpt::math::TTwist2D cur_vel
The actual robot velocities in global (map) coordinates, as read from sensors, in "m/sec" and "rad/se...
bool m_init_done
Whether loadConfigFile() has been called or not.
mrpt::math::LowPassFilter_IIR1 meanTotalExecutionTime
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const override
Saves all current options to a config file.
T hypot_fast(const T x, const T y)
Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code...
static CAbstractHolonomicReactiveMethod::Ptr Factory(const std::string &className) noexcept
virtual bool impl_waypoint_is_reachable(const mrpt::math::TPoint2D &wp_local_wrt_robot) const override
Implements the way to waypoint is free function in children classes: true must be returned if...
double Tac()
Stops the stopwatch.
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i)=0
Gets the i'th PTG.
double leave(const char *func_name)
End of a named section.
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
void build_movement_candidate(CParameterizedTrajectoryGenerator *ptg, const size_t indexPTG, const std::vector< mrpt::math::TPose2D > &relTargets, const mrpt::math::TPose2D &rel_pose_PTG_origin_wrt_sense, TInfoPerPTG &ipf, TCandidateMovementPTG &holonomicMovement, CLogFileRecord &newLogRec, const bool this_is_PTG_continuation, mrpt::nav::CAbstractHolonomicReactiveMethod &holoMethod, const mrpt::system::TTimeStamp tim_start_iteration, const TNavigationParams &navp=TNavigationParams(), const mrpt::math::TPose2D &relPoseVelCmd_NOP=mrpt::poses::CPose2D())
TAbstractPTGNavigatorParams()
int round(const T value)
Returns the closer integer (int) to x.
bool valid_TP
For each PTG, whether target falls into the PTG domain.
The struct for configuring navigation requests to CAbstractPTGBasedReactive and derived classes...
TargetInfo target
Navigation target.
virtual void saveConfigFile(mrpt::utils::CConfigFileBase &c) const override
Saves all current options to a config file.
double m_last_curPoseVelUpdate_robot_time
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) ...
virtual void navigate(const NavInput &ni, NavOutput &no)=0
Invokes the holonomic navigation algorithm itself.
mrpt::math::TTwist2D velGlobal
void registerUserMeasure(const char *event_name, const double value)
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: "[x y yaw]", yaw in degrees) ...
std::vector< const TRuntimeClassId * > getAllRegisteredClassesChildrenOf(const TRuntimeClassId *parent_id)
Like getAllRegisteredClasses(), but filters the list to only include children clases of a given base ...
bool directoryExists(const std::string &fileName)
Test if a given directory exists (it fails if the given path refers to an existing file)...
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...
TSentVelCmd m_lastSentVelCmd
std::shared_ptr< CVehicleVelCmd > Ptr
mrpt::poses::CPose2DInterpolator m_latestOdomPoses
GLuint GLenum GLenum transform
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
virtual void STEP1_InitPTGs()=0
double starting_robot_dist
int ptg_alpha_index
Path index for selected PTG.
unsigned __int32 uint32_t
double secure_distance_end
void enter(const char *func_name)
Start of a named section.
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
bool m_PTGsMustBeReInitialized
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
Dynamic state that may affect the PTG path parameterization.
Output for CAbstractHolonomicReactiveMethod::navigate()
mrpt::math::TPose2D relPoseVelCmd
mrpt::poses::CPose2DInterpolator m_latestPoses
Latest robot poses (updated in CAbstractNavigator::navigationStep() )
double phi
Orientation (rads)
void copy_container_typecasting(const src_container &src, dst_container &trg)
Copy all the elements in a container (vector, deque, list) into a different one performing the approp...
double getLastOutput() const
The structure used to store all relevant information about each transformation into TP-Space...
mrpt::math::LowPassFilter_IIR1 tim_changeSpeed_avr
mrpt::math::TPose2D rawOdometry
raw odometry (frame does not match to "pose", but is expected to be smoother in the short term)...
int sprintf(char *buf, size_t bufSize, const char *format,...) noexcept MRPT_printf_format_check(3
An OS-independent version of sprintf (Notice the bufSize param, which may be ignored in some compiler...
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...
bool evaluate_clearance
Default: false.
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 timeForHolonomicMethod
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...
mrpt::utils::CTicTac tictac
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.