Template Class ActionBasedControllerHandle
Defined in File action_based_controller_handle.hpp
Inheritance Relationships
Base Type
public moveit_simple_controller_manager::ActionBasedControllerHandleBase
(Class ActionBasedControllerHandleBase)
Class Documentation
-
template<typename T>
class ActionBasedControllerHandle : public moveit_simple_controller_manager::ActionBasedControllerHandleBase Base class for controller handles that interact with a controller through a ROS action server.
Public Functions
-
inline bool cancelExecution() override
Cancels trajectory execution by triggering the controller action server’s cancellation callback.
- Returns:
True if cancellation was accepted, false if cancellation failed.
-
virtual void controllerDoneCallback(const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult &wrapped_result) = 0
Callback function to call when the result is received from the controller action server.
- Parameters:
wrapped_result –
-
inline bool waitForExecution(const rclcpp::Duration &timeout = rclcpp::Duration::from_seconds(-1.0)) override
Blocks waiting for the action result to be received.
- Parameters:
timeout – Duration to wait for a result before failing. Default value indicates no timeout.
- Returns:
True if a result was received, false on timeout.
-
inline moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
-
inline virtual void addJoint(const std::string &name) override
-
inline virtual void getJoints(std::vector<std::string> &joints) override
Protected Functions
-
inline bool isConnected() const
Check if the controller’s action server is ready to receive action goals.
- Returns:
True if the action server is ready, false if it is not ready or does not exist.
-
inline std::string getActionName() const
Get the full name of the action using the action namespace and base name.
- Returns:
The action name.
-
inline void finishControllerExecution(const rclcpp_action::ResultCode &state)
Indicate that the controller handle is done executing the trajectory and set the controller manager handle’s ExecutionStatus based on the received action ResultCode.
- Parameters:
rclcpp_action::ResultCode – to convert to moveit_controller_manager::ExecutionStatus.
Protected Attributes
-
const rclcpp::Node::SharedPtr node_
A pointer to the node, required to read parameters and get the time.
-
moveit_controller_manager::ExecutionStatus last_exec_
Status after last trajectory execution.
-
bool done_
Indicates whether the controller handle is done executing its current trajectory.
-
std::string namespace_
The controller namespace. The controller action server’s topics will map to name/ns/goal, name/ns/result, etc.
-
std::vector<std::string> joints_
The joints controlled by this controller.
-
inline bool cancelExecution() override