selfdriving
Public Member Functions | Protected Attributes | List of all members
mpp::ptg::DiffDrive_C Class Reference

#include <mpp/ptgs/DiffDrive_C.h>

Inheritance diagram for mpp::ptg::DiffDrive_C:
mpp::ptg::DiffDriveCollisionGridBased mpp::ptg::SpeedTrimmablePTG

Public Member Functions

 DiffDrive_C ()=default
 
 DiffDrive_C (const mrpt::config::CConfigFileBase &cfg, const std::string &sSection)
 
void loadFromConfigFile (const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
 
void saveToConfigFile (mrpt::config::CConfigFileBase &cfg, const std::string &sSection) const override
 
std::string getDescription () const override
 
bool inverseMap_WS2TP (double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const override
 
bool PTG_IsIntoDomain (double x, double y) const override
 
void ptgDiffDriveSteeringFunction (float alpha, float t, float x, float y, float phi, float &v, float &w) const override
 
void loadDefaultParams () override
 
- Public Member Functions inherited from mpp::ptg::DiffDriveCollisionGridBased
double getMax_V () const
 
double getMax_W () const
 
bool inverseMap_WS2TP (double x, double y, int &out_k, double &out_d, double tolerance_dist=0.10) const override
 
mrpt::kinematics::CVehicleVelCmd::Ptr directionToMotionCommand (uint16_t k) const override
 
mrpt::kinematics::CVehicleVelCmd::Ptr getSupportedKinematicVelocityCommand () const override
 
void setRefDistance (const double refDist) override
 
size_t getPathStepCount (uint16_t k) const override
 
mrpt::math::TPose2D getPathPose (uint16_t k, uint32_t step) const override
 
double getPathDist (uint16_t k, uint32_t step) const override
 
bool getPathStepForDist (uint16_t k, double dist, uint32_t &out_step) const override
 
double getPathStepDuration () const override
 
double getMaxLinVel () const override
 
double getMaxAngVel () const override
 
void updateTPObstacle (double ox, double oy, std::vector< double > &tp_obstacles) const override
 
void updateTPObstacleSingle (double ox, double oy, uint16_t k, double &tp_obstacle_k) const override
 
void onNewNavDynamicState () override
 
- Public Member Functions inherited from mpp::ptg::SpeedTrimmablePTG
 SpeedTrimmablePTG ()=default
 
 ~SpeedTrimmablePTG ()=default
 

Protected Attributes

double K {0}
 
- Protected Attributes inherited from mpp::ptg::DiffDriveCollisionGridBased
double V_MAX {.0}
 
double W_MAX {.0}
 
double turningRadiusReference {.10}
 
std::vector< TCPointVectorm_trajectory
 
double m_resolution {0.05}
 
double m_stepTimeDuration {0.01}
 
CCollisionGrid m_collisionGrid
 
mrpt::containers::CDynamicGrid< TCellForLambdaFunctionm_lambdaFunctionOptimizer
 

Additional Inherited Members

- Public Attributes inherited from mpp::ptg::SpeedTrimmablePTG
double trimmableSpeed_ = 1.0
 
- Protected Types inherited from mpp::ptg::DiffDriveCollisionGridBased
using TCollisionCell = std::vector< std::pair< uint16_t, float > >
 
- Protected Member Functions inherited from mpp::ptg::DiffDriveCollisionGridBased
 DiffDriveCollisionGridBased ()
 
void internal_processNewRobotShape () override
 
void internal_initialize (const std::string &cacheFilename=std::string(), const bool verbose=true) override
 
void internal_deinitialize () override
 
void loadFromConfigFile (const mrpt::config::CConfigFileBase &cfg, const std::string &sSection) override
 
void saveToConfigFile (mrpt::config::CConfigFileBase &cfg, const std::string &sSection) const override
 
void loadDefaultParams () override
 
void internal_readFromStream (mrpt::serialization::CArchive &in) override
 
void internal_writeToStream (mrpt::serialization::CArchive &out) const override
 
void simulateTrajectories (float max_time, float max_dist, float dt)
 
mrpt::math::TTwist2D getPathTwist (uint16_t k, uint32_t step) const override
 
bool saveColGridsToFile (const std::string &filename, const mrpt::math::CPolygon &computed_robotShape) const
 
bool loadColGridsFromFile (const std::string &filename, const mrpt::math::CPolygon &current_robotShape)
 

Detailed Description

A PTG for circular paths ("C" type PTG in papers).

This PT generator functions are:

\[ v(\alpha) = V_{MAX} sign(K) \]

\[ \omega(\alpha) = \dfrac{\alpha}{\pi} W_{MAX} sign(K) \]

So, the radius of curvature of each trajectory is constant for each "alpha" value (the trajectory parameter):

\[ R(\alpha) = \dfrac{v}{\omega} = \dfrac{V_{MAX}}{W_{MAX}} \dfrac{\pi}{\alpha} \]

from which a minimum radius of curvature can be set by selecting the appropriate values of V_MAX and W_MAX, knowning that $ \alpha \in (-\pi,\pi) $.

C-PTG path examples
Note
[Before MRPT 1.5.0 this was named CPTG1]

Constructor & Destructor Documentation

◆ DiffDrive_C() [1/2]

mpp::ptg::DiffDrive_C::DiffDrive_C ( )
default

◆ DiffDrive_C() [2/2]

mpp::ptg::DiffDrive_C::DiffDrive_C ( const mrpt::config::CConfigFileBase &  cfg,
const std::string &  sSection 
)
inline

Member Function Documentation

◆ getDescription()

std::string mpp::ptg::DiffDrive_C::getDescription ( ) const
override

◆ inverseMap_WS2TP()

bool mpp::ptg::DiffDrive_C::inverseMap_WS2TP ( double  x,
double  y,
int &  out_k,
double &  out_d,
double  tolerance_dist = 0.10 
) const
override

◆ loadDefaultParams()

void mpp::ptg::DiffDrive_C::loadDefaultParams ( )
override

◆ loadFromConfigFile()

void mpp::ptg::DiffDrive_C::loadFromConfigFile ( const mrpt::config::CConfigFileBase &  cfg,
const std::string &  sSection 
)
override

◆ PTG_IsIntoDomain()

bool mpp::ptg::DiffDrive_C::PTG_IsIntoDomain ( double  x,
double  y 
) const
override

◆ ptgDiffDriveSteeringFunction()

void mpp::ptg::DiffDrive_C::ptgDiffDriveSteeringFunction ( float  alpha,
float  t,
float  x,
float  y,
float  phi,
float &  v,
float &  w 
) const
overridevirtual

The main method to be implemented in derived classes: it defines the differential-driven differential equation

Implements mpp::ptg::DiffDriveCollisionGridBased.

◆ saveToConfigFile()

void mpp::ptg::DiffDrive_C::saveToConfigFile ( mrpt::config::CConfigFileBase &  cfg,
const std::string &  sSection 
) const
override

Member Data Documentation

◆ K

double mpp::ptg::DiffDrive_C::K {0}
protected

A generation parameter


The documentation for this class was generated from the following file: