Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
mrpt::nav::CPTG_Holo_Blend Class Reference

Detailed Description

A PTG for circular-shaped robots with holonomic kinematics.

Note
[New in MRPT 1.5.0]

Definition at line 28 of file CPTG_Holo_Blend.h.

#include <mrpt/nav/tpspace/CPTG_Holo_Blend.h>

Inheritance diagram for mrpt::nav::CPTG_Holo_Blend:
Inheritance graph

Public Member Functions

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) noexcept
 
void operator delete[] (void *ptr) noexcept
 
void operator delete (void *memory, void *ptr) noexcept
 
voidoperator new (size_t size, const std::nothrow_t &) noexcept
 
void operator delete (void *ptr, const std::nothrow_t &) noexcept
 
 CPTG_Holo_Blend ()
 
 CPTG_Holo_Blend (const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection)
 
virtual ~CPTG_Holo_Blend ()
 
virtual void loadFromConfigFile (const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection) override
 Parameters accepted by this base class: More...
 
virtual void saveToConfigFile (mrpt::utils::CConfigFileBase &cfg, const std::string &sSection) const override
 This method saves the options to a ".ini"-like file or memory-stored string list. More...
 
virtual void loadDefaultParams () override
 Loads a set of default parameters; provided exclusively for the PTG-configurator tool. More...
 
virtual bool supportVelCmdNOP () const override
 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). More...
 
virtual double maxTimeInVelCmdNOP (int path_k) const override
 Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path can be followed without re-issuing a new velcmd. More...
 
std::string getDescription () const override
 Gets a short textual description of the PTG and its parameters. More...
 
bool inverseMap_WS2TP (double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const override
 Computes the closest (alpha,d) TP coordinates of the trajectory point closest to the Workspace (WS) Cartesian coordinates (x,y), relative to the current robot frame. More...
 
bool PTG_IsIntoDomain (double x, double y) const override
 Returns the same than inverseMap_WS2TP() but without any additional cost. More...
 
void onNewNavDynamicState () override
 Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize paths depending on the instantaneous conditions. More...
 
virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand (uint16_t k) const override
 Converts a discretized "alpha" value into a feasible motion command or action. More...
 
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand () const override
 Returns an empty kinematic velocity command object of the type supported by this PTG. More...
 
size_t getPathStepCount (uint16_t k) const override
 Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete "steps" along the trajectory. More...
 
void getPathPose (uint16_t k, uint32_t step, mrpt::math::TPose2D &p) const override
 Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step. More...
 
double getPathDist (uint16_t k, uint32_t step) const override
 Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step. More...
 
bool getPathStepForDist (uint16_t k, double dist, uint32_t &out_step) const override
 Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < dist More...
 
double getPathStepDuration () const override
 Returns the duration (in seconds) of each "step". More...
 
double getMaxLinVel () const override
 Returns the maximum linear velocity expected from this PTG [m/s]. More...
 
double getMaxAngVel () const override
 Returns the maximum angular velocity expected from this PTG [rad/s]. More...
 
void updateTPObstacle (double ox, double oy, std::vector< double > &tp_obstacles) const override
 Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy) More...
 
void updateTPObstacleSingle (double ox, double oy, uint16_t k, double &tp_obstacle_k) const override
 Like updateTPObstacle() but for one direction only (k) in TP-Space. More...
 
void add_robotShape_to_setOfLines (mrpt::opengl::CSetOfLines &gl_shape, const mrpt::poses::CPose2D &origin=mrpt::poses::CPose2D()) const override
 Auxiliary function for rendering. More...
 
bool isPointInsideRobotShape (const double x, const double y) const override
 Returns true if the point lies within the robot shape. More...
 
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 dynamic conditions. More...
 
const TNavDynamicStategetCurrentNavDynamicState () const
 
void initialize (const std::string &cacheFilename=std::string(), const bool verbose=true)
 Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc. More...
 
void deinitialize ()
 This must be called to de-initialize the PTG if some parameter is to be changed. More...
 
bool isInitialized () const
 Returns true if initialize() has been called and there was no errors, so the PTG is ready to be queried for paths, obstacles, etc. More...
 
uint16_t getAlphaValuesCount () const
 Get the number of different, discrete paths in this family. More...
 
uint16_t getPathCount () const
 Get the number of different, discrete paths in this family. More...
 
double index2alpha (uint16_t k) const
 Alpha value for the discrete corresponding value. More...
 
uint16_t alpha2index (double alpha) const
 Discrete index value for the corresponding alpha value. More...
 
double getRefDistance () const
 
void initTPObstacles (std::vector< double > &TP_Obstacles) const
 Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ranges, in "pseudometers", un-normalized). More...
 
void initTPObstacleSingle (uint16_t k, double &TP_Obstacle_k) const
 
double getScorePriority () const
 When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG. More...
 
void setScorePriorty (double prior)
 
unsigned getClearanceStepCount () const
 
void setClearanceStepCount (const unsigned res)
 
unsigned getClearanceDecimatedPaths () const
 
void setClearanceDecimatedPaths (const unsigned num)
 
virtual void renderPathAsSimpleLine (const uint16_t k, mrpt::opengl::CSetOfLines &gl_obj, const double decimate_distance=0.1, const double max_path_distance=-1.0) const
 Returns the representation of one trajectory of this PTG as a 3D OpenGL object (a simple curved line). More...
 
