ros2_control - rolling
gripper_action_controller_impl.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_IMPL_HPP_
18 #define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
19 
20 #include "gripper_controllers/gripper_action_controller.hpp"
21 
22 #include <memory>
23 #include <string>
24 
26 {
27 template <const char * HardwareInterface>
28 void GripperActionController<HardwareInterface>::preempt_active_goal()
29 {
30  // Cancels the currently active goal
31  const auto active_goal = *rt_active_goal_.readFromNonRT();
32  if (active_goal)
33  {
34  // Marks the current goal as canceled
35  active_goal->setCanceled(std::make_shared<GripperCommandAction::Result>());
36  rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
37  }
38 }
39 
40 template <const char * HardwareInterface>
41 controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_init()
42 {
43  RCLCPP_WARN(
44  get_node()->get_logger(),
45  "[Deprecated]: the `position_controllers/GripperActionController` and "
46  "`effort_controllers::GripperActionController` controllers are replaced by "
47  "'parallel_gripper_controllers/GripperActionController' controller");
48  try
49  {
50  param_listener_ = std::make_shared<ParamListener>(get_node());
51  params_ = param_listener_->get_params();
52  }
53  catch (const std::exception & e)
54  {
55  fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
56  return controller_interface::CallbackReturn::ERROR;
57  }
58 
59  return controller_interface::CallbackReturn::SUCCESS;
60 }
61 
62 template <const char * HardwareInterface>
63 controller_interface::return_type GripperActionController<HardwareInterface>::update(
64  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
65 {
66  command_struct_rt_ = *(command_.readFromRT());
67 
68  const double current_position = joint_position_state_interface_->get().get_value();
69  const double current_velocity = joint_velocity_state_interface_->get().get_value();
70 
71  const double error_position = command_struct_rt_.position_ - current_position;
72  const double error_velocity = -current_velocity;
73 
74  check_for_success(get_node()->now(), error_position, current_position, current_velocity);
75 
76  // Hardware interface adapter: Generate and send commands
77  computed_command_ = hw_iface_adapter_.updateCommand(
78  command_struct_rt_.position_, 0.0, error_position, error_velocity,
79  command_struct_rt_.max_effort_);
80  return controller_interface::return_type::OK;
81 }
82 
83 template <const char * HardwareInterface>
85  const rclcpp_action::GoalUUID &, std::shared_ptr<const GripperCommandAction::Goal>)
86 {
87  RCLCPP_INFO(get_node()->get_logger(), "Received & accepted new action goal");
88  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
89 }
90 
91 template <const char * HardwareInterface>
92 void GripperActionController<HardwareInterface>::accepted_callback(
93  std::shared_ptr<GoalHandle> goal_handle) // Try to update goal
94 {
95  auto rt_goal = std::make_shared<RealtimeGoalHandle>(goal_handle);
96 
97  // Accept new goal
98  preempt_active_goal();
99 
100  // This is the non-realtime command_struct
101  // We use command_ for sharing
102  command_struct_.position_ = goal_handle->get_goal()->command.position;
103  command_struct_.max_effort_ = goal_handle->get_goal()->command.max_effort;
104  command_.writeFromNonRT(command_struct_);
105 
106  pre_alloc_result_->reached_goal = false;
107  pre_alloc_result_->stalled = false;
108 
109  last_movement_time_ = get_node()->now();
110  rt_goal->execute();
111  rt_active_goal_.writeFromNonRT(rt_goal);
112 
113  // Set smartpointer to expire for create_wall_timer to delete previous entry from timer list
114  goal_handle_timer_.reset();
115 
116  // Setup goal status checking timer
117  goal_handle_timer_ = get_node()->create_wall_timer(
118  action_monitor_period_.to_chrono<std::chrono::nanoseconds>(),
119  std::bind(&RealtimeGoalHandle::runNonRealtime, rt_goal));
120 }
121 
122 template <const char * HardwareInterface>
123 rclcpp_action::CancelResponse GripperActionController<HardwareInterface>::cancel_callback(
124  const std::shared_ptr<GoalHandle> goal_handle)
125 {
126  RCLCPP_INFO(get_node()->get_logger(), "Got request to cancel goal");
127 
128  // Check that cancel request refers to currently active goal (if any)
129  const auto active_goal = *rt_active_goal_.readFromNonRT();
130  if (active_goal && active_goal->gh_ == goal_handle)
131  {
132  // Enter hold current position mode
133  set_hold_position();
134 
135  RCLCPP_INFO(
136  get_node()->get_logger(), "Canceling active action goal because cancel callback received.");
137 
138  // Mark the current goal as canceled
139  auto action_res = std::make_shared<GripperCommandAction::Result>();
140  active_goal->setCanceled(action_res);
141  // Reset current goal
142  rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
143  }
144  return rclcpp_action::CancelResponse::ACCEPT;
145 }
146 
147 template <const char * HardwareInterface>
148 void GripperActionController<HardwareInterface>::set_hold_position()
149 {
150  command_struct_.position_ = joint_position_state_interface_->get().get_value();
151  command_struct_.max_effort_ = params_.max_effort;
152  command_.writeFromNonRT(command_struct_);
153 }
154 
155 template <const char * HardwareInterface>
157  const rclcpp::Time & time, double error_position, double current_position,
158  double current_velocity)
159 {
160  const auto active_goal = *rt_active_goal_.readFromNonRT();
161  if (!active_goal)
162  {
163  return;
164  }
165 
166  if (fabs(error_position) < params_.goal_tolerance)
167  {
168  pre_alloc_result_->effort = computed_command_;
169  pre_alloc_result_->position = current_position;
170  pre_alloc_result_->reached_goal = true;
171  pre_alloc_result_->stalled = false;
172  RCLCPP_DEBUG(get_node()->get_logger(), "Successfully moved to goal.");
173  active_goal->setSucceeded(pre_alloc_result_);
174  rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
175  }
176  else
177  {
178  if (fabs(current_velocity) > params_.stall_velocity_threshold)
179  {
180  last_movement_time_ = time;
181  }
182  else if ((time - last_movement_time_).seconds() > params_.stall_timeout)
183  {
184  pre_alloc_result_->effort = computed_command_;
185  pre_alloc_result_->position = current_position;
186  pre_alloc_result_->reached_goal = false;
187  pre_alloc_result_->stalled = true;
188 
189  if (params_.allow_stalling)
190  {
191  RCLCPP_DEBUG(get_node()->get_logger(), "Stall detected moving to goal. Returning success.");
192  active_goal->setSucceeded(pre_alloc_result_);
193  }
194  else
195  {
196  RCLCPP_DEBUG(get_node()->get_logger(), "Stall detected moving to goal. Aborting action!");
197  active_goal->setAborted(pre_alloc_result_);
198  }
199  rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
200  }
201  }
202 }
203 
204 template <const char * HardwareInterface>
205 controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_configure(
206  const rclcpp_lifecycle::State &)
207 {
208  const auto logger = get_node()->get_logger();
209  if (!param_listener_)
210  {
211  RCLCPP_ERROR(get_node()->get_logger(), "Error encountered during init");
212  return controller_interface::CallbackReturn::ERROR;
213  }
214  params_ = param_listener_->get_params();
215 
216  // Action status checking update rate
217  action_monitor_period_ = rclcpp::Duration::from_seconds(1.0 / params_.action_monitor_rate);
218  RCLCPP_INFO_STREAM(
219  logger, "Action status changes will be monitored at " << params_.action_monitor_rate << "Hz.");
220 
221  // Controlled joint
222  if (params_.joint.empty())
223  {
224  RCLCPP_ERROR(logger, "Joint name cannot be empty");
225  return controller_interface::CallbackReturn::ERROR;
226  }
227 
228  return controller_interface::CallbackReturn::SUCCESS;
229 }
230 template <const char * HardwareInterface>
231 controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_activate(
232  const rclcpp_lifecycle::State &)
233 {
234  auto command_interface_it = std::find_if(
235  command_interfaces_.begin(), command_interfaces_.end(),
236  [](const hardware_interface::LoanedCommandInterface & command_interface)
237  { return command_interface.get_interface_name() == HardwareInterface; });
238  if (command_interface_it == command_interfaces_.end())
239  {
240  RCLCPP_ERROR_STREAM(
241  get_node()->get_logger(), "Expected 1 " << HardwareInterface << " command interface");
242  return controller_interface::CallbackReturn::ERROR;
243  }
244  if (command_interface_it->get_prefix_name() != params_.joint)
245  {
246  RCLCPP_ERROR_STREAM(
247  get_node()->get_logger(), "Command interface is different than joint name `"
248  << command_interface_it->get_prefix_name() << "` != `"
249  << params_.joint << "`");
250  return controller_interface::CallbackReturn::ERROR;
251  }
252  const auto position_state_interface_it = std::find_if(
253  state_interfaces_.begin(), state_interfaces_.end(),
254  [](const hardware_interface::LoanedStateInterface & state_interface)
255  { return state_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
256  if (position_state_interface_it == state_interfaces_.end())
257  {
258  RCLCPP_ERROR(get_node()->get_logger(), "Expected 1 position state interface");
259  return controller_interface::CallbackReturn::ERROR;
260  }
261  if (position_state_interface_it->get_prefix_name() != params_.joint)
262  {
263  RCLCPP_ERROR_STREAM(
264  get_node()->get_logger(), "Position state interface is different than joint name `"
265  << position_state_interface_it->get_prefix_name() << "` != `"
266  << params_.joint << "`");
267  return controller_interface::CallbackReturn::ERROR;
268  }
269  const auto velocity_state_interface_it = std::find_if(
270  state_interfaces_.begin(), state_interfaces_.end(),
271  [](const hardware_interface::LoanedStateInterface & state_interface)
272  { return state_interface.get_interface_name() == hardware_interface::HW_IF_VELOCITY; });
273  if (velocity_state_interface_it == state_interfaces_.end())
274  {
275  RCLCPP_ERROR(get_node()->get_logger(), "Expected 1 velocity state interface");
276  return controller_interface::CallbackReturn::ERROR;
277  }
278  if (velocity_state_interface_it->get_prefix_name() != params_.joint)
279  {
280  RCLCPP_ERROR_STREAM(
281  get_node()->get_logger(), "Velocity command interface is different than joint name `"
282  << velocity_state_interface_it->get_prefix_name() << "` != `"
283  << params_.joint << "`");
284  return controller_interface::CallbackReturn::ERROR;
285  }
286 
287  joint_command_interface_ = *command_interface_it;
288  joint_position_state_interface_ = *position_state_interface_it;
289  joint_velocity_state_interface_ = *velocity_state_interface_it;
290 
291  // Hardware interface adapter
292  hw_iface_adapter_.init(joint_command_interface_, get_node());
293 
294  // Command - non RT version
295  command_struct_.position_ = joint_position_state_interface_->get().get_value();
296  command_struct_.max_effort_ = params_.max_effort;
297  command_.initRT(command_struct_);
298 
299  // Result
300  pre_alloc_result_ = std::make_shared<control_msgs::action::GripperCommand::Result>();
301  pre_alloc_result_->position = command_struct_.position_;
302  pre_alloc_result_->reached_goal = false;
303  pre_alloc_result_->stalled = false;
304 
305  // Action interface
306  action_server_ = rclcpp_action::create_server<control_msgs::action::GripperCommand>(
307  get_node(), "~/gripper_cmd",
308  std::bind(
309  &GripperActionController::goal_callback, this, std::placeholders::_1, std::placeholders::_2),
310  std::bind(&GripperActionController::cancel_callback, this, std::placeholders::_1),
311  std::bind(&GripperActionController::accepted_callback, this, std::placeholders::_1));
312 
313  return controller_interface::CallbackReturn::SUCCESS;
314 }
315 
316 template <const char * HardwareInterface>
317 controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_deactivate(
318  const rclcpp_lifecycle::State &)
319 {
320  joint_command_interface_ = std::nullopt;
321  joint_position_state_interface_ = std::nullopt;
322  joint_velocity_state_interface_ = std::nullopt;
323  release_interfaces();
324  return controller_interface::CallbackReturn::SUCCESS;
325 }
326 
327 template <const char * HardwareInterface>
330 {
331  return {
332  controller_interface::interface_configuration_type::INDIVIDUAL,
333  {params_.joint + "/" + HardwareInterface}};
334 }
335 
336 template <const char * HardwareInterface>
339 {
340  return {
341  controller_interface::interface_configuration_type::INDIVIDUAL,
342  {params_.joint + "/" + hardware_interface::HW_IF_POSITION,
343  params_.joint + "/" + hardware_interface::HW_IF_VELOCITY}};
344 }
345 
346 template <const char * HardwareInterface>
348 : controller_interface::ControllerInterface(),
349  action_monitor_period_(rclcpp::Duration::from_seconds(0))
350 {
351 }
352 
353 } // namespace gripper_action_controller
354 
355 #endif // GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
Controller for executing a gripper command action for simple single-dof grippers.
Definition: gripper_action_controller.hpp:61
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
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
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
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: loaned_command_interface.hpp:27
Definition: loaned_state_interface.hpp:27
Definition: gripper_action_controller.hpp:50
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition: hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition: hardware_interface_type_values.hpp:21
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:56