28 #ifndef HOLD_TRAJECTORY_BUILDER_H 29 #define HOLD_TRAJECTORY_BUILDER_H 42 template<
class SegmentImpl,
class HardwareInterface>
53 using JointHandle =
typename HardwareInterface::ResourceHandleType;
74 template<
class SegmentImpl,
class HardwareInterface>
81 template<
class SegmentImpl,
class HardwareInterface>
96 for (
unsigned int joint_index = 0; joint_index <
joints_.size(); ++joint_index)
102 Segment& segment {(*hold_traj)[joint_index].front()};
112 #endif // HOLD_TRAJECTORY_BUILDER_H const std::vector< JointHandle > & joints_
typename HardwareInterface::ResourceHandleType JointHandle
Segment::State hold_start_state_
bool buildTrajectory(Trajectory *hold_traj) override
See base class.
void setGoalHandle(RealtimeGoalHandlePtr rt_goal_handle)
Set the (realtime) goal handle associated to this segment.
Builder creating a trajectory "simply" holding (without motion) the specified position.
std::vector< Segment > TrajectoryPerJoint
Class representing a multi-dimensional quintic spline segment with a start and end time...
Base class for classes used to construct diffent trajectory types.
RealtimeGoalHandlePtr createGoalHandlePtr() const
Return the set goal handle or a default one, if no goal handle was set.
const boost::optional< typename Segment::Time > & getStartTime() const
Return the set start time.
HoldTrajectoryBuilder(const std::vector< JointHandle > &joints)
std::vector< TrajectoryPerJoint > Trajectory
Segment::State hold_end_state_