37 std::string CAbstractPTGBasedReactive::TNavigationParamsPTG::getAsText()
const 39 std::string s = CWaypointsNavigator::TNavigationParamsWaypoints::getAsText();
40 s +=
"restrict_PTG_indices: ";
50 CWaypointsNavigator::TNavigationParamsWaypoints::isEqual(rhs) &&
57 CAbstractPTGBasedReactive::CAbstractPTGBasedReactive(
CRobot2NavInterface &react_iterf_impl,
bool enableConsoleOutput,
bool enableLogFile,
const std::string &sLogDir):
61 m_prev_logfile (nullptr),
62 m_enableKeepLogRecords (false),
63 m_enableConsoleOutput (enableConsoleOutput),
66 m_PTGsMustBeReInitialized (true),
74 m_closing_navigator (false),
77 m_navlogfiles_dir (sLogDir),
78 m_copy_prev_navParams (nullptr)
140 MRPT_LOG_DEBUG(
"[CAbstractPTGBasedReactive::enableLogFile] Stopping logging.");
154 unsigned int nFile = 0;
155 bool free_name =
false;
172 bool ok = fil->open(aux, 1 );
185 }
catch (std::exception &e) {
186 MRPT_LOG_ERROR_FMT(
"[CAbstractPTGBasedReactive::enableLogFile] Exception: %s",e.what());
205 case hmFULL_EVAL: className =
"CHolonomicFullEval";
break;
206 default:
THROW_EXCEPTION_FMT(
"Unknown Holonomic method: %u", static_cast<unsigned int>(method))
227 for (
size_t i = 0; i<nPTGs; i++)
247 m_navProfiler,
"CAbstractPTGBasedReactive::performNavigationStep()");
266 for (
size_t i=0;i<nPTGs;i++)
274 newLogRec.
infoPerPTG[i].ptg = mrpt::nav::CParameterizedTrajectoryGeneratorPtr ( buf.
ReadObject() );
291 if (target_changed_since_last_iteration) {
298 std::vector<CAbstractNavigator::TargetInfo> targets;
301 if (
p && !
p->multiple_targets.empty())
303 targets =
p->multiple_targets;
310 const size_t nTargets = targets.size();
321 "CAbstractPTGBasedReactive::performNavigationStep().STEP2_" 329 doEmergencyStop(
"Error while loading and sorting the obstacles. Robot will be stopped.");
332 CPose2D rel_cur_pose_wrt_last_vel_cmd_NOP, rel_pose_PTG_origin_wrt_sense_NOP;
334 std::vector<mrpt::math::TPose2D>() ,
339 rel_cur_pose_wrt_last_vel_cmd_NOP,
340 rel_pose_PTG_origin_wrt_sense_NOP,
343 tim_start_iteration);
354 mrpt::math::TPose2D rel_pose_PTG_origin_wrt_sense(0,0,0),relPoseSense(0,0,0), relPoseVelCmd(0,0,0);
377 newLogRec.
values[
"timoff_obstacles"] = timoff_obstacles;
383 newLogRec.
values[
"timoff_curPoseVelAge"] = timoff_curPoseVelAge;
387 const double timoff_pose2sense = timoff_obstacles - timoff_curPoseVelAge;
389 double timoff_pose2VelCmd;
391 newLogRec.
values[
"timoff_pose2sense"] = timoff_pose2sense;
392 newLogRec.
values[
"timoff_pose2VelCmd"] = timoff_pose2VelCmd;
394 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);
395 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);
402 rel_pose_PTG_origin_wrt_sense = relPoseVelCmd - relPoseSense;
413 for (
auto &
t : targets)
425 t.target_coords = robot_frame2map_frame +
t.target_coords;
430 std::vector<TPose2D> relTargets;
433 targets.begin(), targets.end(),
434 std::back_inserter(relTargets),
440 const double relTargetDist = relTargets.begin()->norm();
454 "CAbstractPTGBasedReactive::performNavigationStep().update_PTG_" 457 for (
size_t i = 0; i < nPTGs; i++)
463 vector<TCandidateMovementPTG> candidate_movs(nPTGs+1);
465 for (
size_t indexPTG=0;indexPTG<nPTGs;indexPTG++)
469 "CAbstractPTGBasedReactive::performNavigationStep().eval_" 478 holoMethod->setAssociatedPTG(this->
getPTG(indexPTG));
486 relTargets, rel_pose_PTG_origin_wrt_sense,
496 bool is_all_ptg_collision =
true;
497 for (
size_t indexPTG = 0; indexPTG < nPTGs; indexPTG++)
499 bool is_collision =
true;
501 for (
const auto o : obs) {
503 is_collision =
false;
508 is_all_ptg_collision =
false;
512 if (is_all_ptg_collision) {
520 bool NOP_not_too_old =
true;
521 bool NOP_not_too_close_and_have_to_slowdown =
true;
522 double NOP_max_time = -1.0, NOP_At = -1.0;
523 double slowdowndist = .0;
533 const bool can_do_nop_motion =
536 !target_changed_since_last_iteration &&
548 (NOP_not_too_close_and_have_to_slowdown =
558 if (!NOP_not_too_old) {
559 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);
561 if (!NOP_not_too_close_and_have_to_slowdown) {
562 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);
565 mrpt::math::TPose2D rel_cur_pose_wrt_last_vel_cmd_NOP(0,0,0), rel_pose_PTG_origin_wrt_sense_NOP(0,0,0);
567 if (can_do_nop_motion)
571 "CAbstractPTGBasedReactive::performNavigationStep().eval_NOP");
584 bool valid_odom, valid_pose;
589 if (valid_odom && valid_pose)
591 ASSERT_(last_sent_ptg!=
nullptr);
593 std::vector<TPose2D> relTargets_NOPs;
595 targets.begin(), targets.end(),
596 std::back_inserter(relTargets_NOPs),
609 newLogRec.
additional_debug_msgs[
"rel_cur_pose_wrt_last_vel_cmd_NOP(interp)"] = rel_cur_pose_wrt_last_vel_cmd_NOP.asString();
610 newLogRec.
additional_debug_msgs[
"robot_odom_at_send_cmd(interp)"] = robot_odom_at_send_cmd.asString();
618 relTargets_NOPs, rel_pose_PTG_origin_wrt_sense_NOP,
624 rel_cur_pose_wrt_last_vel_cmd_NOP);
630 candidate_movs[nPTGs].speed = -0.01;
639 int best_ptg_idx =
m_multiobjopt->decide(candidate_movs, mo_info);
645 for (
unsigned int i = 0; i < newLogRec.
infoPerPTG.size(); i++) {
657 if (best_ptg_idx >= 0) {
658 selectedHolonomicMovement = &candidate_movs[best_ptg_idx];
662 const bool best_is_NOP_cmdvel = (best_ptg_idx==int(nPTGs));
667 mrpt::kinematics::CVehicleVelCmdPtr new_vel_cmd;
668 if (best_is_NOP_cmdvel)
673 doEmergencyStop(
"\nERROR calling changeSpeedsNOP()!! Stopping robot and finishing navigation\n");
682 rel_cur_pose_wrt_last_vel_cmd_NOP,
683 rel_pose_PTG_origin_wrt_sense_NOP,
686 tim_start_iteration);
694 for (
size_t i = 0; i < nPTGs; i++) {
700 double cmd_vel_speed_ratio = 1.0;
701 if (selectedHolonomicMovement)
704 m_timelogger,
"navigationStep.selectedHolonomicMovement");
705 cmd_vel_speed_ratio =
710 if (!new_vel_cmd || new_vel_cmd->isStopCmd()) {
711 MRPT_LOG_DEBUG(
"Best velocity command is STOP (no way found), calling robot.stop()");
723 newLogRec.
timestamps[
"tim_send_cmd_vel"] = tim_send_cmd_vel;
726 doEmergencyStop(
"\nERROR calling changeSpeeds()!! Stopping robot and finishing navigation\n");
736 rel_cur_pose_wrt_last_vel_cmd_NOP,
737 rel_pose_PTG_origin_wrt_sense_NOP,
740 tim_start_iteration);
767 newLogRec.
values[
"timoff_sendVelCmd"] = timoff_sendVelCmd;
798 "T=%.01lfms Exec:%.01lfms|%.01lfms " 800 new_vel_cmd ? new_vel_cmd->asString().c_str() :
"NOP",
801 selectedHolonomicMovement ? selectedHolonomicMovement->
speed : .0,
816 rel_cur_pose_wrt_last_vel_cmd_NOP,
817 rel_pose_PTG_origin_wrt_sense_NOP,
820 tim_start_iteration);
823 catch (std::exception &e) {
827 doEmergencyStop(
"[CAbstractPTGBasedReactive::performNavigationStep] Stopping robot and finishing navigation due to untyped exception." );
832 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)
838 m_navProfiler,
"CAbstractPTGBasedReactive::STEP8_GenerateLogRecord()");
850 newLogRec.
cmd_vel = new_vel_cmd;
852 newLogRec.
values[
"executionTime"] = executionTimeValue;
854 newLogRec.
values[
"time_changeSpeeds()"] = tim_changeSpeed;
858 newLogRec.
timestamps[
"tim_start_iteration"] = tim_start_iteration;
860 newLogRec.
nPTGs = nPTGs;
881 if (
m_logFile) (*m_logFile) << newLogRec;
892 const std::vector<double> & in_TPObstacles,
894 const std::vector<mrpt::math::TPose2D> & WS_Targets,
895 const std::vector<CAbstractPTGBasedReactive::PTGTarget> & TP_Targets,
898 const bool this_is_PTG_continuation,
900 const unsigned int ptg_idx4weights,
902 const mrpt::nav::CHolonomicLogFileRecordPtr &hlfr)
907 "CAbstractPTGBasedReactive::calc_move_candidate_scores()");
918 size_t selected_trg_idx = 0;
920 double best_trg_angdist = std::numeric_limits<double>::max();
921 for (
size_t i = 0; i < TP_Targets.size(); i++)
924 if (angdist < best_trg_angdist) {
925 best_trg_angdist = angdist;
926 selected_trg_idx = i;
930 ASSERT_(selected_trg_idx<WS_Targets.size());
931 const auto WS_Target = WS_Targets[selected_trg_idx];
932 const auto TP_Target = TP_Targets[selected_trg_idx];
934 const double target_d_norm = TP_Target.target_dist;
938 const double target_WS_d = WS_Target.norm();
941 const double d =
std::min( in_TPObstacles[ move_k ], 0.99*target_d_norm);
959 const double f =
std::min(1.0,Vf + target_WS_d*(1.0-Vf)/TARGET_SLOW_APPROACHING_DISTANCE);
967 cm.
props[
"ptg_idx"] = ptg_idx4weights;
968 cm.
props[
"ref_dist"] = ref_dist;
969 cm.
props[
"target_dir"] = TP_Target.target_alpha;
970 cm.
props[
"target_k"] = TP_Target.target_k;
971 cm.
props[
"target_d_norm"] = target_d_norm;
972 cm.
props[
"move_k"] = move_k;
973 double & move_cur_d = cm.
props[
"move_cur_d"] = 0;
974 cm.
props[
"is_PTG_cont"] = this_is_PTG_continuation ? 1 : 0;
975 cm.
props[
"num_paths"] = in_TPObstacles.size();
976 cm.
props[
"WS_target_x"] = WS_Target.x;
977 cm.
props[
"WS_target_y"] = WS_Target.y;
978 cm.
props[
"robpose_x"] = pose.
x;
979 cm.
props[
"robpose_y"] = pose.
y;
982 const bool is_slowdown =
983 this_is_PTG_continuation ?
986 target_d_norm < 0.99 * in_TPObstacles[move_k]);
987 cm.
props[
"is_slowdown"] = is_slowdown ? 1:0;
988 cm.
props[
"holo_stage_eval"] =
989 this_is_PTG_continuation ?
992 (hlfr && !hlfr->dirs_eval.empty() && hlfr->dirs_eval.rbegin()->size() == in_TPObstacles.size()) ? hlfr->dirs_eval.rbegin()->at(move_k) : .0
997 double & colfree = cm.
props[
"collision_free_distance"];
1000 colfree = in_TPObstacles[move_k];
1005 if (this_is_PTG_continuation)
1008 double cur_norm_d=.0;
1009 bool is_exact, is_time_based =
false;
1014 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) {
1015 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);
1019 is_time_based =
true;
1039 newLogRec.
additional_debug_msgs[
"PTG_eval"] =
"PTG-continuation not allowed, cur. pose out of PTG domain.";
1042 bool WS_point_is_unique =
true;
1054 WS_point_is_unique =
1055 WS_point_is_unique &&
1059 "isBijectiveAt(): k=%i step=%i -> %s",
1060 static_cast<int>(cur_k), static_cast<int>(cur_ptg_step),
1061 WS_point_is_unique ?
"yes" :
"no");
1063 if (!WS_point_is_unique)
1067 cur_ptg_step = predicted_step;
1086 (!is_slowdown || (target_d_norm - cur_norm_d)*ref_dist>2.0 )
1090 newLogRec.
additional_debug_msgs[
"PTG_eval"] =
"PTG-continuation not allowed, mismatchDistance above threshold.";
1096 newLogRec.
additional_debug_msgs[
"PTG_eval"] =
"PTG-continuation not allowed, couldn't get PTG step for cur. robot pose.";
1106 colfree = WS_point_is_unique ?
1107 std::min(in_TPObstacles[move_k], in_TPObstacles[cur_k])
1109 in_TPObstacles[move_k];
1112 if (colfree < 0.99) {
1113 colfree -= cur_norm_d;
1117 move_cur_d = cur_norm_d;
1127 typedef std::map<double, double> map_d2d_t;
1128 map_d2d_t pathDists;
1130 const int num_steps = ceil( D * 2.0);
1131 for (
int i = 0; i < num_steps; i++) {
1132 pathDists[i / double(num_steps)] = 100.0;
1137 const auto it = std::min_element(
1138 pathDists.begin(), pathDists.end(),
1139 [colfree](map_d2d_t::value_type& l, map_d2d_t::value_type&
r) ->
bool {
1140 return (l.second <
r.second) && l.first<colfree;
1148 double &hysteresis = cm.
props[
"hysteresis"];
1153 hysteresis = this_is_PTG_continuation ? 1.0 : 0.;
1157 mrpt::kinematics::CVehicleVelCmdPtr desired_cmd;
1161 if(
typeid(*ptr1) ==
typeid(*ptr2)){
1164 double simil_score = 0.5;
1165 for (
size_t i = 0; i < desired_cmd->getVelCmdLength(); i++)
1167 const double scr = exp(-std::abs(desired_cmd->getVelCmdElement(i) -
m_last_vel_cmd->getVelCmdElement(i)) / 0.20);
1170 hysteresis = simil_score;
1177 double &clearance = cm.
props[
"clearance"];
1178 clearance = in_clearance.
getClearance(move_k, target_d_norm*1.01,
false );
1179 cm.
props[
"clearance_50p"] = in_clearance.
getClearance(move_k, target_d_norm*0.5,
false );
1180 cm.
props[
"clearance_path"] = in_clearance.
getClearance(move_k, target_d_norm*0.9,
true );
1181 cm.
props[
"clearance_path_50p"] = in_clearance.
getClearance(move_k, target_d_norm*0.5,
true );
1185 double &eta = cm.
props[
"eta"];
1190 const double path_len_meters = d * ref_dist;
1200 double discount_time = .0;
1201 if (this_is_PTG_continuation)
1208 eta -= discount_time;
1218 double cmdvel_speed_scale = 1.0;
1221 if (in_movement.
speed == 0)
1225 new_vel_cmd->setToStop();
1233 new_vel_cmd->cmdVel_scale(in_movement.
speed);
1234 cmdvel_speed_scale *= in_movement.
speed;
1246 catch (std::exception &e)
1250 return cmdvel_speed_scale;
1264 for (
size_t i=0;i<N;i++)
1268 const std::vector<double> & tp_obs =
m_infoPerPTG[i].TP_Obstacles;
1275 if (!is_into_domain)
1278 ASSERT_(wp_k<
int(tp_obs.size()));
1280 const double collision_free_dist = tp_obs[wp_k];
1281 if (collision_free_dist>1.01*wp_norm_d)
1309 ptg_alpha_index = -1;
1312 colfreedist_move_k = .0;
1313 was_slowdown =
false;
1316 original_holo_eval = .0;
1326 const size_t indexPTG,
1327 const std::vector<mrpt::math::TPose2D> &relTargets,
1332 const bool this_is_PTG_continuation,
1340 m_navProfiler,
"CAbstractPTGBasedReactive::build_movement_candidate()");
1344 const size_t idx_in_log_infoPerPTGs = this_is_PTG_continuation ?
getPTG_count() : indexPTG;
1346 CHolonomicLogFileRecordPtr HLFR;
1351 bool use_this_ptg =
true;
1356 use_this_ptg =
false;
1359 use_this_ptg =
true;
1364 double timeForTPObsTransformation = .0, timeForHolonomicMethod = .0;
1367 bool any_TPTarget_is_valid =
false;
1370 for (
size_t i=0;i<relTargets.size();i++)
1372 const auto & trg = relTargets[i];
1376 if (!ptg_target.
valid_TP)
continue;
1378 any_TPTarget_is_valid =
true;
1383 ipf.
targets.emplace_back(ptg_target);
1387 if (!any_TPTarget_is_valid)
1389 newLogRec.
additional_debug_msgs[
mrpt::format(
"mov_candidate_%u", static_cast<unsigned int>(indexPTG))] =
"PTG discarded since target(s) is(are) out of domain.";
1419 for (
size_t i = 0; i < Ki; i++) ipf.
TP_Obstacles[i] *= _refD;
1421 timeForTPObsTransformation =
tictac.
Tac();
1428 if (!this_is_PTG_continuation)
1444 for (
const auto &
t : ipf.
targets) {
1445 ni.
targets.push_back(
t.TP_Target );
1460 double obsFreeNormalizedDistance = ipf.
TP_Obstacles[kDirection];
1466 obsFreeNormalizedDistance =
std::min(obsFreeNormalizedDistance, std::max(0.90, obsFreeNormalizedDistance - d) );
1469 double velScale = 1.0;
1479 cm.
speed *= velScale;
1503 newLogRec.
infoPerPTG[idx_in_log_infoPerPTGs], newLogRec,
1504 this_is_PTG_continuation, rel_cur_pose_wrt_last_vel_cmd_NOP,
1506 tim_start_iteration,
1510 cm.
props[
"original_col_free_dist"] =
1511 this_is_PTG_continuation ?
1524 if (fill_log_record)
1527 if (!this_is_PTG_continuation)
1534 for (
const auto &
t : ipf.
targets) {
1549 robot_absolute_speed_limits.loadConfigFile(
c,
s);
1569 robot_absolute_speed_limits.saveToConfigFile(
c,
s);
1572 string lstHoloStr =
"# List of known classes:\n";
1575 for (
const auto &
c : lst)
1578 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);
1581 string lstDecidersStr =
"# List of known classes:\n";
1584 for (
const auto &
c : lst)
1590 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)");
1591 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.");
1592 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.");
1594 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)");
1595 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.");
1598 MRPT_SAVE_CONFIG_VAR_COMMENT(max_dist_for_timebased_path_prediction,
"Max dist [meters] to use time-based path prediction for NOP evaluation");
1603 ptg_cache_files_directory(
"."),
1605 speedfilter_tau(0.0),
1606 secure_distance_start(0.05),
1607 secure_distance_end(0.20),
1608 use_delays_model(false),
1609 max_distance_predicted_actual_path(0.15),
1610 min_normalized_free_space_for_ptg_continuation(0.2),
1611 robot_absolute_speed_limits(),
1612 enable_obstacle_filtering(true),
1613 evaluate_clearance(false),
1614 max_dist_for_timebased_path_prediction(2.0)
1634 filter->options.loadFromConfigFile(
c,
"CPointCloudFilterByDistance");
1667 filter.options.saveToConfigFile(
c,
"CPointCloudFilterByDistance");
1680 for (
const auto &cl : lst) {
1699 for (
const auto &cl : lst) {
1712 o->setTargetApproachSlowDownDistance(dist);
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...
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.
double original_holo_eval
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...
bool BASE_IMPEXP createDirectory(const std::string &dirName)
Creates a directory.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
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 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...
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...
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.
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:
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.
mrpt::utils::CStream * m_logFile
#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. 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.
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.
#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
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.
mrpt::system::TTimeStamp m_WS_Obstacles_timestamp
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,...)
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()
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...
bool STEP2_SenseObstacles()
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.
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.
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.
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)
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.
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].
double timeForTPObsTransformation
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.
mrpt::system::TTimeStamp timestamp
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't ever been called "enter" wit...
mrpt::system::TTimeStamp m_infoPerPTG_timestamp
#define MRPT_LOG_DEBUG(_STRING)
void enableApproachTargetSlowDown(bool enable)
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 starting_robot_dir
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
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.
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.
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...
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.
ClearanceDiagram clearance
Clearance for each path.
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.
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::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
static CMultiObjectiveMotionOptimizerBase * Create(const std::string &className) MRPT_NO_THROWS
Class factory from C++ class name.
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...
virtual void doEmergencyStop(const std::string &msg)
Stops the robot and set navigation state to error.
mrpt::utils::CTimeLogger m_navProfiler
Publicly available time profiling object.
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
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...
double Tac()
Stops the stopwatch.
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
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'th PTG.
double leave(const char *func_name)
End of a named section.
mrpt::math::LowPassFilter_IIR1 meanExecutionTime
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.
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...
TargetInfo target
Navigation target.
double m_last_curPoseVelUpdate_robot_time
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...
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) ...
virtual TNavigationParams * clone() const
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)
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)...
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...
TSentVelCmd m_lastSentVelCmd
struct BASE_IMPEXP CObjectPtr
A smart pointer to a CObject object.
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
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.
virtual void STEP1_InitPTGs()=0
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. ...
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)
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
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 target_dist
TP-Target.
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)...
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(). 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...
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.
double desiredSpeed
The results from the holonomic method.