|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Base class for controller handles that interact with a controller through a ROS action server. More...
#include <action_based_controller_handle.hpp>


Public Member Functions | |
| ActionBasedControllerHandle (const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const std::string &logger_name) | |
| bool | cancelExecution () override |
| Cancels trajectory execution by triggering the controller action server's cancellation callback. | |
| 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. | |
| bool | waitForExecution (const rclcpp::Duration &timeout=rclcpp::Duration::from_seconds(-1.0)) override |
| Blocks waiting for the action result to be received. | |
| moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () override |
| Return the execution status of the last trajectory sent to the controller. | |
| void | addJoint (const std::string &name) override |
| void | getJoints (std::vector< std::string > &joints) override |
Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase | |
| ActionBasedControllerHandleBase (const std::string &name, const std::string &logger_name) | |
Public Member Functions inherited from moveit_controller_manager::MoveItControllerHandle | |
| MoveItControllerHandle (const std::string &name) | |
| Each controller has a name. The handle is initialized with that name. | |
| virtual | ~MoveItControllerHandle () |
| const std::string & | getName () const |
| Get the name of the controller this handle can send commands to. | |
| virtual bool | sendTrajectory (const moveit_msgs::msg::RobotTrajectory &trajectory)=0 |
| Send a trajectory to the controller. | |
Protected Member Functions | |
| bool | isConnected () const |
| Check if the controller's action server is ready to receive action goals. | |
| std::string | getActionName () const |
| Get the full name of the action using the action namespace and base name. | |
| 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. | |
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. | |
| rclcpp_action::Client< T >::SharedPtr | controller_action_client_ |
| Action client to send trajectories to the controller's action server. | |
| rclcpp_action::ClientGoalHandle< T >::SharedPtr | current_goal_ |
| Current goal that has been sent to the action server. | |
Protected Attributes inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase | |
| const rclcpp::Logger | logger_ |
Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
| std::string | name_ |
Base class for controller handles that interact with a controller through a ROS action server.
Definition at line 79 of file action_based_controller_handle.hpp.
|
inline |
Definition at line 82 of file action_based_controller_handle.hpp.

|
inlineoverridevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 175 of file action_based_controller_handle.hpp.
|
inlineoverridevirtual |
Cancels trajectory execution by triggering the controller action server's cancellation callback.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 96 of file action_based_controller_handle.hpp.
|
pure virtual |
Callback function to call when the result is received from the controller action server.
| wrapped_result |

|
inlineprotected |
Indicate that the controller handle is done executing the trajectory and set the controller manager handle's ExecutionStatus based on the received action ResultCode.
| rclcpp_action::ResultCode | to convert to moveit_controller_manager::ExecutionStatus. |
Definition at line 221 of file action_based_controller_handle.hpp.
|
inlineprotected |
Get the full name of the action using the action namespace and base name.
Definition at line 204 of file action_based_controller_handle.hpp.

|
inlineoverridevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 180 of file action_based_controller_handle.hpp.
|
inlineoverridevirtual |
Return the execution status of the last trajectory sent to the controller.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 170 of file action_based_controller_handle.hpp.
|
inlineprotected |
Check if the controller's action server is ready to receive action goals.
Definition at line 195 of file action_based_controller_handle.hpp.
|
inlineoverridevirtual |
Blocks waiting for the action result to be received.
| timeout | Duration to wait for a result before failing. Default value indicates no timeout. |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 127 of file action_based_controller_handle.hpp.

|
protected |
Action client to send trajectories to the controller's action server.
Definition at line 270 of file action_based_controller_handle.hpp.
|
protected |
Current goal that has been sent to the action server.
Definition at line 275 of file action_based_controller_handle.hpp.
|
protected |
Indicates whether the controller handle is done executing its current trajectory.
Definition at line 255 of file action_based_controller_handle.hpp.
|
protected |
The joints controlled by this controller.
Definition at line 265 of file action_based_controller_handle.hpp.
|
protected |
Status after last trajectory execution.
Definition at line 250 of file action_based_controller_handle.hpp.
|
protected |
The controller namespace. The controller action server's topics will map to name/ns/goal, name/ns/result, etc.
Definition at line 260 of file action_based_controller_handle.hpp.
|
protected |
A pointer to the node, required to read parameters and get the time.
Definition at line 189 of file action_based_controller_handle.hpp.