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

MoveIt sends commands to a controller via a handle that satisfies this interface. More...

#include <controller_manager.h>

Inheritance diagram for moveit_controller_manager::MoveItControllerHandle:
Inheritance graph
[legend]

Public Member Functions

 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

std::string name_
 

Detailed Description

MoveIt sends commands to a controller via a handle that satisfies this interface.

Definition at line 105 of file controller_manager.h.

Constructor & Destructor Documentation

◆ MoveItControllerHandle()

moveit_controller_manager::MoveItControllerHandle::MoveItControllerHandle ( const std::string &  name)
inline

Each controller has a name. The handle is initialized with that name.

Definition at line 109 of file controller_manager.h.

◆ ~MoveItControllerHandle()

virtual moveit_controller_manager::MoveItControllerHandle::~MoveItControllerHandle ( )
inlinevirtual

Definition at line 113 of file controller_manager.h.

Member Function Documentation

◆ cancelExecution()

virtual bool moveit_controller_manager::MoveItControllerHandle::cancelExecution ( )
pure virtual

◆ getLastExecutionStatus()

virtual ExecutionStatus moveit_controller_manager::MoveItControllerHandle::getLastExecutionStatus ( )
pure virtual

◆ getName()

const std::string& moveit_controller_manager::MoveItControllerHandle::getName ( ) const
inline

Get the name of the controller this handle can send commands to.

Definition at line 118 of file controller_manager.h.

◆ sendTrajectory()

virtual bool moveit_controller_manager::MoveItControllerHandle::sendTrajectory ( const moveit_msgs::msg::RobotTrajectory &  trajectory)
pure virtual

Send a trajectory to the controller.

The controller is expected to execute the trajectory, but this function call should not block. Blocking is achievable by calling waitForExecution(). Return false when the controller cannot accept the trajectory.

Implemented in moveit_simple_controller_manager::GripperControllerHandle, moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle, moveit_simple_controller_manager::EmptyControllerHandle, and test_moveit_controller_manager::TestMoveItControllerHandle.

◆ waitForExecution()

virtual bool moveit_controller_manager::MoveItControllerHandle::waitForExecution ( const rclcpp::Duration &  timeout = rclcpp::Duration::from_nanoseconds(-1))
pure virtual

Wait for the current execution to complete, or until the timeout is reached.

Return true if the execution is complete (whether successful or not). Return false if timeout was reached. If timeout is -1 (default argument), wait until the execution is complete (no timeout).

Implemented in moveit_simple_controller_manager::ActionBasedControllerHandle< T >, moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::FollowJointTrajectory >, moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::GripperCommand >, test_moveit_controller_manager::TestMoveItControllerHandle, and moveit_simple_controller_manager::EmptyControllerHandle.

Member Data Documentation

◆ name_

std::string moveit_controller_manager::MoveItControllerHandle::name_
protected

Definition at line 147 of file controller_manager.h.


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