Main MRPT website > C++ reference for MRPT 1.9.9
CPTG_Holo_Blend.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
13 
14 namespace mrpt
15 {
16 namespace nav
17 {
18 /** A PTG for circular-shaped robots with holonomic kinematics.
19  * - **Compatible kinematics**: Holonomic robot capable of velocity commands
20  * with a linear interpolation ("ramp "or "blending") time. See
21  * mrpt::kinematics::CVehicleSimul_Holo
22  * - **Compatible robot shape**: Circular robots
23  * - **PTG parameters**: Use the app `ptg-configurator`
24  *
25  * \note [New in MRPT 1.5.0]
26  * \ingroup nav_tpspace
27  */
29 {
31  public:
34  const mrpt::config::CConfigFileBase& cfg, const std::string& sSection);
35  virtual ~CPTG_Holo_Blend();
36 
37  virtual void loadFromConfigFile(
39  const std::string& sSection) override;
40  virtual void saveToConfigFile(
42  const std::string& sSection) const override;
43  virtual void loadDefaultParams() override;
44  virtual bool supportVelCmdNOP() const override;
45  virtual double maxTimeInVelCmdNOP(int path_k) const override;
46 
47  std::string getDescription() const override;
48  bool inverseMap_WS2TP(
49  double x, double y, int& out_k, double& out_d,
50  double tolerance_dist = 0.10) const override;
51  bool PTG_IsIntoDomain(double x, double y) const override;
52  void onNewNavDynamicState() override;
53 
54  /** Converts a discretized "alpha" value into a feasible motion command or
55  * action. See derived classes for the meaning of these actions */
57  uint16_t k) const override;
59  getSupportedKinematicVelocityCommand() const override;
60 
61  size_t getPathStepCount(uint16_t k) const override;
62  void getPathPose(
63  uint16_t k, uint32_t step, mrpt::math::TPose2D& p) const override;
64  double getPathDist(uint16_t k, uint32_t step) const override;
65  bool getPathStepForDist(
66  uint16_t k, double dist, uint32_t& out_step) const override;
67  double getPathStepDuration() const override;
68  double getMaxLinVel() const override { return V_MAX; }
69  double getMaxAngVel() const override { return W_MAX; }
70  void updateTPObstacle(
71  double ox, double oy, std::vector<double>& tp_obstacles) const override;
73  double ox, double oy, uint16_t k, double& tp_obstacle_k) const override;
74 
75  /** Duration of each PTG "step" (default: 10e-3=10 ms) */
76  static double PATH_TIME_STEP;
77  /** Mathematical "epsilon", to detect ill-conditioned situations (e.g. 1/0)
78  * (Default: 1e-4) */
79  static double eps;
80 
81  protected:
82  double T_ramp_max;
83  double V_MAX, W_MAX;
85 
87  mutable std::vector<int> m_pathStepCountCache;
88 
89  // Compilation of user-given expressions
91  double m_expr_dir; // Used as symbol "dir" in m_expr_v and m_expr_w
92 
93  /** Evals expr_v */
94  double internal_get_v(const double dir) const;
95  /** Evals expr_w */
96  double internal_get_w(const double dir) const;
97  /** Evals expr_T_ramp */
98  double internal_get_T_ramp(const double dir) const;
99 
101 
102  void internal_processNewRobotShape() override;
103  void internal_initialize(
104  const std::string& cacheFilename = std::string(),
105  const bool verbose = true) override;
106  void internal_deinitialize() override;
107 
108  public:
109  /** Axiliary function for computing the line-integral distance along the
110  * trajectory, handling special cases of 1/0: */
111  static double calc_trans_distance_t_below_Tramp(
112  double k2, double k4, double vxi, double vyi, double t);
113  /** Axiliary function for calc_trans_distance_t_below_Tramp() and others */
115  double t, double a, double b, double c);
116 };
117 }
118 }
mrpt::nav::CPTG_RobotShape_Circular
Base class for all PTGs using a 2D circular robot shape model.
Definition: CParameterizedTrajectoryGenerator.h:548
CParameterizedTrajectoryGenerator.h
mrpt::nav::CPTG_Holo_Blend::inverseMap_WS2TP
bool inverseMap_WS2TP(double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const override
Computes the closest (alpha,d) TP coordinates of the trajectory point closest to the Workspace (WS) C...
Definition: CPTG_Holo_Blend.cpp:309
mrpt::nav::CPTG_Holo_Blend::maxTimeInVelCmdNOP
virtual double maxTimeInVelCmdNOP(int path_k) const override
Only for PTGs supporting supportVelCmdNOP(): this is the maximum time (in seconds) for which the path...
Definition: CPTG_Holo_Blend.cpp:778
mrpt::nav::CPTG_Holo_Blend::T_ramp_max
double T_ramp_max
Definition: CPTG_Holo_Blend.h:82
mrpt::nav::CPTG_Holo_Blend::supportVelCmdNOP
virtual bool supportVelCmdNOP() const override
Returns true if it is possible to stop sending velocity commands to the robot and,...
Definition: CPTG_Holo_Blend.cpp:777
mrpt::nav::CPTG_Holo_Blend::getPathStepForDist
bool getPathStepForDist(uint16_t k, double dist, uint32_t &out_step) const override
Access path k ([0,N-1]=>[-pi,pi] in alpha): largest step count for which the traversed distance is < ...
Definition: CPTG_Holo_Blend.cpp:536
mrpt::nav::CPTG_Holo_Blend::m_expr_v
mrpt::expr::CRuntimeCompiledExpression m_expr_v
Definition: CPTG_Holo_Blend.h:90
t
GLdouble GLdouble t
Definition: glext.h:3689
uint16_t
unsigned __int16 uint16_t
Definition: rptypes.h:44
mrpt::nav::CPTG_Holo_Blend::m_pathStepCountCache
std::vector< int > m_pathStepCountCache
Definition: CPTG_Holo_Blend.h:87
mrpt::nav::CPTG_Holo_Blend::eps
static double eps
Mathematical "epsilon", to detect ill-conditioned situations (e.g.
Definition: CPTG_Holo_Blend.h:79
mrpt::nav::CPTG_Holo_Blend::turningRadiusReference
double turningRadiusReference
Definition: CPTG_Holo_Blend.h:84
c
const GLubyte * c
Definition: glext.h:6313
mrpt::nav::CPTG_Holo_Blend::W_MAX
double W_MAX
Definition: CPTG_Holo_Blend.h:83
mrpt::nav::CPTG_Holo_Blend::getPathPose
void getPathPose(uint16_t k, uint32_t step, mrpt::math::TPose2D &p) const override
Access path k ([0,N-1]=>[-pi,pi] in alpha): pose of the vehicle at discrete step step.
Definition: CPTG_Holo_Blend.cpp:456
mrpt::nav::CPTG_Holo_Blend::saveToConfigFile
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.
Definition: CPTG_Holo_Blend.cpp:218
mrpt::nav::CPTG_Holo_Blend::m_expr_w
mrpt::expr::CRuntimeCompiledExpression m_expr_w
Definition: CPTG_Holo_Blend.h:90
mrpt::nav::CPTG_Holo_Blend::updateTPObstacleSingle
void updateTPObstacleSingle(double ox, double oy, uint16_t k, double &tp_obstacle_k) const override
Like updateTPObstacle() but for one direction only (k) in TP-Space.
Definition: CPTG_Holo_Blend.cpp:631
mrpt::nav::CPTG_Holo_Blend::CPTG_Holo_Blend
CPTG_Holo_Blend()
Definition: CPTG_Holo_Blend.cpp:792
mrpt::nav::CPTG_Holo_Blend::getPathStepDuration
double getPathStepDuration() const override
Returns the duration (in seconds) of each "step".
Definition: CPTG_Holo_Blend.cpp:791
mrpt::nav::CPTG_Holo_Blend::V_MAX
double V_MAX
Definition: CPTG_Holo_Blend.h:83
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::nav::CPTG_Holo_Blend::getPathStepCount
size_t getPathStepCount(uint16_t k) const override
Access path k ([0,N-1]=>[-pi,pi] in alpha): number of discrete "steps" along the trajectory.
Definition: CPTG_Holo_Blend.cpp:435
mrpt::nav::CPTG_Holo_Blend::loadDefaultParams
virtual void loadDefaultParams() override
Loads a set of default parameters; provided exclusively for the PTG-configurator tool.
Definition: CPTG_Holo_Blend.cpp:189
mrpt::nav::CPTG_Holo_Blend::m_expr_dir
double m_expr_dir
Definition: CPTG_Holo_Blend.h:91
p
GLfloat GLfloat p
Definition: glext.h:6305
CRuntimeCompiledExpression.h
mrpt::nav::CPTG_Holo_Blend::getSupportedKinematicVelocityCommand
virtual mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const override
Returns an empty kinematic velocity command object of the type supported by this PTG.
Definition: CPTG_Holo_Blend.cpp:771
mrpt::nav::CPTG_Holo_Blend::PTG_IsIntoDomain
bool PTG_IsIntoDomain(double x, double y) const override
Returns the same than inverseMap_WS2TP() but without any additional cost.
Definition: CPTG_Holo_Blend.cpp:408
mrpt::nav::CPTG_Holo_Blend::expr_V
std::string expr_V
Definition: CPTG_Holo_Blend.h:86
mrpt::nav::CPTG_Holo_Blend::getMaxLinVel
double getMaxLinVel() const override
Returns the maximum linear velocity expected from this PTG [m/s].
Definition: CPTG_Holo_Blend.h:68
mrpt::nav::CPTG_Holo_Blend::updateTPObstacle
void updateTPObstacle(double ox, double oy, std::vector< double > &tp_obstacles) const override
Updates the radial map of closest TP-Obstacles given a single obstacle point at (ox,...
Definition: CPTG_Holo_Blend.cpp:754
mrpt::nav::CPTG_Holo_Blend::internal_construct_exprs
void internal_construct_exprs()
Definition: CPTG_Holo_Blend.cpp:807
mrpt::nav::CPTG_Holo_Blend::internal_get_T_ramp
double internal_get_T_ramp(const double dir) const
Evals expr_T_ramp.
Definition: CPTG_Holo_Blend.cpp:836
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::nav::CPTG_Holo_Blend::getDescription
std::string getDescription() const override
Gets a short textual description of the PTG and its parameters.
Definition: CPTG_Holo_Blend.cpp:259
b
GLubyte GLubyte b
Definition: glext.h:6279
mrpt::nav::CPTG_Holo_Blend::~CPTG_Holo_Blend
virtual ~CPTG_Holo_Blend()
Definition: CPTG_Holo_Blend.cpp:806
mrpt::math::TPose2D
Lightweight 2D pose.
Definition: lightweight_geom_data.h:186
mrpt::nav::CPTG_Holo_Blend::internal_processNewRobotShape
void internal_processNewRobotShape() override
Will be called whenever the robot shape is set / updated.
Definition: CPTG_Holo_Blend.cpp:765
mrpt::expr::CRuntimeCompiledExpression
A wrapper of exprtk runtime expression compiler: it takes a string representing an expression (from a...
Definition: CRuntimeCompiledExpression.h:52
mrpt::nav::CPTG_Holo_Blend::PATH_TIME_STEP
static double PATH_TIME_STEP
Duration of each PTG "step" (default: 10e-3=10 ms)
Definition: CPTG_Holo_Blend.h:76
mrpt::nav::CPTG_Holo_Blend::onNewNavDynamicState
void onNewNavDynamicState() override
Invoked when m_nav_dyn_state has changed; gives the PTG the opportunity to react and parameterize pat...
Definition: CPTG_Holo_Blend.cpp:184
mrpt::nav::CPTG_Holo_Blend::internal_get_v
double internal_get_v(const double dir) const
Evals expr_v.
Definition: CPTG_Holo_Blend.cpp:826
mrpt::nav::CPTG_Holo_Blend::internal_deinitialize
void internal_deinitialize() override
This must be called to de-initialize the PTG if some parameter is to be changed.
Definition: CPTG_Holo_Blend.cpp:415
mrpt::kinematics::CVehicleVelCmd::Ptr
std::shared_ptr< CVehicleVelCmd > Ptr
Definition: CVehicleVelCmd.h:24
mrpt::nav::CPTG_Holo_Blend::getMaxAngVel
double getMaxAngVel() const override
Returns the maximum angular velocity expected from this PTG [rad/s].
Definition: CPTG_Holo_Blend.h:69
mrpt::nav::CPTG_Holo_Blend::expr_W
std::string expr_W
Definition: CPTG_Holo_Blend.h:86
mrpt::nav::CPTG_Holo_Blend
A PTG for circular-shaped robots with holonomic kinematics.
Definition: CPTG_Holo_Blend.h:28
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:102
mrpt::nav::CPTG_Holo_Blend::directionToMotionCommand
virtual mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const override
Converts a discretized "alpha" value into a feasible motion command or action.
Definition: CPTG_Holo_Blend.cpp:420
mrpt::nav::CPTG_Holo_Blend::internal_get_w
double internal_get_w(const double dir) const
Evals expr_w.
Definition: CPTG_Holo_Blend.cpp:831
mrpt::nav::CPTG_Holo_Blend::calc_trans_distance_t_below_Tramp
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 cas...
Definition: CPTG_Holo_Blend.cpp:152
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::nav::CPTG_Holo_Blend::getPathDist
double getPathDist(uint16_t k, uint32_t step) const override
Access path k ([0,N-1]=>[-pi,pi] in alpha): traversed distance at discrete step step.
Definition: CPTG_Holo_Blend.cpp:512
mrpt::nav::CPTG_Holo_Blend::loadFromConfigFile
virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
Parameters accepted by this base class:
Definition: CPTG_Holo_Blend.cpp:200
mrpt::nav::CPTG_Holo_Blend::m_expr_T_ramp
mrpt::expr::CRuntimeCompiledExpression m_expr_T_ramp
Definition: CPTG_Holo_Blend.h:90
y
GLenum GLint GLint y
Definition: glext.h:3538
mrpt::nav::CPTG_Holo_Blend::expr_T_ramp
std::string expr_T_ramp
Definition: CPTG_Holo_Blend.h:86
mrpt::nav::CPTG_Holo_Blend::internal_initialize
void internal_initialize(const std::string &cacheFilename=std::string(), const bool verbose=true) override
Must be called after setting all PTG parameters and before requesting converting obstacles to TP-Spac...
Definition: CPTG_Holo_Blend.cpp:842
uint32_t
unsigned __int32 uint32_t
Definition: rptypes.h:47
x
GLenum GLint x
Definition: glext.h:3538
a
GLubyte GLubyte GLubyte a
Definition: glext.h:6279
mrpt::nav::CPTG_Holo_Blend::calc_trans_distance_t_below_Tramp_abc
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.
Definition: CPTG_Holo_Blend.cpp:136



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