9 #ifndef CAbstractPTGBasedReactive_H    10 #define CAbstractPTGBasedReactive_H    99                         bool enableConsoleOutput = 
true,
   100                         bool enableLogFile = 
false,
   114                 void setHolonomicMethod(const 
std::
string & method, const 
mrpt::utils::CConfigFileBase & cfgBase);
   126                 void enableKeepLogRecords(
bool enable=true) { m_enableKeepLogRecords=enable; }
   129                 void enableLogFile(
bool enable);
   187                         m_timelogger.enable(enable);
   193                 virtual size_t getPTG_count() 
const = 0;  
   207                 void setTargetApproachSlowDownDistance(
const double dist);  
   208                 double getTargetApproachSlowDownDistance() 
const;  
   215                 mrpt::utils::CStream  *m_logFile, *m_prev_logfile;         
   216                 bool                   m_enableKeepLogRecords; 
   218                 mrpt::kinematics::CVehicleVelCmdPtr m_last_vel_cmd ; 
   220                 mrpt::synch::CCriticalSectionRecursive  m_critZoneLastLog; 
   222                 bool    m_enableConsoleOutput;  
   224                 mrpt::utils::CTicTac    timerForExecutionPeriod;
   226                 mrpt::utils::CTimeLogger m_timelogger; 
   227                 bool  m_PTGsMustBeReInitialized;
   231                 mrpt::utils::CTicTac totalExecutionTime, executionTime, tictac;
   232                 mrpt::math::LowPassFilter_IIR1  meanExecutionTime;
   233                 mrpt::math::LowPassFilter_IIR1  meanTotalExecutionTime;
   234                 mrpt::math::LowPassFilter_IIR1  meanExecutionPeriod;    
   235                 mrpt::math::LowPassFilter_IIR1  tim_changeSpeed_avr, timoff_obstacles_avr, timoff_curPoseAndSpeed_avr, timoff_sendVelCmd_avr;
   238                 virtual 
bool impl_waypoint_is_reachable(const 
mrpt::math::TPoint2D &wp_local_wrt_robot) const 
MRPT_OVERRIDE; 
   242                 virtual 
void STEP1_InitPTGs() = 0;
   245                 virtual 
bool implementSenseObstacles(
mrpt::system::
TTimeStamp &obs_timestamp) = 0;
   246                 bool STEP2_SenseObstacles();
   251                 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;
   254                 virtual 
void loggingGetWSObstaclesAndShape(
CLogFileRecord &out_log) = 0;
   268                         const std::vector<double>        & in_TPObstacles,
   270                         const std::vector<mrpt::math::TPose2D>  & WS_Targets,
   271                         const std::vector<PTGTarget> & TP_Targets,
   274                         const bool this_is_PTG_continuation,
   276                         const unsigned int ptg_idx4weights,
   278                         const mrpt::nav::CHolonomicLogFileRecordPtr &hlfr);
   281                 virtual double generate_vel_cmd(
const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmdPtr &new_vel_cmd );
   282                 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);
   283                 void preDestructor(); 
   286                 bool m_closing_navigator; 
   291                 mrpt::nav::CMultiObjectiveMotionOptimizerBasePtr m_multiobjopt;
   305                         const size_t indexPTG,
   306                         const std::vector<mrpt::math::TPose2D> &relTargets,
   311                         const bool this_is_PTG_continuation,
   330                         bool isValid() 
const;
   338                 void deleteHolonomicObjects(); 
 uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
 
double original_holo_eval
 
const mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & getCurrentRobotSpeedLimits() const
Get the current, global (honored for all PTGs) robot speed limits. 
 
#define MRPT_MAKE_ALIGNED_OPERATOR_NEW
 
#define MRPT_OVERRIDE
C++11 "override" for virtuals: 
 
double m_expr_var_num_paths
 
TRobotPoseVel poseVel
Robot pose & velocities and timestamp of when it was queried. 
 
Base for all high-level navigation commands. 
 
void setLogFileDirectory(const std::string &sDir)
Changes the prefix for new log files. 
 
A base class for holonomic reactive navigation methods. 
 
std::string holonomic_method
C++ class name of the holonomic navigation method to run in the transformed TP-Space. 
 
Clearance information for one particular PTG and one set of obstacles. 
 
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. 
 
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...
 
The struct for configuring navigation requests to CWaypointsNavigator and derived classes...
 
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) 
 
The struct for configuring navigation requests. 
 
This is the base class for any user-defined PTG. 
 
double speed_scale
[0,1] scale of the raw cmd_vel as generated by the PTG 
 
TNavigationParams * m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes. 
 
double min_normalized_free_space_for_ptg_continuation
Min normalized dist [0,1] after current pose in a PTG continuation to allow it. 
 
stlplus::smart_ptr< CPointCloudFilterBase > CPointCloudFilterBasePtr
 
std::string motion_decider_method
C++ class name of the motion chooser. 
 
double max_dist_for_timebased_path_prediction
Max dist [meters] to use time-based path prediction for NOP evaluation. 
 
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
 
std::string getLogFileDirectory() const
 
mrpt::system::TTimeStamp m_infoPerPTG_timestamp
 
const mrpt::utils::CTimeLogger & getTimeLogger() const
Gives access to a const-ref to the internal time logger. 
 
GLsizei const GLchar ** string
 
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
 
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
 
THolonomicMethod
The implemented reactive navigation methods. 
 
std::string ptg_cache_files_directory
(Default: ".") 
 
double speedfilter_tau
Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0:...
 
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits. 
 
ClearanceDiagram clearance
Clearance for each path. 
 
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. 
 
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() 
 
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
 
TAbstractPTGNavigatorParams params_abstract_ptg_navigator
 
#define MRPT_DEPRECATED(msg)
Usage: MRPT_DEPRECATED("Use XX instead") void myFunc(double);. 
 
GLuint const GLchar * name
 
std::string m_navlogfiles_dir
Default: "./reactivenav.logs". 
 
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats. 
 
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & changeCurrentRobotSpeedLimits()
Changes the current, global (honored for all PTGs) robot speed limits, via returning a reference to a...
 
void enableTimeLog(bool enable=true)
Enables/disables the detailed time logger (default:disabled upon construction) When enabled...
 
double ref_distance
Maximum distance up to obstacles will be considered (D_{max} in papers). 
 
bool valid_TP
For each PTG, whether target falls into the PTG domain. 
 
The struct for configuring navigation requests to CAbstractPTGBasedReactive and derived classes...
 
double max_distance_predicted_actual_path
Max distance [meters] to discard current PTG and issue a new vel cmd (default= 0.05) ...
 
TSentVelCmd m_lastSentVelCmd
 
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
 
int ptg_alpha_index
Path index for selected PTG. 
 
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent. 
 
Parameters that may be used by cmdVel_limits() in any derived classes. 
 
GLubyte GLubyte GLubyte a
 
Dynamic state that may affect the PTG path parameterization. 
 
double target_dist
TP-Target. 
 
The structure used to store all relevant information about each transformation into TP-Space...
 
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
 
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...
 
Stores a candidate movement in TP-Space-based navigation.