Public Member Functions | Public Attributes | Private Attributes | List of all members
base_local_planner::Trajectory Class Reference

Holds a trajectory generated by considering an x, y, and theta velocity. More...

#include <trajectory.h>

Public Member Functions

void addPoint (double x, double y, double th)
 Add a point to the end of a trajectory. More...
 
void getEndpoint (double &x, double &y, double &th) const
 Get the last point of the trajectory. More...
 
void getPoint (unsigned int index, double &x, double &y, double &th) const
 Get a point within the trajectory. More...
 
unsigned int getPointsSize () const
 Return the number of points in the trajectory. More...
 
void resetPoints ()
 Clear the trajectory's points. More...
 
void setPoint (unsigned int index, double x, double y, double th)
 Set a point within the trajectory. More...
 
 Trajectory ()
 Default constructor. More...
 
 Trajectory (double xv, double yv, double thetav, double time_delta, unsigned int num_pts)
 Constructs a trajectory. More...
 

Public Attributes

double cost_
 The cost/score of the trajectory. More...
 
double thetav_
 The x, y, and theta velocities of the trajectory. More...
 
double time_delta_
 The time gap between points. More...
 
double xv_
 
double yv_
 

Private Attributes

std::vector< double > th_pts_
 The theta points in the trajectory. More...
 
std::vector< double > x_pts_
 The x points in the trajectory. More...
 
std::vector< double > y_pts_
 The y points in the trajectory. More...
 

Detailed Description

Holds a trajectory generated by considering an x, y, and theta velocity.

Definition at line 44 of file trajectory.h.

Constructor & Destructor Documentation

base_local_planner::Trajectory::Trajectory ( )

Default constructor.

Definition at line 37 of file trajectory.cpp.

base_local_planner::Trajectory::Trajectory ( double  xv,
double  yv,
double  thetav,
double  time_delta,
unsigned int  num_pts 
)

Constructs a trajectory.

Parameters
xvThe x velocity used to seed the trajectory
yvThe y velocity used to seed the trajectory
thetavThe theta velocity used to seed the trajectory
num_ptsThe expected number of points for a trajectory

Definition at line 42 of file trajectory.cpp.

Member Function Documentation

void base_local_planner::Trajectory::addPoint ( double  x,
double  y,
double  th 
)

Add a point to the end of a trajectory.

Parameters
xThe x position
yThe y position
thThe theta position

Definition at line 59 of file trajectory.cpp.

void base_local_planner::Trajectory::getEndpoint ( double &  x,
double &  y,
double &  th 
) const

Get the last point of the trajectory.

Parameters
xWill be set to the x position of the point
yWill be set to the y position of the point
thWill be set to the theta position of the point

Definition at line 71 of file trajectory.cpp.

void base_local_planner::Trajectory::getPoint ( unsigned int  index,
double &  x,
double &  y,
double &  th 
) const

Get a point within the trajectory.

Parameters
indexThe index of the point to get
xWill be set to the x position of the point
yWill be set to the y position of the point
thWill be set to the theta position of the point

Definition at line 47 of file trajectory.cpp.

unsigned int base_local_planner::Trajectory::getPointsSize ( ) const

Return the number of points in the trajectory.

Returns
The number of points in the trajectory

Definition at line 77 of file trajectory.cpp.

void base_local_planner::Trajectory::resetPoints ( )

Clear the trajectory's points.

Definition at line 65 of file trajectory.cpp.

void base_local_planner::Trajectory::setPoint ( unsigned int  index,
double  x,
double  y,
double  th 
)

Set a point within the trajectory.

Parameters
indexThe index of the point to set
xThe x position
yThe y position
thThe theta position

Definition at line 53 of file trajectory.cpp.

Member Data Documentation

double base_local_planner::Trajectory::cost_

The cost/score of the trajectory.

Definition at line 62 of file trajectory.h.

std::vector<double> base_local_planner::Trajectory::th_pts_
private

The theta points in the trajectory.

Definition at line 114 of file trajectory.h.

double base_local_planner::Trajectory::thetav_

The x, y, and theta velocities of the trajectory.

Definition at line 60 of file trajectory.h.

double base_local_planner::Trajectory::time_delta_

The time gap between points.

Definition at line 64 of file trajectory.h.

std::vector<double> base_local_planner::Trajectory::x_pts_
private

The x points in the trajectory.

Definition at line 112 of file trajectory.h.

double base_local_planner::Trajectory::xv_

Definition at line 60 of file trajectory.h.

std::vector<double> base_local_planner::Trajectory::y_pts_
private

The y points in the trajectory.

Definition at line 113 of file trajectory.h.

double base_local_planner::Trajectory::yv_

Definition at line 60 of file trajectory.h.


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


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25