Class GripperActionController
Defined in File parallel_gripper_action_controller.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class GripperActionController : public controller_interface::ControllerInterface
Controller for executing a
ParallelGripperCommand
action.- Template Parameters:
HardwareInterface – Controller hardware interface. Currently
hardware_interface::HW_IF_POSITION
andhardware_interface::HW_IF_EFFORT
are supported out-of-the-box.
Public Functions
-
GRIPPER_ACTION_CONTROLLER_PUBLIC GripperActionController()
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
command_interface_configuration This controller requires the position command interfaces for the controlled joints
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
Public Members
Protected Types
-
using GripperCommandAction = control_msgs::action::ParallelGripperCommand
-
using ActionServer = rclcpp_action::Server<GripperCommandAction>
-
using ActionServerPtr = ActionServer::SharedPtr
-
using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>
-
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<control_msgs::action::ParallelGripperCommand>
-
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>
-
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>
Protected Functions
-
void preempt_active_goal()
-
void set_hold_position()
-
void check_for_success(const rclcpp::Time &time, double error_position, double current_position, double current_velocity)
Check for success and publish appropriate result and feedback.
Protected Attributes
-
bool update_hold_position_
-
bool verbose_ = false
Hard coded verbose flag to help in debugging.
-
std::string name_
Controller name.
-
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_command_interface_
-
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> effort_interface_
-
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> speed_interface_
-
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> joint_position_state_interface_
-
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> joint_velocity_state_interface_
-
std::shared_ptr<ParamListener> param_listener_
-
Params params_
-
RealtimeGoalHandleBuffer rt_active_goal_
Container for the currently active action goal, if any.
-
control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_
-
rclcpp::Duration action_monitor_period_
-
ActionServerPtr action_server_
-
rclcpp::TimerBase::SharedPtr goal_handle_timer_
-
rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME)
Store stall time.
-
double computed_command_
Computed command.
-
struct Commands
Store position and max effort in struct to allow easier realtime buffer usage.