ros2_control - rolling
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 
26 #include "control_toolbox/pid.hpp"
27 #include "hardware_interface/types/hardware_interface_type_values.hpp"
28 #include "rclcpp/time.hpp"
29 #include "rclcpp_lifecycle/lifecycle_node.hpp"
30 
39 template <const char * HardwareInterface>
41 {
42 public:
43  bool init(
44  std::optional<
45  std::reference_wrapper<hardware_interface::LoanedCommandInterface>> /* joint_handle */,
46  std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & /* node */)
47  {
48  return false;
49  }
50 
51  void starting(const rclcpp::Time & /* time */) {}
52  void stopping(const rclcpp::Time & /* time */) {}
53 
54  double updateCommand(
55  double /* desired_position */, double /* desired_velocity */, double /* error_position */,
56  double /* error_velocity */, double /* max_allowed_effort */)
57  {
58  return 0.0;
59  }
60 };
61 
66 template <>
68 {
69 public:
70  bool init(
71  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle,
72  const rclcpp_lifecycle::LifecycleNode::SharedPtr & /* node */)
73  {
74  joint_handle_ = joint_handle;
75  return true;
76  }
77 
78  void starting(const rclcpp::Time & /* time */) {}
79  void stopping(const rclcpp::Time & /* time */) {}
80 
81  double updateCommand(
82  double desired_position, double /* desired_velocity */, double /* error_position */,
83  double /* error_velocity */, double max_allowed_effort)
84  {
85  // Forward desired position to command
86  joint_handle_->get().set_value(desired_position);
87  return max_allowed_effort;
88  }
89 
90 private:
91  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle_;
92 };
93 
108 template <>
110 {
111 public:
112  template <typename ParameterT>
113  auto auto_declare(
114  const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const std::string & name,
115  const ParameterT & default_value)
116  {
117  if (!node->has_parameter(name))
118  {
119  return node->declare_parameter<ParameterT>(name, default_value);
120  }
121  else
122  {
123  return node->get_parameter(name).get_value<ParameterT>();
124  }
125  }
126 
127  bool init(
128  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle,
129  const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node)
130  {
131  joint_handle_ = joint_handle;
132  // Init PID gains from ROS parameter server
133  const std::string prefix = "gains." + joint_handle_->get().get_prefix_name();
134  const auto k_p = auto_declare<double>(node, prefix + ".p", 0.0);
135  const auto k_i = auto_declare<double>(node, prefix + ".i", 0.0);
136  const auto k_d = auto_declare<double>(node, prefix + ".d", 0.0);
137  const auto i_clamp = auto_declare<double>(node, prefix + ".i_clamp", 0.0);
138  // Initialize PID
139  pid_ = std::make_shared<control_toolbox::Pid>(k_p, k_i, k_d, i_clamp, -i_clamp);
140  return true;
141  }
142 
143  void starting(const rclcpp::Time & /* time */)
144  {
145  if (!joint_handle_)
146  {
147  return;
148  }
149  // Reset PIDs, zero effort commands
150  pid_->reset();
151  joint_handle_->get().set_value(0.0);
152  }
153 
154  void stopping(const rclcpp::Time & /* time */) {}
155 
156  double updateCommand(
157  double /* desired_position */, double /* desired_velocity */, double error_position,
158  double error_velocity, double max_allowed_effort)
159  {
160  // Preconditions
161  if (!joint_handle_)
162  {
163  return 0.0;
164  }
165  // Time since the last call to update
166  const auto period = std::chrono::steady_clock::now() - last_update_time_;
167  // Update PIDs
168  double command = pid_->computeCommand(error_position, error_velocity, period.count());
169  command = std::min<double>(
170  fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
171  joint_handle_->get().set_value(command);
172  last_update_time_ = std::chrono::steady_clock::now();
173  return command;
174  }
175 
176 private:
177  using PidPtr = std::shared_ptr<control_toolbox::Pid>;
178  PidPtr pid_;
179  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle_;
180  std::chrono::steady_clock::time_point last_update_time_;
181 };
182 
183 #endif // GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition: hardware_interface_adapter.hpp:41
Definition: actuator.hpp:34