Public Member Functions | Protected Member Functions | Static Protected Member Functions | Private Types | Private Attributes | List of all members
joint_trajectory_controller::TrajectoryBuilder< SegmentImpl > Class Template Referenceabstract

Base class for classes used to construct diffent trajectory types. More...

#include <trajectory_builder.h>

Inheritance diagram for joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >:
Inheritance graph
[legend]

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::Timestart_time_ {boost::none}
 

Detailed Description

template<class SegmentImpl>
class joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >

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:

builder.setStartTime(start_time);
builder.setGoalHandle(goal_handle);
builder.buildTrajectory(trajectory);

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.

Member Typedef Documentation

◆ RealtimeGoalHandle

template<class SegmentImpl>
using joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<control_msgs::FollowJointTrajectoryAction>
private

Definition at line 77 of file trajectory_builder.h.

◆ RealtimeGoalHandlePtr

Definition at line 78 of file trajectory_builder.h.

◆ Segment

template<class SegmentImpl>
using joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::Segment = JointTrajectorySegment<SegmentImpl>
private

Definition at line 73 of file trajectory_builder.h.

◆ Trajectory

template<class SegmentImpl>
using joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::Trajectory = std::vector<TrajectoryPerJoint>
private

Definition at line 75 of file trajectory_builder.h.

◆ TrajectoryPerJoint

template<class SegmentImpl>
using joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::TrajectoryPerJoint = std::vector<Segment>
private

Definition at line 74 of file trajectory_builder.h.

Constructor & Destructor Documentation

◆ ~TrajectoryBuilder()

template<class SegmentImpl>
virtual joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::~TrajectoryBuilder ( )
virtualdefault

Virtual destructor because this class is a base class.

Member Function Documentation

◆ buildTrajectory()

template<class SegmentImpl>
virtual bool joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::buildTrajectory ( Trajectory trajectory)
pure virtual

Creates the type of trajectory described by the builder.

Parameters
trajectory[Out] Trajectory which has to be build.

Implemented in joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >, and joint_trajectory_controller::HoldTrajectoryBuilder< SegmentImpl, HardwareInterface >.

◆ createDefaultGoalHandle()

template<class SegmentImpl >
TrajectoryBuilder< SegmentImpl >::RealtimeGoalHandlePtr joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::createDefaultGoalHandle ( )
inlinestaticprotected

Definition at line 165 of file trajectory_builder.h.

◆ createGoalHandlePtr()

template<class SegmentImpl >
TrajectoryBuilder< SegmentImpl >::RealtimeGoalHandlePtr joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::createGoalHandlePtr ( ) const
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.

◆ getStartTime()

template<class SegmentImpl >
const boost::optional< typename TrajectoryBuilder< SegmentImpl >::Segment::Time > & joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::getStartTime ( ) const
inlineprotected

Return the set start time.

Definition at line 146 of file trajectory_builder.h.

◆ isTrajectoryValid()

template<class SegmentImpl >
bool joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::isTrajectoryValid ( const Trajectory trajectory,
const unsigned int  expected_number_of_joints,
const unsigned int  expected_number_of_segments 
)
staticprotected

Check if the elements of a given trajectory are sized properly.

Parameters
trajectory
expected_number_of_jointsThe count of TrajectoryPerJoint in trajectory has to match the number of joints.
expected_number_of_segmentsEach TrajectoryPerJoint in trajectory has to contain this number of segments.

Definition at line 178 of file trajectory_builder.h.

◆ reset()

template<class SegmentImpl >
void joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::reset ( )
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.

◆ setGoalHandle()

template<class SegmentImpl>
TrajectoryBuilder< SegmentImpl > * joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::setGoalHandle ( RealtimeGoalHandlePtr goal_handle)
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.

◆ setStartTime()

template<class SegmentImpl>
TrajectoryBuilder< SegmentImpl > * joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::setStartTime ( const typename Segment::Time start_time)
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.

Member Data Documentation

◆ goal_handle_

template<class SegmentImpl>
boost::optional<RealtimeGoalHandlePtr&> joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::goal_handle_ {boost::none}
private

Definition at line 134 of file trajectory_builder.h.

◆ start_time_

template<class SegmentImpl>
boost::optional<typename Segment::Time> joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >::start_time_ {boost::none}
private

Definition at line 131 of file trajectory_builder.h.


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


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Feb 3 2023 03:19:15