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.h>
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. More... | |
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. More... | |
bool | waitForExecution (const rclcpp::Duration &timeout=rclcpp::Duration::from_seconds(-1.0)) override |
Blocks waiting for the action result to be received. More... | |
moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () override |
Return the execution status of the last trajectory sent to the controller. More... | |
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. More... | |
virtual | ~MoveItControllerHandle () |
const std::string & | getName () const |
Get the name of the controller this handle can send commands to. More... | |
virtual bool | sendTrajectory (const moveit_msgs::msg::RobotTrajectory &trajectory)=0 |
Send a trajectory to the controller. More... | |
Protected Member Functions | |
bool | isConnected () const |
Check if the controller's action server is ready to receive action goals. More... | |
std::string | getActionName () const |
Get the full name of the action using the action namespace and base name. More... | |
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. More... | |
Protected Attributes | |
const rclcpp::Node::SharedPtr | node_ |
A pointer to the node, required to read parameters and get the time. More... | |
moveit_controller_manager::ExecutionStatus | last_exec_ |
Status after last trajectory execution. More... | |
bool | done_ |
Indicates whether the controller handle is done executing its current trajectory. More... | |
std::string | namespace_ |
The controller namespace. The controller action server's topics will map to name/ns/goal, name/ns/result, etc. More... | |
std::vector< std::string > | joints_ |
The joints controlled by this controller. More... | |
rclcpp_action::Client< T >::SharedPtr | controller_action_client_ |
Action client to send trajectories to the controller's action server. More... | |
rclcpp_action::ClientGoalHandle< T >::SharedPtr | current_goal_ |
Current goal that has been sent to the action server. More... | |
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.h.
|
inline |
Definition at line 82 of file action_based_controller_handle.h.
|
inlineoverridevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 175 of file action_based_controller_handle.h.
|
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.h.
|
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 217 of file action_based_controller_handle.h.
|
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.h.
|
inlineoverridevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 180 of file action_based_controller_handle.h.
|
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.h.
|
inlineprotected |
Check if the controller's action server is ready to receive action goals.
Definition at line 195 of file action_based_controller_handle.h.
|
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.h.
|
protected |
Action client to send trajectories to the controller's action server.
Definition at line 256 of file action_based_controller_handle.h.
|
protected |
Current goal that has been sent to the action server.
Definition at line 261 of file action_based_controller_handle.h.
|
protected |
Indicates whether the controller handle is done executing its current trajectory.
Definition at line 241 of file action_based_controller_handle.h.
|
protected |
The joints controlled by this controller.
Definition at line 251 of file action_based_controller_handle.h.
|
protected |
Status after last trajectory execution.
Definition at line 236 of file action_based_controller_handle.h.
|
protected |
The controller namespace. The controller action server's topics will map to name/ns/goal, name/ns/result, etc.
Definition at line 246 of file action_based_controller_handle.h.
|
protected |
A pointer to the node, required to read parameters and get the time.
Definition at line 189 of file action_based_controller_handle.h.