Base class for classes used to construct diffent trajectory types. More...
#include <trajectory_builder.h>
Public Member Functions | |
virtual bool | buildTrajectory (Trajectory *trajectory)=0 |
Creates the type of trajectory described by the builder. More... | |
virtual void | reset () |
Ensures re-usability by allowing the user to reset members of the builder which should be reset between calls to buildTrajectory(). More... | |
TrajectoryBuilder< SegmentImpl > * | setGoalHandle (RealtimeGoalHandlePtr &goal_handle) |
Set the goal handle that will be attached to the trajectory segments. More... | |
TrajectoryBuilder< SegmentImpl > * | setStartTime (const typename Segment::Time &start_time) |
Set the start time [seconds] of the trajectory to be built. More... | |
virtual | ~TrajectoryBuilder ()=default |
Virtual destructor because this class is a base class. More... | |
Protected Member Functions | |
RealtimeGoalHandlePtr | createGoalHandlePtr () const |
Return the set goal handle or a default one, if no goal handle was set. More... | |
const boost::optional< typename Segment::Time > & | getStartTime () const |
Return the set start time. More... | |
Static Protected Member Functions | |
static RealtimeGoalHandlePtr | createDefaultGoalHandle () |
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. More... | |
Private Types | |
using | RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > |
using | RealtimeGoalHandlePtr = boost::shared_ptr< RealtimeGoalHandle > |
using | Segment = JointTrajectorySegment< SegmentImpl > |
using | Trajectory = std::vector< TrajectoryPerJoint > |
using | TrajectoryPerJoint = std::vector< Segment > |
Private Attributes | |
boost::optional< RealtimeGoalHandlePtr & > | goal_handle_ {boost::none} |
boost::optional< typename Segment::Time > | start_time_ {boost::none} |
Base class for classes used to construct diffent trajectory types.
A derived class has to implement buildTrajectory().
The following code snippet shows the intended usage of a builder class:
Setting a start time is mandatory whereas setting a goal handle can be omitted. Also note that trajectory
has to reference a valid trajectory (see isTrajectoryValid()).
Definition at line 64 of file trajectory_builder.h.
|
private |
Definition at line 77 of file trajectory_builder.h.
|
private |
Definition at line 78 of file trajectory_builder.h.
|
private |
Definition at line 73 of file trajectory_builder.h.
|
private |
Definition at line 75 of file trajectory_builder.h.
|
private |
Definition at line 74 of file trajectory_builder.h.
|
virtualdefault |
Virtual destructor because this class is a base class.
|
pure virtual |
Creates the type of trajectory described by the builder.
trajectory | [Out] Trajectory which has to be build. |
Implemented in joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >, and joint_trajectory_controller::HoldTrajectoryBuilder< SegmentImpl, HardwareInterface >.
|
inlinestaticprotected |
Definition at line 165 of file trajectory_builder.h.
|
inlineprotected |
Return the set goal handle or a default one, if no goal handle was set.
Definition at line 159 of file trajectory_builder.h.
|
inlineprotected |
Return the set start time.
Definition at line 146 of file trajectory_builder.h.
|
staticprotected |
Check if the elements of a given trajectory are sized properly.
trajectory | |
expected_number_of_joints | The count of TrajectoryPerJoint in trajectory has to match the number of joints. |
expected_number_of_segments | Each TrajectoryPerJoint in trajectory has to contain this number of segments. |
Definition at line 178 of file trajectory_builder.h.
|
inlinevirtual |
Ensures re-usability by allowing the user to reset members of the builder which should be reset between calls to buildTrajectory().
Definition at line 171 of file trajectory_builder.h.
|
inline |
Set the goal handle that will be attached to the trajectory segments.
The goal handle is reset by reset().
Definition at line 152 of file trajectory_builder.h.
|
inline |
Set the start time [seconds] of the trajectory to be built.
The start time is reset by reset().
Definition at line 139 of file trajectory_builder.h.
|
private |
Definition at line 134 of file trajectory_builder.h.
|
private |
Definition at line 131 of file trajectory_builder.h.