17#ifndef PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
18#define PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
24#include <hardware_interface/types/hardware_interface_type_values.hpp>
25#include "parallel_gripper_controller/parallel_gripper_action_controller.hpp"
30void GripperActionController::preempt_active_goal()
33 RealtimeGoalHandlePtr active_goal;
38 active_goal->setCanceled(std::make_shared<GripperCommandAction::Result>());
40 { stored_value = RealtimeGoalHandlePtr(); });
48 param_listener_ = std::make_shared<ParamListener>(get_node());
50 catch (
const std::exception & e)
52 fprintf(stderr,
"Exception thrown during init stage with message: %s \n", e.what());
53 return controller_interface::CallbackReturn::ERROR;
56 return controller_interface::CallbackReturn::SUCCESS;
60 const rclcpp::Time & ,
const rclcpp::Duration & )
62 auto logger = get_node()->get_logger();
63 auto command_struct_rt_op = command_.try_get();
64 if (command_struct_rt_op.has_value())
66 command_struct_rt_ = command_struct_rt_op.value();
68 const auto current_position_op = joint_position_state_interface_->get().get_optional();
69 if (!current_position_op.has_value())
71 RCLCPP_DEBUG(logger,
"Unable to retrieve current position value");
72 return controller_interface::return_type::OK;
74 const auto current_velocity_op = joint_velocity_state_interface_->get().get_optional();
75 if (!current_velocity_op.has_value())
77 RCLCPP_DEBUG(logger,
"Unable to retrieve current velocity value");
78 return controller_interface::return_type::OK;
81 const double error_position = command_struct_rt_.position_cmd_ - current_position_op.value();
84 get_node()->now(), error_position, current_position_op.value(), current_velocity_op.value());
86 if (!joint_command_interface_->get().set_value(command_struct_rt_.position_cmd_))
89 logger,
"Unable to set the joint position command to: %f", command_struct_rt_.position_cmd_);
90 return controller_interface::return_type::OK;
93 speed_interface_.has_value() &&
94 !speed_interface_->get().set_value(command_struct_rt_.max_velocity_))
96 RCLCPP_WARN(logger,
"Unable to set the speed command to: %f", command_struct_rt_.max_velocity_);
98 return controller_interface::return_type::OK;
101 effort_interface_.has_value() &&
102 !effort_interface_->get().set_value(command_struct_rt_.max_effort_))
104 RCLCPP_WARN(logger,
"Unable to set the effort command to: %f", command_struct_rt_.max_effort_);
105 return controller_interface::return_type::OK;
108 return controller_interface::return_type::OK;
111rclcpp_action::GoalResponse GripperActionController::goal_callback(
112 const rclcpp_action::GoalUUID &, std::shared_ptr<const GripperCommandAction::Goal> goal_handle)
114 if (goal_handle->command.position.size() != 1)
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);
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;
126 RCLCPP_INFO(get_node()->get_logger(),
"Received & accepted new action goal");
127 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
130void GripperActionController::accepted_callback(
131 std::shared_ptr<GoalHandle> goal_handle)
133 auto rt_goal = std::make_shared<RealtimeGoalHandle>(goal_handle);
136 preempt_active_goal();
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())
143 command_struct_.max_velocity_ = goal_handle->get_goal()->command.velocity[0];
147 command_struct_.max_velocity_ = params_.max_velocity;
149 if (!params_.max_effort_interface.empty() && !goal_handle->get_goal()->command.effort.empty())
151 command_struct_.max_effort_ = goal_handle->get_goal()->command.effort[0];
155 command_struct_.max_effort_ = params_.max_effort;
157 command_.set(command_struct_);
159 pre_alloc_result_->reached_goal =
false;
160 pre_alloc_result_->stalled =
false;
164 rt_active_goal_.
set([rt_goal](RealtimeGoalHandlePtr & stored_value) { stored_value = rt_goal; });
167 goal_handle_timer_.reset();
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));
175rclcpp_action::CancelResponse GripperActionController::cancel_callback(
176 const std::shared_ptr<GoalHandle> goal_handle)
178 RCLCPP_INFO(get_node()->get_logger(),
"Got request to cancel goal");
181 RealtimeGoalHandlePtr active_goal;
183 if (active_goal && active_goal->gh_ == goal_handle)
189 get_node()->get_logger(),
"Canceling active action goal because cancel callback received.");
192 auto action_res = std::make_shared<GripperCommandAction::Result>();
193 active_goal->setCanceled(action_res);
196 { stored_value = RealtimeGoalHandlePtr(); });
198 return rclcpp_action::CancelResponse::ACCEPT;
201void GripperActionController::set_hold_position()
203 const auto position_op = joint_position_state_interface_->get().get_optional();
204 if (!position_op.has_value())
206 RCLCPP_DEBUG(get_node()->get_logger(),
"Unable to retrieve data of joint position");
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_);
215 const rclcpp::Time & time,
double error_position,
double current_position,
216 double current_velocity)
218 RealtimeGoalHandlePtr active_goal;
225 if (fabs(error_position) < params_.goal_tolerance)
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_);
234 { stored_value = RealtimeGoalHandlePtr(); });
238 if (fabs(current_velocity) > params_.stall_velocity_threshold)
245 pre_alloc_result_->state.position[0] = current_position;
246 pre_alloc_result_->reached_goal =
false;
247 pre_alloc_result_->stalled =
true;
249 if (params_.allow_stalling)
251 RCLCPP_DEBUG(get_node()->get_logger(),
"Stall detected moving to goal. Returning success.");
252 active_goal->setSucceeded(pre_alloc_result_);
256 RCLCPP_DEBUG(get_node()->get_logger(),
"Stall detected moving to goal. Aborting action!");
257 active_goal->setAborted(pre_alloc_result_);
260 { stored_value = RealtimeGoalHandlePtr(); });
265controller_interface::CallbackReturn GripperActionController::on_configure(
266 const rclcpp_lifecycle::State &)
268 const auto logger = get_node()->get_logger();
269 params_ = param_listener_->get_params();
272 action_monitor_period_ = rclcpp::Duration::from_seconds(1.0 / params_.action_monitor_rate);
274 logger,
"Action status changes will be monitored at %f Hz.", params_.action_monitor_rate);
277 if (params_.joint.empty())
279 RCLCPP_ERROR(logger,
"Joint name cannot be empty");
280 return controller_interface::CallbackReturn::ERROR;
282 RCLCPP_INFO(logger,
"Joint name is : %s", params_.joint.c_str());
284 return controller_interface::CallbackReturn::SUCCESS;
287controller_interface::CallbackReturn GripperActionController::on_activate(
288 const rclcpp_lifecycle::State &)
290 auto command_interface_it = std::find_if(
293 { return command_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
297 get_node()->get_logger(),
"Expected 1 %s command interface",
299 return controller_interface::CallbackReturn::ERROR;
301 if (command_interface_it->get_prefix_name() != params_.joint)
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;
308 const auto position_state_interface_it = std::find_if(
311 { return state_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
314 RCLCPP_ERROR(get_node()->get_logger(),
"Expected 1 position state interface");
315 return controller_interface::CallbackReturn::ERROR;
317 if (position_state_interface_it->get_prefix_name() != params_.joint)
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;
325 const auto velocity_state_interface_it = std::find_if(
328 { return state_interface.get_interface_name() == hardware_interface::HW_IF_VELOCITY; });
331 RCLCPP_ERROR(get_node()->get_logger(),
"Expected 1 velocity state interface");
332 return controller_interface::CallbackReturn::ERROR;
334 if (velocity_state_interface_it->get_prefix_name() != params_.joint)
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;
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;
349 if (interface.get_interface_name() ==
"set_gripper_max_effort")
351 effort_interface_ = interface;
353 else if (interface.get_interface_name() ==
"set_gripper_max_velocity")
355 speed_interface_ = interface;
360 const auto position_op = joint_position_state_interface_->get().get_optional();
361 if (!position_op.has_value())
363 RCLCPP_DEBUG(get_node()->get_logger(),
"Unable to retrieve data of joint position");
367 command_struct_.position_cmd_ = position_op.value();
369 command_struct_.max_effort_ = params_.max_effort;
370 command_struct_.max_velocity_ = params_.max_velocity;
371 command_.try_set(command_struct_);
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;
382 action_server_ = rclcpp_action::create_server<control_msgs::action::ParallelGripperCommand>(
383 get_node(),
"~/gripper_cmd",
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));
389 return controller_interface::CallbackReturn::SUCCESS;
392controller_interface::CallbackReturn GripperActionController::on_deactivate(
393 const rclcpp_lifecycle::State &)
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;
405 if (!params_.max_effort_interface.empty())
407 names.push_back({params_.max_effort_interface});
409 if (!params_.max_velocity_interface.empty())
411 names.push_back({params_.max_velocity_interface});
414 return {controller_interface::interface_configuration_type::INDIVIDUAL, names};
420 std::vector<std::string> interface_names;
421 for (
const auto & interface : params_.state_interfaces)
423 interface_names.push_back(params_.joint +
"/" + interface);
425 return {controller_interface::interface_configuration_type::INDIVIDUAL, interface_names};
428GripperActionController::GripperActionController()
429: controller_interface::ControllerInterface(),
430 action_monitor_period_(rclcpp::Duration::from_seconds(0))
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
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