moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit_simple_controller_manager::ActionBasedControllerHandle< T > Class Template Referenceabstract

Base class for controller handles that interact with a controller through a ROS action server. More...

#include <action_based_controller_handle.h>

Inheritance diagram for moveit_simple_controller_manager::ActionBasedControllerHandle< T >:
Inheritance graph
[legend]
Collaboration diagram for moveit_simple_controller_manager::ActionBasedControllerHandle< T >:
Collaboration graph
[legend]

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_
 

Detailed Description

template<typename T>
class moveit_simple_controller_manager::ActionBasedControllerHandle< T >

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.

Constructor & Destructor Documentation

◆ ActionBasedControllerHandle()

template<typename T >
moveit_simple_controller_manager::ActionBasedControllerHandle< T >::ActionBasedControllerHandle ( const rclcpp::Node::SharedPtr &  node,
const std::string &  name,
const std::string &  ns,
const std::string &  logger_name 
)
inline

Definition at line 82 of file action_based_controller_handle.h.

Member Function Documentation

◆ addJoint()

template<typename T >
void moveit_simple_controller_manager::ActionBasedControllerHandle< T >::addJoint ( const std::string &  name)
inlineoverridevirtual

◆ cancelExecution()

template<typename T >
bool moveit_simple_controller_manager::ActionBasedControllerHandle< T >::cancelExecution ( )
inlineoverridevirtual

Cancels trajectory execution by triggering the controller action server's cancellation callback.

Returns
True if cancellation was accepted, false if cancellation failed.

Implements moveit_controller_manager::MoveItControllerHandle.

Definition at line 96 of file action_based_controller_handle.h.

◆ controllerDoneCallback()

template<typename T >
virtual void moveit_simple_controller_manager::ActionBasedControllerHandle< T >::controllerDoneCallback ( const typename rclcpp_action::ClientGoalHandle< T >::WrappedResult &  wrapped_result)
pure virtual

Callback function to call when the result is received from the controller action server.

Parameters
wrapped_result

◆ finishControllerExecution()

template<typename T >
void moveit_simple_controller_manager::ActionBasedControllerHandle< T >::finishControllerExecution ( const rclcpp_action::ResultCode &  state)
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.

Parameters
rclcpp_action::ResultCodeto convert to moveit_controller_manager::ExecutionStatus.

Definition at line 221 of file action_based_controller_handle.h.

◆ getActionName()

template<typename T >
std::string moveit_simple_controller_manager::ActionBasedControllerHandle< T >::getActionName ( ) const
inlineprotected

Get the full name of the action using the action namespace and base name.

Returns
The action name.

Definition at line 204 of file action_based_controller_handle.h.

◆ getJoints()

template<typename T >
void moveit_simple_controller_manager::ActionBasedControllerHandle< T >::getJoints ( std::vector< std::string > &  joints)
inlineoverridevirtual

◆ getLastExecutionStatus()

template<typename T >
moveit_controller_manager::ExecutionStatus moveit_simple_controller_manager::ActionBasedControllerHandle< T >::getLastExecutionStatus ( )
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.

◆ isConnected()

template<typename T >
bool moveit_simple_controller_manager::ActionBasedControllerHandle< T >::isConnected ( ) const
inlineprotected

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.

Definition at line 195 of file action_based_controller_handle.h.

◆ waitForExecution()

template<typename T >
bool moveit_simple_controller_manager::ActionBasedControllerHandle< T >::waitForExecution ( const rclcpp::Duration &  timeout = rclcpp::Duration::from_seconds(-1.0))
inlineoverridevirtual

Blocks waiting for the action result to be received.

Parameters
timeoutDuration to wait for a result before failing. Default value indicates no timeout.
Returns
True if a result was received, false on timeout.

Implements moveit_controller_manager::MoveItControllerHandle.

Definition at line 127 of file action_based_controller_handle.h.

Member Data Documentation

◆ controller_action_client_

template<typename T >
rclcpp_action::Client<T>::SharedPtr moveit_simple_controller_manager::ActionBasedControllerHandle< T >::controller_action_client_
protected

Action client to send trajectories to the controller's action server.

Definition at line 270 of file action_based_controller_handle.h.

◆ current_goal_

template<typename T >
rclcpp_action::ClientGoalHandle<T>::SharedPtr moveit_simple_controller_manager::ActionBasedControllerHandle< T >::current_goal_
protected

Current goal that has been sent to the action server.

Definition at line 275 of file action_based_controller_handle.h.

◆ done_

template<typename T >
bool moveit_simple_controller_manager::ActionBasedControllerHandle< T >::done_
protected

Indicates whether the controller handle is done executing its current trajectory.

Definition at line 255 of file action_based_controller_handle.h.

◆ joints_

template<typename T >
std::vector<std::string> moveit_simple_controller_manager::ActionBasedControllerHandle< T >::joints_
protected

The joints controlled by this controller.

Definition at line 265 of file action_based_controller_handle.h.

◆ last_exec_

Status after last trajectory execution.

Definition at line 250 of file action_based_controller_handle.h.

◆ namespace_

template<typename T >
std::string moveit_simple_controller_manager::ActionBasedControllerHandle< T >::namespace_
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.h.

◆ node_

template<typename T >
const rclcpp::Node::SharedPtr moveit_simple_controller_manager::ActionBasedControllerHandle< T >::node_
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.


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