Parasol Planning Library (PPL)
LPSweptDistance Class Reference

#include <LPSweptDistance.h>

Inheritance diagram for LPSweptDistance:
Inheritance graph
[legend]
Collaboration diagram for LPSweptDistance:
Collaboration graph
[legend]

Public Types

Local Types
typedef MPBaseObject::GroupCfgType GroupCfgType
 
- Public Types inherited from DistanceMetricMethod
typedef MPBaseObject::RoadmapType RoadmapType
 
typedef RoadmapType::VID VID
 
typedef MPBaseObject::GroupCfgType GroupCfgType
 
typedef GroupCfgType::Formation Formation
 
- Public Types inherited from MPBaseObject
typedef DefaultWeight< CfgWeightType
 
typedef GenericStateGraph< Cfg, WeightTypeRoadmapType
 
typedef GroupCfg< RoadmapTypeGroupCfgType
 
typedef GroupLocalPlan< RoadmapTypeGroupWeightType
 
typedef GroupRoadmap< GroupCfgType, GroupWeightTypeGroupRoadmapType
 

Public Member Functions

Construction
 LPSweptDistance (string _lpLabel="sl", double _positionRes=0.1, double _orientationRes=0.1, bool _bbox=false)
 
 LPSweptDistance (XMLNode &_node)
 
virtual ~LPSweptDistance ()=default
 
MPBaseObject Overrides
virtual void Print (std::ostream &_os) const override
 
DistanceMetricMethod Overrides
virtual double Distance (const Cfg &_c1, const Cfg &_c2) override
 
- Public Member Functions inherited from DistanceMetricMethod
 DistanceMetricMethod ()=default
 
 DistanceMetricMethod (XMLNode &_node)
 
virtual ~DistanceMetricMethod ()=default
 
virtual double Distance (const GroupCfgType &_c1, const GroupCfgType &_c2)
 
double EdgeWeight (const RoadmapType *const _r, const typename RoadmapType::CEI &_edge) noexcept
 
double EdgeWeight (const RoadmapType *const _r, const VID _source, const VID _target) noexcept
 
virtual void ScaleCfg (double _length, Cfg &_c, const Cfg &_o)
 
void ScaleCfg (double _length, Cfg &_c)
 
virtual void ScaleCfg (double _length, GroupCfgType &_c, const GroupCfgType &_o)
 
void ScaleCfg (double _length, GroupCfgType &_c)
 
- Public Member Functions inherited from MPBaseObject
 MPBaseObject (const std::string &_label="", const std::string &_name="", bool _debug=false)
 
 MPBaseObject (XMLNode &_node)
 
virtual ~MPBaseObject ()
 
virtual void Initialize ()
 
const std::string & GetName () const
 Get the class name for this object. More...
 
const std::string & GetLabel () const
 Get the unique label for this object. More...
 
std::string GetNameAndLabel () const
 Get the unique string identifier for this object "m_name::m_label". More...
 
void SetLabel (const std::string &)
 Set the unique label for this object. More...
 
void SetMPLibrary (MPLibrary *) noexcept
 Set the owning MPLibrary. More...
 
MPLibraryGetMPLibrary () const noexcept
 Get the owning MPLibrary. More...
 
bool IsRunning () const noexcept
 Check the library's running flag. More...
 
MPProblemGetMPProblem () const noexcept
 Get the library's current MPProblem. More...
 
EnvironmentGetEnvironment () const noexcept
 Get the current environment. More...
 
MPTaskGetTask () const noexcept
 Get the current task. More...
 
GroupTaskGetGroupTask () const noexcept
 Get the current group task. More...
 
MPSolutionTypeGetMPSolution () const noexcept
 
RoadmapTypeGetRoadmap (Robot *const _r=nullptr) const noexcept
 Get the current free-space roadmap. More...
 
GroupRoadmapTypeGetGroupRoadmap (RobotGroup *const _g=nullptr) const noexcept
 Get the current free-space group roadmap. More...
 
RoadmapTypeGetBlockRoadmap (Robot *const _r=nullptr) const noexcept
 Get the current obstacle-space roadmap. More...
 
PathGetPath (Robot *const _r=nullptr) const noexcept
 
GroupPathGetGroupPath (RobotGroup *const _g=nullptr) const noexcept
 Get the current best group path. More...
 
StatClassGetStatClass () const noexcept
 Get the current StatClass. More...
 
LocalObstacleMapGetLocalObstacleMap () const noexcept
 Get the local obstacle map. More...
 

Protected Member Functions

Helpers
double SweptDistance (const std::vector< GMSPolyhedron > &_poly1, const std::vector< GMSPolyhedron > &_poly2)
 
- Protected Member Functions inherited from MPBaseObject
void SetName (const std::string &_s)
 
const std::string & GetBaseFilename () const
 

Protected Attributes

Internal State
string m_lpLabel
 For Local Planner type. More...
 
double m_positionRes
 For position resolution. More...
 
double m_orientationRes
 For orientation resolution. More...
 
bool m_useBBox
 for whether to use bounding box More...
 
- Protected Attributes inherited from MPBaseObject
bool m_debug
 Print debug info? More...
 

Detailed Description

Measures the distance swept by a robot when moving between two configurations. The distance is the summed vertex displacements along the path generated by the LocalPlanner.

Member Typedef Documentation

◆ GroupCfgType

Constructor & Destructor Documentation

◆ LPSweptDistance() [1/2]

LPSweptDistance::LPSweptDistance ( string  _lpLabel = "sl",
double  _positionRes = 0.1,
double  _orientationRes = 0.1,
bool  _bbox = false 
)

◆ LPSweptDistance() [2/2]

LPSweptDistance::LPSweptDistance ( XMLNode _node)

◆ ~LPSweptDistance()

virtual LPSweptDistance::~LPSweptDistance ( )
virtualdefault

Member Function Documentation

◆ Distance()

double LPSweptDistance::Distance ( const Cfg _c1,
const Cfg _c2 
)
overridevirtual

Compute a distance between two configurations.

Parameters
_c1The first configuration.
_c2The second configuration.
Returns
The computed distance between _c1 and _c2.
Todo:
Verify this, I believe m_path does include _c1 and _c2 for some lps. We need to make sure the usage is consistent across all of them.

Implements DistanceMetricMethod.

Reimplemented in BinaryLPSweptDistance.

◆ Print()

void LPSweptDistance::Print ( std::ostream &  _os) const
overridevirtual

Print internal state of this object.

Parameters
_osThe std::ostream to print to.

Reimplemented from MPBaseObject.

Reimplemented in BinaryLPSweptDistance.

◆ SweptDistance()

double LPSweptDistance::SweptDistance ( const std::vector< GMSPolyhedron > &  _poly1,
const std::vector< GMSPolyhedron > &  _poly2 
)
protected

Field Documentation

◆ m_lpLabel

string LPSweptDistance::m_lpLabel
protected

For Local Planner type.

◆ m_orientationRes

double LPSweptDistance::m_orientationRes
protected

For orientation resolution.

◆ m_positionRes

double LPSweptDistance::m_positionRes
protected

For position resolution.

◆ m_useBBox

bool LPSweptDistance::m_useBBox
protected

for whether to use bounding box


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