Hardware interface for forwarding trajectories. More...
#include <trajectory_interface.h>
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... | |
![]() | |
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_ |
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:
TrajectoryType | Distinguish between joint-based and Cartesian trajectories |
FeedbackType | The type of feedback for the trajectory used. |
Definition at line 104 of file trajectory_interface.h.
|
inline |
Get trajectory feedback.
This can be used by PassThroughControllers to continuously poll trajectory feedback from the hardware interface.
Definition at line 205 of file trajectory_interface.h.
|
inline |
Get the joint names (resources) associated with this interface.
Definition at line 215 of file trajectory_interface.h.
|
inline |
Register a RobotHW-side callback for canceling requests.
f | The function to be called for canceling trajectory execution |
Definition at line 126 of file trajectory_interface.h.
|
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.
f | The function to be called when trajectory execution is done |
Definition at line 139 of file trajectory_interface.h.
|
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.
f | The function to be called for starting trajectory execution |
Definition at line 116 of file trajectory_interface.h.
|
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.
|
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.
state | The final state after trajectory execution |
Definition at line 178 of file trajectory_interface.h.
|
inline |
Set trajectory feedback for PassThroughControllers.
This should be used by the RobotHW to provide continuous feedback on trajectory execution for the PassThroughControllers.
feedback | The feedback content to write to the interface |
Definition at line 192 of file trajectory_interface.h.
|
inline |
Definition at line 312 of file trajectory_interface.h.
|
inline |
Definition at line 247 of file trajectory_interface.h.
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.
command | The new trajectory |
|
inline |
Associate resources with this interface.
\Note: Call this inside the PassThroughController's constructor to manage resource conflicts with other ROS controllers.
resources | A list of resource names |
Definition at line 228 of file trajectory_interface.h.
|
private |
Definition at line 239 of file trajectory_interface.h.
|
private |
Definition at line 240 of file trajectory_interface.h.
|
private |
Definition at line 241 of file trajectory_interface.h.
|
private |
Definition at line 238 of file trajectory_interface.h.
|
private |
Definition at line 242 of file trajectory_interface.h.