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

Detailed Description

Base class for all PTGs suitable to non-holonomic, differentially-driven (or Ackermann) vehicles based on numerical integration of the trajectories and collision look-up-table.

Regarding initialize(): in this this family of PTGs, the method builds the collision grid or load it from a cache file. Collision grids must be calculated before calling getTPObstacle(). Robot shape must be set before initializing with setRobotShape(). The rest of PTG parameters should have been set at the constructor.

Definition at line 52 of file CPTG_DiffDrive_CollisionGridBased.h.

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

Inheritance diagram for mrpt::nav::CPTG_DiffDrive_CollisionGridBased:
Inheritance graph

Classes

class  CCollisionGrid
 An internal class for storing the collision grid
More...
 
struct  TCellForLambdaFunction
 Specifies the min/max values for "k" and "n", respectively. More...
 

Public Member Functions

virtual void ptgDiffDriveSteeringFunction (float alpha, float t, float x, float y, float phi, float &v, float &w) const =0
 The main method to be implemented in derived classes: it defines the differential-driven differential equation. More...
 
double getMax_V () const
 
double getMax_W () const
 
bool isPointInsideRobotShape (const double x, const double y) const override
 Returns true if the point lies within the robot shape. 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...
 
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...
 
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...
 

Static Public Member Functions

