Public Types | Public Member Functions
joint_trajectory_controller::JointTrajectorySegment< Segment >::State Struct Reference

#include <joint_trajectory_segment.h>

List of all members.

Public Types

typedef Segment::State::Scalar Scalar

Public Member Functions

void init (const trajectory_msgs::JointTrajectoryPoint &point, const std::vector< unsigned int > &permutation=std::vector< unsigned int >(), const std::vector< Scalar > &position_offset=std::vector< Scalar >())
 State ()
 State (unsigned int size)
 State (const trajectory_msgs::JointTrajectoryPoint &point, const std::vector< unsigned int > &permutation=std::vector< unsigned int >(), const std::vector< Scalar > &position_offset=std::vector< Scalar >())

Detailed Description

template<class Segment>
struct joint_trajectory_controller::JointTrajectorySegment< Segment >::State

Definition at line 79 of file joint_trajectory_segment.h.


Member Typedef Documentation

template<class Segment >
typedef Segment::State::Scalar joint_trajectory_controller::JointTrajectorySegment< Segment >::State::Scalar

Definition at line 81 of file joint_trajectory_segment.h.


Constructor & Destructor Documentation

template<class Segment >
joint_trajectory_controller::JointTrajectorySegment< Segment >::State::State ( ) [inline]

Definition at line 82 of file joint_trajectory_segment.h.

template<class Segment >
joint_trajectory_controller::JointTrajectorySegment< Segment >::State::State ( unsigned int  size) [inline]

Definition at line 83 of file joint_trajectory_segment.h.

template<class Segment >
joint_trajectory_controller::JointTrajectorySegment< Segment >::State::State ( const trajectory_msgs::JointTrajectoryPoint &  point,
const std::vector< unsigned int > &  permutation = std::vector<unsigned int>(),
const std::vector< Scalar > &  position_offset = std::vector<Scalar>() 
) [inline]
Parameters:
pointTrajectory point.
permutationPermutation vector for mapping the joint order of a point to a desired order. For instance, if point contains data associated to joints "{B, D, A, C}", and we are interested in constructing a segment with joints ordered as "{A, B, C, D}", the permutation vector should be set to "{2, 0, 3, 1}". If unspecified (empty), the joint order of point is preserved; if specified, its size must coincide with that of point. This vector can be computed using the permutation utility function.
position_offsetPosition offset to applpy to the data in point. This parameter is useful for handling joints that wrap around (ie. continuous), to compensate for multi-turn offsets. If unspecified (empty), zero offsets are applied; if specified, its size must coincide with that of point.
Note:
The offsets in position_offsets correspond to joints not ordered according to point, but to joints in the expected order, that is point with permutation applied to it.

Definition at line 104 of file joint_trajectory_segment.h.


Member Function Documentation

template<class Segment >
void joint_trajectory_controller::JointTrajectorySegment< Segment >::State::init ( const trajectory_msgs::JointTrajectoryPoint &  point,
const std::vector< unsigned int > &  permutation = std::vector<unsigned int>(),
const std::vector< Scalar > &  position_offset = std::vector<Scalar>() 
) [inline]

Definition at line 111 of file joint_trajectory_segment.h.


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


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Aug 28 2015 12:36:48