ros2_control - foxy
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 <memory>
21#include <string>
22
24{
25template <const char * HardwareInterface>
26void GripperActionController<HardwareInterface>::preempt_active_goal()
27{
28 // Cancels the currently active goal
29 if (rt_active_goal_)
30 {
31 // Marks the current goal as canceled
32 rt_active_goal_->setCanceled(std::make_shared<GripperCommandAction::Result>());
33 rt_active_goal_.reset();
34 }
35}
36
37template <const char * HardwareInterface>
38controller_interface::return_type GripperActionController<HardwareInterface>::init(
39 const std::string & controller_name)
40{
41 // initialize lifecycle node
42 const auto ret = ControllerInterface::init(controller_name);
43 if (ret != controller_interface::return_type::OK)
44 {
45 return ret;
46 }
47
48 // with the lifecycle node being initialized, we can declare parameters
49 auto_declare<double>("action_monitor_rate", 20.0);
50 auto_declare<std::string>("joint", joint_name_);
51 auto_declare<double>("goal_tolerance", 0.01);
52 auto_declare<double>("max_effort", 0.0);
53 auto_declare<double>("stall_velocity_threshold", 0.001);
54 auto_declare<double>("stall_timeout", 1.0);
55
56 return controller_interface::return_type::OK;
57}
58
59template <const char * HardwareInterface>
60controller_interface::return_type GripperActionController<HardwareInterface>::update()
61{
62 command_struct_rt_ = *(command_.readFromRT());
63
64 const double current_position = joint_position_state_interface_->get().get_value();
65 const double current_velocity = joint_velocity_state_interface_->get().get_value();
66
67 const double error_position = command_struct_rt_.position_ - current_position;
68 const double error_velocity = -current_velocity;
69
70 check_for_success(node_->now(), error_position, current_position, current_velocity);
71
72 // Hardware interface adapter: Generate and send commands
73 computed_command_ = hw_iface_adapter_.updateCommand(
74 command_struct_rt_.position_, 0.0, error_position, error_velocity,
75 command_struct_rt_.max_effort_);
76 return controller_interface::return_type::OK;
77}
78
79template <const char * HardwareInterface>
80rclcpp_action::GoalResponse GripperActionController<HardwareInterface>::goal_callback(
81 const rclcpp_action::GoalUUID &, std::shared_ptr<const GripperCommandAction::Goal>)
82{
83 RCLCPP_INFO(node_->get_logger(), "Received & accepted new action goal");
84 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
85}
86
87template <const char * HardwareInterface>
88void GripperActionController<HardwareInterface>::accepted_callback(
89 std::shared_ptr<GoalHandle> goal_handle) // Try to update goal
90{
91 {
92 auto rt_goal = std::make_shared<RealtimeGoalHandle>(goal_handle);
93
94 // Accept new goal
95 preempt_active_goal();
96
97 // This is the non-realtime command_struct
98 // We use command_ for sharing
99 command_struct_.position_ = goal_handle->get_goal()->command.position;
100 command_struct_.max_effort_ = goal_handle->get_goal()->command.max_effort;
101 command_.writeFromNonRT(command_struct_);
102
103 pre_alloc_result_->reached_goal = false;
104 pre_alloc_result_->stalled = false;
105
106 last_movement_time_ = node_->now();
107 rt_active_goal_ = rt_goal;
108 rt_active_goal_->execute();
109 }
110 // Setup goal status checking timer
111 goal_handle_timer_ = node_->create_wall_timer(
112 action_monitor_period_.to_chrono<std::chrono::seconds>(),
113 std::bind(&RealtimeGoalHandle::runNonRealtime, rt_active_goal_));
114}
115
116template <const char * HardwareInterface>
117rclcpp_action::CancelResponse GripperActionController<HardwareInterface>::cancel_callback(
118 const std::shared_ptr<GoalHandle> goal_handle)
119{
120 RCLCPP_INFO(node_->get_logger(), "Got request to cancel goal");
121
122 // Check that cancel request refers to currently active goal (if any)
123 if (rt_active_goal_ && rt_active_goal_->gh_ == goal_handle)
124 {
125 // Enter hold current position mode
126 set_hold_position();
127
128 RCLCPP_INFO(
129 node_->get_logger(), "Canceling active action goal because cancel callback received.");
130
131 // Mark the current goal as canceled
132 auto action_res = std::make_shared<GripperCommandAction::Result>();
133 rt_active_goal_->setCanceled(action_res);
134 // Reset current goal
135 rt_active_goal_.reset();
136 }
137 return rclcpp_action::CancelResponse::ACCEPT;
138}
139
140template <const char * HardwareInterface>
141void GripperActionController<HardwareInterface>::set_hold_position()
142{
143 command_struct_.position_ = joint_position_state_interface_->get().get_value();
144 command_struct_.max_effort_ = default_max_effort_;
145 command_.writeFromNonRT(command_struct_);
146}
147
148template <const char * HardwareInterface>
149void GripperActionController<HardwareInterface>::check_for_success(
150 const rclcpp::Time & time, double error_position, double current_position,
151 double current_velocity)
152{
153 if (!rt_active_goal_)
154 {
155 return;
156 }
157
158 if (fabs(error_position) < goal_tolerance_)
159 {
160 pre_alloc_result_->effort = computed_command_;
161 pre_alloc_result_->position = current_position;
162 pre_alloc_result_->reached_goal = true;
163 pre_alloc_result_->stalled = false;
164 rt_active_goal_->setSucceeded(pre_alloc_result_);
165 rt_active_goal_.reset();
166 }
167 else
168 {
169 if (fabs(current_velocity) > stall_velocity_threshold_)
170 {
171 last_movement_time_ = time;
172 }
173 else if ((time - last_movement_time_).seconds() > stall_timeout_)
174 {
175 pre_alloc_result_->effort = computed_command_;
176 pre_alloc_result_->position = current_position;
177 pre_alloc_result_->reached_goal = false;
178 pre_alloc_result_->stalled = true;
179 rt_active_goal_->setAborted(pre_alloc_result_);
180 rt_active_goal_.reset();
181 }
182 }
183}
184
185template <const char * HardwareInterface>
186rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
187GripperActionController<HardwareInterface>::on_configure(const rclcpp_lifecycle::State &)
188{
189 const auto logger = node_->get_logger();
190
191 // Action status checking update rate
192 const auto action_monitor_rate = node_->get_parameter("action_monitor_rate").as_double();
193 action_monitor_period_ =
194 rclcpp::Duration::from_seconds(1.0 / node_->get_parameter("action_monitor_rate").as_double());
195 RCLCPP_INFO_STREAM(
196 logger, "Action status changes will be monitored at " << action_monitor_rate << "Hz.");
197
198 // Controlled joint
199 joint_name_ = node_->get_parameter("joint").as_string();
200 if (joint_name_.empty())
201 {
202 RCLCPP_ERROR(logger, "Could not find joint name on param server");
203 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
204 }
205
206 // Default tolerances
207 goal_tolerance_ = node_->get_parameter("goal_tolerance").as_double();
208 goal_tolerance_ = fabs(goal_tolerance_);
209 // Max allowable effort
210 default_max_effort_ = node_->get_parameter("max_effort").as_double();
211 default_max_effort_ = fabs(default_max_effort_);
212 // Stall - stall velocity threshold, stall timeout
213 stall_velocity_threshold_ = node_->get_parameter("stall_velocity_threshold").as_double();
214 stall_timeout_ = node_->get_parameter("stall_timeout").as_double();
215
216 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
217}
218template <const char * HardwareInterface>
219rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
220GripperActionController<HardwareInterface>::on_activate(const rclcpp_lifecycle::State &)
221{
222 auto position_command_interface_it = std::find_if(
223 command_interfaces_.begin(), command_interfaces_.end(),
224 [](const hardware_interface::LoanedCommandInterface & command_interface) {
225 return command_interface.get_interface_name() == hardware_interface::HW_IF_POSITION;
226 });
227 if (position_command_interface_it == command_interfaces_.end())
228 {
229 RCLCPP_ERROR(node_->get_logger(), "Expected 1 position command interface");
230 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
231 }
232 if (position_command_interface_it->get_name() != joint_name_)
233 {
234 RCLCPP_ERROR_STREAM(
235 node_->get_logger(), "Position command interface is different than joint name `"
236 << position_command_interface_it->get_name() << "` != `" << joint_name_
237 << "`");
238 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
239 }
240 const auto position_state_interface_it = std::find_if(
241 state_interfaces_.begin(), state_interfaces_.end(),
242 [](const hardware_interface::LoanedStateInterface & state_interface) {
243 return state_interface.get_interface_name() == hardware_interface::HW_IF_POSITION;
244 });
245 if (position_state_interface_it == state_interfaces_.end())
246 {
247 RCLCPP_ERROR(node_->get_logger(), "Expected 1 position state interface");
248 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
249 }
250 if (position_state_interface_it->get_name() != joint_name_)
251 {
252 RCLCPP_ERROR_STREAM(
253 node_->get_logger(), "Position state interface is different than joint name `"
254 << position_state_interface_it->get_name() << "` != `" << joint_name_
255 << "`");
256 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
257 }
258 const auto velocity_state_interface_it = std::find_if(
259 state_interfaces_.begin(), state_interfaces_.end(),
260 [](const hardware_interface::LoanedStateInterface & state_interface) {
261 return state_interface.get_interface_name() == hardware_interface::HW_IF_VELOCITY;
262 });
263 if (velocity_state_interface_it == state_interfaces_.end())
264 {
265 RCLCPP_ERROR(node_->get_logger(), "Expected 1 velocity state interface");
266 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
267 }
268 if (velocity_state_interface_it->get_name() != joint_name_)
269 {
270 RCLCPP_ERROR_STREAM(
271 node_->get_logger(), "Velocity command interface is different than joint name `"
272 << velocity_state_interface_it->get_name() << "` != `" << joint_name_
273 << "`");
274 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
275 }
276
277 joint_position_command_interface_ = *position_command_interface_it;
278 joint_position_state_interface_ = *position_state_interface_it;
279 joint_velocity_state_interface_ = *velocity_state_interface_it;
280
281 // Hardware interface adapter
282 hw_iface_adapter_.init(joint_position_command_interface_, node_);
283
284 // Command - non RT version
285 command_struct_.position_ = joint_position_state_interface_->get().get_value();
286 command_struct_.max_effort_ = default_max_effort_;
287
288 // Result
289 pre_alloc_result_ = std::make_shared<control_msgs::action::GripperCommand::Result>();
290 pre_alloc_result_->position = command_struct_.position_;
291 pre_alloc_result_->reached_goal = false;
292 pre_alloc_result_->stalled = false;
293
294 // Action interface
295 action_server_ = rclcpp_action::create_server<control_msgs::action::GripperCommand>(
296 node_, "~/gripper_cmd",
297 std::bind(
298 &GripperActionController::goal_callback, this, std::placeholders::_1, std::placeholders::_2),
299 std::bind(&GripperActionController::cancel_callback, this, std::placeholders::_1),
300 std::bind(&GripperActionController::accepted_callback, this, std::placeholders::_1));
301
302 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
303}
304
305template <const char * HardwareInterface>
306rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
307GripperActionController<HardwareInterface>::on_deactivate(const rclcpp_lifecycle::State &)
308{
309 joint_position_command_interface_ = std::experimental::nullopt;
310 joint_position_state_interface_ = std::experimental::nullopt;
311 joint_velocity_state_interface_ = std::experimental::nullopt;
312 release_interfaces();
313 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
314}
315
316template <const char * HardwareInterface>
319{
320 return {
321 controller_interface::interface_configuration_type::INDIVIDUAL,
322 {joint_name_ + "/" + hardware_interface::HW_IF_POSITION}};
323}
324
325template <const char * HardwareInterface>
328{
329 return {
330 controller_interface::interface_configuration_type::INDIVIDUAL,
331 {joint_name_ + "/" + hardware_interface::HW_IF_POSITION,
332 joint_name_ + "/" + hardware_interface::HW_IF_VELOCITY}};
333}
334
335template <const char * HardwareInterface>
337: controller_interface::ControllerInterface(), action_monitor_period_(0)
338{
339}
340
341} // namespace gripper_action_controller
342
343#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:60
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:327
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:318
Definition loaned_command_interface.hpp:27
Definition loaned_state_interface.hpp:27
Definition controller_interface.hpp:32
Definition gripper_action_controller.hpp:49
Configuring what command/state interfaces to claim.
Definition controller_interface.hpp:63