ros2_control - rolling
parallel_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 PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_HPP_
18 #define PARALLEL_GRIPPER_CONTROLLER__PARALLEL_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/parallel_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 "hardware_interface/loaned_command_interface.hpp"
38 #include "hardware_interface/loaned_state_interface.hpp"
39 #include "parallel_gripper_controller/visibility_control.hpp"
40 #include "realtime_tools/realtime_buffer.h"
41 #include "realtime_tools/realtime_server_goal_handle.h"
42 
43 // Project
44 #include "parallel_gripper_action_controller_parameters.hpp"
45 
47 {
57 {
58 public:
63  struct Commands
64  {
65  double position_cmd_; // Commanded position
66  double max_velocity_; // Desired max gripper velocity
67  double max_effort_; // Desired max allowed effort
68  };
69 
70  GRIPPER_ACTION_CONTROLLER_PUBLIC GripperActionController();
71 
76  GRIPPER_ACTION_CONTROLLER_PUBLIC
78 
83  GRIPPER_ACTION_CONTROLLER_PUBLIC
85 
86  GRIPPER_ACTION_CONTROLLER_PUBLIC
87  controller_interface::return_type update(
88  const rclcpp::Time & time, const rclcpp::Duration & period) override;
89 
90  GRIPPER_ACTION_CONTROLLER_PUBLIC
91  controller_interface::CallbackReturn on_init() override;
92 
93  GRIPPER_ACTION_CONTROLLER_PUBLIC
94  controller_interface::CallbackReturn on_configure(
95  const rclcpp_lifecycle::State & previous_state) override;
96 
97  GRIPPER_ACTION_CONTROLLER_PUBLIC
98  controller_interface::CallbackReturn on_activate(
99  const rclcpp_lifecycle::State & previous_state) override;
100 
101  GRIPPER_ACTION_CONTROLLER_PUBLIC
102  controller_interface::CallbackReturn on_deactivate(
103  const rclcpp_lifecycle::State & previous_state) override;
104 
106  // pre-allocated memory that is re-used to set the realtime buffer
107  Commands command_struct_, command_struct_rt_;
108 
109 protected:
110  using GripperCommandAction = control_msgs::action::ParallelGripperCommand;
111  using ActionServer = rclcpp_action::Server<GripperCommandAction>;
112  using ActionServerPtr = ActionServer::SharedPtr;
113  using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
114  using RealtimeGoalHandle =
116  using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
118 
119  bool update_hold_position_;
120 
121  bool verbose_ = false;
122  std::string name_;
123  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
124  joint_command_interface_;
125  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
126  effort_interface_;
127  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
128  speed_interface_;
129  std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
130  joint_position_state_interface_;
131  std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
132  joint_velocity_state_interface_;
133 
134  std::shared_ptr<ParamListener> param_listener_;
135  Params params_;
136 
139  control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_;
140 
141  rclcpp::Duration action_monitor_period_;
142 
143  // ROS API
144  ActionServerPtr action_server_;
145 
146  rclcpp::TimerBase::SharedPtr goal_handle_timer_;
147 
148  rclcpp_action::GoalResponse goal_callback(
149  const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
150 
151  rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle);
152 
153  void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
154 
155  void preempt_active_goal();
156 
157  void set_hold_position();
158 
159  rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
161 
165  void check_for_success(
166  const rclcpp::Time & time, double error_position, double current_position,
167  double current_velocity);
168 };
169 
170 } // namespace parallel_gripper_action_controller
171 
172 #include "parallel_gripper_controller/parallel_gripper_action_controller_impl.hpp"
173 
174 #endif // PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_HPP_
Definition: controller_interface.hpp:28
Controller for executing a ParallelGripperCommand action.
Definition: parallel_gripper_action_controller.hpp:57
bool verbose_
Hard coded verbose flag to help in debugging.
Definition: parallel_gripper_action_controller.hpp:121
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition: parallel_gripper_action_controller_impl.hpp:57
double computed_command_
Computed command.
Definition: parallel_gripper_action_controller.hpp:160
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: parallel_gripper_action_controller_impl.hpp:361
std::string name_
Controller name.
Definition: parallel_gripper_action_controller.hpp:122
rclcpp::Time last_movement_time_
Store stall time.
Definition: parallel_gripper_action_controller.hpp:159
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: parallel_gripper_action_controller_impl.hpp:377
RealtimeGoalHandleBuffer rt_active_goal_
Container for the currently active action goal, if any.
Definition: parallel_gripper_action_controller.hpp:138
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition: parallel_gripper_action_controller_impl.hpp:42
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: parallel_gripper_action_controller_impl.hpp:177
Definition: realtime_buffer.h:49
Definition: realtime_server_goal_handle.h:44
Definition: parallel_gripper_action_controller.hpp:47
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:56
Store position and max effort in struct to allow easier realtime buffer usage.
Definition: parallel_gripper_action_controller.hpp:64