Go to the documentation of this file.
30 m_alphaValuesCount(0),
31 m_score_priority(1.0),
32 m_clearance_num_points(5),
33 m_clearance_decimated_paths(15),
35 m_nav_dyn_state_target_k(INVALID_PTG_PATH_INDEX),
36 m_is_initialized(false)
40 void CParameterizedTrajectoryGenerator::loadDefaultParams()
98 const int WN = 25, WV = 30;
102 "Number of discrete paths (`resolution`) in the PTG");
105 "Maximum distance (meters) for building trajectories (visibility "
109 "When used in path planning, a multiplying factor (default=1.0) for "
110 "the scores for this PTG. Assign values <1 to PTGs with low priority.");
113 "Number of steps for the piecewise-constant approximation of clearance "
118 "Number of decimated paths for estimation of clearance (Default=15).");
123 "(Only for debugging) Current robot velocity vx [m/s].");
126 "(Only for debugging) Current robot velocity vy [m/s].");
129 WV,
"(Only for debugging) Current robot velocity omega [deg/s].");
133 "(Only for debugging) Relative target x [m].");
136 "(Only for debugging) Relative target y [m].");
139 WN, WV,
"(Only for debugging) Relative target phi [deg].");
143 "(Only for debugging) Desired relative speed at target [0,1]");
166 bool old_use_approx_clearance;
167 in >> old_use_approx_clearance;
195 uint16_t k,
const unsigned int num_paths)
198 return M_PI * (-1.0 + 2.0 * (k + 0.5) / num_paths);
207 double alpha,
const unsigned int num_paths)
212 if (k >=
static_cast<int>(num_paths)) k = num_paths - 1;
223 const double decimate_distance,
const double max_path_distance)
const
229 double last_added_dist = 0.0;
230 for (
size_t n = 0;
n < nPointsInPath;
n++)
236 if (max_path_distance >= 0.0 && d >= max_path_distance)
break;
238 if (d < last_added_dist + decimate_distance &&
n != 0)
257 std::vector<double>& TP_Obstacles)
const
264 uint16_t k,
double& TP_Obstacle_k)
const
284 const string sFilTxt_x =
285 mrpt::format(
"%s/PTGs/PTG%s_x.txt", sPath, ptg_name.c_str());
286 const string sFilTxt_y =
287 mrpt::format(
"%s/PTGs/PTG%s_y.txt", sPath, ptg_name.c_str());
288 const string sFilTxt_phi =
289 mrpt::format(
"%s/PTGs/PTG%s_phi.txt", sPath, ptg_name.c_str());
290 const string sFilTxt_t =
291 mrpt::format(
"%s/PTGs/PTG%s_t.txt", sPath, ptg_name.c_str());
292 const string sFilTxt_d =
293 mrpt::format(
"%s/PTGs/PTG%s_d.txt", sPath, ptg_name.c_str());
295 ofstream fx(sFilTxt_x.c_str());
296 if (!fx.is_open())
return false;
297 ofstream fy(sFilTxt_y.c_str());
298 if (!fy.is_open())
return false;
299 ofstream fp(sFilTxt_phi.c_str());
300 if (!fp.is_open())
return false;
301 ofstream fd(sFilTxt_d.c_str());
302 if (!fd.is_open())
return false;
307 fx <<
"% PTG data file for 'x'. Each row is the trajectory for a different "
308 "'alpha' parameter value."
310 fy <<
"% PTG data file for 'y'. Each row is the trajectory for a different "
311 "'alpha' parameter value."
313 fp <<
"% PTG data file for 'phi'. Each row is the trajectory for a "
314 "different 'alpha' parameter value."
316 fd <<
"% PTG data file for 'd'. Each row is the trajectory for a different "
317 "'alpha' parameter value."
320 vector<size_t> path_length(nPaths);
323 size_t maxPoints = 0;
324 for (
size_t k = 0; k < nPaths; k++)
325 maxPoints = max(maxPoints, path_length[k]);
327 for (
size_t k = 0; k < nPaths; k++)
329 for (
size_t n = 0;
n < maxPoints;
n++)
331 const size_t nn =
std::min(
n, path_length[k] - 1);
355 const bool force_update)
378 double target_norm_d;
383 target_k, target_norm_d, 1.0 );
384 if (target_norm_d > 0.01 && target_norm_d < 0.99 && target_k >= 0 &&
395 const std::string& cacheFilename,
const bool verbose)
400 !cacheFilename.empty()
417 const double ox,
const double oy,
const double new_tp_obs_dist,
418 double& inout_tp_obs)
const
421 if (!is_obs_inside_robot_shape)
468 const double numStepsPerIncr =
472 for (
double step_pointer_dbl = 0.0; step_pointer_dbl < numPathSteps;
473 step_pointer_dbl += numStepsPerIncr)
476 const double dist_over_path = this->
getPathDist(real_k, step);
477 cl_path[dist_over_path] = 1.0;
507 const double ox,
const double oy,
const uint16_t k,
509 bool treat_as_obstacle)
const
511 bool had_collision =
false;
514 ASSERT_(numPathSteps > inout_realdist2clearance.size());
516 const double numStepsPerIncr =
517 (numPathSteps - 1.0) / (inout_realdist2clearance.size());
519 double step_pointer_dbl = 0.0;
523 for (
auto& e : inout_realdist2clearance)
525 step_pointer_dbl += numStepsPerIncr;
528 double& inout_clearance = e.second;
535 inout_clearance = .0;
544 const double this_clearance =
547 if (this_clearance <= .0 && treat_as_obstacle)
550 had_collision =
true;
551 inout_clearance = .0;
556 const double this_clearance_norm =
566 : curVelLocal(0, 0, 0),
567 relTarget(20.0, 0, 0),
585 out << curVelLocal << relTarget << targetRelSpeed;
596 in >> curVelLocal >> relTarget >> targetRelSpeed;
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value.
static std::string OUTPUT_DEBUG_PATH_PREFIX
The path used as defaul output in, for example, debugDumpInFiles.
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 ...
void readFromStream(mrpt::serialization::CArchive &in)
bool operator==(const TNavDynamicState &o) 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 set...
size_t get_actual_num_paths() const
uint16_t m_clearance_num_points
Number of steps for the piecewise-constant approximation of clearance from TPS distances [0,...
void write(const std::string §ion, const std::string &name, enum_t value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
mrpt::math::TPoint2D inverseComposePoint(const TPoint2D g) const
double targetRelSpeed
Desired relative speed [0,1] at target.
unsigned __int16 uint16_t
double phi
Orientation (rads)
virtual void internal_readFromStream(mrpt::serialization::CArchive &in)
A set of independent lines (or segments), one line with its own start and end positions (X,...
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.
size_t get_decimated_num_paths() const
static const uint16_t INVALID_PTG_PATH_INDEX
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...
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 pa...
void deinitialize()
This must be called to de-initialize the PTG if some parameter is to be changed.
uint16_t m_clearance_decimated_paths
Number of paths for the decimated paths analysis of clearance.
double vx
Velocity components: X,Y (m/s)
virtual void internal_deinitialize()=0
This must be called to de-initialize the PTG if some parameter is to be changed.
#define THROW_EXCEPTION(msg)
#define ASSERT_(f)
Defines an assertion mechanism.
#define MRPT_LOAD_HERE_CONFIG_VAR_DEGREES( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
GLclampf GLclampf GLclampf alpha
double RAD2DEG(const double x)
Radians to degrees.
mrpt::math::TPose2D relTarget
Current relative target location.
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) C...
double index2alpha(uint16_t k) const
Alpha value for the discrete corresponding value.
Virtual base class for "archives": classes abstracting I/O streams.
#define MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
#define MRPT_LOAD_CONFIG_VAR_NO_DEFAULT( variableName, variableType, configFileObject, sectionNameStr)
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores ('_') or any other user-given char.
uint16_t alpha2index(double alpha) const
Discrete index value for the corresponding alpha value.
mrpt::math::TTwist2D curVelLocal
Current vehicle velocity (local frame of reference)
TNavDynamicState m_nav_dyn_state
Updated before each nav step by
#define ASSERT_BELOW_(__A, __B)
void appendLine(const mrpt::math::TSegment3D &sgm)
Appends a line to the set.
void appendLineStrip(float x, float y, float z)
Appends a line whose starting point is the end point of the last line (similar to OpenGL's GL_LINE_ST...
#define MRPT_LOAD_HERE_CONFIG_VAR( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
virtual bool supportSpeedAtTarget() const
Returns true if this PTG takes into account the desired velocity at target.
int round(const T value)
Returns the closer integer (int) to x.
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-Spac...
void initTPObstacles(std::vector< double > &TP_Obstacles) const
Resizes and populates the initial appropriate contents in a vector of tp-obstacles (collision-free ra...
This class allows loading and storing values and vectors of different types from a configuration text...
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
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-Spac...
void keep_max(T &var, const K test_val)
If the second argument is above the first one, set the first argument to this higher value.
Clearance information for one particular PTG and one set of obstacles.
virtual double getMaxRobotRadius() const =0
Returns an approximation of the robot radius.
uint16_t m_alphaValuesCount
The number of discrete values for "alpha" between -PI and +PI.
std::map< double, double > dist2clearance_t
[TPS_distance] => normalized_clearance_for_exactly_that_robot_pose
virtual std::string getDescription() const =0
Gets a short textual description of the PTG and its parameters.
unsigned __int64 uint64_t
Dynamic state that may affect the PTG path parameterization.
IMPLEMENTS_VIRTUAL_SERIALIZABLE(CParameterizedTrajectoryGenerator, CSerializable, mrpt::nav) CParameterizedTrajectoryGenerator
size_t decimated_k_to_real_k(size_t k) const
virtual void internal_writeToStream(mrpt::serialization::CArchive &out) const
virtual bool supportVelCmdNOP() const
Returns true if it is possible to stop sending velocity commands to the robot and,...
void initTPObstacleSingle(uint16_t k, double &TP_Obstacle_k) const
void writeToStream(mrpt::serialization::CArchive &out) const
@ COLL_BEH_BACK_AWAY
Favor getting back from too-close (almost collision) obstacles.
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.
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.
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)...
PTG_collision_behavior_t
Defines behaviors for where there is an obstacle inside the robot shape right at the beginning of a P...
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.
virtual double maxTimeInVelCmdNOP(int path_k) const
Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path...
virtual void saveToConfigFile(mrpt::config::CConfigFileBase &cfg, const std::string &sSection) const override
This method saves the options to a ".ini"-like file or memory-stored string list.
uint16_t m_nav_dyn_state_target_k
Update in updateNavDynamicState(), contains the path index (k) for the target.
void updateClearancePost(ClearanceDiagram &cd, const std::vector< double > &TP_obstacles) const
virtual bool isPointInsideRobotShape(const double x, const double y) const =0
Returns true if the point lies within the robot shape.
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 dynam...
GLsizei const GLchar ** string
@ COLL_BEH_STOP
Totally dissallow any movement if there is any too-close (almost collision) obstacles.
double norm() const
Point norm.
bool isInitialized() const
Returns true if initialize() has been called and there was no errors, so the PTG is ready to be queri...
void resize(size_t actual_num_paths, size_t decimated_num_paths)
Initializes the container to allocate decimated_num_paths entries, as a decimated subset of a total o...
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
bool createDirectory(const std::string &dirName)
Creates a directory.
bool debugDumpInFiles(const std::string &ptg_name) const
Dump PTG trajectories in four text files: .
double omega
Angular velocity (rad/s)
This is the base class for any user-defined PTG.
virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
Parameters accepted by this base class:
This namespace provides a OS-independent interface to many useful functions: filenames manipulation,...
uint16_t getAlphaValuesCount() const
Get the number of different, discrete paths in this family.
CParameterizedTrajectoryGenerator()
Default ctor.
dist2clearance_t & get_path_clearance_decimated(size_t decim_k)
virtual void onNewNavDynamicState()=0
Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize pat...
void initClearanceDiagram(ClearanceDiagram &cd) const
Must be called to resize a CD to its correct size, before calling updateClearance()
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |