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