ompl::base::DubinsStateSpace::DubinsPath Class Reference

Complete description of a Dubins path. More...

#include <ompl/base/spaces/DubinsStateSpace.h>

Public Member Functions

 DubinsPath (const std::vector< DubinsPathSegmentType > *type=&dubinsPathType[0], double t=0., double p=std::numeric_limits< double >::max(), double q=0.)
 
double length () const
 

Public Attributes

const std::vector< DubinsPathSegmentType > * type_
 
double length_ [3]
 
bool reverse_ {false}
 

Friends

std::ostream & operator<< (std::ostream &os, const DubinsPath &path)
 

Detailed Description

Complete description of a Dubins path.

Definition at line 172 of file DubinsStateSpace.h.

Member Data Documentation

◆ length_

double ompl::base::DubinsStateSpace::DubinsPath::length_[3]

Path segment lengths

Definition at line 195 of file DubinsStateSpace.h.

◆ reverse_

bool ompl::base::DubinsStateSpace::DubinsPath::reverse_ {false}

Whether the path should be followed "in reverse"

Definition at line 197 of file DubinsStateSpace.h.

◆ type_

const std::vector<DubinsPathSegmentType>* ompl::base::DubinsStateSpace::DubinsPath::type_

Path segment types

Definition at line 193 of file DubinsStateSpace.h.


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