Go to the documentation of this file.
28 #ifndef TRAJECTORY_BUILDER_H
29 #define TRAJECTORY_BUILDER_H
34 #include <boost/shared_ptr.hpp>
35 #include <boost/optional.hpp>
38 #include <control_msgs/FollowJointTrajectoryAction.h>
63 template<
class SegmentImpl>
100 virtual void reset();
115 const boost::optional<typename Segment::Time>&
getStartTime()
const;
127 const unsigned int expected_number_of_joints,
128 const unsigned int expected_number_of_segments);
131 boost::optional<typename Segment::Time>
start_time_ {boost::none};
138 template<
class SegmentImpl>
141 start_time_ = start_time;
145 template<
class SegmentImpl>
151 template<
class SegmentImpl>
154 goal_handle_ = goal_handle;
158 template<
class SegmentImpl>
161 return goal_handle_ ? goal_handle_.value() : createDefaultGoalHandle();
164 template<
class SegmentImpl>
170 template<
class SegmentImpl>
173 start_time_ = boost::none;
174 goal_handle_ = boost::none;
177 template<
class SegmentImpl>
179 const unsigned int expected_number_of_joints,
180 const unsigned int expected_number_of_segments)
182 if (trajectory->size() != expected_number_of_joints)
186 for (
const auto& traj_per_joint : *trajectory)
188 if (traj_per_joint.size() != expected_number_of_segments)
198 #endif // TRAJECTORY_BUILDER_H
RealtimeGoalHandlePtr createGoalHandlePtr() const
Return the set goal handle or a default one, if no goal handle was set.
boost::optional< typename Segment::Time > start_time_
const boost::optional< typename Segment::Time > & getStartTime() const
Return the set start time.
virtual void reset()
Ensures re-usability by allowing the user to reset members of the builder which should be reset betwe...
std::vector< TrajectoryPerJoint > Trajectory
boost::optional< RealtimeGoalHandlePtr & > goal_handle_
std::vector< Segment > TrajectoryPerJoint
static RealtimeGoalHandlePtr createDefaultGoalHandle()
TrajectoryBuilder< SegmentImpl > * setStartTime(const typename Segment::Time &start_time)
Set the start time [seconds] of the trajectory to be built.
Class representing a multi-dimensional quintic spline segment with a start and end time.
TrajectoryBuilder< SegmentImpl > * setGoalHandle(RealtimeGoalHandlePtr &goal_handle)
Set the goal handle that will be attached to the trajectory segments.
static bool isTrajectoryValid(const Trajectory *trajectory, const unsigned int expected_number_of_joints, const unsigned int expected_number_of_segments)
Check if the elements of a given trajectory are sized properly.
Base class for classes used to construct diffent trajectory types.
virtual bool buildTrajectory(Trajectory *trajectory)=0
Creates the type of trajectory described by the builder.