ros2_control - rolling
gripper_action_controller.hpp
1 // Copyright 2014, SRI International
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
16 
17 #ifndef GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
18 #define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
19 
20 // C++ standard
21 #include <cassert>
22 #include <memory>
23 #include <stdexcept>
24 #include <string>
25 
26 // ROS
27 #include "rclcpp/rclcpp.hpp"
28 
29 // ROS messages
30 #include "control_msgs/action/gripper_command.hpp"
31 
32 // rclcpp_action
33 #include "rclcpp_action/create_server.hpp"
34 
35 // ros_controls
36 #include "controller_interface/controller_interface.hpp"
37 #include "gripper_controllers/visibility_control.hpp"
38 #include "hardware_interface/loaned_command_interface.hpp"
39 #include "hardware_interface/loaned_state_interface.hpp"
40 #include "realtime_tools/realtime_buffer.hpp"
41 #include "realtime_tools/realtime_server_goal_handle.hpp"
42 
43 // Project
44 #include "gripper_controllers/hardware_interface_adapter.hpp"
45 
46 // auto-generated by generate_parameter_library
47 #include "gripper_action_controller_parameters.hpp"
48 
50 {
59 template <const char * HardwareInterface>
61 {
62 public:
67  struct Commands
68  {
69  double position_; // Last commanded position
70  double max_effort_; // Max allowed effort
71  };
72 
73  GRIPPER_ACTION_CONTROLLER_PUBLIC GripperActionController();
74 
79  GRIPPER_ACTION_CONTROLLER_PUBLIC
81 
86  GRIPPER_ACTION_CONTROLLER_PUBLIC
88 
89  GRIPPER_ACTION_CONTROLLER_PUBLIC
90  controller_interface::return_type update(
91  const rclcpp::Time & time, const rclcpp::Duration & period) override;
92 
93  GRIPPER_ACTION_CONTROLLER_PUBLIC
94  controller_interface::CallbackReturn on_init() override;
95 
96  GRIPPER_ACTION_CONTROLLER_PUBLIC
97  controller_interface::CallbackReturn on_configure(
98  const rclcpp_lifecycle::State & previous_state) override;
99 
100  GRIPPER_ACTION_CONTROLLER_PUBLIC
101  controller_interface::CallbackReturn on_activate(
102  const rclcpp_lifecycle::State & previous_state) override;
103 
104  GRIPPER_ACTION_CONTROLLER_PUBLIC
105  controller_interface::CallbackReturn on_deactivate(
106  const rclcpp_lifecycle::State & previous_state) override;
107 
109  // pre-allocated memory that is re-used to set the realtime buffer
110  Commands command_struct_, command_struct_rt_;
111 
112 protected:
113  using GripperCommandAction = control_msgs::action::GripperCommand;
114  using ActionServer = rclcpp_action::Server<GripperCommandAction>;
115  using ActionServerPtr = ActionServer::SharedPtr;
116  using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
117  using RealtimeGoalHandle =
119  using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
121 
123 
124  bool update_hold_position_;
125 
126  bool verbose_ = false;
127  std::string name_;
128  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
129  joint_command_interface_;
130  std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
131  joint_position_state_interface_;
132  std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
133  joint_velocity_state_interface_;
134 
135  std::shared_ptr<ParamListener> param_listener_;
136  Params params_;
137 
139 
142  control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
143 
144  rclcpp::Duration action_monitor_period_;
145 
146  // ROS API
147  ActionServerPtr action_server_;
148 
149  rclcpp::TimerBase::SharedPtr goal_handle_timer_;
150 
151  rclcpp_action::GoalResponse goal_callback(
152  const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
153 
154  rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle);
155 
156  void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
157 
158  void preempt_active_goal();
159 
160  void set_hold_position();
161 
162  rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
164 
168  void check_for_success(
169  const rclcpp::Time & time, double error_position, double current_position,
170  double current_velocity);
171 };
172 
173 } // namespace gripper_action_controller
174 
175 #include "gripper_controllers/gripper_action_controller_impl.hpp"
176 
177 #endif // GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition: hardware_interface_adapter.hpp:41
Definition: controller_interface.hpp:28
Controller for executing a gripper command action for simple single-dof grippers.
Definition: gripper_action_controller.hpp:61
std::string name_
Controller name.
Definition: gripper_action_controller.hpp:127
RealtimeGoalHandleBuffer rt_active_goal_
Container for the currently active action goal, if any.
Definition: gripper_action_controller.hpp:141
GRIPPER_ACTION_CONTROLLER_PUBLIC 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:138
GRIPPER_ACTION_CONTROLLER_PUBLIC 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:163
bool verbose_
Hard coded verbose flag to help in debugging.
Definition: gripper_action_controller.hpp:126
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:162
GRIPPER_ACTION_CONTROLLER_PUBLIC 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
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition: gripper_action_controller_impl.hpp:63
Definition: realtime_buffer.hpp:44
Definition: realtime_server_goal_handle.hpp:44
Definition: gripper_action_controller.hpp:50
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:58
Store position and max effort in struct to allow easier realtime buffer usage.
Definition: gripper_action_controller.hpp:68