17#ifndef GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
18#define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
27#include "rclcpp/rclcpp.hpp"
30#include "control_msgs/action/gripper_command.hpp"
33#include "rclcpp_action/create_server.hpp"
36#include "controller_interface/controller_interface.hpp"
37#include "hardware_interface/loaned_command_interface.hpp"
38#include "hardware_interface/loaned_state_interface.hpp"
39#include "realtime_tools/realtime_buffer.hpp"
40#include "realtime_tools/realtime_server_goal_handle.hpp"
43#include "gripper_controllers/hardware_interface_adapter.hpp"
46#include "gripper_controllers/gripper_action_controller_parameters.hpp"
58template <const
char * HardwareInterface>
85 controller_interface::return_type
update(
86 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
88 controller_interface::CallbackReturn
on_init()
override;
90 controller_interface::CallbackReturn on_configure(
91 const rclcpp_lifecycle::State & previous_state)
override;
93 controller_interface::CallbackReturn on_activate(
94 const rclcpp_lifecycle::State & previous_state)
override;
96 controller_interface::CallbackReturn on_deactivate(
97 const rclcpp_lifecycle::State & previous_state)
override;
101 Commands command_struct_, command_struct_rt_;
104 using GripperCommandAction = control_msgs::action::GripperCommand;
105 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
106 using ActionServerPtr = ActionServer::SharedPtr;
107 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
110 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
115 bool update_hold_position_;
119 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
120 joint_command_interface_;
121 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
122 joint_position_state_interface_;
123 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
124 joint_velocity_state_interface_;
126 std::shared_ptr<ParamListener> param_listener_;
133 control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
135 rclcpp::Duration action_monitor_period_;
138 ActionServerPtr action_server_;
140 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
142 rclcpp_action::GoalResponse goal_callback(
143 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
145 rclcpp_action::CancelResponse cancel_callback(
const std::shared_ptr<GoalHandle> goal_handle);
147 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
149 void preempt_active_goal();
151 void set_hold_position();
160 const rclcpp::Time & time,
double error_position,
double current_position,
161 double current_velocity);
166#include "gripper_controllers/gripper_action_controller_impl.hpp"
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition hardware_interface_adapter.hpp:41
Definition controller_interface.hpp:27
Controller for executing a gripper command action for simple single-dof grippers.
Definition gripper_action_controller.hpp:60
std::string name_
Controller name.
Definition gripper_action_controller.hpp:118
RealtimeGoalHandleBuffer rt_active_goal_
Container for the currently active action goal, if any.
Definition gripper_action_controller.hpp:132
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition gripper_action_controller_impl.hpp:41
HwIfaceAdapter hw_iface_adapter_
Adapts desired goal state to HW interface.
Definition gripper_action_controller.hpp:129
controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration This controller requires the position and velocity state interfaces f...
Definition gripper_action_controller_impl.hpp:338
double computed_command_
Computed command.
Definition gripper_action_controller.hpp:154
bool verbose_
Hard coded verbose flag to help in debugging.
Definition gripper_action_controller.hpp:117
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.
Definition gripper_action_controller_impl.hpp:156
rclcpp::Time last_movement_time_
Store stall time.
Definition gripper_action_controller.hpp:153
controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration This controller requires the position command interfaces for the cont...
Definition gripper_action_controller_impl.hpp:329
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition gripper_action_controller_impl.hpp:63
Definition gripper_action_controller.hpp:49
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57
Store position and max effort in struct to allow easier realtime buffer usage.
Definition gripper_action_controller.hpp:67