MRPT
1.9.9
|
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>
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 TNavDynamicState & | getCurrentNavDynamicState () 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 mxArray * | writeToMatlab () 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 CObject * | clone () 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 §ion) |
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 §ion) 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_t & | COLLISION_BEHAVIOR () |
Defines the behavior when there is an obstacle inside the robot shape right at the beginning of a PTG trajectory. More... | |
Protected Member Functions | |
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::TRuntimeClassId * | GetRuntimeClass () const override |
Returns information about the class of an object in runtime. More... | |
static const mrpt::rtti::TRuntimeClassId & | GetRuntimeClassIdStatic () |
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... | |
using mrpt::nav::CParameterizedTrajectoryGenerator::ConstPtr = std::shared_ptr<const CParameterizedTrajectoryGenerator > |
Definition at line 82 of file CParameterizedTrajectoryGenerator.h.
|
inherited |
using mrpt::nav::CParameterizedTrajectoryGenerator::Ptr = std::shared_ptr< CParameterizedTrajectoryGenerator > |
Definition at line 82 of file CParameterizedTrajectoryGenerator.h.
|
inherited |
mrpt::nav::CParameterizedTrajectoryGenerator::CParameterizedTrajectoryGenerator | ( | ) |
Default ctor.
Must call loadFromConfigFile()
before initialization
|
overridedefault |
Destructor.
|
staticprotected |
|
pure virtual |
Auxiliary function for rendering.
Implemented in mrpt::nav::CPTG_RobotShape_Circular, and mrpt::nav::CPTG_RobotShape_Polygonal.
uint16_t CParameterizedTrajectoryGenerator::alpha2index | ( | double | alpha | ) | const |
Discrete index value for the corresponding alpha value.
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().
|
static |
Definition at line 213 of file CParameterizedTrajectoryGenerator.cpp.
References M_PI, mrpt::round(), and mrpt::math::wrapToPi().
|
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().
|
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().
|
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.
std::logic_error | On 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().
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
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.
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().
|
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().
|
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().
|
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().
|
staticprotectedinherited |
Definition at line 62 of file CLoadableOptions.cpp.
References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.
|
staticprotectedinherited |
Definition at line 56 of file CLoadableOptions.cpp.
References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.
|
staticprotectedinherited |
Definition at line 50 of file CLoadableOptions.cpp.
References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.
|
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.
|
staticprotectedinherited |
Definition at line 69 of file CLoadableOptions.cpp.
References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.
|
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().
|
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.
treat_as_obstacle | true: 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().
|
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().
|
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().
|
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.
|
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().
|
inline |
Definition at line 387 of file CParameterizedTrajectoryGenerator.h.
References m_clearance_decimated_paths.
|
inline |
Definition at line 381 of file CParameterizedTrajectoryGenerator.h.
References m_clearance_num_points.
|
inline |
Definition at line 336 of file CParameterizedTrajectoryGenerator.h.
References m_nav_dyn_state.
|
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().
|
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.
|
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.
|
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().
|
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().
|
pure virtual |
Access path k
([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step
.
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().
|
pure virtual |
Access path k
([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step
.
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().
|
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().
|
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.
Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.
Referenced by debugDumpInFiles(), evalClearanceSingleObstacle(), initClearanceDiagram(), initTPObstacleSingle(), and renderPathAsSimpleLine().
|
pure virtual |
Returns the duration (in seconds) of each "step".
Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), and getPathTwist().
|
pure virtual |
Access path k
([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < dist
[in] | dist | Distance in pseudometers (real distance, NOT normalized to [0,1] for [0,refDist]) |
k
(e.g. out of reference distance). Note that, anyway, the maximum distance (closest point) is returned in out_step
. Implemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased, and mrpt::nav::CPTG_Holo_Blend.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().
|
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.
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.
|
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().
|
overridevirtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::serialization::CSerializable.
Reimplemented 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.
|
static |
|
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().
|
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().
double CParameterizedTrajectoryGenerator::index2alpha | ( | uint16_t | k | ) | const |
Alpha value for the discrete corresponding value.
Definition at line 208 of file CParameterizedTrajectoryGenerator.cpp.
References m_alphaValuesCount.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CPTG_Holo_Blend::directionToMotionCommand(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::directionToMotionCommand(), evalClearanceSingleObstacle(), mrpt::nav::CPTG_Holo_Blend::getPathDist(), mrpt::nav::CPTG_Holo_Blend::getPathPose(), mrpt::nav::CPTG_Holo_Blend::getPathStepForDist(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), and mrpt::nav::CPTG_Holo_Blend::updateTPObstacleSingle().
|
static |
Definition at line 201 of file CParameterizedTrajectoryGenerator.cpp.
References ASSERT_BELOW_, and M_PI.
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().
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.
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).
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().
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().
|
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().
|
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().
|
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().
|
protected |
To be called by implementors of updateTPObstacle() and updateTPObstacleSingle() to honor the user settings regarding COLLISION_BEHAVIOR.
new_tp_obs_dist | The newly determiend collision-free ranges, in "pseudometers", un-normalized, for some "k" direction. |
inout_tp_obs | The 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().
|
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().
|
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.
[in] | x | X coordinate of the query point, relative to the robot frame. |
[in] | y | Y coordinate of the query point, relative to the robot frame. |
[out] | out_k | Trajectory parameter index (discretized alpha value, 0-based index). |
[out] | out_d | Trajectory distance, normalized such that D_max becomes 1. |
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().
|
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().
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.
|
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().
|
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().
|
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().
|
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.
Definition at line 22 of file CLoadableOptions.cpp.
References mrpt::config::CLoadableOptions::loadFromConfigFile().
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().
|
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.
path_k | Queried 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().
|
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().
|
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().
|
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().
|
virtual |
Returns the representation of one trajectory of this PTG as a 3D OpenGL object (a simple curved line).
[in] | k | The 0-based index of the selected trajectory (discrete "alpha" parameter). |
[out] | gl_obj | Output object. |
[in] | decimate_distance | Minimum distance between path points (in meters). |
[in] | max_path_distance | If >=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().
|
overridevirtual |
This method saves the options to a ".ini"-like file or memory-stored string list.
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().
|
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.
Definition at line 36 of file CLoadableOptions.cpp.
References mrpt::config::CLoadableOptions::saveToConfigFile().
|
protectedpure virtualinherited |
Pure virtual method for reading (deserializing) from an abstract archive.
Users don't call this method directly. Instead, use stream >> object;
.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On 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().
|
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.
|
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().
|
protectedpure virtualinherited |
Pure virtual method for writing (serializing) to an abstract archive.
Users don't call this method directly. Instead, use stream << object;
.
std::exception | On 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().
|
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.
|
inline |
Definition at line 391 of file CParameterizedTrajectoryGenerator.h.
References m_clearance_decimated_paths.
|
inline |
Definition at line 382 of file CParameterizedTrajectoryGenerator.h.
References m_clearance_num_points.
|
inlinevirtual |
Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.
Definition at line 195 of file CParameterizedTrajectoryGenerator.h.
References refDistance.
|
inline |
Definition at line 380 of file CParameterizedTrajectoryGenerator.h.
References m_score_priority.
|
inlinevirtual |
Returns true if this PTG takes into account the desired velocity at target.
Definition at line 291 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and updateNavDynamicState().
|
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().
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.
[in,out] | cd | The clearance will be updated here. |
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().
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().
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().
|
pure virtual |
Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy)
[in,out] | tp_obstacles | A vector of length getAlphaValuesCount() , initialized with initTPObstacles() (collision-free ranges, in "pseudometers", un-normalized). |
[in] | ox | Obstacle point (X), relative coordinates wrt origin of the PTG. |
[in] | oy | Obstacle point (Y), relative coordinates wrt origin of the PTG. |
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().
|
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().
|
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.
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.
|
staticprotected |
Definition at line 479 of file CParameterizedTrajectoryGenerator.h.
Referenced by initTPObstacleSingle(), and updateNavDynamicState().
|
protected |
The number of discrete values for "alpha" between -PI and +PI.
Definition at line 466 of file CParameterizedTrajectoryGenerator.h.
Referenced by alpha2index(), getAlphaValuesCount(), getPathCount(), index2alpha(), initClearanceDiagram(), initTPObstacles(), mrpt::nav::CPTG_Holo_Blend::internal_initialize(), internal_readFromStream(), internal_writeToStream(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), updateClearance(), and updateNavDynamicState().
|
protected |
Number of paths for the decimated paths analysis of clearance.
Definition at line 472 of file CParameterizedTrajectoryGenerator.h.
Referenced by getClearanceDecimatedPaths(), initClearanceDiagram(), internal_readFromStream(), internal_writeToStream(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), and setClearanceDecimatedPaths().
|
protected |
Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5)
Definition at line 470 of file CParameterizedTrajectoryGenerator.h.
Referenced by getClearanceStepCount(), initClearanceDiagram(), internal_readFromStream(), internal_writeToStream(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), setClearanceStepCount(), and updateClearance().
|
protected |
Definition at line 481 of file CParameterizedTrajectoryGenerator.h.
Referenced by deinitialize(), initialize(), and isInitialized().
|
protected |
Updated before each nav step by.
Definition at line 474 of file CParameterizedTrajectoryGenerator.h.
Referenced by getCurrentNavDynamicState(), getPathTwist(), loadFromConfigFile(), saveToConfigFile(), and updateNavDynamicState().
|
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().
|
protected |
Definition at line 467 of file CParameterizedTrajectoryGenerator.h.
Referenced by getScorePriority(), internal_readFromStream(), internal_writeToStream(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), and setScorePriorty().
|
protected |
Definition at line 464 of file CParameterizedTrajectoryGenerator.h.
Referenced by evalClearanceSingleObstacle(), getActualUnloopedPathLength(), getRefDistance(), initTPObstacleSingle(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), internal_readFromStream(), internal_writeToStream(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), loadDefaultParams(), loadFromConfigFile(), saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::setRefDistance(), and setRefDistance().
|
staticprotected |
Definition at line 82 of file CParameterizedTrajectoryGenerator.h.
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |