MRPT  2.0.4
List of all members | Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
mrpt::nav::CParameterizedTrajectoryGenerator Class Referenceabstract

Detailed Description

This is the base class for any user-defined PTG.

There is a class factory interface in CParameterizedTrajectoryGenerator::CreatePTG.

Papers:

Changes history:

Definition at line 78 of file CParameterizedTrajectoryGenerator.h.

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

Inheritance diagram for mrpt::nav::CParameterizedTrajectoryGenerator:

Classes

struct  TNavDynamicState
 Dynamic state that may affect the PTG path parameterization. More...
 

Public Types

using UniquePtr = std::unique_ptr< CObject >
 
using ConstUniquePtr = std::unique_ptr< const CObject >
 

Public Member Functions

 CParameterizedTrajectoryGenerator ()
 Default ctor. More...
 
 ~CParameterizedTrajectoryGenerator () override=default
 Destructor. 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 loadFromConfigFile (const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
 Parameters accepted by this base class: More...
 
void saveToConfigFile (mrpt::config::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 add_robotShape_to_setOfLines (mrpt::opengl::CSetOfLines &gl_shape, const mrpt::poses::CPose2D &origin=mrpt::poses::CPose2D()) const =0
 Auxiliary function for rendering. 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...
 
virtual CObjectclone () const =0
 Returns a deep copy (clone) of the object, indepently of its 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 (std::ostream &out) const
 This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. More...
 
RTTI classes and functions for polymorphic hierarchies
mrpt::rtti::CObject::Ptr duplicateGetSmartPtr () const
 Makes a deep copy of the object and returns a smart pointer to it. More...
 

Static Public Member Functions

static CParameterizedTrajectoryGenerator::Ptr CreatePTG (const std::string &ptgClassName, const mrpt::config::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 std::string & OUTPUT_DEBUG_PATH_PREFIX ()
 The path used as defaul output in, for example, debugDumpInFiles. More...
 
static double index2alpha (uint16_t k, const unsigned int num_paths)
 
static uint16_t alpha2index (double alpha, const unsigned int num_paths)
 
static PTG_collision_behavior_tCOLLISION_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

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::serialization::CArchive &in)
 
virtual void internal_writeToStream (mrpt::serialization::CArchive &out) const
 
CSerializable virtual methods
virtual uint8_t serializeGetVersion () const =0
 Must return the current versioning number of the object. More...
 
virtual void serializeTo (CArchive &out) const =0
 Pure virtual method for writing (serializing) to an abstract archive. More...
 
virtual void serializeTo (CSchemeArchiveBase &out) const
 Virtual method for writing (serializing) to an abstract schema based archive. More...
 
virtual void serializeFrom (CArchive &in, uint8_t serial_version)=0
 Pure virtual method for reading (deserializing) from an abstract archive. More...
 
virtual void serializeFrom (CSchemeArchiveBase &in)
 Virtual method for reading (deserializing) from an abstract schema based archive. More...
 

Static Protected Member Functions

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

Protected Attributes

double refDistance {.0}
 
uint16_t m_alphaValuesCount {0}
 The number of discrete values for "alpha" between -PI and +PI. More...
 
double m_score_priority {1.0}
 
uint16_t m_clearance_num_points {5}
 Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5) More...
 
uint16_t m_clearance_decimated_paths {15}
 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 {false}
 

Static Protected Attributes

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

RTTI stuff

using Ptr = std::shared_ptr< CParameterizedTrajectoryGenerator >
 
using ConstPtr = std::shared_ptr< const CParameterizedTrajectoryGenerator >
 
static const mrpt::rtti::TRuntimeClassId runtimeClassId
 
static const mrpt::rtti::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
static const mrpt::rtti::TRuntimeClassIdGetRuntimeClassIdStatic ()
 

Virtual interface of each PTG implementation

virtual std::string getDescription () const =0
 Gets a short textual description of the PTG and its parameters. More...
 
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) Cartesian coordinates (x,y), relative to the current robot frame. More...
 
virtual bool PTG_IsIntoDomain (double x, double y) const
 Returns the same than inverseMap_WS2TP() but without any additional cost. More...
 
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 mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand (uint16_t k) const =0
 Converts a discretized "alpha" value into a feasible motion command or action. More...
 
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand () const =0
 Returns an empty kinematic velocity command object of the type supported by this PTG. More...
 
virtual void setRefDistance (const double refDist)
 
virtual size_t getPathStepCount (uint16_t k) const =0
 Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete "steps" along the trajectory. More...
 
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. More...
 
virtual mrpt::math::TPose2D getPathPose (uint16_t k, uint32_t step) const
 
virtual mrpt::math::TTwist2D getPathTwist (uint16_t k, uint32_t step) const
 Gets velocity ("twist") for path k ([0,N-1]=>[-pi,pi] in alpha), at vehicle discrete step step. More...
 
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. More...
 
virtual double getPathStepDuration () const =0
 Returns the duration (in seconds) of each "step". More...
 
virtual double getMaxLinVel () const =0
 Returns the maximum linear velocity expected from this PTG [m/s]. More...
 
virtual double getMaxAngVel () const =0
 Returns the maximum angular velocity expected from this PTG [rad/s]. More...
 
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 < dist More...
 
virtual void updateTPObstacle (double ox, double oy, std::vector< double > &tp_obstacles) const =0
 Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy) More...
 
virtual void updateTPObstacleSingle (double ox, double oy, uint16_t k, double &tp_obstacle_k) const =0
 Like updateTPObstacle() but for one direction only (k) in TP-Space. More...
 
virtual void loadDefaultParams ()
 Loads a set of default parameters into the PTG. More...
 
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). More...
 
virtual bool supportSpeedAtTarget () const
 Returns true if this PTG takes into account the desired velocity at target. More...
 
virtual double maxTimeInVelCmdNOP (int path_k) const
 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...
 
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...
 
virtual double getMaxRobotRadius () const =0
 Returns an approximation of the robot radius. More...
 
virtual bool isPointInsideRobotShape (const double x, const double y) const =0
 Returns true if the point lies within the robot shape. More...
 
virtual double evalClearanceToRobotShape (const double ox, const double oy) const =0
 Evals the clearance from an obstacle (ox,oy) in coordinates relative to the robot center. More...
 
virtual void internal_initialize (const std::string &cacheFilename=std::string(), const bool verbose=true)=0
 Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc. More...
 
virtual void internal_deinitialize ()=0
 This must be called to de-initialize the PTG if some parameter is to be changed. More...
 
virtual void onNewNavDynamicState ()=0
 Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize paths depending on the instantaneous conditions. More...
 

Member Typedef Documentation

◆ ConstPtr

Definition at line 82 of file CParameterizedTrajectoryGenerator.h.

◆ ConstUniquePtr

using mrpt::rtti::CObject::ConstUniquePtr = std::unique_ptr<const CObject>
inherited

Definition at line 187 of file CObject.h.

◆ Ptr

Definition at line 82 of file CParameterizedTrajectoryGenerator.h.

◆ UniquePtr

using mrpt::rtti::CObject::UniquePtr = std::unique_ptr<CObject>
inherited

Definition at line 186 of file CObject.h.

Constructor & Destructor Documentation

◆ CParameterizedTrajectoryGenerator()

mrpt::nav::CParameterizedTrajectoryGenerator::CParameterizedTrajectoryGenerator ( )

Default ctor.

Must call loadFromConfigFile() before initialization

◆ ~CParameterizedTrajectoryGenerator()

mrpt::nav::CParameterizedTrajectoryGenerator::~CParameterizedTrajectoryGenerator ( )
overridedefault

Destructor.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::rtti::TRuntimeClassId* mrpt::nav::CParameterizedTrajectoryGenerator::_GetBaseClass ( )
staticprotected

◆ add_robotShape_to_setOfLines()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::add_robotShape_to_setOfLines ( mrpt::opengl::CSetOfLines gl_shape,
const mrpt::poses::CPose2D origin = mrpt::poses::CPose2D() 
) const
pure virtual

Auxiliary function for rendering.

Implemented in mrpt::nav::CPTG_RobotShape_Circular, and mrpt::nav::CPTG_RobotShape_Polygonal.

◆ alpha2index() [1/2]

uint16_t CParameterizedTrajectoryGenerator::alpha2index ( double  alpha) const

Discrete index value for the corresponding alpha value.

See also
index2alpha

Definition at line 223 of file CParameterizedTrajectoryGenerator.cpp.

References m_alphaValuesCount.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::generate_vel_cmd(), mrpt::nav::CPTG_Holo_Blend::inverseMap_WS2TP(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and mrpt::nav::ClearanceDiagram::renderAs3DObject().

Here is the caller graph for this function:

◆ alpha2index() [2/2]

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

Definition at line 213 of file CParameterizedTrajectoryGenerator.cpp.

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

Here is the call graph for this function:

◆ clone()

virtual CObject* mrpt::rtti::CObject::clone ( ) const
pure virtualinherited

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

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_ND, mrpt::nav::CLogFileRecord_FullEval, mrpt::img::CImage, mrpt::maps::CMultiMetricMap, mrpt::obs::CObservationIMU, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationVelodyneScan, mrpt::maps::TMapGenericParams, mrpt::maps::CRandomFieldGridMap3D, mrpt::hmtslam::THypothesisIDSet, mrpt::detectors::CDetectable3D, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::opengl::COctoMapVoxels, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::obs::CRawlog, mrpt::opengl::COpenGLViewport, mrpt::obs::CObservationRotatingScan, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::opengl::COpenGLScene, mrpt::slam::CIncrementalMapPartitioner, mrpt::vision::CFeature, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CObservation2DRangeScan, mrpt::opengl::CFrustum, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::poses::CPose2DInterpolator, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CPointCloud, mrpt::opengl::CPointCloudColoured, mrpt::poses::CPose3DQuat, mrpt::opengl::CPolyhedron, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CAssimpModel, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CText3D, mrpt::maps::COctoMap, mrpt::opengl::CBox, mrpt::opengl::CEllipsoid2D, mrpt::poses::CPose2D, mrpt::maps::CReflectivityGridMap2D, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CEllipsoid3D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CVectorField3D, mrpt::poses::CPose3DPDFGaussian, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMesh, mrpt::opengl::CMeshFast, mrpt::poses::CPosePDFParticles, MyNS::Bar, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::opengl::CMesh3D, mrpt::opengl::CVectorField2D, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CColorBar, mrpt::maps::CBeacon, mrpt::maps::COccupancyGridMap3D, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::opengl::CText, mrpt::maps::CRBPFParticleData, mrpt::maps::CLandmark, mrpt::maps::CHeightGridMap2D_MRF, mrpt::opengl::CCamera, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::obs::CObservationPointCloud, mrpt::opengl::CSetOfLines, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::obs::CObservationBatteryState, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CSimplePointsMap, mrpt::obs::CActionRobotMovement2D, mrpt::opengl::CDisk, mrpt::maps::CColouredPointsMap, mrpt::maps::CWeightedPointsMap, mrpt::nav::CLogFileRecord, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CAxis, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::opengl::CSphere, mrpt::poses::CPointPDFParticles, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::poses::CPosePDFGaussian, MyNS::MyDerived2, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CPointsMapXYZI, mrpt::nav::CMultiObjMotionOpt_Scalarization, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::opengl::CSetOfObjects, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::poses::CPose3DPDFGrid, mrpt::obs::CObservationVisualLandmarks, mrpt::math::CMatrixD, mrpt::math::CSplineInterpolator1D, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::poses::CPoses2DSequence, mrpt::img::TStereoCamera, mrpt::poses::CPoses3DSequence, mrpt::math::CMatrixF, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrixB, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::opengl::CSetOfTexturedTriangles, MyNS::MyDerived1, mrpt::math::CPolygon, mrpt::opengl::CTexturedPlane, mrpt::poses::CPoint2DPDFGaussian, MyNS::Foo, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, mrpt::opengl::CSimpleLine, and MyNS::Foo.

Referenced by mrpt::rtti::CObject::duplicateGetSmartPtr(), mrpt::maps::CSimpleMap::insert(), mrpt::obs::CActionCollection::insert(), and mrpt::poses::CPoseRandomSampler::setPosePDF().

Here is the caller graph for this function:

◆ COLLISION_BEHAVIOR()

PTG_collision_behavior_t & CParameterizedTrajectoryGenerator::COLLISION_BEHAVIOR ( )
static

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 31 of file CParameterizedTrajectoryGenerator.cpp.

References COLLISION_BEHAVIOR.

Referenced by internal_TPObsDistancePostprocess().

Here is the caller graph for this function:

◆ CreatePTG()

CParameterizedTrajectoryGenerator::Ptr CParameterizedTrajectoryGenerator::CreatePTG ( const std::string &  ptgClassName,
const mrpt::config::CConfigFileBase cfg,
const std::string &  sSection,
const std::string &  sKeyPrefix 
)
static

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::serialization::CSerializable class.

Exceptions
std::logic_errorOn invalid or missing parameters.

Definition at line 22 of file CParameterizedTrajectoryGenerator_factory.cpp.

References mrpt::config::CConfigFilePrefixer::bind(), mrpt::rtti::TRuntimeClassId::createObject(), mrpt::rtti::findRegisteredClass(), mrpt::ptr_cast< CAST_TO >::from(), MRPT_END, MRPT_START, mrpt::rtti::registerAllPendingClasses(), mrpt::config::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

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 279 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::system::createDirectory(), mrpt::format(), getAlphaValuesCount(), getPathDist(), getPathPose(), getPathStepCount(), OUTPUT_DEBUG_PATH_PREFIX(), mrpt::math::TPose2D::phi, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

Here is the call graph for this function:

◆ deinitialize()

void CParameterizedTrajectoryGenerator::deinitialize ( )

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 415 of file CParameterizedTrajectoryGenerator.cpp.

References internal_deinitialize(), and m_is_initialized.

Referenced by internal_readFromStream().

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

◆ directionToMotionCommand()

virtual mrpt::kinematics::CVehicleVelCmd::Ptr mrpt::nav::CParameterizedTrajectoryGenerator::directionToMotionCommand ( uint16_t  k) const
pure virtual

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

See derived classes for the meaning of these actions

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

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

Here is the caller 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 43 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::dumpToTextStream().

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::ros1bridge::MapHdl::loadMap(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::printParams(), and mrpt::apps::CGridMapAlignerApp::run().

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

◆ dumpToTextStream()

void CLoadableOptions::dumpToTextStream ( std::ostream &  out) const
virtualinherited

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

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::hmtslam::CHMTSLAM::TOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams, mrpt::maps::CLandmarksMap::TLikelihoodOptions, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::CPointsMap::TRenderOptions, mrpt::maps::CPointsMap::TLikelihoodOptions, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions, mrpt::vision::TStereoSystemParams, mrpt::maps::CLandmarksMap::TInsertionOptions, mrpt::maps::CPointsMap::TInsertionOptions, mrpt::maps::CColouredPointsMap::TColourOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams, mrpt::slam::CRangeBearingKFSLAM::TOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams, mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams, mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams, mrpt::maps::CBeaconMap::TInsertionOptions, mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams, 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::CHeightGridMap2D::TInsertionOptions, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions, mrpt::vision::CFeatureExtraction::TOptions, mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams, mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions, mrpt::bayes::TKF_options, mrpt::graphslam::TSlidingWindow, mrpt::maps::CReflectivityGridMap2D::TInsertionOptions, mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions, mrpt::slam::CGridMapAligner::TConfigParams, mrpt::hmtslam::CTopLCDetector_FabMap::TOptions, mrpt::graphslam::TUncertaintyPath< GRAPH_T >, mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions, mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions, mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions, mrpt::maps::TMetricMapInitializer, mrpt::slam::CMetricMapBuilderICP::TConfigParams, and mrpt::slam::TKLDParams.

Definition at line 76 of file CLoadableOptions.cpp.

References mrpt::config::CConfigFileMemory::getContent(), out, and mrpt::config::CLoadableOptions::saveToConfigFile().

Referenced by mrpt::config::CLoadableOptions::dumpToConsole(), mrpt::maps::TMetricMapInitializer::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::COccupancyGridMap3D::TMapDefinition::dumpToTextStream_map_specific(), and mrpt::apps::ICP_SLAM_App_Base::run().

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

◆ dumpVar_bool()

void CLoadableOptions::dumpVar_bool ( std::ostream &  out,
const char *  varName,
bool  v 
)
staticprotectedinherited

Definition at line 62 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_double()

void CLoadableOptions::dumpVar_double ( std::ostream &  out,
const char *  varName,
double  v 
)
staticprotectedinherited

Definition at line 56 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_float()

void CLoadableOptions::dumpVar_float ( std::ostream &  out,
const char *  varName,
float  v 
)
staticprotectedinherited

Definition at line 50 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_int()

void CLoadableOptions::dumpVar_int ( std::ostream &  out,
const char *  varName,
int  v 
)
staticprotectedinherited

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

Definition at line 44 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_string()

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

Definition at line 69 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ duplicateGetSmartPtr()

mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Makes a deep copy of the object and returns a smart pointer to it.

Definition at line 204 of file CObject.h.

References mrpt::rtti::CObject::clone().

Referenced by mrpt::obs::CRawlog::insert().

Here is the call graph for this function:
Here is the caller 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
virtual

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 512 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::math::angDistance(), mrpt::DEG2RAD(), evalClearanceToRobotShape(), getPathPose(), getPathStepCount(), index2alpha(), mrpt::math::TPose2D::inverseComposePoint(), mrpt::keep_min(), mrpt::math::TPoint2D_< T >::norm(), refDistance, mrpt::round(), mrpt::math::TPoint2D_data< T >::x, and mrpt::math::TPoint2D_data< T >::y.

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

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

◆ evalClearanceToRobotShape()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceToRobotShape ( const double  ox,
const double  oy 
) const
pure virtual

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

Zero or negative means collision.

Implemented in mrpt::nav::CPTG_RobotShape_Circular, and mrpt::nav::CPTG_RobotShape_Polygonal.

Referenced by evalClearanceSingleObstacle().

Here is the caller graph for this function:

◆ evalPathRelativePriority()

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

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 312 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
inlinevirtual

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 305 of file CParameterizedTrajectoryGenerator.h.

References refDistance.

◆ getAlphaValuesCount()

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

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

Definition at line 358 of file CParameterizedTrajectoryGenerator.h.

References m_alphaValuesCount.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), debugDumpInFiles(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize().

Here is the caller graph for this function:

◆ getClearanceDecimatedPaths()

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

Definition at line 387 of file CParameterizedTrajectoryGenerator.h.

References m_clearance_decimated_paths.

◆ getClearanceStepCount()

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

Definition at line 381 of file CParameterizedTrajectoryGenerator.h.

References m_clearance_num_points.

◆ getCurrentNavDynamicState()

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

Definition at line 336 of file CParameterizedTrajectoryGenerator.h.

References m_nav_dyn_state.

◆ getDescription()

virtual std::string mrpt::nav::CParameterizedTrajectoryGenerator::getDescription ( ) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CPTG_Holo_Blend, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, and mrpt::nav::CPTG_DiffDrive_CS.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), and initialize().

Here is the caller graph for this function:

◆ getMaxAngVel()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getMaxAngVel ( ) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

◆ getMaxLinVel()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getMaxLinVel ( ) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

◆ getMaxRobotRadius()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getMaxRobotRadius ( ) const
pure virtual

Returns an approximation of the robot radius.

Implemented in mrpt::nav::CPTG_RobotShape_Circular, and mrpt::nav::CPTG_RobotShape_Polygonal.

Referenced by internal_TPObsDistancePostprocess().

Here is the caller graph for this function:

◆ getPathCount()

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

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

Definition at line 360 of file CParameterizedTrajectoryGenerator.h.

References m_alphaValuesCount.

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

Here is the caller graph for this function:

◆ getPathDist()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist ( uint16_t  k,
uint32_t  step 
) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), debugDumpInFiles(), initClearanceDiagram(), initTPObstacleSingle(), and renderPathAsSimpleLine().

Here is the caller graph for this function:

◆ getPathPose() [1/2]

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose ( uint16_t  k,
uint32_t  step,
mrpt::math::TPose2D p 
) const
pure virtual

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

See also
getPathStepCount(), getAlphaValuesCount(), getPathTwist()

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), debugDumpInFiles(), evalClearanceSingleObstacle(), getPathPose(), getPathTwist(), and renderPathAsSimpleLine().

Here is the caller graph for this function:

◆ getPathPose() [2/2]

virtual mrpt::math::TPose2D mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose ( uint16_t  k,
uint32_t  step 
) const
inlinevirtual

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 209 of file CParameterizedTrajectoryGenerator.h.

References getPathPose().

Here is the call graph for this function:

◆ getPathStepCount()

virtual size_t mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount ( uint16_t  k) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by debugDumpInFiles(), evalClearanceSingleObstacle(), initClearanceDiagram(), initTPObstacleSingle(), and renderPathAsSimpleLine().

Here is the caller graph for this function:

◆ getPathStepDuration()

virtual double mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepDuration ( ) const
pure virtual

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

See also
getPathStepCount()

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

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

Here is the caller graph for this function:

◆ getPathStepForDist()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepForDist ( uint16_t  k,
double  dist,
uint32_t &  out_step 
) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

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

Here is the caller graph for this function:

◆ getPathTwist()

mrpt::math::TTwist2D CParameterizedTrajectoryGenerator::getPathTwist ( uint16_t  k,
uint32_t  step 
) const
virtual

Gets velocity ("twist") for path k ([0,N-1]=>[-pi,pi] in alpha), at vehicle discrete step step.

The default implementation in this base class uses numerical differentiation to estimate the twist (vx,vy,omega). Velocity is given in "global" coordinates, relative to the starting pose of the robot at t=0 for this PTG path.

See also
getPathStepCount(), getAlphaValuesCount(), getPathPose()

Definition at line 584 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::math::angDistance(), ASSERT_ABOVE_, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::curVelLocal, getPathPose(), getPathStepDuration(), and m_nav_dyn_state.

Here is the call graph for this function:

◆ getRefDistance()

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

Definition at line 370 of file CParameterizedTrajectoryGenerator.h.

References refDistance.

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

Here is the caller graph for this function:

◆ GetRuntimeClass()

virtual const mrpt::rtti::TRuntimeClassId* mrpt::nav::CParameterizedTrajectoryGenerator::GetRuntimeClass ( ) const
overridevirtual

◆ GetRuntimeClassIdStatic()

static const mrpt::rtti::TRuntimeClassId& mrpt::nav::CParameterizedTrajectoryGenerator::GetRuntimeClassIdStatic ( )
static

◆ getScorePriority()

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

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 379 of file CParameterizedTrajectoryGenerator.h.

