A PTG for circular-shaped robots with holonomic kinematics.
ptg-configurator
Definition at line 28 of file CPTG_Holo_Blend.h.
#include <mrpt/nav/tpspace/CPTG_Holo_Blend.h>
Public Member Functions | |
void * | operator new (size_t size) |
void * | operator new[] (size_t size) |
void | operator delete (void *ptr) throw () |
void | operator delete[] (void *ptr) throw () |
void | operator delete (void *memory, void *ptr) throw () |
void * | operator new (size_t size, const std::nothrow_t &) throw () |
void | operator delete (void *ptr, const std::nothrow_t &) throw () |
CPTG_Holo_Blend () | |
CPTG_Holo_Blend (const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection) | |
virtual | ~CPTG_Holo_Blend () |
virtual void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection) MRPT_OVERRIDE |
Parameters accepted by this base class: More... | |
virtual void | saveToConfigFile (mrpt::utils::CConfigFileBase &cfg, const std::string &sSection) const MRPT_OVERRIDE |
This method saves the options to a ".ini"-like file or memory-stored string list. More... | |
virtual void | loadDefaultParams () MRPT_OVERRIDE |
Loads a set of default parameters; provided exclusively for the PTG-configurator tool. More... | |
virtual bool | supportVelCmdNOP () const MRPT_OVERRIDE |
Returns true if it is possible to stop sending velocity commands to the robot and, still, the robot controller will be able to keep following the last sent trajectory ("NOP" velocity commands). More... | |
virtual double | maxTimeInVelCmdNOP (int path_k) const MRPT_OVERRIDE |
Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path can be followed without re-issuing a new velcmd. More... | |
std::string | getDescription () const MRPT_OVERRIDE |
Gets a short textual description of the PTG and its parameters. More... | |
bool | inverseMap_WS2TP (double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const MRPT_OVERRIDE |
Computes the closest (alpha,d) TP coordinates of the trajectory point closest to the Workspace (WS) Cartesian coordinates (x,y), relative to the current robot frame. More... | |
bool | PTG_IsIntoDomain (double x, double y) const MRPT_OVERRIDE |
Returns the same than inverseMap_WS2TP() but without any additional cost. More... | |
void | onNewNavDynamicState () MRPT_OVERRIDE |
Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize paths depending on the instantaneous conditions. More... | |
virtual mrpt::kinematics::CVehicleVelCmdPtr | directionToMotionCommand (uint16_t k) const MRPT_OVERRIDE |
Converts a discretized "alpha" value into a feasible motion command or action. More... | |
virtual mrpt::kinematics::CVehicleVelCmdPtr | getSupportedKinematicVelocityCommand () const MRPT_OVERRIDE |
Returns an empty kinematic velocity command object of the type supported by this PTG. More... | |
size_t | getPathStepCount (uint16_t k) const MRPT_OVERRIDE |
Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete "steps" along the trajectory. More... | |
void | getPathPose (uint16_t k, uint32_t step, mrpt::math::TPose2D &p) const MRPT_OVERRIDE |
Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step . More... | |
double | getPathDist (uint16_t k, uint32_t step) const MRPT_OVERRIDE |
Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step . More... | |
bool | getPathStepForDist (uint16_t k, double dist, uint32_t &out_step) const MRPT_OVERRIDE |
Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < dist More... | |
double | getPathStepDuration () const MRPT_OVERRIDE |
Returns the duration (in seconds) of each "step". More... | |
double | getMaxLinVel () const MRPT_OVERRIDE |
Returns the maximum linear velocity expected from this PTG [m/s]. More... | |
double | getMaxAngVel () const MRPT_OVERRIDE |
Returns the maximum angular velocity expected from this PTG [rad/s]. More... | |
void | updateTPObstacle (double ox, double oy, std::vector< double > &tp_obstacles) const MRPT_OVERRIDE |
Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,oy) More... | |
void | updateTPObstacleSingle (double ox, double oy, uint16_t k, double &tp_obstacle_k) const MRPT_OVERRIDE |
Like updateTPObstacle() but for one direction only (k ) in TP-Space. More... | |
void | add_robotShape_to_setOfLines (mrpt::opengl::CSetOfLines &gl_shape, const mrpt::poses::CPose2D &origin=mrpt::poses::CPose2D()) const MRPT_OVERRIDE |
Auxiliary function for rendering. More... | |
bool | isPointInsideRobotShape (const double x, const double y) const MRPT_OVERRIDE |
Returns true if the point lies within the robot shape. More... | |
void | updateNavDynamicState (const TNavDynamicState &newState, const bool force_update=false) |
To be invoked by the navigator before each navigation step, to let the PTG to react to changing dynamic conditions. More... | |
const 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 | 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... | |
CObject * | clone () const |
Cloning interface for smart pointers. 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 (mrpt::utils::CStream &out) const |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream. More... | |
Robot shape | |
void | setRobotShapeRadius (const double robot_radius) |
Robot shape must be set before initialization, either from ctor params or via this method. More... | |
double | getRobotShapeRadius () const |
double | getMaxRobotRadius () const MRPT_OVERRIDE |
Returns an approximation of the robot radius. More... | |
virtual double | evalClearanceToRobotShape (const double ox, const double oy) const MRPT_OVERRIDE |
Evals the clearance from an obstacle (ox,oy) in coordinates relative to the robot center. More... | |
Virtual interface of each PTG implementation | |
virtual bool | isBijectiveAt (uint16_t k, uint32_t step) const |
Returns true if a given TP-Space point maps to a unique point in Workspace, and viceversa. More... | |
virtual void | setRefDistance (const double refDist) |
virtual bool | supportSpeedAtTarget () const |
Returns true if this PTG takes into account the desired velocity at target. More... | |
virtual double | getActualUnloopedPathLength (uint16_t k) const |
Returns the actual distance (in meters) of the path, discounting possible circular loops of the path (e.g. More... | |
virtual double | evalPathRelativePriority (uint16_t k, double target_distance) const |
Query the PTG for the relative priority factor (0,1) of this PTG, in comparison to others, if the k-th path is to be selected. More... | |
RTTI classes and functions | |
mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
Static Public Member Functions | |
static void * | operator new (size_t size, void *ptr) |
static double | calc_trans_distance_t_below_Tramp (double k2, double k4, double vxi, double vyi, double t) |
Axiliary function for computing the line-integral distance along the trajectory, handling special cases of 1/0: More... | |
static double | calc_trans_distance_t_below_Tramp_abc (double t, double a, double b, double c) |
Axiliary function for calc_trans_distance_t_below_Tramp() and others. More... | |
static CParameterizedTrajectoryGenerator * | CreatePTG (const std::string &ptgClassName, const mrpt::utils::CConfigFileBase &cfg, const std::string &sSection, const std::string &sKeyPrefix) |
The class factory for creating a PTG from a list of parameters in a section of a given config file (physical file or in memory). More... | |
static double | index2alpha (uint16_t k, const unsigned int num_paths) |
static uint16_t | alpha2index (double alpha, const unsigned int num_paths) |
Static Public Attributes | |
static double | PATH_TIME_STEP = 10e-3 |
Duration of each PTG "step" (default: 10e-3=10 ms) More... | |
static double | eps = 1e-4 |
Mathematical "epsilon", to detect ill-conditioned situations (e.g. 1/0) (Default: 1e-4) More... | |
static std::string | OUTPUT_DEBUG_PATH_PREFIX = "./reactivenav.logs" |
The path used as defaul output in, for example, debugDumpInFiles. (Default="./reactivenav.logs/") More... | |
static PTG_collision_behavior_t | COLLISION_BEHAVIOR = mrpt::nav::COLL_BEH_BACK_AWAY |
Defines the behavior when there is an obstacle inside the robot shape right at the beginning of a PTG trajectory. More... | |
static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCParameterizedTrajectoryGenerator |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
double | internal_get_v (const double dir) const |
Evals expr_v. More... | |
double | internal_get_w (const double dir) const |
Evals expr_w. More... | |
double | internal_get_T_ramp (const double dir) const |
Evals expr_T_ramp. More... | |
void | internal_construct_exprs () |
void | internal_processNewRobotShape () MRPT_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) MRPT_OVERRIDE |
Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc. More... | |
void | internal_deinitialize () MRPT_OVERRIDE |
This must be called to de-initialize the PTG if some parameter is to be changed. More... | |
void | loadShapeFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) |
void | internal_shape_loadFromStream (mrpt::utils::CStream &in) |
void | internal_shape_saveToStream (mrpt::utils::CStream &out) const |
void | internal_TPObsDistancePostprocess (const double ox, const double oy, const double new_tp_obs_dist, double &inout_tp_obs) const |
To be called by implementors of updateTPObstacle() and updateTPObstacleSingle() to honor the user settings regarding COLLISION_BEHAVIOR. More... | |
virtual void | internal_readFromStream (mrpt::utils::CStream &in) |
virtual void | internal_writeToStream (mrpt::utils::CStream &out) const |
CSerializable virtual methods | |
void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
Introduces a pure virtual method responsible for writing to a CStream. More... | |
void | readFromStream (mrpt::utils::CStream &in, int version) |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
Static Protected Member Functions | |
static void | dumpVar_int (CStream &out, const char *varName, int v) |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More... | |
static void | dumpVar_float (CStream &out, const char *varName, float v) |
static void | dumpVar_double (CStream &out, const char *varName, double v) |
static void | dumpVar_bool (CStream &out, const char *varName, bool v) |
static void | dumpVar_string (CStream &out, const char *varName, const std::string &v) |
Protected Attributes | |
double | T_ramp_max |
double | V_MAX |
double | W_MAX |
double | turningRadiusReference |
std::string | expr_V |
std::string | expr_W |
std::string | expr_T_ramp |
std::vector< int > | m_pathStepCountCache |
mrpt::math::CRuntimeCompiledExpression | m_expr_v |
mrpt::math::CRuntimeCompiledExpression | m_expr_w |
mrpt::math::CRuntimeCompiledExpression | m_expr_T_ramp |
double | m_expr_dir |
double | m_robotRadius |
double | refDistance |
uint16_t | m_alphaValuesCount |
The number of discrete values for "alpha" between -PI and +PI. More... | |
double | m_score_priority |
uint16_t | m_clearance_num_points |
Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5) More... | |
uint16_t | m_clearance_decimated_paths |
Number of paths for the decimated paths analysis of clearance. More... | |
TNavDynamicState | m_nav_dyn_state |
Updated before each nav step by. More... | |
uint16_t | m_nav_dyn_state_target_k |
Update in updateNavDynamicState(), contains the path index (k) for the target. More... | |
bool | m_is_initialized |
Static Protected Attributes | |
static const uint16_t | INVALID_PTG_PATH_INDEX = static_cast<uint16_t>(-1) |
RTTI stuff | |
typedef CPTG_Holo_BlendPtr | Ptr |
typedef CPTG_Holo_BlendPtr | ConstPtr |
static mrpt::utils::CLASSINIT | _init_CPTG_Holo_Blend |
static mrpt::utils::TRuntimeClassId | classCPTG_Holo_Blend |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
static CPTG_Holo_BlendPtr | Create () |
typedef CPTG_Holo_BlendPtr mrpt::nav::CPTG_Holo_Blend::ConstPtr |
Definition at line 30 of file CPTG_Holo_Blend.h.
typedef CPTG_Holo_BlendPtr mrpt::nav::CPTG_Holo_Blend::Ptr |
A typedef for the associated smart pointer
Definition at line 30 of file CPTG_Holo_Blend.h.
CPTG_Holo_Blend::CPTG_Holo_Blend | ( | ) |
Definition at line 709 of file CPTG_Holo_Blend.cpp.
References internal_construct_exprs().
CPTG_Holo_Blend::CPTG_Holo_Blend | ( | const mrpt::utils::CConfigFileBase & | cfg, |
const std::string & | sSection | ||
) |
Definition at line 718 of file CPTG_Holo_Blend.cpp.
References internal_construct_exprs(), and loadFromConfigFile().
|
virtual |
Definition at line 725 of file CPTG_Holo_Blend.cpp.
|
staticprotected |
|
virtualinherited |
Auxiliary function for rendering.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 54 of file CPTG_RobotShape_Circular.cpp.
References mrpt::opengl::CSetOfLines::appendLine(), mrpt::opengl::CSetOfLines::appendLineStrip(), mrpt::poses::CPose2D::composePoint(), M_PI, mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, R, mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().
|
inherited |
Discrete index value for the corresponding alpha value.
Definition at line 164 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::generate_vel_cmd(), inverseMap_WS2TP(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and mrpt::nav::ClearanceDiagram::renderAs3DObject().
|
staticinherited |
Definition at line 155 of file CParameterizedTrajectoryGenerator.cpp.
References M_PI, mrpt::utils::round(), and mrpt::math::wrapToPi().
|
static |
Axiliary function for computing the line-integral distance along the trajectory, handling special cases of 1/0:
Definition at line 145 of file CPTG_Holo_Blend.cpp.
References eps.
|
static |
Axiliary function for calc_trans_distance_t_below_Tramp() and others.
Definition at line 131 of file CPTG_Holo_Blend.cpp.
References calc_trans_distance_t_below_Tramp_abc_numeric().
|
inlineinherited |
|
static |
|
static |
|
staticinherited |
The class factory for creating a PTG from a list of parameters in a section of a given config file (physical file or in memory).
Possible parameters are:
ptgClassName
can be any PTG class name which has been registered as any other mrpt::utils::CSerializable class.
std::logic_error | On invalid or missing parameters. |
Definition at line 21 of file CParameterizedTrajectoryGenerator_factory.cpp.
References mrpt::utils::CConfigFilePrefixer::bind(), mrpt::utils::TRuntimeClassId::createObject(), mrpt::utils::findRegisteredClass(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), MRPT_END, MRPT_START, mrpt::utils::registerAllPendingClasses(), mrpt::utils::CConfigFilePrefixer::setPrefixes(), THROW_EXCEPTION_FMT, and mrpt::system::trim().
Referenced by mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), and mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile().
|
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`
Definition at line 222 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::system::createDirectory(), mrpt::mrpt::format(), mrpt::nav::CParameterizedTrajectoryGenerator::getAlphaValuesCount(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), min, and mrpt::nav::CParameterizedTrajectoryGenerator::OUTPUT_DEBUG_PATH_PREFIX.
|
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 329 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::internal_deinitialize(), and mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream().
|
virtual |
Converts a discretized "alpha" value into a feasible motion command or action.
See derived classes for the meaning of these actions
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 371 of file CPTG_Holo_Blend.cpp.
References mrpt::kinematics::CVehicleVelCmd_Holo::dir_local, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::kinematics::CVehicleVelCmd_Holo::ramp_time, mrpt::kinematics::CVehicleVelCmd_Holo::rot_speed, mrpt::mrpt::utils::signWithZero(), and mrpt::kinematics::CVehicleVelCmd_Holo::vel.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Definition at line 47 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::dumpToTextStream(), and loadable_opts_my_cout.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::hmtslam::CHMTSLAM::loadOptions(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams().
|
virtualinherited |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.
Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams, mrpt::vision::TMultiResDescMatchOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams, mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions, mrpt::hmtslam::CHMTSLAM::TOptions, mrpt::maps::COccupancyGridMap2D::TInsertionOptions, mrpt::vision::TMatchingOptions, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::CLandmarksMap::TLikelihoodOptions, mrpt::maps::CColouredPointsMap::TColourOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams, mrpt::maps::CPointsMap::TLikelihoodOptions, mrpt::maps::CLandmarksMap::TInsertionOptions, mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams, mrpt::vision::TStereoSystemParams, mrpt::maps::CPointsMap::TInsertionOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams, mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions, mrpt::slam::CRangeBearingKFSLAM::TOptions, mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams, mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams, mrpt::maps::CBeaconMap::TInsertionOptions, mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions, mrpt::maps::CMultiMetricMapPDF::TPredictionParams, mrpt::maps::CBeaconMap::TLikelihoodOptions, mrpt::slam::CRangeBearingKFSLAM2D::TOptions, mrpt::maps::CHeightGridMap2D::TInsertionOptions, mrpt::graphslam::TSlidingWindow, mrpt::slam::CGridMapAligner::TConfigParams, mrpt::bayes::CParticleFilter::TParticleFilterOptions, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions, mrpt::bayes::TKF_options, mrpt::maps::CReflectivityGridMap2D::TInsertionOptions, mrpt::vision::CFeatureExtraction::TOptions, mrpt::graphslam::TUncertaintyPath< GRAPH_T >, mrpt::maps::TMapGenericParams, mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions, mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions, mrpt::hmtslam::CTopLCDetector_FabMap::TOptions, mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions, mrpt::slam::CICP::TConfigParams, mrpt::slam::CIncrementalMapPartitioner::TOptions, mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions, mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions, mrpt::slam::CMetricMapBuilderICP::TConfigParams, mrpt::maps::TMetricMapInitializer, mrpt::vision::CCamModel, and mrpt::slam::TKLDParams.
Definition at line 80 of file CLoadableOptions.cpp.
References mrpt::utils::CConfigFileMemory::getContent(), mrpt::utils::CStream::printf(), and mrpt::utils::CLoadableOptions::saveToConfigFile().
Referenced by mrpt::utils::CLoadableOptions::dumpToConsole().
|
staticprotectedinherited |
Definition at line 67 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 62 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 57 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
Definition at line 52 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 72 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
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 162 of file CObject.h.
References mrpt::utils::CObjectPtr.
Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().
|
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.
treat_as_obstacle | true: normal use for obstacles; false: compute shortest distances to a target point (no collision) |
Definition at line 411 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::math::angDistance(), mrpt::mrpt::utils::DEG2RAD(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceToRobotShape(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathPose(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::math::TPose2D::inverseComposePoint(), mrpt::mrpt::utils::keep_min(), mrpt::math::TPoint2D::norm(), mrpt::nav::CParameterizedTrajectoryGenerator::refDistance, mrpt::utils::round(), mrpt::math::TPoint2D::x, and mrpt::math::TPoint2D::y.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateClearance().
|
virtualinherited |
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 112 of file CPTG_RobotShape_Circular.cpp.
References mrpt::mrpt::math::hypot_fast(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.
|
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 210 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().
|
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 207 of file CParameterizedTrajectoryGenerator.h.
|
inlineinherited |
Get the number of different, discrete paths in this family.
Definition at line 236 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize().
|
inlineinherited |
Definition at line 261 of file CParameterizedTrajectoryGenerator.h.
|
inlineinherited |
Definition at line 258 of file CParameterizedTrajectoryGenerator.h.
|
inlineinherited |
Definition at line 224 of file CParameterizedTrajectoryGenerator.h.
|
virtual |
Gets a short textual description of the PTG and its parameters.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 224 of file CPTG_Holo_Blend.cpp.
References mrpt::mrpt::format().
|
inlinevirtual |
Returns the maximum angular velocity expected from this PTG [rad/s].
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 57 of file CPTG_Holo_Blend.h.
|
inlinevirtual |
Returns the maximum linear velocity expected from this PTG [m/s].
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 56 of file CPTG_Holo_Blend.h.
|
virtualinherited |
Returns an approximation of the robot radius.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 102 of file CPTG_RobotShape_Circular.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.
|
inlineinherited |
Get the number of different, discrete paths in this family.
Definition at line 238 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::impl_waypoint_is_reachable(), and TEST().
Access path k
([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step
.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 453 of file CPTG_Holo_Blend.cpp.
References COMMON_PTG_DESIGN_PARAMS, and mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha().
|
virtual |
Access path k
([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step
.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 401 of file CPTG_Holo_Blend.cpp.
References COMMON_PTG_DESIGN_PARAMS, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::mrpt::utils::signWithZero(), and mrpt::math::solve_poly2().
|
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.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 384 of file CPTG_Holo_Blend.cpp.
References ASSERT_, and THROW_EXCEPTION_FMT.
|
virtual |
Returns the duration (in seconds) of each "step".
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 704 of file CPTG_Holo_Blend.cpp.
|
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
. Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 475 of file CPTG_Holo_Blend.cpp.
References ASSERT_, COMMON_PTG_DESIGN_PARAMS, eps, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), PERFORMANCE_BENCHMARK, and mrpt::utils::round().
|
inlineinherited |
Definition at line 248 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), and TEST().
|
inlineinherited |
Definition at line 390 of file CParameterizedTrajectoryGenerator.h.
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.
|
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 255 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().
|
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.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 685 of file CPTG_Holo_Blend.cpp.
|
inherited |
Alpha value for the discrete corresponding value.
Definition at line 150 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), directionToMotionCommand(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::directionToMotionCommand(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), getPathDist(), getPathPose(), getPathStepForDist(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), and updateTPObstacleSingle().
|
staticinherited |
Definition at line 143 of file CParameterizedTrajectoryGenerator.cpp.
References ASSERT_BELOW_, and M_PI.
|
inherited |
Must be called to resize a CD to its correct size, before calling updateClearance()
Definition at line 373 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::ClearanceDiagram::decimated_k_to_real_k(), mrpt::nav::ClearanceDiagram::get_path_clearance_decimated(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_decimated_paths, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points, mrpt::nav::ClearanceDiagram::resize(), and mrpt::utils::round().
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate().
|
inherited |
Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc.
Definition at line 317 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::system::fileNameStripInvalidChars(), mrpt::nav::CParameterizedTrajectoryGenerator::getDescription(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_initialize(), and mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.
|
inherited |
Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ranges, in "pseudometers", un-normalized).
Definition at line 204 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().
|
inherited |
Definition at line 210 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::getPathDist(), mrpt::nav::CParameterizedTrajectoryGenerator::getPathStepCount(), mrpt::nav::CParameterizedTrajectoryGenerator::INVALID_PTG_PATH_INDEX, mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state_target_k, min, and mrpt::nav::CParameterizedTrajectoryGenerator::refDistance.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacles(), and mrpt::nav::PlannerTPS_VirtualBase::spaceTransformerOneDirectionOnly().
|
protected |
Definition at line 729 of file CPTG_Holo_Blend.cpp.
References expr_T_ramp, expr_V, expr_W, m_expr_dir, m_expr_T_ramp, m_expr_v, m_expr_w, mrpt::math::CRuntimeCompiledExpression::register_symbol_table(), T_ramp_max, V_MAX, and W_MAX.
Referenced by CPTG_Holo_Blend().
|
protectedvirtual |
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 366 of file CPTG_Holo_Blend.cpp.
|
protected |
Evals expr_T_ramp.
Definition at line 758 of file CPTG_Holo_Blend.cpp.
References mrpt::math::CRuntimeCompiledExpression::eval(), m_expr_dir, and m_expr_T_ramp.
|
protected |
Evals expr_v.
Definition at line 748 of file CPTG_Holo_Blend.cpp.
References mrpt::math::CRuntimeCompiledExpression::eval(), m_expr_dir, and m_expr_v.
|
protected |
Evals expr_w.
Definition at line 753 of file CPTG_Holo_Blend.cpp.
References mrpt::math::CRuntimeCompiledExpression::eval(), m_expr_dir, and m_expr_w.
|
protectedvirtual |
Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Space, inverseMap_WS2TP(), etc.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 764 of file CPTG_Holo_Blend.cpp.
References ASSERT_, mrpt::math::CRuntimeCompiledExpression::compile(), expr_T_ramp, expr_V, expr_W, mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, m_expr_T_ramp, m_expr_v, m_expr_w, m_pathStepCountCache, mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, T_ramp_max, V_MAX, and W_MAX.
|
protectedvirtual |
Will be called whenever the robot shape is set / updated.
Implements mrpt::nav::CPTG_RobotShape_Circular.
Definition at line 680 of file CPTG_Holo_Blend.cpp.
|
protectedvirtualinherited |
Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.
Definition at line 103 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::deinitialize(), mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_decimated_paths, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points, mrpt::nav::CParameterizedTrajectoryGenerator::m_score_priority, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, mrpt::nav::CParameterizedTrajectoryGenerator::refDistance, and version.
Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_readFromStream(), and readFromStream().
|
protectedinherited |
Definition at line 79 of file CPTG_RobotShape_Circular.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and version.
Referenced by readFromStream().
|
protectedinherited |
Definition at line 94 of file CPTG_RobotShape_Circular.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, and version.
Referenced by writeToStream().
|
protectedinherited |
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 336 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::COLL_BEH_BACK_AWAY, mrpt::nav::COLL_BEH_STOP, mrpt::nav::CParameterizedTrajectoryGenerator::COLLISION_BEHAVIOR, mrpt::nav::CParameterizedTrajectoryGenerator::getMaxRobotRadius(), mrpt::nav::CParameterizedTrajectoryGenerator::isPointInsideRobotShape(), mrpt::mrpt::utils::keep_min(), and THROW_EXCEPTION.
Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::updateTPObstacle(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::updateTPObstacleSingle().
|
protectedvirtualinherited |
Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.
Definition at line 134 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_decimated_paths, mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points, mrpt::nav::CParameterizedTrajectoryGenerator::m_score_priority, mrpt::nav::CParameterizedTrajectoryGenerator::refDistance, and version.
Referenced by mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_writeToStream(), and writeToStream().
|
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. |
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 274 of file CPTG_Holo_Blend.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::alpha2index(), ASSERT_, MRPT_UNUSED_PARAM, PERFORMANCE_BENCHMARK, and mrpt::mrpt::math::square().
|
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 112 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores().
|
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 281 of file CParameterizedTrajectoryGenerator.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::m_is_initialized.
|
virtualinherited |
Returns true if the point lies within the robot shape.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 107 of file CPTG_RobotShape_Circular.cpp.
References mrpt::mrpt::math::hypot_fast(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.
|
virtual |
Loads a set of default parameters; provided exclusively for the PTG-configurator tool.
Reimplemented from mrpt::nav::CPTG_RobotShape_Circular.
Definition at line 177 of file CPTG_Holo_Blend.cpp.
References mrpt::mrpt::utils::DEG2RAD(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), and mrpt::nav::CPTG_RobotShape_Circular::loadDefaultParams().
|
virtual |
Parameters accepted by this base class:
${sKeyPrefix}num_paths
: The number of different paths in this family (number of discrete alpha
values).${sKeyPrefix}ref_distance
: The maximum distance in PTGs [meters]${sKeyPrefix}score_priority
: When used in path planning, a multiplying factor (default=1.0) for the scores for this PTG. Assign values <1 to PTGs with low priority. Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 188 of file CPTG_Holo_Blend.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::loadShapeFromConfigFile(), MRPT_LOAD_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR, MRPT_LOAD_HERE_CONFIG_VAR_DEGREES_NO_DEFAULT, and MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT.
Referenced by CPTG_Holo_Blend().
|
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 23 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::loadFromConfigFile().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
protectedinherited |
Definition at line 39 of file CPTG_RobotShape_Circular.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::internal_processNewRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius, and MRPT_LOAD_HERE_CONFIG_VAR.
Referenced by loadFromConfigFile().
|
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 from mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 695 of file CPTG_Holo_Blend.cpp.
|
virtual |
Invoked when m_nav_dyn_state
has changed; gives the PTG the opportunity to react and parameterize paths depending on the instantaneous conditions.
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 172 of file CPTG_Holo_Blend.cpp.
Definition at line 30 of file CPTG_Holo_Blend.h.
|
inline |
Definition at line 30 of file CPTG_Holo_Blend.h.
Definition at line 30 of file CPTG_Holo_Blend.h.
Definition at line 30 of file CPTG_Holo_Blend.h.
|
inline |
Definition at line 30 of file CPTG_Holo_Blend.h.
Definition at line 30 of file CPTG_Holo_Blend.h.
|
inline |
Definition at line 30 of file CPTG_Holo_Blend.h.
|
inline |
Definition at line 30 of file CPTG_Holo_Blend.h.
|
virtual |
Returns the same than inverseMap_WS2TP() but without any additional cost.
The default implementation just calls inverseMap_WS2TP() and discards (k,d).
Reimplemented from mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 359 of file CPTG_Holo_Blend.cpp.
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
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 error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 230 of file CPTG_Holo_Blend.cpp.
References mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CPTG_RobotShape_Circular::internal_shape_loadFromStream(), MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and version.
|
virtualinherited |
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 169 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().
|
virtual |
This method saves the options to a ".ini"-like file or memory-stored string list.
Reimplemented from mrpt::nav::CPTG_RobotShape_Circular.
Definition at line 202 of file CPTG_Holo_Blend.cpp.
References MRPT_END, MRPT_START, mrpt::mrpt::utils::RAD2DEG(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::saveToConfigFile(), and mrpt::utils::CConfigFileBase::write().
|
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 39 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::saveToConfigFile().
|
inlineinherited |
Definition at line 262 of file CParameterizedTrajectoryGenerator.h.
|
inlineinherited |
Definition at line 259 of file CParameterizedTrajectoryGenerator.h.
|
inlinevirtualinherited |
Reimplemented in mrpt::nav::CPTG_DiffDrive_CollisionGridBased.
Definition at line 140 of file CParameterizedTrajectoryGenerator.h.
|
inherited |
Robot shape must be set before initialization, either from ctor params or via this method.
Definition at line 28 of file CPTG_RobotShape_Circular.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::internal_processNewRobotShape(), and mrpt::nav::CPTG_RobotShape_Circular::m_robotRadius.
Referenced by mrpt::nav::PlannerTPS_VirtualBase::internal_initialize_PTG(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), and mrpt::nav::CReactiveNavigationSystem3D::STEP1_InitPTGs().
|
inlineinherited |
Definition at line 256 of file CParameterizedTrajectoryGenerator.h.
|
inlinevirtualinherited |
Returns true if this PTG takes into account the desired velocity at target.
Definition at line 195 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), and mrpt::nav::CParameterizedTrajectoryGenerator::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 from mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 690 of file CPTG_Holo_Blend.cpp.
|
inherited |
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 392 of file CParameterizedTrajectoryGenerator.cpp.
References ASSERT_, mrpt::nav::ClearanceDiagram::decimated_k_to_real_k(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::ClearanceDiagram::get_actual_num_paths(), mrpt::nav::ClearanceDiagram::get_decimated_num_paths(), mrpt::nav::ClearanceDiagram::get_path_clearance_decimated(), mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, and mrpt::nav::CParameterizedTrajectoryGenerator::m_clearance_num_points.
Referenced by mrpt::nav::CReactiveNavigationSystem::STEP3_WSpaceToTPSpace().
|
inherited |
Definition at line 406 of file CParameterizedTrajectoryGenerator.cpp.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate().
|
inherited |
To be invoked by the navigator before each navigation step, to let the PTG to react to changing dynamic conditions.
Definition at line 286 of file CParameterizedTrajectoryGenerator.cpp.
References ASSERT_, mrpt::nav::CParameterizedTrajectoryGenerator::INVALID_PTG_PATH_INDEX, mrpt::nav::CParameterizedTrajectoryGenerator::inverseMap_WS2TP(), mrpt::nav::CParameterizedTrajectoryGenerator::m_alphaValuesCount, mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state, mrpt::nav::CParameterizedTrajectoryGenerator::m_nav_dyn_state_target_k, mrpt::nav::CParameterizedTrajectoryGenerator::onNewNavDynamicState(), mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::relTarget, mrpt::nav::CParameterizedTrajectoryGenerator::supportSpeedAtTarget(), mrpt::nav::CParameterizedTrajectoryGenerator::TNavDynamicState::targetRelSpeed, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.
Referenced by mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep().
|
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. Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 670 of file CPTG_Holo_Blend.cpp.
References PERFORMANCE_BENCHMARK.
|
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).
Implements mrpt::nav::CParameterizedTrajectoryGenerator.
Definition at line 561 of file CPTG_Holo_Blend.cpp.
References COMMON_PTG_DESIGN_PARAMS, eps, mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::mrpt::math::isFinite(), mrpt::mrpt::utils::keep_min(), min, R, mrpt::math::solve_poly3(), and mrpt::math::solve_poly4().
|
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 NULL is class does not support conversion to MATLAB. Definition at line 79 of file CSerializable.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
out | The output binary stream where object must be dumped. |
getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 259 of file CPTG_Holo_Blend.cpp.
References mrpt::nav::CPTG_RobotShape_Circular::internal_shape_saveToStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), and version.
|
staticprotected |
Definition at line 30 of file CPTG_Holo_Blend.h.
|
staticinherited |
|
staticinherited |
Definition at line 64 of file CParameterizedTrajectoryGenerator.h.
|
static |
Definition at line 30 of file CPTG_Holo_Blend.h.
|
staticinherited |
Definition at line 42 of file CSerializable.h.
|
static |
Definition at line 30 of file CPTG_Holo_Blend.h.
|
staticinherited |
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 295 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess().
|
static |
Mathematical "epsilon", to detect ill-conditioned situations (e.g. 1/0) (Default: 1e-4)
Definition at line 63 of file CPTG_Holo_Blend.h.
|
protected |
Definition at line 70 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
|
protected |
Definition at line 70 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
|
protected |
Definition at line 70 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
|
staticprotectedinherited |
Definition at line 316 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacleSingle(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState().
|
protectedinherited |
The number of discrete values for "alpha" between -PI and +PI.
Definition at line 309 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::alpha2index(), mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), mrpt::nav::CParameterizedTrajectoryGenerator::initClearanceDiagram(), mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacles(), internal_initialize(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::nav::CParameterizedTrajectoryGenerator::updateClearance(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState().
|
protectedinherited |
Number of paths for the decimated paths analysis of clearance.
Definition at line 312 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::initClearanceDiagram(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), and mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile().
|
protectedinherited |
Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,1] (Default=5)
Definition at line 311 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::initClearanceDiagram(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateClearance().
|
protected |
Definition at line 75 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), internal_get_T_ramp(), internal_get_v(), and internal_get_w().
|
protected |
Definition at line 74 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), internal_get_T_ramp(), and internal_initialize().
|
protected |
Definition at line 74 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), internal_get_v(), and internal_initialize().
|
protected |
Definition at line 74 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), internal_get_w(), and internal_initialize().
|
protectedinherited |
|
protectedinherited |
Updated before each nav step by.
Definition at line 313 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState().
|
protectedinherited |
Update in updateNavDynamicState(), contains the path index (k) for the target.
Definition at line 314 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacleSingle(), and mrpt::nav::CParameterizedTrajectoryGenerator::updateNavDynamicState().
|
mutableprotected |
Definition at line 71 of file CPTG_Holo_Blend.h.
Referenced by internal_initialize().
|
protectedinherited |
Definition at line 398 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), mrpt::nav::CPTG_RobotShape_Circular::evalClearanceToRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::getMaxRobotRadius(), internal_initialize(), mrpt::nav::CPTG_RobotShape_Circular::internal_shape_loadFromStream(), mrpt::nav::CPTG_RobotShape_Circular::internal_shape_saveToStream(), mrpt::nav::CPTG_RobotShape_Circular::isPointInsideRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::loadDefaultParams(), mrpt::nav::CPTG_RobotShape_Circular::loadShapeFromConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::saveToConfigFile(), and mrpt::nav::CPTG_RobotShape_Circular::setRobotShapeRadius().
|
protectedinherited |
Definition at line 310 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), and mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile().
|
staticinherited |
The path used as defaul output in, for example, debugDumpInFiles. (Default="./reactivenav.logs/")
Definition at line 226 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles().
|
static |
Duration of each PTG "step" (default: 10e-3=10 ms)
Definition at line 62 of file CPTG_Holo_Blend.h.
|
protectedinherited |
Definition at line 308 of file CParameterizedTrajectoryGenerator.h.
Referenced by mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::CParameterizedTrajectoryGenerator::initTPObstacleSingle(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_readFromStream(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_writeToStream(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::nav::CParameterizedTrajectoryGenerator::loadDefaultParams(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), and mrpt::nav::CPTG_DiffDrive_CollisionGridBased::setRefDistance().
|
protected |
Definition at line 66 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
|
protected |
Definition at line 68 of file CPTG_Holo_Blend.h.
|
protected |
Definition at line 67 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
|
protected |
Definition at line 67 of file CPTG_Holo_Blend.h.
Referenced by internal_construct_exprs(), and internal_initialize().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |