Public Member Functions | Static Public Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
fastrack::state::PlanarDubins3D Class Reference

#include <planar_dubins_3d.h>

Inheritance diagram for fastrack::state::PlanarDubins3D:
Inheritance graph
[legend]

Public Member Functions

VectorXd Configuration () const
 
void FromRos (const fastrack_msgs::State &msg)
 
void FromVector (const VectorXd &x)
 
std::vector< Vector3d > OccupiedPositions () const
 
PlanarDubins3Doperator*= (double s)
 
PlanarDubins3Doperator+= (const PlanarDubins3D &rhs)
 
PlanarDubins3Doperator-= (const PlanarDubins3D &rhs)
 
PlanarDubins3Doperator/= (double s)
 
 PlanarDubins3D ()
 
 PlanarDubins3D (double x, double y, double theta)
 
 PlanarDubins3D (double x, double y, double theta, double v)
 
 PlanarDubins3D (const fastrack_msgs::State &msg)
 
 PlanarDubins3D (const VectorXd &config)
 
Vector3d Position () const
 
void SetConfigurationDot (const VectorXd &configuration_dot)
 
double Theta () const
 
double & Theta ()
 
fastrack_msgs::State ToRos () const
 
VectorXd ToVector () const
 
double V () const
 
double & V ()
 
Vector3d Velocity () const
 
double Vx () const
 
double Vy () const
 
double Vz () const
 
double X () const
 
double & X ()
 
double Y () const
 
double & Y ()
 
double Z () const
 
double & Z ()
 
 ~PlanarDubins3D ()
 
- Public Member Functions inherited from fastrack::state::State
void FromRosPtr (const fastrack_msgs::State::ConstPtr &msg)
 
virtual ~State ()
 

Static Public Member Functions

static constexpr size_t ConfigurationDimension ()
 
static VectorXd GetConfigurationLower ()
 
static VectorXd GetConfigurationUpper ()
 
static const PlanarDubins3DGetLower ()
 
static const PlanarDubins3DGetUpper ()
 
static PlanarDubins3D Sample ()
 
static VectorXd SampleConfiguration ()
 
static void SetBounds (const PlanarDubins3D &lower, const PlanarDubins3D &upper)
 
static void SetBounds (const std::vector< double > &lower, const std::vector< double > &upper)
 
static constexpr size_t StateDimension ()
 
- Static Public Member Functions inherited from fastrack::state::State
static void Seed (unsigned int seed)
 

Private Attributes

double theta_
 
double v_
 
double x_
 
double y_
 

Static Private Attributes

static PlanarDubins3D lower_ = PlanarDubins3D()
 
static PlanarDubins3D upper_ = PlanarDubins3D()
 
static double z_ = constants::kDefaultHeight
 

Friends

PlanarDubins3D operator* (PlanarDubins3D lhs, double s)
 
PlanarDubins3D operator* (double s, PlanarDubins3D rhs)
 
PlanarDubins3D operator+ (PlanarDubins3D lhs, const PlanarDubins3D &rhs)
 
PlanarDubins3D operator- (PlanarDubins3D lhs, const PlanarDubins3D &rhs)
 
PlanarDubins3D operator/ (PlanarDubins3D lhs, double s)
 
PlanarDubins3D operator/ (double s, PlanarDubins3D rhs)
 

Additional Inherited Members

- Protected Member Functions inherited from fastrack::state::State
 State ()
 
- Static Protected Attributes inherited from fastrack::state::State
static std::random_device rd_
 
static std::default_random_engine rng_ = std::default_random_engine(State::rd_())
 

Detailed Description

Definition at line 51 of file planar_dubins_3d.h.

Constructor & Destructor Documentation

fastrack::state::PlanarDubins3D::~PlanarDubins3D ( )
inline

Definition at line 53 of file planar_dubins_3d.h.

fastrack::state::PlanarDubins3D::PlanarDubins3D ( )
inlineexplicit

Definition at line 54 of file planar_dubins_3d.h.

fastrack::state::PlanarDubins3D::PlanarDubins3D ( double  x,
double  y,
double  theta 
)
inlineexplicit

Definition at line 56 of file planar_dubins_3d.h.

fastrack::state::PlanarDubins3D::PlanarDubins3D ( double  x,
double  y,
double  theta,
double  v 
)
inlineexplicit

Definition at line 58 of file planar_dubins_3d.h.

fastrack::state::PlanarDubins3D::PlanarDubins3D ( const fastrack_msgs::State &  msg)
explicit

Definition at line 59 of file planar_dubins_3d.cpp.

fastrack::state::PlanarDubins3D::PlanarDubins3D ( const VectorXd &  config)
explicit

Definition at line 79 of file planar_dubins_3d.cpp.

Member Function Documentation

VectorXd fastrack::state::PlanarDubins3D::Configuration ( ) const
inlinevirtual

Implements fastrack::state::State.

Definition at line 77 of file planar_dubins_3d.h.

static constexpr size_t fastrack::state::PlanarDubins3D::ConfigurationDimension ( )
inlinestatic

Definition at line 112 of file planar_dubins_3d.h.

void fastrack::state::PlanarDubins3D::FromRos ( const fastrack_msgs::State &  msg)
virtual

Implements fastrack::state::State.

Definition at line 198 of file planar_dubins_3d.cpp.

void fastrack::state::PlanarDubins3D::FromVector ( const VectorXd &  x)
virtual

Implements fastrack::state::State.

Definition at line 175 of file planar_dubins_3d.cpp.

VectorXd fastrack::state::PlanarDubins3D::GetConfigurationLower ( )
static

Definition at line 235 of file planar_dubins_3d.cpp.

VectorXd fastrack::state::PlanarDubins3D::GetConfigurationUpper ( )
static

Definition at line 238 of file planar_dubins_3d.cpp.

const PlanarDubins3D & fastrack::state::PlanarDubins3D::GetLower ( )
static

Definition at line 231 of file planar_dubins_3d.cpp.

const PlanarDubins3D & fastrack::state::PlanarDubins3D::GetUpper ( )
static

Definition at line 232 of file planar_dubins_3d.cpp.

std::vector< Vector3d > fastrack::state::PlanarDubins3D::OccupiedPositions ( ) const
virtual

Implements fastrack::state::State.

Definition at line 146 of file planar_dubins_3d.cpp.

PlanarDubins3D & fastrack::state::PlanarDubins3D::operator*= ( double  s)

Definition at line 257 of file planar_dubins_3d.cpp.

PlanarDubins3D & fastrack::state::PlanarDubins3D::operator+= ( const PlanarDubins3D rhs)

Definition at line 243 of file planar_dubins_3d.cpp.

PlanarDubins3D & fastrack::state::PlanarDubins3D::operator-= ( const PlanarDubins3D rhs)

Definition at line 250 of file planar_dubins_3d.cpp.

PlanarDubins3D & fastrack::state::PlanarDubins3D::operator/= ( double  s)

Definition at line 264 of file planar_dubins_3d.cpp.

Vector3d fastrack::state::PlanarDubins3D::Position ( ) const
inlinevirtual

Implements fastrack::state::State.

Definition at line 75 of file planar_dubins_3d.h.

PlanarDubins3D fastrack::state::PlanarDubins3D::Sample ( )
static

Definition at line 129 of file planar_dubins_3d.cpp.

VectorXd fastrack::state::PlanarDubins3D::SampleConfiguration ( )
static

Definition at line 108 of file planar_dubins_3d.cpp.

void fastrack::state::PlanarDubins3D::SetBounds ( const PlanarDubins3D lower,
const PlanarDubins3D upper 
)
static

Definition at line 151 of file planar_dubins_3d.cpp.

void fastrack::state::PlanarDubins3D::SetBounds ( const std::vector< double > &  lower,
const std::vector< double > &  upper 
)
static

Definition at line 159 of file planar_dubins_3d.cpp.

