Public Member Functions | Public Attributes | Private Attributes | Friends | List of all members
ecl::Trajectory< JointAngles > Class Template Reference

Joint angle based manipulator trajectory. More...

#include <trajectory.hpp>

Public Member Functions

void append (const WayPoint< JointAngles > &waypoint)
 Appends a waypoint to the trajectory specification. More...
 
void clear ()
 Clear the waypoints and splines. More...
 
void clearSplines ()
 Clean up the memory allocated to the spline functions. More...
 
double dderivative (const unsigned int &joint, const double &time)
 Access the 2nd derivative of the joint trajectory at the specified point. More...
 
double derivative (const unsigned int &joint, const double &time)
 Access the derivative of the joint trajectory at the specified point. More...
 
unsigned int dimension () const
 Dimension, or degrees of freedom for the trajectory. More...
 
const double & duration () const
 Total trajectory duration (in seconds). More...
 
Array< SmoothLinearSplinegenerateLinearSplines ()
 
Array< TensionSplinegenerateTensionSplines (const double &tension, const double initial_time=0.0)
 
bool initialiseWaypointDurations ()
 
WayPoint< JointAngles > & last ()
 Get the last waypoint in the trajectory. More...
 
const WayPoint< JointAngles > & last () const
 Const version of the last waypoint in the trajectory. More...
 
void linearSplineInterpolation ()
 Generate a smoothed linear spline interpolation from the specified waypoints. More...
 
Array< double > & maxAccelerations ()
 Handle to the max accelerations array, use to initialise the polynomial. More...
 
void maxAccelerations (const double &max_acceleration)
 Configure the entire trajectory with a uniform max acceleration bound. More...
 
const Array< double > & maxAccelerations () const
 Non-modifiable handle to the max accelerations array. More...
 
double operator() (const unsigned int &joint, const double &time)
 Access the value of the joint trajectory at the specified point. More...
 
void redimension (const unsigned int &dim)
 Reset the dimension, or degrees of freedom for the trajectory. More...
 
unsigned int size () const
 Number of waypoints in the trajectory. More...
 
void tensionSplineInterpolation (const double &tension)
 Generate a tension spline interpolation from the specified waypoints. More...
 
 Trajectory (const char *name_identifier="")
 Default constructor, only (optionally) configures the trajectory name. More...
 
 Trajectory (const unsigned int &dimension, const char *name_identifier="")
 Configures the joint dimension, and also (optionally) the trajectory name. More...
 
void updateDuration ()
 
bool validateWaypoints (unsigned int min_no_waypoints)
 
const WayPoint< JointAngles > & waypoint (const unsigned int &index)
 Get a handle to the specified waypoint. More...
 
virtual ~Trajectory ()
 Default destructor. More...
 

Public Attributes

Parameter< std::string > name
 String name identifier. More...
 

Private Attributes

Array< double > max_accelerations
 
Array< std::vector< GenericSplineFunction * > > spline_functions
 
double trajectory_duration
 
std::vector< WayPoint< JointAngles > > waypoints
 

Friends

template<typename OutputStream >
OutputStream & operator<< (OutputStream &ostream, Trajectory< JointAngles > &trajectory)
 Streaming output insertion operator for for waypoints. More...
 

Detailed Description

template<>
class ecl::Trajectory< JointAngles >

Joint angle based manipulator trajectory.

Joint angle based manipulator trajectory. Construction simply provides an empty instantiation for the trajectory. You must

to fully define the resulting trajectory.

See also
Trajectory.

Definition at line 86 of file trajectory.hpp.

Constructor & Destructor Documentation

ecl::Trajectory< JointAngles >::Trajectory ( const char *  name_identifier = "")
inline

Default constructor, only (optionally) configures the trajectory name.

Parameters
name_identifier: string identifier for the trajectory name.

Definition at line 93 of file trajectory.hpp.

ecl::Trajectory< JointAngles >::Trajectory ( const unsigned int &  dimension,
const char *  name_identifier = "" 
)
inline

Configures the joint dimension, and also (optionally) the trajectory name.

Parameters
dimension: number of joints in this trajectory.
name_identifier: string identifier for the trajectory name.

Definition at line 102 of file trajectory.hpp.

virtual ecl::Trajectory< JointAngles >::~Trajectory ( )
inlinevirtual

Default destructor.

Cleans up the memory allocations for the spline functions.

Definition at line 113 of file trajectory.hpp.

Member Function Documentation

void ecl::Trajectory< JointAngles >::append ( const WayPoint< JointAngles > &  waypoint)
inline

Appends a waypoint to the trajectory specification.

This is the only means of configuring waypoints for the trajectory. Note that you cannot delete them, nor insert them into the middle of the waypoint sequence. These functions are not really necessary and just complicate the interface, but keep it in mind when programming for trajectories.

Exceptions
StandardException : throws if waypoint dimension doesn't match.