static CParameterizedTrajectoryGeneratorCreatePTG (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 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 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 Types

using TCollisionCell = std::vector< std::pair< uint16_t, float > >
 A list of all the pairs (alpha,distance) such as the robot collides at that cell. More...
 

Protected Member Functions

 CPTG_DiffDrive_CollisionGridBased ()
 Constructor: possible values in "params": More...
 
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...
 
virtual void loadFromConfigFile (const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
 Possible values in "params" (those in CParameterizedTrajectoryGenerator, which is called internally, plus): More...
 
virtual 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 loadDefaultParams () override
 Loads a set of default parameters; provided exclusively for the PTG-configurator tool. More...
 
void internal_readFromStream (mrpt::serialization::CArchive &in) override
 
void internal_writeToStream (mrpt::serialization::CArchive &out) const override
 
void simulateTrajectories (float max_time, float max_dist, unsigned int max_n, float diferencial_t, float min_dist, float *out_max_acc_v=nullptr, float *out_max_acc_w=nullptr)
 Numerically solve the diferential equations to generate a family of trajectories. More...
 
bool saveColGridsToFile (const std::string &filename, const mrpt::math::CPolygon &computed_robotShape) const
 
bool loadColGridsFromFile (const std::string &filename, const mrpt::math::CPolygon &current_robotShape)
 
void loadShapeFromConfigFile (const mrpt::config::CConfigFileBase &source, const std::string &section)
 
void internal_shape_loadFromStream (mrpt::serialization::CArchive &in)
 
void internal_shape_saveToStream (mrpt::serialization::CArchive &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...
 

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 V_MAX
 
double W_MAX
 
double turningRadiusReference
 
std::vector< TCPointVectorm_trajectory
 
double m_resolution
 
double m_stepTimeDuration
 
CCollisionGrid m_collisionGrid
 The collision grid. More...
 
mrpt::containers::CDynamicGrid< TCellForLambdaFunctionm_lambdaFunctionOptimizer
 This grid will contain indexes data for speeding-up the default, brute-force lambda function. More...
 
mrpt::math::CPolygon m_robotShape
 
double m_robotMaxRadius
 
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


virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
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 ()
 
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 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 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...
 

Member Typedef Documentation

◆ ConstPtr

Definition at line 80 of file CParameterizedTrajectoryGenerator.h.

◆ Ptr

Definition at line 80 of file CParameterizedTrajectoryGenerator.h.

◆ TCollisionCell

using mrpt::nav::CPTG_DiffDrive_CollisionGridBased::TCollisionCell = std::vector<std::pair<uint16_t, float> >
protected

A list of all the pairs (alpha,distance) such as the robot collides at that cell.

  • map key (uint16_t) -> alpha value (k)
    • map value (float) -> the MINIMUM distance (d), in meters, associated with that "k".

Definition at line 165 of file CPTG_DiffDrive_CollisionGridBased.h.

Constructor & Destructor Documentation

◆ CPTG_DiffDrive_CollisionGridBased()

CPTG_DiffDrive_CollisionGridBased::CPTG_DiffDrive_CollisionGridBased ( )
protected

Constructor: possible values in "params":

  • ref_distance: The maximum distance in PTGs
  • resolution: The cell size
  • v_max, w_max: Maximum robot speeds.

Definition at line 30 of file CPTG_DiffDrive_CollisionGridBased.cpp.

Member Function Documentation

◆ _GetBaseClass()

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

◆ add_robotShape_to_setOfLines()

void CPTG_RobotShape_Polygonal::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

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

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

◆ CreatePTG()

CParameterizedTrajectoryGenerator * CParameterizedTrajectoryGenerator::CreatePTG ( const std::string ptgClassName,
const mrpt::config::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::serialization::CSerializable class.

Exceptions
std::logic_errorOn invalid or missing parameters.

Definition at line 21 of file CParameterizedTrajectoryGenerator_factory.cpp.

References mrpt::config::CConfigFilePrefixer::bind(), mrpt::rtti::TRuntimeClassId::createObject(), mrpt::rtti::findRegisteredClass(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), 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().

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

References mrpt::system::createDirectory(), 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.

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

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

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

◆ directionToMotionCommand()

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

In this class, out_action_cmd contains: [0]: linear velocity (m/s), [1]: angular velocity (rad/s).

In this class, out_action_cmd contains: [0]: linear velocity (m/s), [1]: angular velocity (rad/s)

See more docs in CParameterizedTrajectoryGenerator::directionToMotionCommand()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 276 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References mrpt::kinematics::CVehicleVelCmd_DiffDriven::ang_vel, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::kinematics::CVehicleVelCmd_DiffDriven::lin_vel, and ptgDiffDriveSteeringFunction().

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

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().

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

Definition at line 77 of file CLoadableOptions.cpp.

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

Referenced by mrpt::config::CLoadableOptions::dumpToConsole(), and mrpt::maps::TMetricMapInitializer::dumpToTextStream().

◆ dumpVar_bool()

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

Definition at line 63 of file CLoadableOptions.cpp.

References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.

◆ dumpVar_double()

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

Definition at line 57 of file CLoadableOptions.cpp.

References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.

◆ dumpVar_float()

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

Definition at line 51 of file CLoadableOptions.cpp.

References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.

◆ 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 45 of file CLoadableOptions.cpp.

References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.

◆ dumpVar_string()

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

Definition at line 70 of file CLoadableOptions.cpp.

References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.

◆ duplicateGetSmartPtr()

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

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

Definition at line 169 of file CObject.h.

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

Referenced by mrpt::obs::CRawlog::addActions(), and mrpt::obs::CRawlog::addObservations().

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

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

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

◆ evalClearanceToRobotShape()

double CPTG_RobotShape_Polygonal::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 158 of file CPTG_RobotShape_Polygonal.cpp.

References mrpt::hypot_fast(), mrpt::nav::CPTG_RobotShape_Polygonal::isPointInsideRobotShape(), mrpt::keep_max(), and mrpt::nav::CPTG_RobotShape_Polygonal::m_robotMaxRadius.

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

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

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

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

◆ getMax_V()

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::getMax_V ( ) const
inline

Definition at line 112 of file CPTG_DiffDrive_CollisionGridBased.h.

References V_MAX.

◆ getMax_W()

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::getMax_W ( ) const
inline

Definition at line 113 of file CPTG_DiffDrive_CollisionGridBased.h.

References W_MAX.

◆ getMaxAngVel()

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

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

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 98 of file CPTG_DiffDrive_CollisionGridBased.h.

References W_MAX.

◆ getMaxLinVel()

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

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

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 97 of file CPTG_DiffDrive_CollisionGridBased.h.

References V_MAX.

◆ getMaxRobotRadius()

double CPTG_RobotShape_Polygonal::getMaxRobotRadius ( ) const
overridevirtualinherited

Returns an approximation of the robot radius.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 147 of file CPTG_RobotShape_Polygonal.cpp.

References mrpt::nav::CPTG_RobotShape_Polygonal::m_robotMaxRadius.

◆ getPathCount()

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

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

Definition at line 343 of file CParameterizedTrajectoryGenerator.h.

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

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

◆ getPathDist()

double CPTG_DiffDrive_CollisionGridBased::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 858 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERT_, and m_trajectory.

Referenced by internal_initialize().

◆ getPathPose()

void CPTG_DiffDrive_CollisionGridBased::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 847 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERT_, and m_trajectory.

Referenced by internal_initialize().

◆ getPathStepCount()

size_t CPTG_DiffDrive_CollisionGridBased::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 840 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERT_, and m_trajectory.

Referenced by internal_initialize().

◆ getPathStepDuration()

double CPTG_DiffDrive_CollisionGridBased::getPathStepDuration ( ) const
overridevirtual

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

See also
getPathStepCount()

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 956 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References m_stepTimeDuration.

◆ getPathStepForDist()

bool CPTG_DiffDrive_CollisionGridBased::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 867 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERT_, and m_trajectory.

◆ getRefDistance()

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

◆ getRobotShape()

const mrpt::math::CPolygon& mrpt::nav::CPTG_RobotShape_Polygonal::getRobotShape ( ) const
inlineinherited

◆ GetRuntimeClass()

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

◆ GetRuntimeClassIdStatic()

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

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

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

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

◆ getSupportedKinematicVelocityCommand()

mrpt::kinematics::CVehicleVelCmd::Ptr CPTG_DiffDrive_CollisionGridBased::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 949 of file CPTG_DiffDrive_CollisionGridBased.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 194 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

◆ 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 256 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().

◆ initTPObstacleSingle()

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

◆ internal_deinitialize()

void CPTG_DiffDrive_CollisionGridBased::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 683 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References m_trajectory.

Referenced by internal_readFromStream(), and simulateTrajectories().

◆ internal_initialize()

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

◆ internal_processNewRobotShape()

void CPTG_DiffDrive_CollisionGridBased::internal_processNewRobotShape ( )
overrideprotectedvirtual

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

Implements mrpt::nav::CPTG_RobotShape_Polygonal.

Definition at line 676 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERTMSG_, and m_trajectory.

◆ internal_readFromStream()

void CPTG_DiffDrive_CollisionGridBased::internal_readFromStream ( mrpt::serialization::CArchive in)
overrideprotectedvirtual

◆ internal_shape_loadFromStream()

void CPTG_RobotShape_Polygonal::internal_shape_loadFromStream ( mrpt::serialization::CArchive in)
protectedinherited

◆ internal_shape_saveToStream()

void CPTG_RobotShape_Polygonal::internal_shape_saveToStream ( mrpt::serialization::CArchive out) const
protectedinherited

◆ 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 416 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::keep_min(), and THROW_EXCEPTION.

Referenced by updateTPObstacle(), and updateTPObstacleSingle().

◆ internal_writeToStream()

void CPTG_DiffDrive_CollisionGridBased::internal_writeToStream ( mrpt::serialization::CArchive out) const
overrideprotectedvirtual

◆ inverseMap_WS2TP()

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

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

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

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

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

◆ isPointInsideRobotShape()

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

◆ loadColGridsFromFile()

bool CPTG_DiffDrive_CollisionGridBased::loadColGridsFromFile ( const std::string filename,
const mrpt::math::CPolygon current_robotShape 
)
protected

◆ loadDefaultParams()

void CPTG_DiffDrive_CollisionGridBased::loadDefaultParams ( )
overrideprotectedvirtual

◆ loadFromConfigFile()

void CPTG_DiffDrive_CollisionGridBased::loadFromConfigFile ( const mrpt::config::CConfigFileBase cfg,
const std::string sSection 
)
overrideprotectedvirtual

Possible values in "params" (those in CParameterizedTrajectoryGenerator, which is called internally, plus):

  • ${sKeyPrefix}resolution: The cell size
  • ${sKeyPrefix}v_max, ${sKeyPrefix}w_max`: Maximum robot speeds.
  • `${sKeyPrefix}shape_x{0,1,2..}`,${sKeyPrefix}shape_y{0,1,2..}`: Polygonal robot shape [Optional, can be also set via setRobotPolygonShape()]

See docs of derived classes for additional parameters in setParams()

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

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

Definition at line 50 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CPTG_RobotShape_Polygonal::loadShapeFromConfigFile(), m_resolution, MRPT_LOAD_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR_DEGREES_NO_DEFAULT, MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT, turningRadiusReference, V_MAX, and W_MAX.

Referenced by IMPLEMENTS_SERIALIZABLE().

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

◆ loadShapeFromConfigFile()

void CPTG_RobotShape_Polygonal::loadShapeFromConfigFile ( const mrpt::config::CConfigFileBase source,
const std::string section 
)
protectedinherited

◆ maxTimeInVelCmdNOP()

double CParameterizedTrajectoryGenerator::maxTimeInVelCmdNOP ( int  path_k) const
virtualinherited

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

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

◆ onNewNavDynamicState()

virtual void mrpt::nav::CPTG_DiffDrive_CollisionGridBased::onNewNavDynamicState ( )
inlineoverridevirtual

This family of PTGs ignores the dynamic states.

Implements mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 105 of file CPTG_DiffDrive_CollisionGridBased.h.

◆ PTG_IsIntoDomain()

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

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

References mrpt::nav::CParameterizedTrajectoryGenerator::inverseMap_WS2TP().

◆ ptgDiffDriveSteeringFunction()

virtual void mrpt::nav::CPTG_DiffDrive_CollisionGridBased::ptgDiffDriveSteeringFunction ( float  alpha,
float  t,
float  x,
float  y,
float  phi,
float &  v,
float &  w 
) const
pure virtual

The main method to be implemented in derived classes: it defines the differential-driven differential equation.

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

Referenced by directionToMotionCommand(), and simulateTrajectories().

◆ 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 221 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().

◆ saveColGridsToFile()

bool CPTG_DiffDrive_CollisionGridBased::saveColGridsToFile ( const std::string filename,
const mrpt::math::CPolygon computed_robotShape 
) const
protected

◆ saveToConfigFile()

void CPTG_DiffDrive_CollisionGridBased::saveToConfigFile ( mrpt::config::CConfigFileBase target,
const std::string section 
) const
overrideprotectedvirtual

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

◆ serializeFrom()

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

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

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

◆ serializeTo()

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

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

◆ setClearanceDecimatedPaths()

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

◆ setClearanceStepCount()

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

◆ setRefDistance()

void CPTG_DiffDrive_CollisionGridBased::setRefDistance ( const double  refDist)
overridevirtual

Launches an exception in this class: it is not allowed in numerical integration-based PTGs to change the reference distance after initialization.

Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.

Definition at line 667 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERTMSG_, m_trajectory, and mrpt::nav::CParameterizedTrajectoryGenerator::refDistance.

◆ setRobotShape()

void CPTG_RobotShape_Polygonal::setRobotShape ( const mrpt::math::CPolygon robotShape)
inherited

◆ setScorePriorty()

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

◆ simulateTrajectories()

void CPTG_DiffDrive_CollisionGridBased::simulateTrajectories ( float  max_time,
float  max_dist,
unsigned int  max_n,
float  diferencial_t,
float  min_dist,
float *  out_max_acc_v = nullptr,
float *  out_max_acc_w = nullptr 
)
protected

◆ supportSpeedAtTarget()

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

◆ supportVelCmdNOP()

bool CParameterizedTrajectoryGenerator::supportVelCmdNOP ( ) const
virtualinherited

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

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

◆ updateClearance()

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

◆ updateClearancePost()

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

◆ updateNavDynamicState()

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

◆ updateTPObstacle()

void CPTG_DiffDrive_CollisionGridBased::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 888 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERTMSG_, mrpt::nav::CPTG_DiffDrive_CollisionGridBased::CCollisionGrid::getTPObstacle(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess(), m_collisionGrid, and m_trajectory.

◆ updateTPObstacleSingle()

void CPTG_DiffDrive_CollisionGridBased::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 901 of file CPTG_DiffDrive_CollisionGridBased.cpp.

References ASSERTMSG_, mrpt::nav::CPTG_DiffDrive_CollisionGridBased::CCollisionGrid::getTPObstacle(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess(), m_collisionGrid, and m_trajectory.

◆ 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 70 of file CSerializable.h.

Member Data Documentation

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

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

◆ 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_collisionGrid

CCollisionGrid mrpt::nav::CPTG_DiffDrive_CollisionGridBased::m_collisionGrid
protected

◆ m_is_initialized

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

◆ m_lambdaFunctionOptimizer

mrpt::containers::CDynamicGrid<TCellForLambdaFunction> mrpt::nav::CPTG_DiffDrive_CollisionGridBased::m_lambdaFunctionOptimizer
protected

This grid will contain indexes data for speeding-up the default, brute-force lambda function.

Definition at line 245 of file CPTG_DiffDrive_CollisionGridBased.h.

Referenced by inverseMap_WS2TP(), and simulateTrajectories().

◆ 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_resolution

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::m_resolution
protected

◆ m_robotMaxRadius

double mrpt::nav::CPTG_RobotShape_Polygonal::m_robotMaxRadius
protectedinherited

◆ m_robotShape

mrpt::math::CPolygon mrpt::nav::CPTG_RobotShape_Polygonal::m_robotShape
protectedinherited

◆ m_score_priority

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

◆ m_stepTimeDuration

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::m_stepTimeDuration
protected

◆ m_trajectory

std::vector<TCPointVector> mrpt::nav::CPTG_DiffDrive_CollisionGridBased::m_trajectory
protected

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

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

◆ refDistance

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

◆ runtimeClassId

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

Definition at line 80 of file CParameterizedTrajectoryGenerator.h.

◆ turningRadiusReference

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::turningRadiusReference
protected

◆ V_MAX

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::V_MAX
protected

◆ W_MAX

double mrpt::nav::CPTG_DiffDrive_CollisionGridBased::W_MAX
protected
mrpt::nav::COLL_BEH_BACK_AWAY
@ COLL_BEH_BACK_AWAY
Favor getting back from too-close (almost collision) obstacles.
Definition: CParameterizedTrajectoryGenerator.h:42



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST