Drake
PiecewiseCartesianTrajectory< T > Class Template Reference

A wrapper class that represents a Cartesian trajectory, whose position part is a PiecewiseCubicTrajectory, and the rotation part is a PiecewiseQuaternionSlerp. More...

#include <drake/manipulation/util/trajectory_utils.h>

Public Member Functions

 PiecewiseCartesianTrajectory ()
 
 PiecewiseCartesianTrajectory (const PiecewisePolynomial< T > &pos_traj, const PiecewiseQuaternionSlerp< T > &rot_traj)
 Constructor. More...
 
 PiecewiseCartesianTrajectory (const PiecewiseCubicTrajectory< T > &pos_traj, const PiecewiseQuaternionSlerp< T > &rot_traj)
 Constructor. More...
 
Isometry3< T > get_pose (double time) const
 Returns the interpolated pose at time. More...
 
Vector6< T > get_velocity (double time) const
 Returns the interpolated velocity at time or zero if time is before this trajectory's start time or after its end time. More...
 
Vector6< T > get_acceleration (double time) const
 Returns the interpolated acceleration at time or zero if time is before this trajectory's start time or after its end time. More...
 
bool is_approx (const PiecewiseCartesianTrajectory< T > &other, const T &tol) const
 Returns true if the position and orientation trajectories are both within tol from the other's. More...
 
const PiecewiseCubicTrajectory< T > & get_position_trajectory () const
 Returns the position trajectory. More...
 
const PiecewiseQuaternionSlerp< T > & get_orientation_trajectory () const
 Returns the orientation trajectory. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 PiecewiseCartesianTrajectory (const PiecewiseCartesianTrajectory &)=default
 
PiecewiseCartesianTrajectoryoperator= (const PiecewiseCartesianTrajectory &)=default
 
 PiecewiseCartesianTrajectory (PiecewiseCartesianTrajectory &&)=default
 
PiecewiseCartesianTrajectoryoperator= (PiecewiseCartesianTrajectory &&)=default
 

Static Public Member Functions

static PiecewiseCartesianTrajectory< T > MakeCubicLinearWithEndLinearVelocity (const std::vector< T > &times, const std::vector< Isometry3< T >> &poses, const Vector3< T > &vel0, const Vector3< T > &vel1)
 Constructs a PiecewiseCartesianTrajectory from given time and poses. More...
 

Detailed Description

template<typename T>
class drake::manipulation::PiecewiseCartesianTrajectory< T >

A wrapper class that represents a Cartesian trajectory, whose position part is a PiecewiseCubicTrajectory, and the rotation part is a PiecewiseQuaternionSlerp.

Constructor & Destructor Documentation

PiecewiseCartesianTrajectory ( const PiecewisePolynomial< T > &  pos_traj,
const PiecewiseQuaternionSlerp< T > &  rot_traj 
)
inline

Constructor.

Parameters
pos_trajPosition trajectory.
rot_trajOrientation trajectory.
PiecewiseCartesianTrajectory ( const PiecewiseCubicTrajectory< T > &  pos_traj,
const PiecewiseQuaternionSlerp< T > &  rot_traj 
)
inline

Constructor.

Parameters
pos_trajPosition trajectory.
rot_trajOrientation trajectory.

Member Function Documentation

Vector6<T> get_acceleration ( double  time) const
inline

Returns the interpolated acceleration at time or zero if time is before this trajectory's start time or after its end time.

Here is the caller graph for this function:

const PiecewiseQuaternionSlerp<T>& get_orientation_trajectory ( ) const
inline

Returns the orientation trajectory.

Isometry3<T> get_pose ( double  time) const
inline

Returns the interpolated pose at time.

Here is the caller graph for this function:

const PiecewiseCubicTrajectory<T>& get_position_trajectory ( ) const
inline

Returns the position trajectory.

Here is the caller graph for this function:

Vector6<T> get_velocity ( double  time) const
inline

Returns the interpolated velocity at time or zero if time is before this trajectory's start time or after its end time.

Here is the caller graph for this function:

bool is_approx ( const PiecewiseCartesianTrajectory< T > &  other,
const T &  tol 
) const
inline

Returns true if the position and orientation trajectories are both within tol from the other's.

Here is the caller graph for this function:

static PiecewiseCartesianTrajectory<T> MakeCubicLinearWithEndLinearVelocity ( const std::vector< T > &  times,
const std::vector< Isometry3< T >> &  poses,
const Vector3< T > &  vel0,
const Vector3< T > &  vel1 
)
inlinestatic

Constructs a PiecewiseCartesianTrajectory from given time and poses.

A cubic polynomial with zero end velocities is used to construct the position part. There must be at least two elements in times and poses.

Parameters
timesBreaks used to build the splines.
posesKnots used to build the splines.
vel0Start linear velocity. vel1 End linear velocity.

Here is the caller graph for this function:

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

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