29 const float x_,
const float y_,
const float phi_,
const float t_,
30 const float dist_,
const float v_,
const float w_)
31 :
x(x_),
y(y_),
phi(phi_),
t(t_),
dist(dist_),
v(v_),
w(w_)
58 float alpha,
float t,
float x,
float y,
float phi,
float& v,
72 double x,
double y,
int& out_k,
double& out_d,
73 double tolerance_dist = 0.10)
const override;
80 uint16_t k)
const override;
93 double getPathDist(uint16_t k, uint32_t step)
const override;
95 uint16_t k,
double dist, uint32_t& out_step)
const override;
100 double ox,
double oy, std::vector<double>& tp_obstacles)
const override;
102 double ox,
double oy, uint16_t k,
double& tp_obstacle_k)
const override;
120 const std::string& cacheFilename = std::string(),
121 const bool verbose =
true)
override;
136 const std::string& sSection)
override;
139 const std::string& sSection)
const override;
156 float max_time,
float max_dist,
unsigned int max_n,
float diferencial_t,
157 float min_dist,
float* out_max_acc_v =
nullptr,
158 float* out_max_acc_w =
nullptr);
176 float x_min,
float x_max,
float y_min,
float y_max,
179 x_min, x_max, y_min, y_max, resolution),
196 const float obsX,
const float obsY)
const;
205 const unsigned int icx,
const unsigned int icy,
const uint16_t k,
212 const std::string& filename,
215 const std::string& filename,
227 :
k_min(
std::numeric_limits<uint16_t>::max()),
228 k_max(
std::numeric_limits<uint16_t>::min()),
229 n_min(
std::numeric_limits<uint32_t>::max()),
230 n_max(
std::numeric_limits<uint32_t>::min())
239 return k_min == std::numeric_limits<uint16_t>::max();
An internal class for storing the collision grid.
#define MRPT_DECLARE_TTYPENAME_NAMESPACE(_TYPE, __NS)
Declares a typename to be "namespace::type".
double getMaxAngVel() const override
Returns the maximum angular velocity expected from this PTG [rad/s].
void setRefDistance(const double refDist) override
Launches an exception in this class: it is not allowed in numerical integration-based PTGs to change ...
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &i, mrpt::nav::TCPoint &p)
A 2D grid of dynamic size which stores any kind of data at each cell.
bool saveColGridsToFile(const std::string &filename, const mrpt::math::CPolygon &computed_robotShape) const
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 < ...
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...
Specifies the min/max values for "k" and "n", respectively.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
Possible values in "params" (those in CParameterizedTrajectoryGenerator, which is called internally...
const TCollisionCell & getTPObstacle(const float obsX, const float obsY) const
For an obstacle (x,y), returns a vector with all the pairs (a,d) such as the robot collides...
Trajectory points in C-Space for non-holonomic robots.
bool loadFromFile(mrpt::serialization::CArchive *fil, const mrpt::math::CPolygon ¤t_robotShape)
Load from file, true = OK.
void internal_deinitialize() override
This must be called to de-initialize the PTG if some parameter is to be changed.
A wrapper of a TPolygon2D class, implementing CSerializable.
void internal_readFromStream(mrpt::serialization::CArchive &in) override
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.
mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand(uint16_t k) const override
In this class, out_action_cmd contains: [0]: linear velocity (m/s), [1]: angular velocity (rad/s)...
TCPoint(const float x_, const float y_, const float phi_, const float t_, const float dist_, const float v_, const float w_)
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &o, const mrpt::nav::TCPoint &p)
This class allows loading and storing values and vectors of different types from a configuration text...
bool inverseMap_WS2TP(double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const override
The default implementation in this class relies on a look-up-table.
CDynamicGrid(double x_min=-10., double x_max=10., double y_min=-10., double y_max=10., double resolution=0.1)
Constructor.
double getMaxLinVel() const override
Returns the maximum linear velocity expected from this PTG [m/s].
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.
Base class for all PTGs using a 2D polygonal robot shape model.
CPTG_DiffDrive_CollisionGridBased()
Constructor: possible values in "params":
bool loadColGridsFromFile(const std::string &filename, const mrpt::math::CPolygon ¤t_robotShape)
double m_stepTimeDuration
~CCollisionGrid() override=default
void updateCellInfo(const unsigned int icx, const unsigned int icy, const uint16_t k, const float dist)
Updates the info into a cell: It updates the cell only if the distance d for the path k is lower than...
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.
void internal_processNewRobotShape() override
Will be called whenever the robot shape is set / updated.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool saveToFile(mrpt::serialization::CArchive *fil, const mrpt::math::CPolygon &computed_robotShape) const
Save to file, true = OK.
mrpt::containers::CDynamicGrid< TCellForLambdaFunction > m_lambdaFunctionOptimizer
This grid will contain indexes data for speeding-up the default, brute-force lambda function...
Virtual base class for "archives": classes abstracting I/O streams.
std::vector< TCPoint > TCPointVector
CCollisionGrid m_collisionGrid
The collision grid.
mrpt::vision::TStereoCalibResults out
Base class for all PTGs suitable to non-holonomic, differentially-driven (or Ackermann) vehicles base...
CCollisionGrid(float x_min, float x_max, float y_min, float y_max, float resolution, CPTG_DiffDrive_CollisionGridBased *parent)
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.
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,oy)
std::vector< std::pair< uint16_t, float > > TCollisionCell
A list of all the pairs (alpha,distance) such as the robot collides at that cell. ...
virtual void ptgDiffDriveSteeringFunction(float alpha, float t, float x, float y, float phi, float &v, float &w) const =0
The main method to be implemented in derived classes: it defines the differential-driven differential...
void loadDefaultParams() override
Loads a set of default parameters; provided exclusively for the PTG-configurator tool.
double turningRadiusReference
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. ...
std::vector< TCPointVector > m_trajectory
mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand() const override
Returns an empty kinematic velocity command object of the type supported by this PTG.
void onNewNavDynamicState() override
This family of PTGs ignores the dynamic states.
void internal_writeToStream(mrpt::serialization::CArchive &out) const override
void simulateTrajectories(float max_time, float max_dist, unsigned int max_n, float diferencial_t, float min_dist, float *out_max_acc_v=nullptr, float *out_max_acc_w=nullptr)
Numerically solve the diferential equations to generate a family of trajectories. ...
CPTG_DiffDrive_CollisionGridBased const * m_parent
double getPathStepDuration() const override
Returns the duration (in seconds) of each "step".