Public Member Functions | Private Types | Private Attributes | List of all members
joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl > Class Template Reference

Builder creating a trajectory stopping the robot. More...

#include <stop_trajectory_builder.h>

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

Public Member Functions

bool buildTrajectory (Trajectory *hold_traj) override
 Creates a trajectory which reaches the settle position in a fixed time. More...
 
 StopTrajectoryBuilder (const typename Segment::Time &stop_traj_duration, const typename Segment::State &hold_state)
 
- Public Member Functions inherited from joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >
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...
 

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

Segment::State hold_end_state_ {typename Segment::State(1)}
 
Segment::State hold_start_state_ {typename Segment::State(1)}
 
const Segment::Statehold_state_
 Stores a reference to the state where the stop motion shall start. More...
 
const Segment::Time stop_traj_duration_
 

Additional Inherited Members

- Protected Member Functions inherited from joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >
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 inherited from joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >
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...
 

Detailed Description

template<class SegmentImpl>
class joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >

Builder creating a trajectory stopping the robot.

Definition at line 42 of file stop_trajectory_builder.h.

Member Typedef Documentation

◆ RealtimeGoalHandle

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

Definition at line 49 of file stop_trajectory_builder.h.

◆ RealtimeGoalHandlePtr

Definition at line 50 of file stop_trajectory_builder.h.

◆ Segment

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

Definition at line 45 of file stop_trajectory_builder.h.

◆ Trajectory

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

Definition at line 47 of file stop_trajectory_builder.h.

◆ TrajectoryPerJoint

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

Definition at line 46 of file stop_trajectory_builder.h.

Constructor & Destructor Documentation

◆ StopTrajectoryBuilder()

template<class SegmentImpl >
joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::StopTrajectoryBuilder ( const typename Segment::Time stop_traj_duration,
const typename Segment::State hold_state 
)
Parameters
stop_traj_durationDesired time span [seconds] in which the settle position has to be reached.
hold_stateReference to the state where the stop motion shall start.
Note
If there is a time delay in the system it is better to calculate the stop trajectory starting from the desired position. Otherwise there would be a jerk in the motion.

Definition at line 90 of file stop_trajectory_builder.h.

Member Function Documentation

◆ buildTrajectory()

template<class SegmentImpl >
bool joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::buildTrajectory ( Trajectory hold_traj)
overridevirtual

Creates a trajectory which reaches the settle position in a fixed time.

The calculation is done as follows:

  • Create segment that goes from current (pos,vel) to (pos,-vel) in 2x the desired stop time.
  • Assuming segment symmetry, sample segment at its midpoint (desired stop time). It should have zero velocity.
  • Create segment that goes from current state to above zero velocity state, in the desired time.
Note
The symmetry assumption from the second point above might not hold for all possible segment types.
Returns
true if the building of the stop trajectory succeeds, otherwise false.

Implements joint_trajectory_controller::TrajectoryBuilder< SegmentImpl >.

Definition at line 98 of file stop_trajectory_builder.h.

Member Data Documentation

◆ hold_end_state_

template<class SegmentImpl >
Segment::State joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::hold_end_state_ {typename Segment::State(1)}
private

Definition at line 86 of file stop_trajectory_builder.h.

◆ hold_start_state_

template<class SegmentImpl >
Segment::State joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::hold_start_state_ {typename Segment::State(1)}
private

Definition at line 85 of file stop_trajectory_builder.h.

◆ hold_state_

template<class SegmentImpl >
const Segment::State& joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::hold_state_
private

Stores a reference to the state where the stop motion shall start.

Definition at line 82 of file stop_trajectory_builder.h.

◆ stop_traj_duration_

template<class SegmentImpl >
const Segment::Time joint_trajectory_controller::StopTrajectoryBuilder< SegmentImpl >::stop_traj_duration_
private

Definition at line 80 of file stop_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