References m_score_priority.

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

Here is the caller graph for this function:

◆ getSupportedKinematicVelocityCommand()

virtual mrpt::kinematics::CVehicleVelCmd::Ptr mrpt::nav::CParameterizedTrajectoryGenerator::getSupportedKinematicVelocityCommand ( ) const
pure virtual

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.

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

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

Here is the caller graph for this function:

◆ index2alpha() [1/2]

double CParameterizedTrajectoryGenerator::index2alpha ( uint16_t  k) const

◆ index2alpha() [2/2]

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

Definition at line 201 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_BELOW_, and M_PI.

◆ initClearanceDiagram()

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

Must be called to resize a CD to its correct size, before calling updateClearance()

Definition at line 465 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::ClearanceDiagram::decimated_k_to_real_k(), mrpt::nav::ClearanceDiagram::get_path_clearance_decimated(), getPathDist(), getPathStepCount(), m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, mrpt::nav::ClearanceDiagram::resize(), and mrpt::round().

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

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

◆ initialize()

void CParameterizedTrajectoryGenerator::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.

Definition at line 400 of file CParameterizedTrajectoryGenerator.cpp.

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

Here is the call graph for this function:

◆ initTPObstacles()

void CParameterizedTrajectoryGenerator::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).

See also
updateTPObstacle()

Definition at line 263 of file CParameterizedTrajectoryGenerator.cpp.

References initTPObstacleSingle(), and m_alphaValuesCount.

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

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

Definition at line 270 of file CParameterizedTrajectoryGenerator.cpp.

References getPathDist(), getPathStepCount(), INVALID_PTG_PATH_INDEX, m_nav_dyn_state_target_k, and refDistance.

Referenced by initTPObstacles(), and mrpt::nav::PlannerTPS_VirtualBase::spaceTransformerOneDirectionOnly().

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

◆ internal_deinitialize()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::internal_deinitialize ( )
protectedpure virtual

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

After changing it, call initialize again

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by deinitialize().

Here is the caller graph for this function:

◆ internal_initialize()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::internal_initialize ( const std::string &  cacheFilename = std::string(),
const bool  verbose = true 
)
protectedpure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by initialize().

Here is the caller graph for this function:

◆ internal_readFromStream()

void CParameterizedTrajectoryGenerator::internal_readFromStream ( mrpt::serialization::CArchive in)
protectedvirtual

Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.

Definition at line 155 of file CParameterizedTrajectoryGenerator.cpp.

References deinitialize(), m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, m_score_priority, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and refDistance.

Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_readFromStream(), and mrpt::nav::CPTG_Holo_Blend::serializeFrom().

Here is the call graph for this function:
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
protected

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 422 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::COLL_BEH_BACK_AWAY, mrpt::nav::COLL_BEH_STOP, COLLISION_BEHAVIOR(), getMaxRobotRadius(), isPointInsideRobotShape(), mrpt::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::serialization::CArchive out) const
protectedvirtual

Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.

Definition at line 190 of file CParameterizedTrajectoryGenerator.cpp.

References m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, m_score_priority, out, and refDistance.

Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_writeToStream(), and mrpt::nav::CPTG_Holo_Blend::serializeTo().

Here is the caller graph for this function:

◆ inverseMap_WS2TP()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::inverseMap_WS2TP ( double  x,
double  y,
int &  out_k,
double &  out_normalized_d,
double  tolerance_dist = 0.10 
) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CPTG_DiffDrive_C, and mrpt::nav::CPTG_Holo_Blend.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), PTG_IsIntoDomain(), and updateNavDynamicState().

Here is the caller graph for this function:

◆ isBijectiveAt()

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

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

Default implementation returns true.

Definition at line 154 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

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 355 of file CParameterizedTrajectoryGenerator.cpp.

References m_is_initialized.

◆ isPointInsideRobotShape()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::isPointInsideRobotShape ( const double  x,
const double  y 
) const
pure virtual

Returns true if the point lies within the robot shape.

Implemented in mrpt::nav::CPTG_RobotShape_Circular, and mrpt::nav::CPTG_RobotShape_Polygonal.

Referenced by internal_TPObsDistancePostprocess().

Here is the caller graph for this function:

◆ loadDefaultParams()

void CParameterizedTrajectoryGenerator::loadDefaultParams ( )
virtual

Loads a set of default parameters into the PTG.

Users normally will call loadFromConfigFile() instead, this method is provided exclusively for the PTG-configurator tool.

Reimplemented in mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.

Definition at line 45 of file CParameterizedTrajectoryGenerator.cpp.

References m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, m_score_priority, and refDistance.

