Drake
Drake C++ Documentation
PiecewiseTrajectory< T > Class Template Reference

Detailed Description

template<typename T>
class drake::trajectories::PiecewiseTrajectory< T >

Abstract class that implements the basic logic of maintaining consequent segments of time (delimited by breaks) to implement a trajectory that is represented by simpler logic in each segment or "piece".

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/common/trajectories/piecewise_trajectory.h>

Public Member Functions

 ~PiecewiseTrajectory () override
 
int get_number_of_segments () const
 
start_time (int segment_number) const
 
end_time (int segment_number) const
 
duration (int segment_number) const
 
start_time () const override
 
end_time () const override
 
boolean< T > is_time_in_range (const T &t) const
 Returns true iff t >= getStartTime() && t <= getEndTime(). More...
 
int get_segment_index (const T &t) const
 
const std::vector< T > & get_segment_times () const
 
void segment_number_range_check (int segment_number) const
 
- Public Member Functions inherited from Trajectory< T >
virtual ~Trajectory ()
 
virtual std::unique_ptr< Trajectory< T > > Clone () const =0
 
virtual MatrixX< T > value (const T &t) const =0
 Evaluates the trajectory at the given time t. More...
 
MatrixX< T > vector_values (const std::vector< T > &t) const
 If cols()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith column corresponding to the ith time. More...
 
MatrixX< T > vector_values (const Eigen::Ref< const VectorX< T >> &t) const
 If cols()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith column corresponding to the ith time. More...
 
bool has_derivative () const
 Returns true iff the Trajectory provides and implementation for EvalDerivative() and MakeDerivative(). More...
 
MatrixX< T > EvalDerivative (const T &t, int derivative_order=1) const
 Evaluates the derivative of this at the given time t. More...
 
std::unique_ptr< Trajectory< T > > MakeDerivative (int derivative_order=1) const
 Takes the derivative of this Trajectory. More...
 
virtual Eigen::Index rows () const =0
 
virtual Eigen::Index cols () const =0
 

Static Public Member Functions

static std::vector< T > RandomSegmentTimes (int num_segments, std::default_random_engine &generator)
 

Static Public Attributes

static constexpr double kEpsilonTime = std::numeric_limits<double>::epsilon()
 Minimum delta quantity used for comparing time. More...
 

Protected Member Functions

 PiecewiseTrajectory ()=default
 
 PiecewiseTrajectory (const std::vector< T > &breaks)
 breaks increments must be greater or equal to kEpsilonTime. More...
 
bool SegmentTimesEqual (const PiecewiseTrajectory &b, double tol=kEpsilonTime) const
 
const std::vector< T > & breaks () const
 
std::vector< T > & get_mutable_breaks ()
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 PiecewiseTrajectory (const PiecewiseTrajectory &)=default
 
PiecewiseTrajectoryoperator= (const PiecewiseTrajectory &)=default
 
 PiecewiseTrajectory (PiecewiseTrajectory &&)=default
 
PiecewiseTrajectoryoperator= (PiecewiseTrajectory &&)=default
 
- Protected Member Functions inherited from Trajectory< T >
 Trajectory ()=default
 
virtual bool do_has_derivative () const
 
virtual MatrixX< T > DoEvalDerivative (const T &t, int derivative_order) const
 
virtual std::unique_ptr< Trajectory< T > > DoMakeDerivative (int derivative_order) const
 
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ ~PiecewiseTrajectory()

~PiecewiseTrajectory ( )
override

◆ PiecewiseTrajectory() [1/4]

PiecewiseTrajectory ( const PiecewiseTrajectory< T > &  )
protecteddefault

◆ PiecewiseTrajectory() [2/4]

PiecewiseTrajectory ( PiecewiseTrajectory< T > &&  )
protecteddefault

◆ PiecewiseTrajectory() [3/4]

PiecewiseTrajectory ( )
protecteddefault

◆ PiecewiseTrajectory() [4/4]

PiecewiseTrajectory ( const std::vector< T > &  breaks)
explicitprotected

breaks increments must be greater or equal to kEpsilonTime.

Member Function Documentation

◆ breaks()

const std::vector<T>& breaks ( ) const
protected

◆ duration()

T duration ( int  segment_number) const

◆ end_time() [1/2]

T end_time ( int  segment_number) const

◆ end_time() [2/2]

T end_time ( ) const
overridevirtual

Implements Trajectory< T >.

◆ get_mutable_breaks()

std::vector<T>& get_mutable_breaks ( )
protected

◆ get_number_of_segments()

int get_number_of_segments ( ) const

◆ get_segment_index()

int get_segment_index ( const T &  t) const

◆ get_segment_times()

const std::vector<T>& get_segment_times ( ) const

◆ is_time_in_range()

boolean<T> is_time_in_range ( const T &  t) const

Returns true iff t >= getStartTime() && t <= getEndTime().

◆ operator=() [1/2]

PiecewiseTrajectory& operator= ( PiecewiseTrajectory< T > &&  )
protecteddefault

◆ operator=() [2/2]

PiecewiseTrajectory& operator= ( const PiecewiseTrajectory< T > &  )
protecteddefault

◆ RandomSegmentTimes()

static std::vector<T> RandomSegmentTimes ( int  num_segments,
std::default_random_engine &  generator 
)
static

◆ segment_number_range_check()

void segment_number_range_check ( int  segment_number) const

◆ SegmentTimesEqual()

bool SegmentTimesEqual ( const PiecewiseTrajectory< T > &  b,
double  tol = kEpsilonTime 
) const
protected

◆ start_time() [1/2]

T start_time ( int  segment_number) const

◆ start_time() [2/2]

T start_time ( ) const
overridevirtual

Implements Trajectory< T >.

Member Data Documentation

◆ kEpsilonTime

constexpr double kEpsilonTime = std::numeric_limits<double>::epsilon()
static

Minimum delta quantity used for comparing time.


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