moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
MoveIt sends commands to a controller via a handle that satisfies this interface. More...
#include <controller_manager.h>
Public Member Functions | |
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. | |
virtual bool | cancelExecution ()=0 |
Cancel the execution of any motion using this controller. | |
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. | |
virtual ExecutionStatus | getLastExecutionStatus ()=0 |
Return the execution status of the last trajectory sent to the controller. | |
Protected Attributes | |
std::string | name_ |
MoveIt sends commands to a controller via a handle that satisfies this interface.
Definition at line 105 of file controller_manager.h.
|
inline |
Each controller has a name. The handle is initialized with that name.
Definition at line 109 of file controller_manager.h.
|
inlinevirtual |
Definition at line 113 of file controller_manager.h.
|
pure virtual |
Cancel the execution of any motion using this controller.
Report false if canceling is not possible. If there is no execution in progress, this function is a no-op and returns true.
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 >, moveit_simple_controller_manager::EmptyControllerHandle, and test_moveit_controller_manager::TestMoveItControllerHandle.
|
pure virtual |
Return the execution status of the last trajectory sent to the controller.
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 >, moveit_simple_controller_manager::EmptyControllerHandle, and test_moveit_controller_manager::TestMoveItControllerHandle.
|
inline |
Get the name of the controller this handle can send commands to.
Definition at line 118 of file controller_manager.h.
|
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 test_moveit_controller_manager::TestMoveItControllerHandle, moveit_simple_controller_manager::EmptyControllerHandle, moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle, and moveit_simple_controller_manager::GripperControllerHandle.
|
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::EmptyControllerHandle, test_moveit_controller_manager::TestMoveItControllerHandle, moveit_simple_controller_manager::ActionBasedControllerHandle< T >, moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::FollowJointTrajectory >, and moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::GripperCommand >.
|
protected |
Definition at line 147 of file controller_manager.h.