17#ifndef GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
18#define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
20#include "gripper_controllers/gripper_action_controller.hpp"
27template <const
char * HardwareInterface>
28void GripperActionController<HardwareInterface>::preempt_active_goal()
31 const auto active_goal = *rt_active_goal_.readFromNonRT();
35 active_goal->setCanceled(std::make_shared<GripperCommandAction::Result>());
36 rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
40template <const
char * HardwareInterface>
45 param_listener_ = std::make_shared<ParamListener>(get_node());
46 params_ = param_listener_->get_params();
48 catch (
const std::exception & e)
50 fprintf(stderr,
"Exception thrown during init stage with message: %s \n", e.what());
51 return controller_interface::CallbackReturn::ERROR;
54 return controller_interface::CallbackReturn::SUCCESS;
57template <const
char * HardwareInterface>
59 const rclcpp::Time & ,
const rclcpp::Duration & )
61 command_struct_rt_ = *(command_.readFromRT());
63 const double current_position = joint_position_state_interface_->get().get_value();
64 const double current_velocity = joint_velocity_state_interface_->get().get_value();
66 const double error_position = command_struct_rt_.position_ - current_position;
67 const double error_velocity = -current_velocity;
69 check_for_success(get_node()->now(), error_position, current_position, current_velocity);
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;
78template <const
char * HardwareInterface>
80 const rclcpp_action::GoalUUID &, std::shared_ptr<const GripperCommandAction::Goal>)
82 RCLCPP_INFO(get_node()->get_logger(),
"Received & accepted new action goal");
83 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
86template <const
char * HardwareInterface>
87void GripperActionController<HardwareInterface>::accepted_callback(
88 std::shared_ptr<GoalHandle> goal_handle)
90 auto rt_goal = std::make_shared<RealtimeGoalHandle>(goal_handle);
93 preempt_active_goal();
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_);
101 pre_alloc_result_->reached_goal =
false;
102 pre_alloc_result_->stalled =
false;
104 last_movement_time_ = get_node()->now();
106 rt_active_goal_.writeFromNonRT(rt_goal);
109 goal_handle_timer_.reset();
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));
117template <const
char * HardwareInterface>
118rclcpp_action::CancelResponse GripperActionController<HardwareInterface>::cancel_callback(
119 const std::shared_ptr<GoalHandle> goal_handle)
121 RCLCPP_INFO(get_node()->get_logger(),
"Got request to cancel goal");
124 const auto active_goal = *rt_active_goal_.readFromNonRT();
125 if (active_goal && active_goal->gh_ == goal_handle)
131 get_node()->get_logger(),
"Canceling active action goal because cancel callback received.");
134 auto action_res = std::make_shared<GripperCommandAction::Result>();
135 active_goal->setCanceled(action_res);
137 rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
139 return rclcpp_action::CancelResponse::ACCEPT;
142template <const
char * HardwareInterface>
143void GripperActionController<HardwareInterface>::set_hold_position()
145 command_struct_.position_ = joint_position_state_interface_->get().get_value();
146 command_struct_.max_effort_ = params_.max_effort;
147 command_.writeFromNonRT(command_struct_);
150template <const
char * HardwareInterface>
152 const rclcpp::Time & time,
double error_position,
double current_position,
153 double current_velocity)
155 const auto active_goal = *rt_active_goal_.readFromNonRT();
161 if (fabs(error_position) < params_.goal_tolerance)
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());
173 if (fabs(current_velocity) > params_.stall_velocity_threshold)
175 last_movement_time_ = time;
177 else if ((time - last_movement_time_).seconds() > params_.stall_timeout)
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;
184 if (params_.allow_stalling)
186 RCLCPP_DEBUG(get_node()->get_logger(),
"Stall detected moving to goal. Returning success.");
187 active_goal->setSucceeded(pre_alloc_result_);
191 RCLCPP_DEBUG(get_node()->get_logger(),
"Stall detected moving to goal. Aborting action!");
192 active_goal->setAborted(pre_alloc_result_);
194 rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
199template <const
char * HardwareInterface>
201 const rclcpp_lifecycle::State &)
203 const auto logger = get_node()->get_logger();
204 if (!param_listener_)
206 RCLCPP_ERROR(get_node()->get_logger(),
"Error encountered during init");
207 return controller_interface::CallbackReturn::ERROR;
209 params_ = param_listener_->get_params();
212 action_monitor_period_ = rclcpp::Duration::from_seconds(1.0 / params_.action_monitor_rate);
214 logger,
"Action status changes will be monitored at " << params_.action_monitor_rate <<
"Hz.");
217 if (params_.joint.empty())
219 RCLCPP_ERROR(logger,
"Joint name cannot be empty");
220 return controller_interface::CallbackReturn::ERROR;
223 return controller_interface::CallbackReturn::SUCCESS;
225template <const
char * HardwareInterface>
226controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_activate(
227 const rclcpp_lifecycle::State &)
229 auto command_interface_it = std::find_if(
230 command_interfaces_.begin(), command_interfaces_.end(),
232 { return command_interface.get_interface_name() == HardwareInterface; });
233 if (command_interface_it == command_interfaces_.end())
236 get_node()->get_logger(),
"Expected 1 " << HardwareInterface <<
" command interface");
237 return controller_interface::CallbackReturn::ERROR;
239 if (command_interface_it->get_prefix_name() != params_.joint)
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;
247 const auto position_state_interface_it = std::find_if(
248 state_interfaces_.begin(), state_interfaces_.end(),
250 { return state_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
251 if (position_state_interface_it == state_interfaces_.end())
253 RCLCPP_ERROR(get_node()->get_logger(),
"Expected 1 position state interface");
254 return controller_interface::CallbackReturn::ERROR;
256 if (position_state_interface_it->get_prefix_name() != params_.joint)
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;
264 const auto velocity_state_interface_it = std::find_if(
265 state_interfaces_.begin(), state_interfaces_.end(),
267 { return state_interface.get_interface_name() == hardware_interface::HW_IF_VELOCITY; });
268 if (velocity_state_interface_it == state_interfaces_.end())
270 RCLCPP_ERROR(get_node()->get_logger(),
"Expected 1 velocity state interface");
271 return controller_interface::CallbackReturn::ERROR;
273 if (velocity_state_interface_it->get_prefix_name() != params_.joint)
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;
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;
287 hw_iface_adapter_.init(joint_command_interface_, get_node());
290 command_struct_.position_ = joint_position_state_interface_->get().get_value();
291 command_struct_.max_effort_ = params_.max_effort;
292 command_.initRT(command_struct_);
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;
301 action_server_ = rclcpp_action::create_server<control_msgs::action::GripperCommand>(
302 get_node(),
"~/gripper_cmd",
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));
308 return controller_interface::CallbackReturn::SUCCESS;
311template <const
char * HardwareInterface>
312controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_deactivate(
313 const rclcpp_lifecycle::State &)
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;
322template <const
char * HardwareInterface>
327 controller_interface::interface_configuration_type::INDIVIDUAL,
328 {params_.joint +
"/" + HardwareInterface}};
331template <const
char * HardwareInterface>
336 controller_interface::interface_configuration_type::INDIVIDUAL,
341template <const
char * HardwareInterface>
343: controller_interface::ControllerInterface(),
344 action_monitor_period_(rclcpp::Duration::from_seconds(0))
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