moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
moveit_simple_controller_manager::EmptyControllerHandle Class Reference

#include <empty_controller_handle.h>

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

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.
 
bool cancelExecution () override
 Cancel the execution of any motion using this controller.
 
bool waitForExecution (const rclcpp::Duration &) override
 Function called when the TrajectoryExecutionManager waits for a trajectory to finish.
 
moveit_controller_manager::ExecutionStatus getLastExecutionStatus () override
 Gets the last trajectory execution status.
 
- 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.
 
virtual ~MoveItControllerHandle ()
 
const std::string & getName () const
 Get the name of the controller this handle can send commands to.
 

Additional Inherited Members

- Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle
std::string name_
 

Detailed Description

Definition at line 47 of file empty_controller_handle.h.

Constructor & Destructor Documentation

◆ EmptyControllerHandle()

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

Definition at line 51 of file empty_controller_handle.h.

Member Function Documentation

◆ cancelExecution()

bool moveit_simple_controller_manager::EmptyControllerHandle::cancelExecution ( )
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.

◆ getLastExecutionStatus()

moveit_controller_manager::ExecutionStatus moveit_simple_controller_manager::EmptyControllerHandle::getLastExecutionStatus ( )
inlineoverridevirtual

Gets the last trajectory execution status.

Returns
Always returns ExecutionStatus::FAILED.

Implements moveit_controller_manager::MoveItControllerHandle.

Definition at line 80 of file empty_controller_handle.h.

◆ sendTrajectory()

bool moveit_simple_controller_manager::EmptyControllerHandle::sendTrajectory ( const moveit_msgs::msg::RobotTrajectory &  trajectory)
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.

◆ waitForExecution()

bool moveit_simple_controller_manager::EmptyControllerHandle::waitForExecution ( const rclcpp::Duration &  )
inlineoverridevirtual

Function called when the TrajectoryExecutionManager waits for a trajectory to finish.

Returns
Always returns true because a trajectory is never in progress.

Implements moveit_controller_manager::MoveItControllerHandle.

Definition at line 71 of file empty_controller_handle.h.


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