bool debugDumpInFiles (const std::string &ptg_name) const
 Dump PTG trajectories in four text files: `. More...
 
void initClearanceDiagram (ClearanceDiagram &cd) const
 Must be called to resize a CD to its correct size, before calling updateClearance() More...
 
void updateClearance (const double ox, const double oy, ClearanceDiagram &cd) const
 Updates the clearance diagram given one (ox,oy) obstacle point, in coordinates relative to the PTG path origin. More...
 
void updateClearancePost (ClearanceDiagram &cd, const std::vector< double > &TP_obstacles) const
 
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 map<>, then keep in the map value the minimum of its current stored clearance, or the computed clearance. More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 
void loadFromConfigFileName (const std::string &config_file, const std::string &section)
 Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More...
 
void saveToConfigFileName (const std::string &config_file, const std::string &section) const
 Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More...
 
void dumpToConsole () const
 Just like dumpToTextStream() but sending the text to the console (std::cout) More...
 
virtual void dumpToTextStream (mrpt::utils::CStream &out) const
 This method should clearly display all the contents of the structure in textual form, sending it to a CStream. More...
 
Robot shape
void setRobotShapeRadius (const double robot_radius)
 Robot shape must be set before initialization, either from ctor params or via this method. More...
 
double getRobotShapeRadius () const
 
double getMaxRobotRadius () const override
 Returns an approximation of the robot radius. More...
 
virtual double evalClearanceToRobotShape (const double ox, const double oy) const override
 Evals the clearance from an obstacle (ox,oy) in coordinates relative to the robot center. More...
 
Virtual interface of each PTG implementation
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. More...
 
virtual void setRefDistance (const double refDist)
 
virtual bool supportSpeedAtTarget () const
 Returns true if this PTG takes into account the desired velocity at target. More...
 
virtual double getActualUnloopedPathLength (uint16_t k) const
 Returns the actual distance (in meters) of the path, discounting possible circular loops of the path (e.g. More...
 
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, if the k-th path is to be selected. More...
 
RTTI classes and functions
mrpt::utils::CObject::Ptr duplicateGetSmartPtr () const
 Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 
static double calc_trans_distance_t_below_Tramp (double k2, double k4, double vxi, double vyi, double t)
 Axiliary function for computing the line-integral distance along the trajectory, handling special cases of 1/0: More...
 
static double calc_trans_distance_t_below_Tramp_abc (double t, double a, double b, double c)
 Axiliary function for calc_trans_distance_t_below_Tramp() and others. More...
 
static CParameterizedTrajectoryGeneratorCreatePTG (const std::string &ptgClassName, const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection, const std::string &sKeyPrefix)
 The class factory for creating a PTG from a list of parameters in a section of a given config file (physical file or in memory). More...
 
static double index2alpha (uint16_t k, const unsigned int num_paths)
 
static uint16_t alpha2index (double alpha, const unsigned int num_paths)
 

Static Public Attributes

static double PATH_TIME_STEP
 Duration of each PTG "step" (default: 10e-3=10 ms) More...
 
static double eps
 Mathematical "epsilon", to detect ill-conditioned situations (e.g. More...
 
static std::string OUTPUT_DEBUG_PATH_PREFIX
 The path used as defaul output in, for example, debugDumpInFiles. More...
 
static PTG_collision_behavior_t COLLISION_BEHAVIOR
 Defines the behavior when there is an obstacle inside the robot shape right at the beginning of a PTG trajectory. More...
 

Protected Member Functions

double internal_get_v (const double dir) const
 Evals expr_v. More...
 
double internal_get_w (const double dir) const
 Evals expr_w. More...
 
double internal_get_T_ramp (const double dir) const
 Evals expr_T_ramp. More...
 
void internal_construct_exprs ()
 
void internal_processNewRobotShape () override
 Will be called whenever the robot shape is set / updated. More...
 
void internal_initialize (const std::string &cacheFilename=std::string(), const bool verbose=true) override
 Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc. More...
 
void internal_deinitialize () override
 This must be called to de-initialize the PTG if some parameter is to be changed. More...
 
void loadShapeFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &section)
 
void internal_shape_loadFromStream (mrpt::utils::CStream &in)
 
void internal_shape_saveToStream (mrpt::utils::CStream &out) const
 
void internal_TPObsDistancePostprocess (const double ox, const double oy, const double new_tp_obs_dist, double &inout_tp_obs) const
 To be called by implementors of updateTPObstacle() and updateTPObstacleSingle() to honor the user settings regarding COLLISION_BEHAVIOR. More...
 
virtual void internal_readFromStream (mrpt::utils::CStream &in)
 
virtual void internal_writeToStream (mrpt::utils::CStream &out) const
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const override
 Introduces a pure virtual method responsible for writing to a CStream. More...
 
void readFromStream (mrpt::utils::CStream &in, int version) override
 Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More...
 

Static Protected Member Functions

static void dumpVar_int (CStream &out, const char *varName, int v)
 Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More...
 
static void dumpVar_float (CStream &out, const char *varName, float v)
 
static void dumpVar_double (CStream &out, const char *varName, double v)
 
static void dumpVar_bool (CStream &out, const char *varName, bool v)
 
static void dumpVar_string (CStream &out, const char *varName, const std::string &v)
 

Protected Attributes

double T_ramp_max
 
double V_MAX
 
double W_MAX
 
double turningRadiusReference
 
std::string expr_V
 
std::string expr_W
 
std::string expr_T_ramp
 
std::vector< int > m_pathStepCountCache
 
mrpt::math::CRuntimeCompiledExpression m_expr_v
 
mrpt::math::CRuntimeCompiledExpression m_expr_w
 
mrpt::math::CRuntimeCompiledExpression m_expr_T_ramp
 
double m_expr_dir
 
double m_robotRadius
 
double refDistance
 
uint16_t m_alphaValuesCount
 The number of discrete values for "alpha" between -PI and +PI. More...
 
double m_score_priority
 
uint16_t m_clearance_num_points
 Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5) More...
 
uint16_t m_clearance_decimated_paths
 Number of paths for the decimated paths analysis of clearance. More...
 
TNavDynamicState m_nav_dyn_state
 Updated before each nav step by. More...
 
uint16_t m_nav_dyn_state_target_k
 Update in updateNavDynamicState(), contains the path index (k) for the target. More...
 
bool m_is_initialized
 

Static Protected Attributes

static const uint16_t INVALID_PTG_PATH_INDEX = static_cast<uint16_t>(-1)
 

RTTI stuff

using Ptr = std::shared_ptr< CPTG_Holo_Blend >
 
using ConstPtr = std::shared_ptr< const CPTG_Holo_Blend >
 
static mrpt::utils::CLASSINIT _init_CPTG_Holo_Blend
 
static const mrpt::utils::TRuntimeClassId runtimeClassId
 
static constexpr const char * className = "CPTG_Holo_Blend"
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
static const mrpt::utils::TRuntimeClassIdGetRuntimeClassIdStatic ()
 
static mrpt::utils::CObjectCreateObject ()
 
template<typename... Args>
static Ptr Create (Args &&... args)
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::utils::CObjectclone () const override
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Member Typedef Documentation

◆ ConstPtr

using mrpt::nav::CPTG_Holo_Blend::ConstPtr = std::shared_ptr<const CPTG_Holo_Blend >

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ Ptr

A typedef for the associated smart pointer

Definition at line 30 of file CPTG_Holo_Blend.h.

Constructor & Destructor Documentation

◆ CPTG_Holo_Blend() [1/2]

CPTG_Holo_Blend::CPTG_Holo_Blend ( )

Definition at line 799 of file CPTG_Holo_Blend.cpp.

References internal_construct_exprs().

Here is the call graph for this function:

◆ CPTG_Holo_Blend() [2/2]

CPTG_Holo_Blend::CPTG_Holo_Blend ( const mrpt::utils::CConfigFileBase cfg,
const std::string sSection 
)

Definition at line 805 of file CPTG_Holo_Blend.cpp.

References internal_construct_exprs(), and loadFromConfigFile().

Here is the call graph for this function:

◆ ~CPTG_Holo_Blend()

CPTG_Holo_Blend::~CPTG_Holo_Blend ( )
virtual

Definition at line 813 of file CPTG_Holo_Blend.cpp.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId* mrpt::nav::CPTG_Holo_Blend::_GetBaseClass ( )
staticprotected

◆ add_robotShape_to_setOfLines()

void CPTG_RobotShape_Circular::add_robotShape_to_setOfLines ( mrpt::opengl::CSetOfLines gl_shape,
const mrpt::poses::CPose2D origin = mrpt::poses::CPose2D() 
) const
overridevirtualinherited

◆ alpha2index() [1/2]

uint16_t CParameterizedTrajectoryGenerator::alpha2index ( double  alpha) const
inherited

◆ alpha2index() [2/2]

uint16_t CParameterizedTrajectoryGenerator::alpha2index ( double  alpha,
const unsigned int  num_paths 
)
staticinherited

Definition at line 208 of file CParameterizedTrajectoryGenerator.cpp.

References M_PI, mrpt::utils::round(), and mrpt::math::wrapToPi().

Here is the call graph for this function:

◆ calc_trans_distance_t_below_Tramp()

double CPTG_Holo_Blend::calc_trans_distance_t_below_Tramp ( double  k2,
double  k4,
double  vxi,
double  vyi,
double  t 
)
static

Axiliary function for computing the line-integral distance along the trajectory, handling special cases of 1/0:

Definition at line 152 of file CPTG_Holo_Blend.cpp.

References eps.

◆ calc_trans_distance_t_below_Tramp_abc()

double CPTG_Holo_Blend::calc_trans_distance_t_below_Tramp_abc ( double  t,
double  a,
double  b,
double  c 
)
static

Axiliary function for calc_trans_distance_t_below_Tramp() and others.

Definition at line 136 of file CPTG_Holo_Blend.cpp.

References calc_trans_distance_t_below_Tramp_abc_numeric().

Here is the call graph for this function:

◆ clone()

virtual mrpt::utils::CObject* mrpt::nav::CPTG_Holo_Blend::clone ( ) const
overridevirtual

Returns a deep copy (clone) of the object, indepently of its class.

Implements mrpt::utils::CObject.

◆ Create()

template<typename... Args>
static Ptr mrpt::nav::CPTG_Holo_Blend::Create ( Args &&...  args)
inlinestatic

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ CreateObject()

static mrpt::utils::CObject* mrpt::nav::CPTG_Holo_Blend::CreateObject ( )
static

◆ CreatePTG()

CParameterizedTrajectoryGenerator * CParameterizedTrajectoryGenerator::CreatePTG ( const std::string ptgClassName,
const mrpt::utils::CConfigFileBase cfg,
const std::string sSection,
const std::string sKeyPrefix 
)
staticinherited

The class factory for creating a PTG from a list of parameters in a section of a given config file (physical file or in memory).

Possible parameters are:

ptgClassName can be any PTG class name which has been registered as any other mrpt::utils::CSerializable class.

Exceptions
std::logic_errorOn invalid or missing parameters.

Definition at line 21 of file CParameterizedTrajectoryGenerator_factory.cpp.

References mrpt::utils::CConfigFilePrefixer::bind(), mrpt::utils::TRuntimeClassId::createObject(), mrpt::utils::findRegisteredClass(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), MRPT_END, MRPT_START, mrpt::utils::registerAllPendingClasses(), mrpt::utils::CConfigFilePrefixer::setPrefixes(), THROW_EXCEPTION_FMT, and mrpt::system::trim().

Referenced by mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), and mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ debugDumpInFiles()

bool CParameterizedTrajectoryGenerator::debugDumpInFiles ( const std::string ptg_name) const
inherited

Dump PTG trajectories in four text files: `.

