9 #ifndef CAbstractPTGBasedReactive_H
10 #define CAbstractPTGBasedReactive_H
98 bool enableConsoleOutput =
true,
99 bool enableLogFile =
false,
113 void setHolonomicMethod(const std::
string & method, const
mrpt::utils::CConfigFileBase & cfgBase);
125 void enableKeepLogRecords(
bool enable=true) { m_enableKeepLogRecords=enable; }
128 void enableLogFile(
bool enable);
186 m_timelogger.enable(enable);
206 void setTargetApproachSlowDownDistance(
const double dist);
207 double getTargetApproachSlowDownDistance()
const;
214 mrpt::utils::CStream *m_logFile, *m_prev_logfile;
215 bool m_enableKeepLogRecords;
217 mrpt::kinematics::CVehicleVelCmdPtr m_last_vel_cmd ;
219 mrpt::synch::CCriticalSectionRecursive m_critZoneLastLog;
221 bool m_enableConsoleOutput;
223 mrpt::utils::CTicTac timerForExecutionPeriod;
225 mrpt::utils::CTimeLogger m_timelogger;
226 bool m_PTGsMustBeReInitialized;
230 mrpt::utils::CTicTac totalExecutionTime, executionTime, tictac;
231 mrpt::math::LowPassFilter_IIR1 meanExecutionTime;
232 mrpt::math::LowPassFilter_IIR1 meanTotalExecutionTime;
233 mrpt::math::LowPassFilter_IIR1 meanExecutionPeriod;
234 mrpt::math::LowPassFilter_IIR1 tim_changeSpeed_avr, timoff_obstacles_avr, timoff_curPoseAndSpeed_avr, timoff_sendVelCmd_avr;
237 virtual
bool impl_waypoint_is_reachable(const
mrpt::math::TPoint2D &wp_local_wrt_robot) const
MRPT_OVERRIDE;
241 virtual
void STEP1_InitPTGs() = 0;
244 virtual
bool implementSenseObstacles(
mrpt::system::
TTimeStamp &obs_timestamp) = 0;
245 bool STEP2_SenseObstacles();
250 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;
267 const std::vector<double> & in_TPObstacles,
269 const std::vector<mrpt::math::TPose2D> & WS_Targets,
270 const std::vector<PTGTarget> & TP_Targets,
273 const bool this_is_PTG_continuation,
275 const unsigned int ptg_idx4weights,
279 virtual double generate_vel_cmd(
const TCandidateMovementPTG &in_movement, mrpt::kinematics::CVehicleVelCmdPtr &new_vel_cmd );
280 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);
281 void preDestructor();
284 bool m_closing_navigator;
289 mrpt::nav::CMultiObjectiveMotionOptimizerBasePtr m_multiobjopt;
303 const size_t indexPTG,
304 const std::vector<mrpt::math::TPose2D> &relTargets,
309 const bool this_is_PTG_continuation,
327 bool isValid()
const;
335 void deleteHolonomicObjects();
A base class for holonomic reactive navigation methods.
Base class for reactive navigator systems based on TP-Space, with an arbitrary holonomic reactive met...
void setLogFileDirectory(const std::string &sDir)
Changes the prefix for new log files.
TNavigationParams * m_copy_prev_navParams
A copy of last-iteration navparams, used to detect changes.
mrpt::system::TTimeStamp m_infoPerPTG_timestamp
TAbstractPTGNavigatorParams params_abstract_ptg_navigator
virtual size_t getPTG_count() const =0
Returns the number of different PTGs that have been setup.
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & changeCurrentRobotSpeedLimits()
Changes the current, global (honored for all PTGs) robot speed limits, via returning a reference to a...
virtual const CParameterizedTrajectoryGenerator * getPTG(size_t i) const =0
Gets the i'th PTG.
virtual CParameterizedTrajectoryGenerator * getPTG(size_t i)=0
Gets the i'th PTG.
void enableTimeLog(bool enable=true)
Enables/disables the detailed time logger (default:disabled upon construction) When enabled,...
std::vector< TInfoPerPTG > m_infoPerPTG
Temporary buffers for working with each PTG during a navigationStep()
TSentVelCmd m_lastSentVelCmd
const mrpt::utils::CTimeLogger & getTimeLogger() const
Gives access to a const-ref to the internal time logger.
const mrpt::kinematics::CVehicleVelCmd::TVelCmdParams & getCurrentRobotSpeedLimits() const
Get the current, global (honored for all PTGs) robot speed limits.
std::string getLogFileDirectory() const
std::string m_navlogfiles_dir
Default: "./reactivenav.logs".
A class for storing, saving and loading a reactive navigation log record for the CReactiveNavigationS...
This is the base class for any user-defined PTG.
The pure virtual interface between a real or simulated robot and any CAbstractNavigator-derived class...
This class extends CAbstractNavigator with the capability of following a list of waypoints.
Clearance information for one particular PTG and one set of obstacles.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle.
This class allows loading and storing values and vectors of different types from a configuration text...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X),...
GLubyte GLubyte GLubyte a
GLuint const GLchar * name
GLsizei const GLchar ** string
THolonomicMethod
The implemented reactive navigation methods.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
#define MRPT_MAKE_ALIGNED_OPERATOR_NEW
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
#define MRPT_DEPRECATED(msg)
Usage: MRPT_DEPRECATED("Use XX instead") void myFunc(double);.
stlplus::smart_ptr< CPointCloudFilterBase > CPointCloudFilterBasePtr
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Parameters that may be used by cmdVel_limits() in any derived classes.
Base for all high-level navigation commands.
The struct for configuring navigation requests.
int target_k
The discrete version of target_alpha.
bool valid_TP
For each PTG, whether target falls into the PTG domain.
mrpt::math::TPoint2D TP_Target
The Target, in TP-Space (x,y)
mrpt::kinematics::CVehicleVelCmd::TVelCmdParams robot_absolute_speed_limits
Params related to speed limits.
double secure_distance_end
double min_normalized_free_space_for_ptg_continuation
Min normalized dist [0,1] after current pose in a PTG continuation to allow it.
std::string ptg_cache_files_directory
(Default: ".")
std::string holonomic_method
C++ class name of the holonomic navigation method to run in the transformed TP-Space.
double max_dist_for_timebased_path_prediction
Max dist [meters] to use time-based path prediction for NOP evaluation.
bool enable_obstacle_filtering
bool evaluate_clearance
Default: false.
std::string motion_decider_method
C++ class name of the motion chooser.
double speedfilter_tau
Time constant (in seconds) for the low-pass filter applied to kinematic velocity commands (default=0:...
double max_distance_predicted_actual_path
Max distance [meters] to discard current PTG and issue a new vel cmd (default= 0.05)
double ref_distance
Maximum distance up to obstacles will be considered (D_{max} in papers).
std::vector< PTGTarget > targets
std::vector< double > TP_Obstacles
One distance per discretized alpha value, describing the "polar plot" of TP obstacles.
ClearanceDiagram clearance
Clearance for each path.
The struct for configuring navigation requests to CAbstractPTGBasedReactive and derived classes.
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...
int ptg_alpha_index
Path index for selected PTG.
double speed_scale
[0,1] scale of the raw cmd_vel as generated by the PTG
int ptg_index
0-based index of used PTG
TRobotPoseVel poseVel
Robot pose & velocities and timestamp of when it was queried.
double colfreedist_move_k
TP-Obstacles in the move direction at the instant of picking this movement.
CParameterizedTrajectoryGenerator::TNavDynamicState ptg_dynState
mrpt::system::TTimeStamp tim_send_cmd_vel
Timestamp of when the cmd was sent.
The structure used to store all relevant information about each transformation into TP-Space.
Dynamic state that may affect the PTG path parameterization.
The struct for configuring navigation requests to CWaypointsNavigator and derived classes.
Stores a candidate movement in TP-Space-based navigation.