moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <empty_controller_handle.h>
Public Member Functions | |
EmptyControllerHandle (const std::string &name, const std::string &logger_name) | |
bool | sendTrajectory (const moveit_msgs::msg::RobotTrajectory &trajectory) override |
Send a trajectory to the controller. More... | |
bool | cancelExecution () override |
Cancel the execution of any motion using this controller. More... | |
bool | waitForExecution (const rclcpp::Duration &) override |
Function called when the TrajectoryExecutionManager waits for a trajectory to finish. More... | |
moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () override |
Gets the last trajectory execution status. More... | |
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... | |
Additional Inherited Members | |
Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
std::string | name_ |
Definition at line 47 of file empty_controller_handle.h.
|
inline |
Definition at line 51 of file empty_controller_handle.h.
|
inlineoverridevirtual |
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.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 62 of file empty_controller_handle.h.
|
inlineoverridevirtual |
Gets the last trajectory execution status.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 80 of file empty_controller_handle.h.
|
inlineoverridevirtual |
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.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 56 of file empty_controller_handle.h.
|
inlineoverridevirtual |
Function called when the TrajectoryExecutionManager waits for a trajectory to finish.
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 71 of file empty_controller_handle.h.