/reactivenav.logs/PTGs/PTGi_{x,y,phi,d}.txt` Text files are loadable from MATLAB/Octave, and can be visualized with the script [MRPT_DIR]/scripts/viewPTG.m

Note
The directory "./reactivenav.logs/PTGs" will be created if doesn't exist.
Returns
false on any error writing to disk.
See also
OUTPUT_DEBUG_PATH_PREFIX

Definition at line 274 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::system::createDirectory(), mrpt::mrpt::format(), mrpt::nav::CParameterizedTrajectoryGenerator::getAlphaValuesCount(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), min, and mrpt::nav::CParameterizedTrajectoryGenerator::OUTPUT_DEBUG_PATH_PREFIX.

Here is the call graph for this function:

◆ deinitialize()

void CParameterizedTrajectoryGenerator::deinitialize ( )
inherited

This must be called to de-initialize the PTG if some parameter is to be changed.

After changing it, call initialize again

Definition at line 411 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::internal_deinitialize(), and mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.

Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ directionToMotionCommand()

mrpt::kinematics::CVehicleVelCmd::Ptr CPTG_Holo_Blend::directionToMotionCommand ( uint16_t  k) const
overridevirtual

Converts a discretized "alpha" value into a feasible motion command or action.

See derived classes for the meaning of these actions

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 425 of file CPTG_Holo_Blend.cpp.

References mrpt::kinematics::CVehicleVelCmd_Holo::dir_local, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::kinematics::CVehicleVelCmd_Holo::ramp_time, mrpt::kinematics::CVehicleVelCmd_Holo::rot_speed, mrpt::mrpt::utils::signWithZero(), and mrpt::kinematics::CVehicleVelCmd_Holo::vel.

Here is the call graph for this function:

◆ dumpToConsole()

void CLoadableOptions::dumpToConsole ( ) const
inherited

Just like dumpToTextStream() but sending the text to the console (std::cout)

Definition at line 44 of file CLoadableOptions.cpp.

References mrpt::utils::CLoadableOptions::dumpToTextStream(), and loadable_opts_my_cout.

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dumpToTextStream()

void CLoadableOptions::dumpToTextStream ( mrpt::utils::CStream out) const
virtualinherited

This method should clearly display all the contents of the structure in textual form, sending it to a CStream.

The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.

Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions, mrpt::maps::COccupancyGridMap2D::TInsertionOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams, mrpt::vision::TMatchingOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams, mrpt::hmtslam::CHMTSLAM::TOptions, mrpt::maps::CLandmarksMap::TLikelihoodOptions, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::CPointsMap::TLikelihoodOptions, mrpt::maps::CColouredPointsMap::TColourOptions, mrpt::vision::TStereoSystemParams, mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::TLikelihoodOptions, mrpt::maps::CLandmarksMap::TInsertionOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams, mrpt::maps::CPointsMap::TInsertionOptions, mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams, mrpt::slam::CRangeBearingKFSLAM::TOptions, mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams, mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams, mrpt::maps::CBeaconMap::TInsertionOptions, mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions, mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams, mrpt::maps::CMultiMetricMapPDF::TPredictionParams, mrpt::maps::CBeaconMap::TLikelihoodOptions, mrpt::slam::CRangeBearingKFSLAM2D::TOptions, mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::TInsertionOptions, mrpt::maps::CHeightGridMap2D::TInsertionOptions, mrpt::maps::TMapGenericParams, mrpt::vision::CFeatureExtraction::TOptions, mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams, mrpt::bayes::TKF_options, mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions, mrpt::graphslam::TSlidingWindow, mrpt::slam::CGridMapAligner::TConfigParams, mrpt::slam::CICP::TConfigParams, mrpt::maps::CReflectivityGridMap2D::TInsertionOptions, mrpt::graphslam::TUncertaintyPath< GRAPH_T >, mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions, mrpt::hmtslam::CTopLCDetector_FabMap::TOptions, mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions, mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions, mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions, mrpt::slam::CIncrementalMapPartitioner::TOptions, mrpt::maps::TMetricMapInitializer, mrpt::slam::CMetricMapBuilderICP::TConfigParams, mrpt::vision::CCamModel, and mrpt::slam::TKLDParams.

Definition at line 83 of file CLoadableOptions.cpp.

References mrpt::utils::CConfigFileMemory::getContent(), mrpt::utils::CStream::printf(), and mrpt::utils::CLoadableOptions::saveToConfigFile().

Referenced by mrpt::utils::CLoadableOptions::dumpToConsole().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dumpVar_bool()

void CLoadableOptions::dumpVar_bool ( CStream out,
const char *  varName,
bool  v 
)
staticprotectedinherited

Definition at line 65 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

Here is the call graph for this function:

◆ dumpVar_double()

void CLoadableOptions::dumpVar_double ( CStream out,
const char *  varName,
double  v 
)
staticprotectedinherited

Definition at line 59 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

Here is the call graph for this function:

◆ dumpVar_float()

void CLoadableOptions::dumpVar_float ( CStream out,
const char *  varName,
float  v 
)
staticprotectedinherited

Definition at line 54 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

Here is the call graph for this function:

◆ dumpVar_int()

void CLoadableOptions::dumpVar_int ( CStream out,
const char *  varName,
int  v 
)
staticprotectedinherited

Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.

Definition at line 49 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

Here is the call graph for this function:

◆ dumpVar_string()

void CLoadableOptions::dumpVar_string ( CStream out,
const char *  varName,
const std::string v 
)
staticprotectedinherited

Definition at line 71 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

Here is the call graph for this function:

◆ evalClearanceSingleObstacle()

void CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle ( const double  ox,
const double  oy,
const uint16_t  k,
ClearanceDiagram::dist2clearance_t inout_realdist2clearance,
bool  treat_as_obstacle = true 
) const
virtualinherited

Evals the robot clearance for each robot pose along path k, for the real distances in the key of the map<>, then keep in the map value the minimum of its current stored clearance, or the computed clearance.

In case of collision, clearance is zero.

Parameters
treat_as_obstacletrue: normal use for obstacles; false: compute shortest distances to a target point (no collision)

Definition at line 508 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_, mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceToRobotShape(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), mrpt::math::TPose2D::inverseComposePoint(), mrpt::mrpt::utils::keep_min(), mrpt::math::TPoint2D::norm(), mrpt::nav::CParameterizedTrajectoryGenerator::refDistance, mrpt::utils::round(), mrpt::math::TPoint2D::x, and mrpt::math::TPoint2D::y.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateClearance().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ evalClearanceToRobotShape()

double CPTG_RobotShape_Circular::evalClearanceToRobotShape ( const double  ox,
const double  oy 
) const
overridevirtualinherited

Evals the clearance from an obstacle (ox,oy) in coordinates relative to the robot center.

Zero or negative means collision.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 113 of file CPTG_RobotShape_Circular.cpp.

References mrpt::mrpt::math::hypot_fast(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.

Here is the call graph for this function:

◆ evalPathRelativePriority()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::evalPathRelativePriority ( uint16_t  k,
double  target_distance 
) const
inlinevirtualinherited

Query the PTG for the relative priority factor (0,1) of this PTG, in comparison to others, if the k-th path is to be selected.

Definition at line 294 of file CParameterizedTrajectoryGenerator.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().

Here is the caller graph for this function:

◆ getActualUnloopedPathLength()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getActualUnloopedPathLength ( uint16_t  k) const
inlinevirtualinherited

Returns the actual distance (in meters) of the path, discounting possible circular loops of the path (e.g.

if it comes back to the origin). Default: refDistance

Definition at line 287 of file CParameterizedTrajectoryGenerator.h.

References mrpt::nav::CParameterizedTrajectoryGenerator::refDistance.

◆ getAlphaValuesCount()

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::getAlphaValuesCount ( ) const
inlineinherited

◆ getClearanceDecimatedPaths()

unsigned mrpt::nav::CParameterizedTrajectoryGenerator::getClearanceDecimatedPaths ( ) const
inlineinherited

◆ getClearanceStepCount()

unsigned mrpt::nav::CParameterizedTrajectoryGenerator::getClearanceStepCount ( ) const
inlineinherited

◆ getCurrentNavDynamicState()

const TNavDynamicState& mrpt::nav::CParameterizedTrajectoryGenerator::getCurrentNavDynamicState ( ) const
inlineinherited

◆ getDescription()

std::string CPTG_Holo_Blend::getDescription ( ) const
overridevirtual

Gets a short textual description of the PTG and its parameters.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 259 of file CPTG_Holo_Blend.cpp.

References mrpt::mrpt::format().

Here is the call graph for this function:

◆ getMaxAngVel()

double mrpt::nav::CPTG_Holo_Blend::getMaxAngVel ( ) const
inlineoverridevirtual

Returns the maximum angular velocity expected from this PTG [rad/s].

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 69 of file CPTG_Holo_Blend.h.

References W_MAX.

◆ getMaxLinVel()

double mrpt::nav::CPTG_Holo_Blend::getMaxLinVel ( ) const
inlineoverridevirtual

Returns the maximum linear velocity expected from this PTG [m/s].

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 68 of file CPTG_Holo_Blend.h.

References V_MAX.

◆ getMaxRobotRadius()

double CPTG_RobotShape_Circular::getMaxRobotRadius ( ) const
overridevirtualinherited

Returns an approximation of the robot radius.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 102 of file CPTG_RobotShape_Circular.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.

◆ getPathCount()

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::getPathCount ( ) const
inlineinherited

Get the number of different, discrete paths in this family.

Definition at line 342 of file CParameterizedTrajectoryGenerator.h.

References mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), and TEST().

Here is the caller graph for this function:

◆ getPathDist()

double CPTG_Holo_Blend::getPathDist ( uint16_t  k,
uint32_t  step 
) const
overridevirtual

Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step.

Returns
Distance in pseudometers (real distance, NOT normalized to [0,1] for [0,refDist])
See also
getPathStepCount(), getAlphaValuesCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 519 of file CPTG_Holo_Blend.cpp.

References COMMON_PTG_DESIGN_PARAMS, and mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha().

Here is the call graph for this function:

◆ getPathPose()

void CPTG_Holo_Blend::getPathPose ( uint16_t  k,
uint32_t  step,
mrpt::math::TPose2D p 
) const
overridevirtual

Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step.

See also
getPathStepCount(), getAlphaValuesCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 462 of file CPTG_Holo_Blend.cpp.

References COMMON_PTG_DESIGN_PARAMS, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::mrpt::utils::signWithZero(), and mrpt::math::solve_poly2().

Here is the call graph for this function:

◆ getPathStepCount()

size_t CPTG_Holo_Blend::getPathStepCount ( uint16_t  k) const
overridevirtual

Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete "steps" along the trajectory.

May be actual steps from a numerical integration or an arbitrary small length for analytical PTGs.

See also
getAlphaValuesCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 441 of file CPTG_Holo_Blend.cpp.

References ASSERT_, and THROW_EXCEPTION_FMT.

◆ getPathStepDuration()

double CPTG_Holo_Blend::getPathStepDuration ( ) const
overridevirtual

Returns the duration (in seconds) of each "step".

See also
getPathStepCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 798 of file CPTG_Holo_Blend.cpp.

◆ getPathStepForDist()

bool CPTG_Holo_Blend::getPathStepForDist ( uint16_t  k,
double  dist,
uint32_t out_step 
) const
overridevirtual

Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < dist

Parameters
[in]distDistance in pseudometers (real distance, NOT normalized to [0,1] for [0,refDist])
Returns
false if no step fulfills the condition for the given trajectory k (e.g. out of reference distance). Note that, anyway, the maximum distance (closest point) is returned in out_step.
See also
getPathStepCount(), getAlphaValuesCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 543 of file CPTG_Holo_Blend.cpp.

References ASSERT_, COMMON_PTG_DESIGN_PARAMS, eps, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), PERFORMANCE_BENCHMARK, and mrpt::utils::round().

Here is the call graph for this function:

◆ getRefDistance()

double mrpt::nav::CParameterizedTrajectoryGenerator::getRefDistance ( ) const
inlineinherited

◆ getRobotShapeRadius()

double mrpt::nav::CPTG_RobotShape_Circular::getRobotShapeRadius ( ) const
inlineinherited

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId* mrpt::nav::CPTG_Holo_Blend::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

◆ GetRuntimeClassIdStatic()

static const mrpt::utils::TRuntimeClassId& mrpt::nav::CPTG_Holo_Blend::GetRuntimeClassIdStatic ( )
static

◆ getScorePriority()

double mrpt::nav::CParameterizedTrajectoryGenerator::getScorePriority ( ) const
inlineinherited

When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG.

Assign values <1 to PTGs with low priority.

Definition at line 361 of file CParameterizedTrajectoryGenerator.h.

References mrpt::nav::CParameterizedTrajectoryGenerator::m_score_priority.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().

Here is the caller graph for this function:

◆ getSupportedKinematicVelocityCommand()

mrpt::kinematics::CVehicleVelCmd::Ptr CPTG_Holo_Blend::getSupportedKinematicVelocityCommand ( ) const
overridevirtual

Returns an empty kinematic velocity command object of the type supported by this PTG.

Can be queried to determine the expected kinematic interface of the PTG.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 778 of file CPTG_Holo_Blend.cpp.

◆ index2alpha() [1/2]

double CParameterizedTrajectoryGenerator::index2alpha ( uint16_t  k) const
inherited

◆ index2alpha() [2/2]

double CParameterizedTrajectoryGenerator::index2alpha ( uint16_t  k,
const unsigned int  num_paths 
)
staticinherited

Definition at line 195 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_BELOW_, and M_PI.

◆ initClearanceDiagram()

void mrpt::nav::CParameterizedTrajectoryGenerator::initClearanceDiagram ( ClearanceDiagram cd) const
inherited

◆ initialize()

void CParameterizedTrajectoryGenerator::initialize ( const std::string cacheFilename = std::string(),
const bool  verbose = true 
)
inherited

Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc.

Definition at line 396 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::system::fileNameStripInvalidChars(), mrpt::nav::CParameterizedTrajectoryGenerator::getDescription(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_initialize(), and mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.

Here is the call graph for this function:

◆ initTPObstacles()

void CParameterizedTrajectoryGenerator::initTPObstacles ( std::vector< double > &  TP_Obstacles) const
inherited

Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ranges, in "pseudometers", un-normalized).

See also
updateTPObstacle()

Definition at line 258 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacleSingle(), and mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::PlannerTPS_VirtualBase::spaceTransformer(), and TEST().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initTPObstacleSingle()

void CParameterizedTrajectoryGenerator::initTPObstacleSingle ( uint16_t  k,
double &  TP_Obstacle_k 
) const
inherited

◆ internal_construct_exprs()

void CPTG_Holo_Blend::internal_construct_exprs ( )
protected

Definition at line 814 of file CPTG_Holo_Blend.cpp.

References expr_T_ramp, expr_V, expr_W, m_expr_dir, m_expr_T_ramp, m_expr_v, m_expr_w, T_ramp_max, V_MAX, and W_MAX.

Referenced by CPTG_Holo_Blend().

Here is the caller graph for this function:

◆ internal_deinitialize()

void CPTG_Holo_Blend::internal_deinitialize ( )
overrideprotectedvirtual

This must be called to de-initialize the PTG if some parameter is to be changed.

After changing it, call initialize again

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 420 of file CPTG_Holo_Blend.cpp.

◆ internal_get_T_ramp()

double CPTG_Holo_Blend::internal_get_T_ramp ( const double  dir) const
protected

Evals expr_T_ramp.

Definition at line 843 of file CPTG_Holo_Blend.cpp.

References m_expr_dir, and m_expr_T_ramp.

◆ internal_get_v()

double CPTG_Holo_Blend::internal_get_v ( const double  dir) const
protected

Evals expr_v.

Definition at line 833 of file CPTG_Holo_Blend.cpp.

References m_expr_dir, and m_expr_v.

◆ internal_get_w()

double CPTG_Holo_Blend::internal_get_w ( const double  dir) const
protected

Evals expr_w.

Definition at line 838 of file CPTG_Holo_Blend.cpp.

References m_expr_dir, and m_expr_w.

◆ internal_initialize()

void CPTG_Holo_Blend::internal_initialize ( const std::string cacheFilename = std::string(),
const bool  verbose = true 
)
overrideprotectedvirtual

◆ internal_processNewRobotShape()

void CPTG_Holo_Blend::internal_processNewRobotShape ( )
overrideprotectedvirtual

Will be called whenever the robot shape is set / updated.

Implements mrpt::nav::CPTG_RobotShape_Circular.

Definition at line 772 of file CPTG_Holo_Blend.cpp.

◆ internal_readFromStream()

void CParameterizedTrajectoryGenerator::internal_readFromStream ( mrpt::utils::CStream in)
protectedvirtualinherited

◆ internal_shape_loadFromStream()

void CPTG_RobotShape_Circular::internal_shape_loadFromStream ( mrpt::utils::CStream in)
protectedinherited

Definition at line 77 of file CPTG_RobotShape_Circular.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, and MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION.

Referenced by readFromStream().

Here is the caller graph for this function:

◆ internal_shape_saveToStream()

void CPTG_RobotShape_Circular::internal_shape_saveToStream ( mrpt::utils::CStream out) const
protectedinherited

Definition at line 93 of file CPTG_RobotShape_Circular.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.

Referenced by writeToStream().

Here is the caller graph for this function:

◆ internal_TPObsDistancePostprocess()

void CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess ( const double  ox,
const double  oy,
const double  new_tp_obs_dist,
double &  inout_tp_obs 
) const
protectedinherited

To be called by implementors of updateTPObstacle() and updateTPObstacleSingle() to honor the user settings regarding COLLISION_BEHAVIOR.

Parameters
new_tp_obs_distThe newly determiend collision-free ranges, in "pseudometers", un-normalized, for some "k" direction.
inout_tp_obsThe target where to store the new TP-Obs distance, if it fulfills the criteria determined by the collision behavior.

Definition at line 418 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::COLL_BEH_BACK_AWAY, mrpt::nav::COLL_BEH_STOP, mrpt::nav::CParameterizedTrajectoryGenerator::COLLISION_BEHAVIOR, mrpt::nav::CParameterizedTrajectoryGenerator::getMaxRobotRadius(), mrpt::nav::CParameterizedTrajectoryGenerator::isPointInsideRobotShape(), mrpt::mrpt::utils::keep_min(), and THROW_EXCEPTION.

Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::updateTPObstacle(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::updateTPObstacleSingle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ internal_writeToStream()

void CParameterizedTrajectoryGenerator::internal_writeToStream ( mrpt::utils::CStream out) const
protectedvirtualinherited

◆ inverseMap_WS2TP()

bool CPTG_Holo_Blend::inverseMap_WS2TP ( double  x,
double  y,
int &  out_k,
double &  out_normalized_d,
double  tolerance_dist = 0.10 
) const
overridevirtual

Computes the closest (alpha,d) TP coordinates of the trajectory point closest to the Workspace (WS) Cartesian coordinates (x,y), relative to the current robot frame.

Parameters
[in]xX coordinate of the query point, relative to the robot frame.
[in]yY coordinate of the query point, relative to the robot frame.
[out]out_kTrajectory parameter index (discretized alpha value, 0-based index).
[out]out_dTrajectory distance, normalized such that D_max becomes 1.
Returns
true if the distance between (x,y) and the actual trajectory point is below the given tolerance (in meters).

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 314 of file CPTG_Holo_Blend.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::alpha2index(), ASSERT_, MRPT_UNUSED_PARAM, PERFORMANCE_BENCHMARK, and mrpt::mrpt::math::square().

Here is the call graph for this function:

◆ isBijectiveAt()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::isBijectiveAt ( uint16_t  k,
uint32_t  step 
) const
inlinevirtualinherited

Returns true if a given TP-Space point maps to a unique point in Workspace, and viceversa.

Default implementation returns true.

Definition at line 151 of file CParameterizedTrajectoryGenerator.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().

Here is the caller graph for this function:

◆ isInitialized()

bool CParameterizedTrajectoryGenerator::isInitialized ( ) const
inherited

Returns true if initialize() has been called and there was no errors, so the PTG is ready to be queried for paths, obstacles, etc.

Definition at line 350 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.

◆ isPointInsideRobotShape()

bool CPTG_RobotShape_Circular::isPointInsideRobotShape ( const double  x,
const double  y 
) const
overridevirtualinherited

Returns true if the point lies within the robot shape.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 107 of file CPTG_RobotShape_Circular.cpp.

References mrpt::mrpt::math::hypot_fast(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.

Here is the call graph for this function:

◆ loadDefaultParams()

void CPTG_Holo_Blend::loadDefaultParams ( )
overridevirtual

Loads a set of default parameters; provided exclusively for the PTG-configurator tool.

Reimplemented from mrpt::nav::CPTG_RobotShape_Circular.

Definition at line 189 of file CPTG_Holo_Blend.cpp.

References mrpt::mrpt::utils::DEG2RAD(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), and mrpt::nav::CPTG_RobotShape_Circular::loadDefaultParams().

Here is the call graph for this function:

◆ loadFromConfigFile()

void CPTG_Holo_Blend::loadFromConfigFile ( const mrpt::utils::CConfigFileBase cfg,
const std::string sSection 
)
overridevirtual

Parameters accepted by this base class:

  • ${sKeyPrefix}num_paths: The number of different paths in this family (number of discrete alpha values).
  • ${sKeyPrefix}ref_distance: The maximum distance in PTGs [meters]
  • ${sKeyPrefix}score_priority: When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG. Assign values <1 to PTGs with low priority.

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 200 of file CPTG_Holo_Blend.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::loadShapeFromConfigFile(), MRPT_LOAD_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR_DEGREES_NO_DEFAULT, and MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT.

Referenced by CPTG_Holo_Blend().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadFromConfigFileName()

void CLoadableOptions::loadFromConfigFileName ( const std::string config_file,
const std::string section 
)
inherited

Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.

See also
loadFromConfigFile

Definition at line 22 of file CLoadableOptions.cpp.

References mrpt::utils::CLoadableOptions::loadFromConfigFile().

Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadShapeFromConfigFile()

void CPTG_RobotShape_Circular::loadShapeFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string section 
)
protectedinherited

Definition at line 28 of file CPTG_RobotShape_Circular.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::internal_processNewRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, and MRPT_LOAD_HERE_CONFIG_VAR.

Referenced by loadFromConfigFile().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ maxTimeInVelCmdNOP()

double CPTG_Holo_Blend::maxTimeInVelCmdNOP ( int  path_k) const
overridevirtual

Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path can be followed without re-issuing a new velcmd.

Note that this is only an absolute maximum duration, navigation implementations will check for many other conditions. Default method in the base virtual class returns 0.

Parameters
path_kQueried path k index [0,N-1]

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 785 of file CPTG_Holo_Blend.cpp.

◆ onNewNavDynamicState()

void CPTG_Holo_Blend::onNewNavDynamicState ( )
overridevirtual

Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize paths depending on the instantaneous conditions.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 184 of file CPTG_Holo_Blend.cpp.

◆ operator delete() [1/3]

void mrpt::nav::CPTG_Holo_Blend::operator delete ( void ptr,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator delete() [2/3]

void mrpt::nav::CPTG_Holo_Blend::operator delete ( void memory,
void ptr 
)
inlinenoexcept

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator delete() [3/3]

void mrpt::nav::CPTG_Holo_Blend::operator delete ( void ptr)
inlinenoexcept

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator delete[]()

void mrpt::nav::CPTG_Holo_Blend::operator delete[] ( void ptr)
inlinenoexcept

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator new() [1/3]

void* mrpt::nav::CPTG_Holo_Blend::operator new ( size_t  size,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator new() [2/3]

static void* mrpt::nav::CPTG_Holo_Blend::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator new() [3/3]

void* mrpt::nav::CPTG_Holo_Blend::operator new ( size_t  size)
inline

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ operator new[]()

void* mrpt::nav::CPTG_Holo_Blend::operator new[] ( size_t  size)
inline

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ PTG_IsIntoDomain()

bool CPTG_Holo_Blend::PTG_IsIntoDomain ( double  x,
double  y 
) const
overridevirtual

Returns the same than inverseMap_WS2TP() but without any additional cost.

The default implementation just calls inverseMap_WS2TP() and discards (k,d).

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 413 of file CPTG_Holo_Blend.cpp.

◆ readFromStream()

void CPTG_Holo_Blend::readFromStream ( mrpt::utils::CStream in,
int  version 
)
overrideprotectedvirtual

Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any error, see CStream::ReadBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 266 of file CPTG_Holo_Blend.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CPTG_RobotShape_Circular::internal_shape_loadFromStream(), and MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION.

Here is the call graph for this function:

◆ renderPathAsSimpleLine()

void CParameterizedTrajectoryGenerator::renderPathAsSimpleLine ( const uint16_t  k,
mrpt::opengl::CSetOfLines gl_obj,
const double  decimate_distance = 0.1,
const double  max_path_distance = -1.0 
) const
virtualinherited

Returns the representation of one trajectory of this PTG as a 3D OpenGL object (a simple curved line).

Parameters
[in]kThe 0-based index of the selected trajectory (discrete "alpha" parameter).
[out]gl_objOutput object.
[in]decimate_distanceMinimum distance between path points (in meters).
[in]max_path_distanceIf >=0, cut the path at this distance (in meters).

Definition at line 223 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::opengl::CSetOfLines::appendLine(), mrpt::opengl::CSetOfLines::appendLineStrip(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose(), and mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount().

Referenced by mrpt::nav::PlannerTPS_VirtualBase::renderMoveTree().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ saveToConfigFile()

void CPTG_Holo_Blend::saveToConfigFile ( mrpt::utils::CConfigFileBase target,
const std::string section 
) const
overridevirtual

This method saves the options to a ".ini"-like file or memory-stored string list.

See also
loadFromConfigFile, saveToConfigFileName

Reimplemented from mrpt::nav::CPTG_RobotShape_Circular.

Definition at line 218 of file CPTG_Holo_Blend.cpp.

References MRPT_END, MRPT_START, mrpt::mrpt::utils::RAD2DEG(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::saveToConfigFile(), and mrpt::utils::CConfigFileBase::write().

Here is the call graph for this function:

◆ saveToConfigFileName()

void CLoadableOptions::saveToConfigFileName ( const std::string config_file,
const std::string section 
) const
inherited

Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.

See also
saveToConfigFile, loadFromConfigFileName

Definition at line 37 of file CLoadableOptions.cpp.

References mrpt::utils::CLoadableOptions::saveToConfigFile().

Here is the call graph for this function:

◆ setClearanceDecimatedPaths()

void mrpt::nav::CParameterizedTrajectoryGenerator::setClearanceDecimatedPaths ( const unsigned  num)
inlineinherited

◆ setClearanceStepCount()

void mrpt::nav::CParameterizedTrajectoryGenerator::setClearanceStepCount ( const unsigned  res)
inlineinherited

◆ setRefDistance()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::setRefDistance ( const double  refDist)
inlinevirtualinherited

◆ setRobotShapeRadius()

void CPTG_RobotShape_Circular::setRobotShapeRadius ( const double  robot_radius)
inherited

Robot shape must be set before initialization, either from ctor params or via this method.

Definition at line 21 of file CPTG_RobotShape_Circular.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::internal_processNewRobotShape(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.

Referenced by mrpt::nav::PlannerTPS_VirtualBase::internal_initialize_PTG(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), and mrpt::nav::CReactiveNavigationSystem3D::STEP1_InitPTGs().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setScorePriorty()

void mrpt::nav::CParameterizedTrajectoryGenerator::setScorePriorty ( double  prior)
inlineinherited

◆ supportSpeedAtTarget()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::supportSpeedAtTarget ( ) const
inlinevirtualinherited

Returns true if this PTG takes into account the desired velocity at target.

See also
updateNavDynamicState()

Definition at line 273 of file CParameterizedTrajectoryGenerator.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState().

Here is the caller graph for this function:

◆ supportVelCmdNOP()

bool CPTG_Holo_Blend::supportVelCmdNOP ( ) const
overridevirtual

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).

Default implementation returns "false".

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 784 of file CPTG_Holo_Blend.cpp.

◆ updateClearance()

void CParameterizedTrajectoryGenerator::updateClearance ( const double  ox,
const double  oy,
ClearanceDiagram cd 
) const
inherited

Updates the clearance diagram given one (ox,oy) obstacle point, in coordinates relative to the PTG path origin.

Parameters
[in,out]cdThe clearance will be updated here.
See also
m_clearance_dist_resolution

Definition at line 484 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_, mrpt::nav::ClearanceDiagram::decimated_k_to_real_k(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::ClearanceDiagram::get_actual_num_paths(), mrpt::nav::ClearanceDiagram::get_decimated_num_paths(), mrpt::nav::ClearanceDiagram::get_path_clearance_decimated(), mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, and mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points.

Referenced by mrpt::nav::CReactiveNavigationSystem::STEP3_WSpaceToTPSpace().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateClearancePost()

void CParameterizedTrajectoryGenerator::updateClearancePost ( ClearanceDiagram cd,
const std::vector< double > &  TP_obstacles 
) const
inherited

Definition at line 502 of file CParameterizedTrajectoryGenerator.cpp.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate().

Here is the caller graph for this function:

◆ updateNavDynamicState()

void CParameterizedTrajectoryGenerator::updateNavDynamicState ( const TNavDynamicState newState,
const bool  force_update = false 
)
inherited

◆ updateTPObstacle()

void CPTG_Holo_Blend::updateTPObstacle ( double  ox,
double  oy,
std::vector< double > &  tp_obstacles 
) const
overridevirtual

Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy)

Parameters
[in,out]tp_obstaclesA vector of length getAlphaValuesCount(), initialized with initTPObstacles() (collision-free ranges, in "pseudometers", un-normalized).
[in]oxObstacle point (X), relative coordinates wrt origin of the PTG.
[in]oyObstacle point (Y), relative coordinates wrt origin of the PTG.
Note
The length of tp_obstacles is not checked for efficiency since this method is potentially called thousands of times per navigation timestap, so it is left to the user responsibility to provide a valid buffer.
tp_obstacles must be initialized with initTPObstacle() before call.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 761 of file CPTG_Holo_Blend.cpp.

References PERFORMANCE_BENCHMARK.

◆ updateTPObstacleSingle()

void CPTG_Holo_Blend::updateTPObstacleSingle ( double  ox,
double  oy,
uint16_t  k,
double &  tp_obstacle_k 
) const
overridevirtual

Like updateTPObstacle() but for one direction only (k) in TP-Space.

tp_obstacle_k must be initialized with initTPObstacleSingle() before call (collision-free ranges, in "pseudometers", un-normalized).

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 638 of file CPTG_Holo_Blend.cpp.

References COMMON_PTG_DESIGN_PARAMS, eps, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::mrpt::utils::keep_min(), min, R, mrpt::math::solve_poly3(), and mrpt::math::solve_poly4().

Here is the call graph for this function:

◆ writeToMatlab()

virtual mxArray* mrpt::utils::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB.

Definition at line 89 of file CSerializable.h.

◆ writeToStream()

void CPTG_Holo_Blend::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
overrideprotectedvirtual

Introduces a pure virtual method responsible for writing to a CStream.

This can not be used directly be users, instead use "stream << object;" for writing it to a stream.

Parameters
outThe output binary stream where object must be dumped.
getVersionIf nullptr, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data.
Exceptions
std::exceptionOn any error, see CStream::WriteBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 298 of file CPTG_Holo_Blend.cpp.

References mrpt::nav::CPTG_RobotShape_Circular::internal_shape_saveToStream(), and mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream().

Here is the call graph for this function:

Member Data Documentation

◆ _init_CPTG_Holo_Blend

mrpt::utils::CLASSINIT mrpt::nav::CPTG_Holo_Blend::_init_CPTG_Holo_Blend
staticprotected

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ className

constexpr const char* mrpt::nav::CPTG_Holo_Blend::className = "CPTG_Holo_Blend"
static

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ COLLISION_BEHAVIOR

PTG_collision_behavior_t CParameterizedTrajectoryGenerator::COLLISION_BEHAVIOR
staticinherited
Initial value:

Defines the behavior when there is an obstacle inside the robot shape right at the beginning of a PTG trajectory.

Default value: COLL_BEH_BACK_AWAY

Definition at line 428 of file CParameterizedTrajectoryGenerator.h.

Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess().

◆ eps

double mrpt::nav::CPTG_Holo_Blend::eps
static

Mathematical "epsilon", to detect ill-conditioned situations (e.g.

1/0) (Default: 1e-4)

Definition at line 79 of file CPTG_Holo_Blend.h.

◆ expr_T_ramp

std::string mrpt::nav::CPTG_Holo_Blend::expr_T_ramp
protected

Definition at line 86 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), and internal_initialize().

◆ expr_V

std::string mrpt::nav::CPTG_Holo_Blend::expr_V
protected

Definition at line 86 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), and internal_initialize().

◆ expr_W

std::string mrpt::nav::CPTG_Holo_Blend::expr_W
protected

Definition at line 86 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), and internal_initialize().

◆ INVALID_PTG_PATH_INDEX

const uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::INVALID_PTG_PATH_INDEX = static_cast<uint16_t>(-1)
staticprotectedinherited

◆ m_alphaValuesCount

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount
protectedinherited

◆ m_clearance_decimated_paths

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_decimated_paths
protectedinherited

◆ m_clearance_num_points

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points
protectedinherited

◆ m_expr_dir

double mrpt::nav::CPTG_Holo_Blend::m_expr_dir
protected

◆ m_expr_T_ramp

mrpt::math::CRuntimeCompiledExpression mrpt::nav::CPTG_Holo_Blend::m_expr_T_ramp
protected

◆ m_expr_v

mrpt::math::CRuntimeCompiledExpression mrpt::nav::CPTG_Holo_Blend::m_expr_v
protected

Definition at line 90 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), internal_get_v(), and internal_initialize().

◆ m_expr_w

mrpt::math::CRuntimeCompiledExpression mrpt::nav::CPTG_Holo_Blend::m_expr_w
protected

Definition at line 90 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), internal_get_w(), and internal_initialize().

◆ m_is_initialized

bool mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized
protectedinherited

◆ m_nav_dyn_state

TNavDynamicState mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state
protectedinherited

◆ m_nav_dyn_state_target_k

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state_target_k
protectedinherited

◆ m_pathStepCountCache

std::vector<int> mrpt::nav::CPTG_Holo_Blend::m_pathStepCountCache
mutableprotected

Definition at line 87 of file CPTG_Holo_Blend.h.

Referenced by internal_initialize().

◆ m_robotRadius

double mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius
protectedinherited

◆ m_score_priority

double mrpt::nav::CParameterizedTrajectoryGenerator::m_score_priority
protectedinherited

◆ OUTPUT_DEBUG_PATH_PREFIX

std::string CParameterizedTrajectoryGenerator::OUTPUT_DEBUG_PATH_PREFIX
staticinherited
Initial value:
=
"./reactivenav.logs"

The path used as defaul output in, for example, debugDumpInFiles.

(Default="./reactivenav.logs/")

Definition at line 325 of file CParameterizedTrajectoryGenerator.h.

Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles().

◆ PATH_TIME_STEP

double mrpt::nav::CPTG_Holo_Blend::PATH_TIME_STEP
static

Duration of each PTG "step" (default: 10e-3=10 ms)

Definition at line 76 of file CPTG_Holo_Blend.h.

◆ refDistance

double mrpt::nav::CParameterizedTrajectoryGenerator::refDistance
protectedinherited

◆ runtimeClassId

const mrpt::utils::TRuntimeClassId mrpt::nav::CPTG_Holo_Blend::runtimeClassId
staticprotected

Definition at line 30 of file CPTG_Holo_Blend.h.

◆ T_ramp_max

double mrpt::nav::CPTG_Holo_Blend::T_ramp_max
protected

Definition at line 82 of file CPTG_Holo_Blend.h.

Referenced by internal_construct_exprs(), and internal_initialize().

◆ turningRadiusReference

double mrpt::nav::CPTG_Holo_Blend::turningRadiusReference
protected

Definition at line 84 of file CPTG_Holo_Blend.h.

◆ V_MAX

double mrpt::nav::CPTG_Holo_Blend::V_MAX
protected

Definition at line 83 of file CPTG_Holo_Blend.h.

Referenced by getMaxLinVel(), internal_construct_exprs(), and internal_initialize().

◆ W_MAX

double mrpt::nav::CPTG_Holo_Blend::W_MAX
protected

Definition at line 83 of file CPTG_Holo_Blend.h.

Referenced by getMaxAngVel(), internal_construct_exprs(), and internal_initialize().




Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019