void fastrack::state::PlanarDubins3D::SetConfigurationDot ( const VectorXd &  configuration_dot)

Definition at line 96 of file planar_dubins_3d.cpp.

static constexpr size_t fastrack::state::PlanarDubins3D::StateDimension ( )
inlinestatic

Definition at line 111 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Theta ( ) const
inline

Definition at line 69 of file planar_dubins_3d.h.

double& fastrack::state::PlanarDubins3D::Theta ( )
inline

Definition at line 89 of file planar_dubins_3d.h.

fastrack_msgs::State fastrack::state::PlanarDubins3D::ToRos ( ) const
virtual

Implements fastrack::state::State.

Definition at line 220 of file planar_dubins_3d.cpp.

VectorXd fastrack::state::PlanarDubins3D::ToVector ( ) const
virtual

Implements fastrack::state::State.

Definition at line 187 of file planar_dubins_3d.cpp.

double fastrack::state::PlanarDubins3D::V ( ) const
inline

Definition at line 70 of file planar_dubins_3d.h.

double& fastrack::state::PlanarDubins3D::V ( )
inline

Definition at line 90 of file planar_dubins_3d.h.

Vector3d fastrack::state::PlanarDubins3D::Velocity ( ) const
inline

Definition at line 76 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Vx ( ) const
inline

Definition at line 71 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Vy ( ) const
inline

Definition at line 72 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Vz ( ) const
inline

Definition at line 73 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::X ( ) const
inlinevirtual

Implements fastrack::state::State.

Definition at line 66 of file planar_dubins_3d.h.

double& fastrack::state::PlanarDubins3D::X ( )
inline

Definition at line 86 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Y ( ) const
inlinevirtual

Implements fastrack::state::State.

Definition at line 67 of file planar_dubins_3d.h.

double& fastrack::state::PlanarDubins3D::Y ( )
inline

Definition at line 87 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::Z ( ) const
inlinevirtual

Implements fastrack::state::State.

Definition at line 68 of file planar_dubins_3d.h.

double& fastrack::state::PlanarDubins3D::Z ( )
inline

Definition at line 88 of file planar_dubins_3d.h.

Friends And Related Function Documentation

PlanarDubins3D operator* ( PlanarDubins3D  lhs,
double  s 
)
friend

Definition at line 282 of file planar_dubins_3d.cpp.

PlanarDubins3D operator* ( double  s,
PlanarDubins3D  rhs 
)
friend

Definition at line 287 of file planar_dubins_3d.cpp.

PlanarDubins3D operator+ ( PlanarDubins3D  lhs,
const PlanarDubins3D rhs 
)
friend

Definition at line 272 of file planar_dubins_3d.cpp.

PlanarDubins3D operator- ( PlanarDubins3D  lhs,
const PlanarDubins3D rhs 
)
friend

Definition at line 277 of file planar_dubins_3d.cpp.

PlanarDubins3D operator/ ( PlanarDubins3D  lhs,
double  s 
)
friend

Definition at line 292 of file planar_dubins_3d.cpp.

PlanarDubins3D operator/ ( double  s,
PlanarDubins3D  rhs 
)
friend

Definition at line 297 of file planar_dubins_3d.cpp.

Member Data Documentation

PlanarDubins3D fastrack::state::PlanarDubins3D::lower_ = PlanarDubins3D()
staticprivate

Definition at line 161 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::theta_
private

Definition at line 151 of file planar_dubins_3d.h.

PlanarDubins3D fastrack::state::PlanarDubins3D::upper_ = PlanarDubins3D()
staticprivate

Definition at line 162 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::v_
private

Definition at line 155 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::x_
private

Definition at line 149 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::y_
private

Definition at line 150 of file planar_dubins_3d.h.

double fastrack::state::PlanarDubins3D::z_ = constants::kDefaultHeight
staticprivate

Definition at line 158 of file planar_dubins_3d.h.


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


fastrack
Author(s): David Fridovich-Keil
autogenerated on Mon Aug 3 2020 21:28:37