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

#include <action_based_controller_handle.h>

Inheritance diagram for moveit_simple_controller_manager::ActionBasedControllerHandleBase:
Inheritance graph
[legend]
Collaboration diagram for moveit_simple_controller_manager::ActionBasedControllerHandleBase:
Collaboration graph
[legend]

Public Member Functions

 ActionBasedControllerHandleBase (const std::string &name, const std::string &logger_name)
 
virtual void addJoint (const std::string &name)=0
 
virtual void getJoints (std::vector< std::string > &joints)=0
 
- 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...
 
virtual bool cancelExecution ()=0
 Cancel the execution of any motion using this controller. More...
 
virtual bool waitForExecution (const rclcpp::Duration &timeout=rclcpp::Duration::from_nanoseconds(-1))=0
 Wait for the current execution to complete, or until the timeout is reached. More...
 
virtual ExecutionStatus getLastExecutionStatus ()=0
 Return the execution status of the last trajectory sent to the controller. More...
 

Protected Attributes

const rclcpp::Logger logger_
 
- Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle
std::string name_
 

Detailed Description

Definition at line 53 of file action_based_controller_handle.h.

Constructor & Destructor Documentation

◆ ActionBasedControllerHandleBase()

moveit_simple_controller_manager::ActionBasedControllerHandleBase::ActionBasedControllerHandleBase ( const std::string &  name,
const std::string &  logger_name 
)
inline

Definition at line 56 of file action_based_controller_handle.h.

Member Function Documentation

◆ addJoint()

virtual void moveit_simple_controller_manager::ActionBasedControllerHandleBase::addJoint ( const std::string &  name)
pure virtual

◆ getJoints()

virtual void moveit_simple_controller_manager::ActionBasedControllerHandleBase::getJoints ( std::vector< std::string > &  joints)
pure virtual

Member Data Documentation

◆ logger_

const rclcpp::Logger moveit_simple_controller_manager::ActionBasedControllerHandleBase::logger_
protected

Definition at line 69 of file action_based_controller_handle.h.


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