Classes | Public Types | Public Member Functions | Private Attributes | List of all members
joint_trajectory_controller::JointTrajectorySegment< Segment > Class Template Reference

Class representing a multi-dimensional quintic spline segment with a start and end time. More...

#include <joint_trajectory_segment.h>

Inheritance diagram for joint_trajectory_controller::JointTrajectorySegment< Segment >:
Inheritance graph
[legend]

Classes

struct  State
 

Public Types

typedef realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RealtimeGoalHandle
 
typedef boost::shared_ptr< RealtimeGoalHandleRealtimeGoalHandlePtr
 
typedef Segment::Scalar Scalar
 
typedef Segment::Time Time
 

Public Member Functions

RealtimeGoalHandlePtr getGoalHandle () const
 
const SegmentTolerancesPerJoint< Scalar > & getTolerances () const
 
 JointTrajectorySegment (const ros::Time &traj_start_time, const trajectory_msgs::JointTrajectoryPoint &start_point, const trajectory_msgs::JointTrajectoryPoint &end_point, const std::vector< Scalar > &position_offset=std::vector< Scalar >())
 Construct a segment from start and end points (boundary conditions) specified in ROS message format. More...
 
 JointTrajectorySegment (const Time &start_time, const State &start_state, const Time &end_time, const State &end_state)
 Construct segment from start and end states (boundary conditions). More...
 
void setGoalHandle (RealtimeGoalHandlePtr rt_goal_handle)
 Set the (realtime) goal handle associated to this segment. More...
 
void setTolerances (const SegmentTolerancesPerJoint< Scalar > &tolerances)
 Set the tolerances this segment is associated to. More...
 

Private Attributes

RealtimeGoalHandlePtr rt_goal_handle_
 
SegmentTolerancesPerJoint< Scalartolerances_
 

Detailed Description

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

Class representing a multi-dimensional quintic spline segment with a start and end time.

It additionally allows to construct the segment and its state type from ROS message data.

Template Parameters
SegmentSegment type. The state type (Segment::State) must define a Scalar type (Segment::State::Scalar), which can be anything convertible to a double; and have the following public members:
std::vector<Scalar> position;
std::vector<Scalar> velocity;
std::vector<Scalar> acceleration;

Definition at line 70 of file joint_trajectory_segment.h.

Member Typedef Documentation

◆ RealtimeGoalHandle

template<class Segment >
typedef realtime_tools::RealtimeServerGoalHandle<control_msgs::FollowJointTrajectoryAction> joint_trajectory_controller::JointTrajectorySegment< Segment >::RealtimeGoalHandle

Definition at line 76 of file joint_trajectory_segment.h.

◆ RealtimeGoalHandlePtr

Definition at line 77 of file joint_trajectory_segment.h.

◆ Scalar

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

Definition at line 73 of file joint_trajectory_segment.h.

◆ Time

template<class Segment >
typedef Segment::Time joint_trajectory_controller::JointTrajectorySegment< Segment >::Time

Definition at line 74 of file joint_trajectory_segment.h.

Constructor & Destructor Documentation

◆ JointTrajectorySegment() [1/2]

template<class Segment >
joint_trajectory_controller::JointTrajectorySegment< Segment >::JointTrajectorySegment ( const Time start_time,
const State start_state,
const Time end_time,
const State end_state 
)
inline

Construct segment from start and end states (boundary conditions).

Parameters
start_timeTime at which the segment state equals start_state.
start_stateState at start_time.
end_timeTime at which the segment state equals end_state.
end_stateState at time end_time.

Definition at line 144 of file joint_trajectory_segment.h.

◆ JointTrajectorySegment() [2/2]

template<class Segment >
joint_trajectory_controller::JointTrajectorySegment< Segment >::JointTrajectorySegment ( const ros::Time traj_start_time,
const trajectory_msgs::JointTrajectoryPoint &  start_point,
const trajectory_msgs::JointTrajectoryPoint &  end_point,
const std::vector< Scalar > &  position_offset = std::vector<Scalar>() 
)
inline

Construct a segment from start and end points (boundary conditions) specified in ROS message format.

Parameters
traj_start_timeTime at which the trajectory containing the segment starts. Note that this is not the segment start time.
start_pointStart state in ROS message format.
end_pointEnd state in ROS message format.
position_offsetSee JointTrajectorySegment::State.
Exceptions
std::invalid_argumentIf input parameters are inconsistent and a valid segment can't be constructed.

Definition at line 165 of file joint_trajectory_segment.h.

Member Function Documentation

◆ getGoalHandle()

template<class Segment >
RealtimeGoalHandlePtr joint_trajectory_controller::JointTrajectorySegment< Segment >::getGoalHandle ( ) const
inline
Returns
Pointer to (realtime) goal handle associated to this segment.

Definition at line 197 of file joint_trajectory_segment.h.

◆ getTolerances()

template<class Segment >
const SegmentTolerancesPerJoint<Scalar>& joint_trajectory_controller::JointTrajectorySegment< Segment >::getTolerances ( ) const
inline
Returns
Tolerances this segment is associated to.

Definition at line 203 of file joint_trajectory_segment.h.

◆ setGoalHandle()

template<class Segment >
void joint_trajectory_controller::JointTrajectorySegment< Segment >::setGoalHandle ( RealtimeGoalHandlePtr  rt_goal_handle)
inline

Set the (realtime) goal handle associated to this segment.

Definition at line 200 of file joint_trajectory_segment.h.

◆ setTolerances()

template<class Segment >
void joint_trajectory_controller::JointTrajectorySegment< Segment >::setTolerances ( const SegmentTolerancesPerJoint< Scalar > &  tolerances)
inline

Set the tolerances this segment is associated to.

Definition at line 206 of file joint_trajectory_segment.h.

Member Data Documentation

◆ rt_goal_handle_

template<class Segment >
RealtimeGoalHandlePtr joint_trajectory_controller::JointTrajectorySegment< Segment >::rt_goal_handle_
private

Definition at line 209 of file joint_trajectory_segment.h.

◆ tolerances_

template<class Segment >
SegmentTolerancesPerJoint<Scalar> joint_trajectory_controller::JointTrajectorySegment< Segment >::tolerances_
private

Definition at line 210 of file joint_trajectory_segment.h.


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


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sun Mar 3 2024 03:19:26