moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <gripper_controller_handle.h>
Public Member Functions | |
GripperControllerHandle (const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const double max_effort=0.0) | |
bool | sendTrajectory (const moveit_msgs::msg::RobotTrajectory &trajectory) override |
Send a trajectory to the controller. More... | |
void | setCommandJoint (const std::string &name) |
void | addCommandJoint (const std::string &name) |
void | allowFailure (bool allow) |
void | setParallelJawGripper (const std::string &left, const std::string &right) |
Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::GripperCommand > | |
ActionBasedControllerHandle (const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const std::string &logger_name) | |
bool | cancelExecution () override |
Cancels trajectory execution by triggering the controller action server's cancellation callback. More... | |
virtual void | controllerDoneCallback (const typename rclcpp_action::ClientGoalHandle< control_msgs::action::GripperCommand >::WrappedResult &wrapped_result)=0 |
Callback function to call when the result is received from the controller action server. More... | |
bool | waitForExecution (const rclcpp::Duration &timeout=rclcpp::Duration::from_seconds(-1.0)) override |
Blocks waiting for the action result to be received. More... | |
moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () override |
Return the execution status of the last trajectory sent to the controller. More... | |
void | addJoint (const std::string &name) override |
void | getJoints (std::vector< std::string > &joints) override |
Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase | |
ActionBasedControllerHandleBase (const std::string &name, const std::string &logger_name) | |
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 Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::GripperCommand > | |
bool | isConnected () const |
Check if the controller's action server is ready to receive action goals. More... | |
std::string | getActionName () const |
Get the full name of the action using the action namespace and base name. More... | |
void | finishControllerExecution (const rclcpp_action::ResultCode &state) |
Indicate that the controller handle is done executing the trajectory and set the controller manager handle's ExecutionStatus based on the received action ResultCode. More... | |
Protected Attributes inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::action::GripperCommand > | |
const rclcpp::Node::SharedPtr | node_ |
A pointer to the node, required to read parameters and get the time. More... | |
moveit_controller_manager::ExecutionStatus | last_exec_ |
Status after last trajectory execution. More... | |
bool | done_ |
Indicates whether the controller handle is done executing its current trajectory. More... | |
std::string | namespace_ |
The controller namespace. The controller action server's topics will map to name/ns/goal, name/ns/result, etc. More... | |
std::vector< std::string > | joints_ |
The joints controlled by this controller. More... | |
rclcpp_action::Client< control_msgs::action::GripperCommand >::SharedPtr | controller_action_client_ |
Action client to send trajectories to the controller's action server. More... | |
rclcpp_action::ClientGoalHandle< control_msgs::action::GripperCommand >::SharedPtr | current_goal_ |
Current goal that has been sent to the action server. More... | |
Protected Attributes inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase | |
const rclcpp::Logger | LOGGER |
Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
std::string | name_ |
Definition at line 50 of file gripper_controller_handle.h.
|
inline |
Definition at line 54 of file gripper_controller_handle.h.
|
inline |
Definition at line 175 of file gripper_controller_handle.h.
|
inline |
Definition at line 180 of file gripper_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 64 of file gripper_controller_handle.h.
|
inline |
Definition at line 169 of file gripper_controller_handle.h.
|
inline |
Definition at line 185 of file gripper_controller_handle.h.