Referenced by mrpt::nav::CPTG_Holo_Blend::loadDefaultParams(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::loadDefaultParams().

Here is the caller graph for this function:

◆ loadFromConfigFile()

void CParameterizedTrajectoryGenerator::loadFromConfigFile ( const mrpt::config::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.

Implements mrpt::config::CLoadableOptions.

Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.

Definition at line 63 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::curVelLocal, mrpt::keep_max(), m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, m_nav_dyn_state, m_score_priority, MRPT_LOAD_CONFIG_VAR_NO_DEFAULT, MRPT_LOAD_HERE_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR_DEGREES, MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT, mrpt::math::TTwist2D::omega, mrpt::math::TPose2D::phi, refDistance, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::relTarget, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::targetRelSpeed, mrpt::math::TTwist2D::vx, mrpt::math::TTwist2D::vy, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

Referenced by mrpt::nav::CPTG_Holo_Blend::loadFromConfigFile(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::loadFromConfigFile().

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::config::CLoadableOptions::loadFromConfigFile().

Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().

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

◆ maxTimeInVelCmdNOP()

double CParameterizedTrajectoryGenerator::maxTimeInVelCmdNOP ( int  path_k) const
virtual

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 in mrpt::nav::CPTG_Holo_Blend.

Definition at line 58 of file CParameterizedTrajectoryGenerator.cpp.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), and mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep().

Here is the caller graph for this function:

◆ onNewNavDynamicState()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::onNewNavDynamicState ( )
protectedpure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by updateNavDynamicState().

Here is the caller graph for this function:

◆ OUTPUT_DEBUG_PATH_PREFIX()

std::string & CParameterizedTrajectoryGenerator::OUTPUT_DEBUG_PATH_PREFIX ( )
static

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

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

Definition at line 25 of file CParameterizedTrajectoryGenerator.cpp.

References OUTPUT_DEBUG_PATH_PREFIX.

Referenced by debugDumpInFiles().

Here is the caller graph for this function:

◆ PTG_IsIntoDomain()

virtual bool mrpt::nav::CParameterizedTrajectoryGenerator::PTG_IsIntoDomain ( double  x,
double  y 
) const
inlinevirtual

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

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

Reimplemented in mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_Holo_Blend, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, and mrpt::nav::CPTG_DiffDrive_CS.

Definition at line 145 of file CParameterizedTrajectoryGenerator.h.

References inverseMap_WS2TP().

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
virtual

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 228 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::opengl::CSetOfLines::appendLine(), mrpt::opengl::CSetOfLines::appendLineStrip(), getPathDist(), getPathPose(), getPathStepCount(), mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

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 CParameterizedTrajectoryGenerator::saveToConfigFile ( mrpt::config::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::config::CLoadableOptions.

Reimplemented in mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.

Definition at line 101 of file CParameterizedTrajectoryGenerator.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::curVelLocal, m_alphaValuesCount, m_clearance_decimated_paths, m_clearance_num_points, m_nav_dyn_state, m_score_priority, MRPT_END, MRPT_START, mrpt::math::TTwist2D::omega, mrpt::math::TPose2D::phi, mrpt::RAD2DEG(), refDistance, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::relTarget, mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::targetRelSpeed, mrpt::math::TTwist2D::vx, mrpt::math::TTwist2D::vy, mrpt::config::CConfigFileBase::write(), mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

Referenced by mrpt::nav::CPTG_Holo_Blend::saveToConfigFile(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::saveToConfigFile().

Here is the call graph for this function:
Here is the caller 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 36 of file CLoadableOptions.cpp.

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

Here is the call graph for this function:

◆ serializeFrom() [1/2]

virtual void mrpt::serialization::CSerializable::serializeFrom ( CArchive in,
uint8_t  serial_version 
)
protectedpure virtualinherited

Pure virtual method for reading (deserializing) from an abstract archive.

Users don't call this method directly. Instead, use stream >> object;.

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 I/O error

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_ND, mrpt::nav::CLogFileRecord_FullEval, mrpt::img::CImage, mrpt::maps::CMultiMetricMap, mrpt::obs::CObservationIMU, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationVelodyneScan, mrpt::maps::TMapGenericParams, mrpt::maps::CRandomFieldGridMap3D, mrpt::hmtslam::THypothesisIDSet, mrpt::detectors::CDetectable3D, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::opengl::COctoMapVoxels, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::obs::CRawlog, mrpt::opengl::COpenGLViewport, mrpt::obs::CObservationRotatingScan, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::opengl::COpenGLScene, mrpt::slam::CIncrementalMapPartitioner, mrpt::vision::CFeature, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CObservation2DRangeScan, mrpt::opengl::CFrustum, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::poses::CPose2DInterpolator, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CPointCloud, mrpt::opengl::CPointCloudColoured, mrpt::poses::CPose3DQuat, mrpt::opengl::CPolyhedron, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CAssimpModel, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CText3D, mrpt::maps::COctoMap, mrpt::opengl::CBox, mrpt::opengl::CEllipsoid2D, mrpt::poses::CPose2D, mrpt::maps::CReflectivityGridMap2D, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CEllipsoid3D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CVectorField3D, mrpt::poses::CPose3DPDFGaussian, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMesh, mrpt::opengl::CMeshFast, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::opengl::CMesh3D, mrpt::opengl::CVectorField2D, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CColorBar, mrpt::maps::CBeacon, mrpt::maps::COccupancyGridMap3D, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::opengl::CText, mrpt::maps::CRBPFParticleData, mrpt::maps::CLandmark, mrpt::maps::CHeightGridMap2D_MRF, mrpt::opengl::CCamera, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::obs::CObservationPointCloud, mrpt::opengl::CSetOfLines, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::obs::CObservationBatteryState, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CSimplePointsMap, mrpt::obs::CActionRobotMovement2D, mrpt::opengl::CDisk, mrpt::maps::CColouredPointsMap, mrpt::maps::CWeightedPointsMap, mrpt::nav::CLogFileRecord, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CAxis, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::opengl::CSphere, mrpt::poses::CPointPDFParticles, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::poses::CPosePDFGaussian, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CPointsMapXYZI, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::opengl::CSetOfObjects, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::poses::CPose3DPDFGrid, mrpt::obs::CObservationVisualLandmarks, mrpt::math::CMatrixD, mrpt::math::CSplineInterpolator1D, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::poses::CPoses2DSequence, mrpt::img::TStereoCamera, mrpt::poses::CPoses3DSequence, mrpt::math::CMatrixF, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrixB, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::opengl::CSetOfTexturedTriangles, mrpt::math::CPolygon, mrpt::opengl::CTexturedPlane, mrpt::poses::CPoint2DPDFGaussian, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, mrpt::opengl::CSimpleLine, and MyNS::Foo.

Referenced by mrpt::serialization::CArchive::internal_ReadObject(), and mrpt::serialization::CSchemeArchiveBase::WriteObject().

Here is the caller graph for this function:

◆ serializeFrom() [2/2]

virtual void mrpt::serialization::CSerializable::serializeFrom ( CSchemeArchiveBase in)
inlineprotectedvirtualinherited

Virtual method for reading (deserializing) from an abstract schema based archive.

Definition at line 74 of file CSerializable.h.

References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ serializeGetVersion()

virtual uint8_t mrpt::serialization::CSerializable::serializeGetVersion ( ) const
protectedpure virtualinherited

Must return the current versioning number of the object.

Start in zero for new classes, and increments each time there is a change in the stored format.

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_ND, mrpt::nav::CLogFileRecord_FullEval, mrpt::img::CImage, mrpt::maps::CMultiMetricMap, mrpt::obs::CObservationIMU, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationVelodyneScan, mrpt::maps::TMapGenericParams, mrpt::maps::CRandomFieldGridMap3D, mrpt::hmtslam::THypothesisIDSet, mrpt::detectors::CDetectable3D, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::opengl::COctoMapVoxels, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::obs::CRawlog, mrpt::opengl::COpenGLViewport, mrpt::obs::CObservationRotatingScan, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::opengl::COpenGLScene, mrpt::slam::CIncrementalMapPartitioner, mrpt::vision::CFeature, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CObservation2DRangeScan, mrpt::opengl::CFrustum, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::poses::CPose2DInterpolator, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CPointCloud, mrpt::opengl::CPointCloudColoured, mrpt::poses::CPose3DQuat, mrpt::opengl::CPolyhedron, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CAssimpModel, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CText3D, mrpt::maps::COctoMap, mrpt::opengl::CBox, mrpt::opengl::CEllipsoid2D, mrpt::poses::CPose2D, mrpt::maps::CReflectivityGridMap2D, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CEllipsoid3D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CVectorField3D, mrpt::poses::CPose3DPDFGaussian, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMesh, mrpt::opengl::CMeshFast, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::opengl::CMesh3D, mrpt::opengl::CVectorField2D, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CColorBar, mrpt::maps::CBeacon, mrpt::maps::COccupancyGridMap3D, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::opengl::CText, mrpt::maps::CRBPFParticleData, mrpt::maps::CLandmark, mrpt::maps::CHeightGridMap2D_MRF, mrpt::opengl::CCamera, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::obs::CObservationPointCloud, mrpt::opengl::CSetOfLines, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::obs::CObservationBatteryState, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CSimplePointsMap, mrpt::obs::CActionRobotMovement2D, mrpt::opengl::CDisk, mrpt::maps::CColouredPointsMap, mrpt::maps::CWeightedPointsMap, mrpt::nav::CLogFileRecord, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CAxis, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::opengl::CSphere, mrpt::poses::CPointPDFParticles, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::poses::CPosePDFGaussian, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CPointsMapXYZI, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::opengl::CSetOfObjects, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::poses::CPose3DPDFGrid, mrpt::obs::CObservationVisualLandmarks, mrpt::math::CMatrixD, mrpt::math::CSplineInterpolator1D, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::poses::CPoses2DSequence, mrpt::img::TStereoCamera, mrpt::poses::CPoses3DSequence, mrpt::math::CMatrixF, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrixB, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::opengl::CSetOfTexturedTriangles, mrpt::math::CPolygon, mrpt::opengl::CTexturedPlane, mrpt::poses::CPoint2DPDFGaussian, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, mrpt::opengl::CSimpleLine, and MyNS::Foo.

Referenced by mrpt::serialization::CArchive::WriteObject().

Here is the caller graph for this function:

◆ serializeTo() [1/2]

virtual void mrpt::serialization::CSerializable::serializeTo ( CArchive out) const
protectedpure virtualinherited

Pure virtual method for writing (serializing) to an abstract archive.

Users don't call this method directly. Instead, use stream << object;.

Exceptions
std::exceptionOn any I/O error

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_ND, mrpt::nav::CLogFileRecord_FullEval, mrpt::img::CImage, mrpt::maps::CMultiMetricMap, mrpt::obs::CObservationIMU, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationVelodyneScan, mrpt::maps::TMapGenericParams, mrpt::maps::CRandomFieldGridMap3D, mrpt::hmtslam::THypothesisIDSet, mrpt::detectors::CDetectable3D, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::opengl::COctoMapVoxels, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::obs::CRawlog, mrpt::opengl::COpenGLViewport, mrpt::obs::CObservationRotatingScan, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::opengl::COpenGLScene, mrpt::slam::CIncrementalMapPartitioner, mrpt::vision::CFeature, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CObservation2DRangeScan, mrpt::opengl::CFrustum, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::poses::CPose2DInterpolator, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CPointCloud, mrpt::opengl::CPointCloudColoured, mrpt::poses::CPose3DQuat, mrpt::opengl::CPolyhedron, mrpt::hmtslam::CLSLAMParticleData, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CAssimpModel, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CText3D, mrpt::maps::COctoMap, mrpt::opengl::CBox, mrpt::opengl::CEllipsoid2D, mrpt::poses::CPose2D, mrpt::maps::CReflectivityGridMap2D, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CEllipsoid3D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::opengl::CVectorField3D, mrpt::poses::CPose3DPDFGaussian, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMesh, mrpt::opengl::CMeshFast, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::opengl::CMesh3D, mrpt::opengl::CVectorField2D, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CColorBar, mrpt::maps::CBeacon, mrpt::maps::COccupancyGridMap3D, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::opengl::CText, mrpt::maps::CRBPFParticleData, mrpt::maps::CLandmark, mrpt::maps::CHeightGridMap2D_MRF, mrpt::opengl::CCamera, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::obs::CObservationPointCloud, mrpt::opengl::CSetOfLines, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::obs::CObservationBatteryState, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CSimplePointsMap, mrpt::obs::CActionRobotMovement2D, mrpt::opengl::CDisk, mrpt::maps::CColouredPointsMap, mrpt::maps::CWeightedPointsMap, mrpt::nav::CLogFileRecord, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CAxis, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::opengl::CSphere, mrpt::poses::CPointPDFParticles, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::poses::CPosePDFGaussian, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CPointsMapXYZI, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::opengl::CSetOfObjects, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::poses::CPose3DPDFGrid, mrpt::obs::CObservationVisualLandmarks, mrpt::math::CMatrixD, mrpt::math::CSplineInterpolator1D, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::poses::CPoses2DSequence, mrpt::img::TStereoCamera, mrpt::poses::CPoses3DSequence, mrpt::math::CMatrixF, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrixB, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::opengl::CSetOfTexturedTriangles, mrpt::math::CPolygon, mrpt::opengl::CTexturedPlane, mrpt::poses::CPoint2DPDFGaussian, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, mrpt::opengl::CSimpleLine, and MyNS::Foo.

Referenced by mrpt::serialization::CSchemeArchiveBase::ReadObject(), and mrpt::serialization::CArchive::WriteObject().

Here is the caller graph for this function:

◆ serializeTo() [2/2]

virtual void mrpt::serialization::CSerializable::serializeTo ( CSchemeArchiveBase out) const
inlineprotectedvirtualinherited

Virtual method for writing (serializing) to an abstract schema based archive.

Definition at line 64 of file CSerializable.h.

References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ setClearanceDecimatedPaths()

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

Definition at line 391 of file CParameterizedTrajectoryGenerator.h.

References m_clearance_decimated_paths.

◆ setClearanceStepCount()

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

Definition at line 382 of file CParameterizedTrajectoryGenerator.h.

References m_clearance_num_points.

◆ setRefDistance()

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

Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.

Definition at line 195 of file CParameterizedTrajectoryGenerator.h.

References refDistance.

◆ setScorePriorty()

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

Definition at line 380 of file CParameterizedTrajectoryGenerator.h.

References m_score_priority.

◆ supportSpeedAtTarget()

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

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

See also
updateNavDynamicState()

Definition at line 291 of file CParameterizedTrajectoryGenerator.h.

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

Here is the caller graph for this function:

◆ supportVelCmdNOP()

bool CParameterizedTrajectoryGenerator::supportVelCmdNOP ( ) const
virtual

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 in mrpt::nav::CPTG_Holo_Blend.

Definition at line 54 of file CParameterizedTrajectoryGenerator.cpp.

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

Here is the caller graph for this function:

◆ updateClearance()

void CParameterizedTrajectoryGenerator::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.

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

Definition at line 488 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_, mrpt::nav::ClearanceDiagram::decimated_k_to_real_k(), evalClearanceSingleObstacle(), mrpt::nav::ClearanceDiagram::get_actual_num_paths(), mrpt::nav::ClearanceDiagram::get_decimated_num_paths(), mrpt::nav::ClearanceDiagram::get_path_clearance_decimated(), m_alphaValuesCount, and 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

Definition at line 506 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 
)

To be invoked by the navigator before each navigation step, to let the PTG to react to changing dynamic conditions.

Definition at line 360 of file CParameterizedTrajectoryGenerator.cpp.

References ASSERT_, INVALID_PTG_PATH_INDEX, inverseMap_WS2TP(), m_alphaValuesCount, m_nav_dyn_state, m_nav_dyn_state_target_k, onNewNavDynamicState(), mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::relTarget, supportSpeedAtTarget(), mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::targetRelSpeed, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

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

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

◆ updateTPObstacle()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::updateTPObstacle ( double  ox,
double  oy,
std::vector< double > &  tp_obstacles 
) const
pure virtual

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.

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

Referenced by mrpt::nav::PlannerTPS_VirtualBase::spaceTransformer(), and mrpt::nav::CReactiveNavigationSystem::STEP3_WSpaceToTPSpace().

Here is the caller graph for this function:

◆ updateTPObstacleSingle()

virtual void mrpt::nav::CParameterizedTrajectoryGenerator::updateTPObstacleSingle ( double  ox,
double  oy,
uint16_t  k,
double &  tp_obstacle_k 
) const
pure virtual

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

Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.

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

Here is the caller graph for this function:

◆ writeToMatlab()

virtual mxArray* mrpt::serialization::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 90 of file CSerializable.h.

Member Data Documentation

◆ INVALID_PTG_PATH_INDEX

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

◆ m_alphaValuesCount

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount {0}
protected

◆ m_clearance_decimated_paths

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_decimated_paths {15}
protected

◆ m_clearance_num_points

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points {5}
protected

Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5)

See also
updateClearance()

Definition at line 470 of file CParameterizedTrajectoryGenerator.h.

Referenced by getClearanceStepCount(), initClearanceDiagram(), internal_readFromStream(), internal_writeToStream(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), setClearanceStepCount(), and updateClearance().

◆ m_is_initialized

bool mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized {false}
protected

Definition at line 481 of file CParameterizedTrajectoryGenerator.h.

Referenced by deinitialize(), initialize(), and isInitialized().

◆ m_nav_dyn_state

TNavDynamicState mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state
protected

◆ m_nav_dyn_state_target_k

uint16_t mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state_target_k
protected

Update in updateNavDynamicState(), contains the path index (k) for the target.

Definition at line 477 of file CParameterizedTrajectoryGenerator.h.

Referenced by initTPObstacleSingle(), and updateNavDynamicState().

◆ m_score_priority

double mrpt::nav::CParameterizedTrajectoryGenerator::m_score_priority {1.0}
protected

◆ refDistance

double mrpt::nav::CParameterizedTrajectoryGenerator::refDistance {.0}
protected

◆ runtimeClassId

const mrpt::rtti::TRuntimeClassId mrpt::nav::CParameterizedTrajectoryGenerator::runtimeClassId
staticprotected

Definition at line 82 of file CParameterizedTrajectoryGenerator.h.




Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020