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