ros2_control - galactic
Loading...
Searching...
No Matches
hardware_interface_adapter.hpp
1// Copyright 2014, SRI International
2// Copyright 2013, PAL Robotics S.L.
3//
4// Licensed under the Apache License, Version 2.0 (the "License");
5// you may not use this file except in compliance with the License.
6// You may obtain a copy of the License at
7//
8// http://www.apache.org/licenses/LICENSE-2.0
9//
10// Unless required by applicable law or agreed to in writing, software
11// distributed under the License is distributed on an "AS IS" BASIS,
12// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13// See the License for the specific language governing permissions and
14// limitations under the License.
15
17
18#ifndef GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
19#define GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
20
21#include <algorithm>
22#include <cassert>
23#include <memory>
24#include <string>
25#include <vector>
26// TODO(JafarAbdi): Remove experimental once the default standard is C++17
27#include "experimental/optional"
28
29#include "rclcpp/time.hpp"
30
31#include "control_toolbox/pid.hpp"
32#include "hardware_interface/types/hardware_interface_type_values.hpp"
33
42template <const char * HardwareInterface>
44{
45public:
46 bool init(
47 std::experimental::optional<
48 std::reference_wrapper<hardware_interface::LoanedCommandInterface>> /* joint_handle */,
49 const rclcpp::Node::SharedPtr & /* node */)
50 {
51 return false;
52 }
53
54 void starting(const rclcpp::Time & /* time */) {}
55 void stopping(const rclcpp::Time & /* time */) {}
56
57 double updateCommand(
58 double /* desired_position */, double /* desired_velocity */, double /* error_position */,
59 double /* error_velocity */, double /* max_allowed_effort */)
60 {
61 return 0.0;
62 }
63};
64
69template <>
71{
72public:
73 bool init(
74 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
75 joint_handle,
76 const rclcpp::Node::SharedPtr & /* node */)
77 {
78 joint_handle_ = joint_handle;
79 return true;
80 }
81
82 void starting(const rclcpp::Time & /* time */) {}
83 void stopping(const rclcpp::Time & /* time */) {}
84
85 double updateCommand(
86 double desired_position, double /* desired_velocity */, double /* error_position */,
87 double /* error_velocity */, double max_allowed_effort)
88 {
89 // Forward desired position to command
90 joint_handle_->get().set_value(desired_position);
91 return max_allowed_effort;
92 }
93
94private:
95 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
96 joint_handle_;
97};
98
113template <>
115{
116public:
117 template <typename ParameterT>
118 auto auto_declare(
119 const rclcpp::Node::SharedPtr & node, const std::string & name,
120 const ParameterT & default_value)
121 {
122 if (!node->has_parameter(name))
123 {
124 return node->declare_parameter<ParameterT>(name, default_value);
125 }
126 else
127 {
128 return node->get_parameter(name).get_value<ParameterT>();
129 }
130 }
131
132 bool init(
133 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
134 joint_handle,
135 const rclcpp::Node::SharedPtr & node)
136 {
137 joint_handle_ = joint_handle;
138 // Init PID gains from ROS parameter server
139 const std::string prefix = "gains." + joint_handle_->get().get_name();
140 const auto k_p = auto_declare<double>(node, prefix + ".p", 0.0);
141 const auto k_i = auto_declare<double>(node, prefix + ".i", 0.0);
142 const auto k_d = auto_declare<double>(node, prefix + ".d", 0.0);
143 const auto i_clamp = auto_declare<double>(node, prefix + ".i_clamp", 0.0);
144 // Initialize PID
145 pid_ = std::make_shared<control_toolbox::Pid>(k_p, k_i, k_d, i_clamp, -i_clamp);
146 return true;
147 }
148
149 void starting(const rclcpp::Time & /* time */)
150 {
151 if (!joint_handle_)
152 {
153 return;
154 }
155 // Reset PIDs, zero effort commands
156 pid_->reset();
157 joint_handle_->get().set_value(0.0);
158 }
159
160 void stopping(const rclcpp::Time & /* time */) {}
161
162 double updateCommand(
163 double /* desired_position */, double /* desired_velocity */, double error_position,
164 double error_velocity, double max_allowed_effort)
165 {
166 // Preconditions
167 if (!joint_handle_)
168 {
169 return 0.0;
170 }
171 // Time since the last call to update
172 const auto period = std::chrono::steady_clock::now() - last_update_time_;
173 // Update PIDs
174 double command = pid_->computeCommand(error_position, error_velocity, period.count());
175 command = std::min<double>(
176 fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
177 joint_handle_->get().set_value(command);
178 last_update_time_ = std::chrono::steady_clock::now();
179 return command;
180 }
181
182private:
183 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
184 PidPtr pid_;
185 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
186 joint_handle_;
187 std::chrono::steady_clock::time_point last_update_time_;
188};
189
190#endif // GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition hardware_interface_adapter.hpp:44
Definition actuator.hpp:29