Definition at line 157 of file trajectory.hpp.

void ecl::Trajectory< JointAngles >::clear ( )
inline

Clear the waypoints and splines.

Definition at line 117 of file trajectory.hpp.

void ecl::Trajectory< JointAngles >::clearSplines ( )

Clean up the memory allocated to the spline functions.

This is used internally by the various interpolation algorithms.

Definition at line 497 of file trajectory.cpp.

double ecl::Trajectory< JointAngles >::dderivative ( const unsigned int &  joint,
const double &  time 
)

Access the 2nd derivative of the joint trajectory at the specified point.

Parameters
joint: specifies the joint you are interested in.
time: the time at which you wish to calculate the value for.
Returns
double : the 2nd derivative of the specified joint trajectory at x.
Exceptions
StandardException : throws if input time value is outside the domain [debug mode only].

Definition at line 415 of file trajectory.cpp.

double ecl::Trajectory< JointAngles >::derivative ( const unsigned int &  joint,
const double &  time 
)

Access the derivative of the joint trajectory at the specified point.

Parameters
joint: specifies the joint you are interested in.
time: the time at which you wish to calculate the value for.
Returns
double : the derivative of the specified joint trajectory at x.
Exceptions
StandardException : throws if input time value is outside the domain [debug mode only].

Definition at line 396 of file trajectory.cpp.

unsigned int ecl::Trajectory< JointAngles >::dimension ( ) const
inline

Dimension, or degrees of freedom for the trajectory.

This is the number of joints being interpolated by the trajectory.

Returns
int : number of joints.

Definition at line 131 of file trajectory.hpp.

const double& ecl::Trajectory< JointAngles >::duration ( ) const
inline

Total trajectory duration (in seconds).

Trajectory duration (in seconds).

Returns
const double& : the time required for the entire trajectory.

Definition at line 334 of file trajectory.hpp.

Array< SmoothLinearSpline > ecl::Trajectory< JointAngles >::generateLinearSplines ( )

Unlike the other generators, this generates the spline over all the waypoints. It is not used in combination with another spline function.

Definition at line 526 of file trajectory.cpp.

Array< TensionSpline > ecl::Trajectory< JointAngles >::generateTensionSplines ( const double &  tension,
const double  initial_time = 0.0 
)

This creates the tension splines across waypoints w_0 -> w_n for the quinticTensionInterpolation. Note that the quintic tension will insert pseudo points at the beginning and end later which will forcibly modify the behaviour of the tension spline endpoints for specific boundary conditions.

Definition at line 802 of file trajectory.cpp.

bool ecl::Trajectory< JointAngles >::initialiseWaypointDurations ( )

This uses the nominal rates to guess durations between each waypoint. Generally, this is used by the interpolations, who then throw if something's gone wrong.

Definition at line 460 of file trajectory.cpp.

Get the last waypoint in the trajectory.

This is just a utility function for checking the last waypoint in the trajectory.

Returns
const WayPoint<JointAngles>& : const handle to the last waypoint in the traectory.

Definition at line 170 of file trajectory.hpp.

const WayPoint<JointAngles>& ecl::Trajectory< JointAngles >::last ( ) const
inline

Const version of the last waypoint in the trajectory.

This is just a utility function for checking the last waypoint in the trajectory.

Returns
const WayPoint<JointAngles>& : const handle to the last waypoint in the traectory.

Definition at line 182 of file trajectory.hpp.

void ecl::Trajectory< JointAngles >::linearSplineInterpolation ( )

Generate a smoothed linear spline interpolation from the specified waypoints.

This generates an interpolation across the waypoints with the following characteristics.

  • Interpolation begins and ends with y' = y'' = 0.
  • C2 continuous.
  • Spline functions are connected as follows:
    • Quintic Polynomial : needed to ensure y' = y'' = 0.
    • Smooth Linear Spline : composition of segments and corners.
    • Quintic Polynomial : needed to ensure y' = y'' = 0.

The quintics are generated from internally generated pseudo-waypoints to ensure that the initial and final resting conditions are met.

Before you call this function, make sure the following requirements are met.

  • Waypoints are assigned with following data set:
    • angles (y)
    • nominal rates (i.e. estimated velocities) OR durations
    • maximum accelerations have been set (via this classes maxAccelerations methods)

Definition at line 282 of file trajectory.cpp.

Array<double>& ecl::Trajectory< JointAngles >::maxAccelerations ( )
inline

Handle to the max accelerations array, use to initialise the polynomial.

This returns a handle to the max accelerations array. Use this with the comma initialiser to conveniently set the polynomial.

Trajectory<2> trajectory;
trajectory.maxAccelerations() = 0.8,0.6;
Returns
Array<double>& : reference to the max accelerations array.

Definition at line 286 of file trajectory.hpp.

void ecl::Trajectory< JointAngles >::maxAccelerations ( const double &  max_acceleration)
inline

