Drake
Drake C++ Documentation
CompositeTrajectory< T > Class Template Referencefinal

Detailed Description

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

A "composite trajectory" is a series of trajectories joined end to end where the end time of one trajectory coincides with the starting time of the next.

See also PiecewisePolynomial::ConcatenateInTime(), which might be preferred if all of the segments are PiecewisePolynomial.

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

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

Public Member Functions

 CompositeTrajectory (std::vector< copyable_unique_ptr< Trajectory< T >>> segments)
 Constructs a composite trajectory from a list of Trajectories. More...
 
 ~CompositeTrajectory () final
 
std::unique_ptr< trajectories::Trajectory< T > > Clone () const final
 
MatrixX< T > value (const T &time) const final
 Evaluates the curve at the given time. More...
 
Eigen::Index rows () const final
 
Eigen::Index cols () const final
 
const Trajectory< T > & segment (int segment_index) const
 Returns a reference to the segment_index trajectory. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 CompositeTrajectory (const CompositeTrajectory &)=default
 
CompositeTrajectoryoperator= (const CompositeTrajectory &)=default
 
 CompositeTrajectory (CompositeTrajectory &&)=default
 
CompositeTrajectoryoperator= (CompositeTrajectory &&)=default
 
- Public Member Functions inherited from PiecewiseTrajectory< T >
 ~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 ()
 
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...
 

Static Public Member Functions

static CompositeTrajectory< T > AlignAndConcatenate (const std::vector< copyable_unique_ptr< Trajectory< T >>> &segments)
 Constructs a composite trajectory from a list of trajectories whose start and end times may not coincide, by translating their start and end times. More...
 
- Static Public Member Functions inherited from PiecewiseTrajectory< T >
static std::vector< T > RandomSegmentTimes (int num_segments, std::default_random_engine &generator)
 

Additional Inherited Members

- Static Public Attributes inherited from PiecewiseTrajectory< T >
static constexpr double kEpsilonTime = std::numeric_limits<double>::epsilon()
 Minimum delta quantity used for comparing time. More...
 
- Protected Member Functions inherited from PiecewiseTrajectory< T >
 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 ()
 
 PiecewiseTrajectory (const PiecewiseTrajectory &)=default
 
PiecewiseTrajectoryoperator= (const PiecewiseTrajectory &)=default
 
 PiecewiseTrajectory (PiecewiseTrajectory &&)=default
 
PiecewiseTrajectoryoperator= (PiecewiseTrajectory &&)=default
 
- Protected Member Functions inherited from Trajectory< T >
 Trajectory ()=default
 
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ CompositeTrajectory() [1/3]

CompositeTrajectory ( const CompositeTrajectory< T > &  )
default

◆ CompositeTrajectory() [2/3]

◆ CompositeTrajectory() [3/3]

CompositeTrajectory ( std::vector< copyable_unique_ptr< Trajectory< T >>>  segments)
explicit

Constructs a composite trajectory from a list of Trajectories.

Precondition
∀i, segments[i].get() != nullptr.
∀i, segments[i+1].start_time() == segments[i].end_time().
∀i, segments[i].rows() == segments[0].rows() and segments[i].cols() == segments[0].cols()`.

◆ ~CompositeTrajectory()

~CompositeTrajectory ( )
final

Member Function Documentation

◆ AlignAndConcatenate()

static CompositeTrajectory<T> AlignAndConcatenate ( const std::vector< copyable_unique_ptr< Trajectory< T >>> &  segments)
static

Constructs a composite trajectory from a list of trajectories whose start and end times may not coincide, by translating their start and end times.

Precondition
∀i, segments[i].get() != nullptr.
∀i, segments[i].rows() == segments[0].rows() and segments[i].cols() == segments[0].cols()`.

◆ Clone()

std::unique_ptr<trajectories::Trajectory<T> > Clone ( ) const
finalvirtual
Returns
A deep copy of this Trajectory.

Implements Trajectory< T >.

◆ cols()

Eigen::Index cols ( ) const
finalvirtual
Returns
The number of columns in the matrix returned by value().

Implements Trajectory< T >.

◆ operator=() [1/2]

CompositeTrajectory& operator= ( CompositeTrajectory< T > &&  )
default

◆ operator=() [2/2]

CompositeTrajectory& operator= ( const CompositeTrajectory< T > &  )
default

◆ rows()

Eigen::Index rows ( ) const
finalvirtual
Returns
The number of rows in the matrix returned by value().

Implements Trajectory< T >.

◆ segment()

const Trajectory<T>& segment ( int  segment_index) const

Returns a reference to the segment_index trajectory.

◆ value()

MatrixX<T> value ( const T &  time) const
finalvirtual

Evaluates the curve at the given time.

Warning
If t does not lie in the range [start_time(), end_time()], the trajectory will silently be evaluated at the closest valid value of time to time. For example, value(-1) will return value(0) for a trajectory defined over [0, 1].

Implements Trajectory< T >.


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