ros2_control - rolling
Loading...
Searching...
No Matches
gripper_action_controller.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_HPP_
18#define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
19
20// C++ standard
21#include <cassert>
22#include <memory>
23#include <stdexcept>
24#include <string>
25
26// ROS
27#include "rclcpp/rclcpp.hpp"
28
29// ROS messages
30#include "control_msgs/action/gripper_command.hpp"
31
32// rclcpp_action
33#include "rclcpp_action/create_server.hpp"
34
35// ros_controls
36#include "controller_interface/controller_interface.hpp"
37#include "hardware_interface/loaned_command_interface.hpp"
38#include "hardware_interface/loaned_state_interface.hpp"
39#include "realtime_tools/realtime_buffer.hpp"
40#include "realtime_tools/realtime_server_goal_handle.hpp"
41
42// Project
43#include "gripper_controllers/hardware_interface_adapter.hpp"
44
45// auto-generated by generate_parameter_library
46#include "gripper_controllers/gripper_action_controller_parameters.hpp"
47
49{
58template <const char * HardwareInterface>
60{
61public:
66 struct Commands
67 {
68 double position_; // Last commanded position
69 double max_effort_; // Max allowed effort
70 };
72
78
84
85 controller_interface::return_type update(
86 const rclcpp::Time & time, const rclcpp::Duration & period) override;
87
88 controller_interface::CallbackReturn on_init() override;
89
90 controller_interface::CallbackReturn on_configure(
91 const rclcpp_lifecycle::State & previous_state) override;
92
93 controller_interface::CallbackReturn on_activate(
94 const rclcpp_lifecycle::State & previous_state) override;
95
96 controller_interface::CallbackReturn on_deactivate(
97 const rclcpp_lifecycle::State & previous_state) override;
98
100 // pre-allocated memory that is re-used to set the realtime buffer
101 Commands command_struct_, command_struct_rt_;
102
103protected:
104 using GripperCommandAction = control_msgs::action::GripperCommand;
105 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
106 using ActionServerPtr = ActionServer::SharedPtr;
107 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
108 using RealtimeGoalHandle =
110 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
112
114
115 bool update_hold_position_;
116
117 bool verbose_ = false;
118 std::string name_;
119 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
120 joint_command_interface_;
121 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
122 joint_position_state_interface_;
123 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
124 joint_velocity_state_interface_;
125
126 std::shared_ptr<ParamListener> param_listener_;
127 Params params_;
128
130
133 control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
134
135 rclcpp::Duration action_monitor_period_;
136
137 // ROS API
138 ActionServerPtr action_server_;
139
140 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
141
142 rclcpp_action::GoalResponse goal_callback(
143 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
144
145 rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle);
146
147 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
148
149 void preempt_active_goal();
150
151 void set_hold_position();
152
153 rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
155
160 const rclcpp::Time & time, double error_position, double current_position,
161 double current_velocity);
162};
163
164} // namespace gripper_action_controller
165
166#include "gripper_controllers/gripper_action_controller_impl.hpp"
167
168#endif // GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition hardware_interface_adapter.hpp:41
Definition controller_interface.hpp:27
Controller for executing a gripper command action for simple single-dof grippers.
Definition gripper_action_controller.hpp:60
std::string name_
Controller name.
Definition gripper_action_controller.hpp:118
RealtimeGoalHandleBuffer rt_active_goal_
Container for the currently active action goal, if any.
Definition gripper_action_controller.hpp:132
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition gripper_action_controller_impl.hpp:41
HwIfaceAdapter hw_iface_adapter_
Adapts desired goal state to HW interface.
Definition gripper_action_controller.hpp:129
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:338
double computed_command_
Computed command.
Definition gripper_action_controller.hpp:154
bool verbose_
Hard coded verbose flag to help in debugging.
Definition gripper_action_controller.hpp:117
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:156
rclcpp::Time last_movement_time_
Store stall time.
Definition gripper_action_controller.hpp:153
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:329
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition gripper_action_controller_impl.hpp:63
Definition realtime_buffer.hpp:44
Definition realtime_server_goal_handle.hpp:44
Definition gripper_action_controller.hpp:49
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57
Store position and max effort in struct to allow easier realtime buffer usage.
Definition gripper_action_controller.hpp:67