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