Class representing a multi-dimensional quintic spline segment with a start and end time. More...
#include <joint_trajectory_segment.h>
Classes | |
struct | State |
Public Types | |
typedef realtime_tools::RealtimeServerGoalHandle < control_msgs::FollowJointTrajectoryAction > | RealtimeGoalHandle |
typedef boost::shared_ptr < RealtimeGoalHandle > | RealtimeGoalHandlePtr |
typedef Segment::Scalar | Scalar |
typedef Segment::Time | Time |
Public Member Functions | |
RealtimeGoalHandlePtr | getGoalHandle () const |
const SegmentTolerances< Scalar > & | getTolerances () const |
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). | |
JointTrajectorySegment (const ros::Time &traj_start_time, const trajectory_msgs::JointTrajectoryPoint &start_point, const trajectory_msgs::JointTrajectoryPoint &end_point, const std::vector< unsigned int > &permutation=std::vector< unsigned int >(), const std::vector< Scalar > &position_offset=std::vector< Scalar >()) | |
Construct a segment from start and end points (boundary conditions) specified in ROS message format. | |
void | setGoalHandle (RealtimeGoalHandlePtr rt_goal_handle) |
Set the (realtime) goal handle associated to this segment. | |
void | setTolerances (const SegmentTolerances< Scalar > &tolerances) |
Set the tolerances this segment is associated to. | |
Private Attributes | |
RealtimeGoalHandlePtr | rt_goal_handle_ |
SegmentTolerances< Scalar > | tolerances_ |
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.
Segment | Segment 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.
typedef realtime_tools::RealtimeServerGoalHandle<control_msgs::FollowJointTrajectoryAction> joint_trajectory_controller::JointTrajectorySegment< Segment >::RealtimeGoalHandle |
Definition at line 76 of file joint_trajectory_segment.h.
typedef boost::shared_ptr<RealtimeGoalHandle> joint_trajectory_controller::JointTrajectorySegment< Segment >::RealtimeGoalHandlePtr |
Definition at line 77 of file joint_trajectory_segment.h.
typedef Segment::Scalar joint_trajectory_controller::JointTrajectorySegment< Segment >::Scalar |
Definition at line 73 of file joint_trajectory_segment.h.
typedef Segment::Time joint_trajectory_controller::JointTrajectorySegment< Segment >::Time |
Definition at line 74 of file joint_trajectory_segment.h.
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).
start_time | Time at which the segment state equals start_state . |
start_state | State at start_time . |
end_time | Time at which the segment state equals end_state . |
end_state | State at time end_time . |
Definition at line 169 of file joint_trajectory_segment.h.
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< unsigned int > & | permutation = std::vector<unsigned int>() , |
||
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.
traj_start_time | Time at which the trajectory containing the segment starts. Note that this is not the segment start time. |
start_point | Start state in ROS message format. |
end_point | End state in ROS message format. |
permutation | See JointTrajectorySegment::State. |
position_offset | See JointTrajectorySegment::State. |
std::invalid_argument | If input parameters are inconsistent and a valid segment can't be constructed. |
Definition at line 191 of file joint_trajectory_segment.h.
RealtimeGoalHandlePtr joint_trajectory_controller::JointTrajectorySegment< Segment >::getGoalHandle | ( | ) | const [inline] |
Definition at line 224 of file joint_trajectory_segment.h.
const SegmentTolerances<Scalar>& joint_trajectory_controller::JointTrajectorySegment< Segment >::getTolerances | ( | ) | const [inline] |
Definition at line 230 of file joint_trajectory_segment.h.
void joint_trajectory_controller::JointTrajectorySegment< Segment >::setGoalHandle | ( | RealtimeGoalHandlePtr | rt_goal_handle | ) | [inline] |
Set the (realtime) goal handle associated to this segment.
Definition at line 227 of file joint_trajectory_segment.h.
void joint_trajectory_controller::JointTrajectorySegment< Segment >::setTolerances | ( | const SegmentTolerances< Scalar > & | tolerances | ) | [inline] |
Set the tolerances this segment is associated to.
Definition at line 233 of file joint_trajectory_segment.h.
RealtimeGoalHandlePtr joint_trajectory_controller::JointTrajectorySegment< Segment >::rt_goal_handle_ [private] |
Definition at line 236 of file joint_trajectory_segment.h.
SegmentTolerances<Scalar> joint_trajectory_controller::JointTrajectorySegment< Segment >::tolerances_ [private] |
Definition at line 237 of file joint_trajectory_segment.h.