Configure the entire trajectory with a uniform max acceleration bound.

Configure the entire trajectory with a uniform max acceleration bound (i.e. each joint's acceleration is limited similarly).

Parameters
max_acceleration: the uniform maximum acceleration bound to use.

Definition at line 295 of file trajectory.hpp.

const Array<double>& ecl::Trajectory< JointAngles >::maxAccelerations ( ) const
inline

Non-modifiable handle to the max accelerations array.

Returns
const Array<double,N>& : non-modifiable reference to the max accelerations array.

Definition at line 305 of file trajectory.hpp.

double ecl::Trajectory< JointAngles >::operator() ( const unsigned int &  joint,
const double &  time 
)

Access the value of the joint trajectory at the specified point.

Parameters
joint: specifies the joint you are interested in.
time: the time at which you wish to calculate the value for.
Returns
double : the value of the specified joint trajectory at x.
Exceptions
StandardException : throws if input time value is outside the domain [debug mode only].

Definition at line 378 of file trajectory.cpp.

void ecl::Trajectory< JointAngles >::redimension ( const unsigned int &  dim)
inline

Reset the dimension, or degrees of freedom for the trajectory.

Reset the number of joints being interpolated by the trajectory.

Parameters
dim: number of joints in this trajectory.

Definition at line 140 of file trajectory.hpp.

unsigned int ecl::Trajectory< JointAngles >::size ( ) const
inline

Number of waypoints in the trajectory.

Returns
unsigned int : number of waypoints stored in the trajectory.

Definition at line 123 of file trajectory.hpp.

void ecl::Trajectory< JointAngles >::tensionSplineInterpolation ( const double &  tension)

Generate a tension spline interpolation from the specified waypoints.

This generates an interpolation across the waypoints with the following characteristics.

  • Interpolation begins and ends with y' = y'' = 0.
  • C2 continuous.
  • Spline functions are connected as follows:
    • Quintic Polynomial : needed to ensure y' = y'' = 0.
    • Tension Spline : guarantees C2 continuity across the interpolation.
    • Quintic Polynomial : needed to ensure y' = y'' = 0.

The quintics are generated from internally generated pseudo-waypoints to ensure that the initial and final resting conditions are met.

Before you call this function, make sure the following requirements are met.

  • Waypoints are assigned with following data set:
    • angles (y)
    • nominal rates (i.e. estimated velocities) OR durations
    • maximum accelerations have been set (via this classes maxAccelerations methods)

Definition at line 36 of file trajectory.cpp.

void ecl::Trajectory< JointAngles >::updateDuration ( )

This is a convenient function for interpolation members to use to update the duration with the latest calculation determined from the sum of the waypoint durations. This is oft used since the interpolations will often adjust the waypoint durations while interpolating.

Definition at line 513 of file trajectory.cpp.

bool ecl::Trajectory< JointAngles >::validateWaypoints ( unsigned int  min_no_waypoints)

This checks various properties of the waypoints to make sure they're valid. Generally, this is used by the interpolations, who then throw if something's gone wrong.

Definition at line 438 of file trajectory.cpp.

const WayPoint<JointAngles>& ecl::Trajectory< JointAngles >::waypoint ( const unsigned int &  index)
inline

Get a handle to the specified waypoint.

This is just a utility function for retrieving a waypoint (const version).

Parameters
index: index of the waypoint to get a handle to.
Returns
WayPoint : the waypoint, if index was correct.
Exceptions
StandardException : throws if index is outside the number of stored waypoints [debug mode only].

Definition at line 195 of file trajectory.hpp.

Friends And Related Function Documentation

template<typename OutputStream >
OutputStream& operator<< ( OutputStream &  ostream,
Trajectory< JointAngles > &  trajectory 
)
friend

Streaming output insertion operator for for waypoints.

Streaming output insertion operator for waypoints.

Template Parameters
OutputStream: the type of stream being used.
Parameters
ostream: the output stream being used.
trajectory: the trajectory.
Returns
OutputStream : the output stream.

Definition at line 389 of file trajectory.hpp.

Member Data Documentation

Array< double> ecl::Trajectory< JointAngles >::max_accelerations
private

Definition at line 340 of file trajectory.hpp.

Parameter<std::string> ecl::Trajectory< JointAngles >::name

String name identifier.

Definition at line 335 of file trajectory.hpp.

Array< std::vector<GenericSplineFunction*> > ecl::Trajectory< JointAngles >::spline_functions
private

Definition at line 339 of file trajectory.hpp.

double ecl::Trajectory< JointAngles >::trajectory_duration
private

Definition at line 341 of file trajectory.hpp.

std::vector< WayPoint<JointAngles> > ecl::Trajectory< JointAngles >::waypoints
private

Definition at line 338 of file trajectory.hpp.


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


ecl_manipulators
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:09:10