Public Member Functions | Public Attributes
joint_trajectory_controller::SegmentTolerances< Scalar > Struct Template Reference

Trajectory segment tolerances. More...

#include <tolerances.h>

List of all members.

Public Member Functions

 SegmentTolerances (const typename std::vector< StateTolerances< Scalar > >::size_type &size=0)

Public Attributes

std::vector< StateTolerances
< Scalar > > 
goal_state_tolerance
Scalar goal_time_tolerance
std::vector< StateTolerances
< Scalar > > 
state_tolerance

Detailed Description

template<class Scalar>
struct joint_trajectory_controller::SegmentTolerances< Scalar >

Trajectory segment tolerances.

Definition at line 73 of file tolerances.h.


Constructor & Destructor Documentation

template<class Scalar>
joint_trajectory_controller::SegmentTolerances< Scalar >::SegmentTolerances ( const typename std::vector< StateTolerances< Scalar > >::size_type &  size = 0) [inline]

Definition at line 75 of file tolerances.h.


Member Data Documentation

template<class Scalar>
std::vector<StateTolerances<Scalar> > joint_trajectory_controller::SegmentTolerances< Scalar >::goal_state_tolerance

State tolerances that apply for the goal state only.

Definition at line 85 of file tolerances.h.

template<class Scalar>
Scalar joint_trajectory_controller::SegmentTolerances< Scalar >::goal_time_tolerance

Extra time after the segment end time allowed to reach the goal state tolerances.

Definition at line 88 of file tolerances.h.

template<class Scalar>
std::vector<StateTolerances<Scalar> > joint_trajectory_controller::SegmentTolerances< Scalar >::state_tolerance

State tolerances that appply during segment execution.

Definition at line 82 of file tolerances.h.


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


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Aug 13 2016 04:20:51