Public Member Functions | Private Attributes | List of all members
hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType > Class Template Reference

Hardware interface for forwarding trajectories. More...

#include <trajectory_interface.h>

Inheritance diagram for hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >:
Inheritance graph
[legend]

Public Member Functions

FeedbackType getFeedback () const
 Get trajectory feedback. More...
 
std::vector< std::string > getJointNames () const
 Get the joint names (resources) associated with this interface. More...
 
void registerCancelCallback (std::function< void()> f)
 Register a RobotHW-side callback for canceling requests. More...
 
void registerDoneCallback (std::function< void(const ExecutionState &)> f)
 Register a Controller-side callback for done signals from the hardware. More...
 
void registerGoalCallback (std::function< void(const TrajectoryType &)> f)
 Register a RobotHW-side callback for new trajectory execution. More...
 
void setCancel ()
 Cancel the current trajectory execution. More...
 
void setDone (const ExecutionState &state)
 RobotHW-side method to mark the execution of a trajectory done. More...
 
void setFeedback (FeedbackType feedback)
 Set trajectory feedback for PassThroughControllers. More...
 
bool setGoal (CartesianTrajectory goal)
 
bool setGoal (JointTrajectory goal)
 
bool setGoal (TrajectoryType goal)
 Start the forwarding of new trajectories. More...
 
void setResources (std::vector< std::string > resources)
 Associate resources with this interface. More...
 
- Public Member Functions inherited from hardware_interface::HardwareInterface
virtual void claim (std::string resource)
 
void clearClaims ()
 
std::set< std::string > getClaims () const
 
virtual ~HardwareInterface ()=default
 

Private Attributes

std::function< void()> cancel_callback_
 
std::function< void(const ExecutionState &)> done_callback_
 
FeedbackType feedback_
 
std::function< void(const TrajectoryType &)> goal_callback_
 
std::vector< std::string > joint_names_
 

Detailed Description

template<class TrajectoryType, class FeedbackType>
class hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >

Hardware interface for forwarding trajectories.

This special hardware interface is primarily used by PassThroughControllers, which forward full trajectories to robots for interpolation. In contrast to other hardware interfaces, this interface does not provide the usual handle mechanism. Instead, callbacks and respective setter methods allow to implement control flow during trajectory execution. Resources need to be claimed in the forwarding controller's constructor with setResources().

The intended usage is as follows:

Template Parameters
TrajectoryTypeDistinguish between joint-based and Cartesian trajectories
FeedbackTypeThe type of feedback for the trajectory used.

Definition at line 104 of file trajectory_interface.h.

Member Function Documentation

◆ getFeedback()

template<class TrajectoryType , class FeedbackType >
FeedbackType hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::getFeedback ( ) const
inline

Get trajectory feedback.

This can be used by PassThroughControllers to continuously poll trajectory feedback from the hardware interface.

Returns
The most recent feedback on the current trajectory execution

Definition at line 205 of file trajectory_interface.h.

◆ getJointNames()

template<class TrajectoryType , class FeedbackType >
std::vector<std::string> hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::getJointNames ( ) const
inline

Get the joint names (resources) associated with this interface.

Returns
Joint names

Definition at line 215 of file trajectory_interface.h.

◆ registerCancelCallback()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::registerCancelCallback ( std::function< void()>  f)
inline

Register a RobotHW-side callback for canceling requests.

Parameters
fThe function to be called for canceling trajectory execution

Definition at line 126 of file trajectory_interface.h.

◆ registerDoneCallback()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::registerDoneCallback ( std::function< void(const ExecutionState &)>  f)
inline

Register a Controller-side callback for done signals from the hardware.

Use this mechanism in the PassThroughController for handling the ExecutionState of the forwarded trajectory.

Parameters
fThe function to be called when trajectory execution is done

Definition at line 139 of file trajectory_interface.h.

◆ registerGoalCallback()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::registerGoalCallback ( std::function< void(const TrajectoryType &)>  f)
inline

Register a RobotHW-side callback for new trajectory execution.

Callback for triggering execution start in the RobotHW. Use this callback mechanism to handle starting of trajectories on the robot vendor controller.

Parameters
fThe function to be called for starting trajectory execution

Definition at line 116 of file trajectory_interface.h.

◆ setCancel()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::setCancel ( )
inline

Cancel the current trajectory execution.

Controller-side method to cancel current trajectory execution on the robot.

Definition at line 162 of file trajectory_interface.h.

◆ setDone()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::setDone ( const ExecutionState state)
inline

RobotHW-side method to mark the execution of a trajectory done.

Call this function when done with a forwarded trajectory in your RobotHW or when unexpected interruptions occur. The PassThroughController will implement a callback to set appropriate result flags for the trajectory action clients.

Parameters
stateThe final state after trajectory execution

Definition at line 178 of file trajectory_interface.h.

◆ setFeedback()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::setFeedback ( FeedbackType  feedback)
inline

Set trajectory feedback for PassThroughControllers.

This should be used by the RobotHW to provide continuous feedback on trajectory execution for the PassThroughControllers.

Parameters
feedbackThe feedback content to write to the interface

Definition at line 192 of file trajectory_interface.h.

◆ setGoal() [1/3]

Definition at line 312 of file trajectory_interface.h.

◆ setGoal() [2/3]

Definition at line 247 of file trajectory_interface.h.

◆ setGoal() [3/3]

template<class TrajectoryType , class FeedbackType >
bool hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::setGoal ( TrajectoryType  goal)

Start the forwarding of new trajectories.

Controller-side method to send incoming trajectories to the RobotHW.

Note: The JointTrajectory type reorders the joints according to the given joint resource list.

Parameters
commandThe new trajectory
Returns
True if goal is feasible, false otherwise

◆ setResources()

template<class TrajectoryType , class FeedbackType >
void hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::setResources ( std::vector< std::string >  resources)
inline

Associate resources with this interface.

\Note: Call this inside the PassThroughController's constructor to manage resource conflicts with other ROS controllers.

Parameters
resourcesA list of resource names

Definition at line 228 of file trajectory_interface.h.

Member Data Documentation

◆ cancel_callback_

template<class TrajectoryType , class FeedbackType >
std::function<void()> hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::cancel_callback_
private

Definition at line 239 of file trajectory_interface.h.

◆ done_callback_

template<class TrajectoryType , class FeedbackType >
std::function<void(const ExecutionState&)> hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::done_callback_
private

Definition at line 240 of file trajectory_interface.h.

◆ feedback_

template<class TrajectoryType , class FeedbackType >
FeedbackType hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::feedback_
private

Definition at line 241 of file trajectory_interface.h.

◆ goal_callback_

template<class TrajectoryType , class FeedbackType >
std::function<void(const TrajectoryType&)> hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::goal_callback_
private

Definition at line 238 of file trajectory_interface.h.

◆ joint_names_

template<class TrajectoryType , class FeedbackType >
std::vector<std::string> hardware_interface::TrajectoryInterface< TrajectoryType, FeedbackType >::joint_names_
private

Definition at line 242 of file trajectory_interface.h.


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


pass_through_controllers
Author(s):
autogenerated on Tue Oct 15 2024 02:10:52