Apollo  6.0
Open source self driving car software
Public Member Functions | List of all members
apollo::planning::PublishableTrajectory Class Reference

#include <publishable_trajectory.h>

Inheritance diagram for apollo::planning::PublishableTrajectory:
Inheritance graph
Collaboration diagram for apollo::planning::PublishableTrajectory:
Collaboration graph

Public Member Functions

 PublishableTrajectory ()=default
 
 PublishableTrajectory (const double header_time, const DiscretizedTrajectory &discretized_trajectory)
 
 PublishableTrajectory (const ADCTrajectory &trajectory_pb)
 
double header_time () const
 
void PopulateTrajectoryProtobuf (ADCTrajectory *trajectory_pb) const
 
- Public Member Functions inherited from apollo::planning::DiscretizedTrajectory
 DiscretizedTrajectory ()=default
 
 DiscretizedTrajectory (const ADCTrajectory &trajectory)
 
 DiscretizedTrajectory (const std::vector< common::TrajectoryPoint > &trajectory_points)
 
void SetTrajectoryPoints (const std::vector< common::TrajectoryPoint > &trajectory_points)
 
virtual ~DiscretizedTrajectory ()=default
 
virtual common::TrajectoryPoint StartPoint () const
 
virtual double GetTemporalLength () const
 
virtual double GetSpatialLength () const
 
virtual common::TrajectoryPoint Evaluate (const double relative_time) const
 
virtual size_t QueryLowerBoundPoint (const double relative_time, const double epsilon=1.0e-5) const
 
virtual size_t QueryNearestPoint (const common::math::Vec2d &position) const
 
size_t QueryNearestPointWithBuffer (const common::math::Vec2d &position, const double buffer) const
 
virtual void AppendTrajectoryPoint (const common::TrajectoryPoint &trajectory_point)
 
void PrependTrajectoryPoints (const std::vector< common::TrajectoryPoint > &trajectory_points)
 
const common::TrajectoryPoint & TrajectoryPointAt (const size_t index) const
 
size_t NumOfPoints () const
 
virtual void Clear ()
 

Constructor & Destructor Documentation

◆ PublishableTrajectory() [1/3]

apollo::planning::PublishableTrajectory::PublishableTrajectory ( )
default

◆ PublishableTrajectory() [2/3]

apollo::planning::PublishableTrajectory::PublishableTrajectory ( const double  header_time,
const DiscretizedTrajectory discretized_trajectory 
)

◆ PublishableTrajectory() [3/3]

apollo::planning::PublishableTrajectory::PublishableTrajectory ( const ADCTrajectory &  trajectory_pb)
explicit

Create a publishable trajectory based on a trajectory protobuf

Member Function Documentation

◆ header_time()

double apollo::planning::PublishableTrajectory::header_time ( ) const

◆ PopulateTrajectoryProtobuf()

void apollo::planning::PublishableTrajectory::PopulateTrajectoryProtobuf ( ADCTrajectory *  trajectory_pb) const

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