hardware_interface_adapter.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // Copyright 2019 FZI Forschungszentrum Informatik
5 //
6 // Licensed under the Apache License, Version 2.0 (the "License");
7 // you may not use this file except in compliance with the License.
8 // You may obtain a copy of the License at
9 //
10 // http://www.apache.org/licenses/LICENSE-2.0
11 //
12 // Unless required by applicable law or agreed to in writing, software
13 // distributed under the License is distributed on an "AS IS" BASIS,
14 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 // See the License for the specific language governing permissions and
16 // limitations under the License.
17 // -- END LICENSE BLOCK ------------------------------------------------
18 
19 //----------------------------------------------------------------------
26 //----------------------------------------------------------------------
27 
28 #ifndef UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
29 #define UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
30 
33 
54 template <class State>
55 class HardwareInterfaceAdapter<ur_controllers::ScaledPositionJointInterface, State>
56 {
57 public:
58  HardwareInterfaceAdapter() : joint_handles_ptr_(0)
59  {
60  }
61 
62  bool init(std::vector<ur_controllers::ScaledJointHandle>& joint_handles, ros::NodeHandle& /*controller_nh*/)
63  {
64  // Store pointer to joint handles
65  joint_handles_ptr_ = &joint_handles;
66 
67  return true;
68  }
69 
70  void starting(const ros::Time& /*time*/)
71  {
72  if (!joint_handles_ptr_)
73  {
74  return;
75  }
76 
77  // Semantic zero for commands
78  for (auto& jh : *joint_handles_ptr_)
79  {
80  jh.setCommand(jh.getPosition());
81  }
82  }
83 
84  void stopping(const ros::Time& /*time*/)
85  {
86  }
87 
88  void updateCommand(const ros::Time& /*time*/, const ros::Duration& /*period*/, const State& desired_state,
89  const State& /*state_error*/)
90  {
91  // Forward desired position to command
92  const unsigned int n_joints = joint_handles_ptr_->size();
93  for (unsigned int i = 0; i < n_joints; ++i)
94  {
95  (*joint_handles_ptr_)[i].setCommand(desired_state.position[i]);
96  }
97  }
98 
99 private:
100  std::vector<ur_controllers::ScaledJointHandle>* joint_handles_ptr_;
101 };
102 
103 namespace ur_controllers
104 {
114 template <class State>
116 {
117 public:
118  ClosedLoopHardwareInterfaceAdapter() : joint_handles_ptr_(0)
119  {
120  }
121 
122  bool init(std::vector<ur_controllers::ScaledJointHandle>& joint_handles, ros::NodeHandle& controller_nh)
123  {
124  // Store pointer to joint handles
125  joint_handles_ptr_ = &joint_handles;
126 
127  // Initialize PIDs
128  pids_.resize(joint_handles.size());
129  for (unsigned int i = 0; i < pids_.size(); ++i)
130  {
131  // Node handle to PID gains
132  ros::NodeHandle joint_nh(controller_nh, std::string("gains/") + joint_handles[i].getName());
133 
134  // Init PID gains from ROS parameter server
135  pids_[i].reset(new control_toolbox::Pid());
136  if (!pids_[i]->init(joint_nh))
137  {
138  ROS_WARN_STREAM("Failed to initialize PID gains from ROS parameter server.");
139  return false;
140  }
141  }
142 
143  // Load velocity feedforward gains from parameter server
144  velocity_ff_.resize(joint_handles.size());
145  for (unsigned int i = 0; i < velocity_ff_.size(); ++i)
146  {
147  controller_nh.param(std::string("velocity_ff/") + joint_handles[i].getName(), velocity_ff_[i], 0.0);
148  }
149 
150  return true;
151  }
152 
153  void starting(const ros::Time& /*time*/)
154  {
155  if (!joint_handles_ptr_)
156  {
157  return;
158  }
159 
160  // Reset PIDs, zero commands
161  for (unsigned int i = 0; i < pids_.size(); ++i)
162  {
163  pids_[i]->reset();
164  (*joint_handles_ptr_)[i].setCommand(0.0);
165  }
166  }
167 
168  void stopping(const ros::Time& /*time*/)
169  {
170  }
171 
172  void updateCommand(const ros::Time& /*time*/, const ros::Duration& period, const State& desired_state,
173  const State& state_error)
174  {
175  const unsigned int n_joints = joint_handles_ptr_->size();
176 
177  // Preconditions
178  if (!joint_handles_ptr_)
179  return;
180  assert(n_joints == state_error.position.size());
181  assert(n_joints == state_error.velocity.size());
182 
183  // Update PIDs
184  for (unsigned int i = 0; i < n_joints; ++i)
185  {
186  const double command = (desired_state.velocity[i] * velocity_ff_[i]) +
187  pids_[i]->computeCommand(state_error.position[i], state_error.velocity[i], period);
188  (*joint_handles_ptr_)[i].setCommand(command);
189  }
190  }
191 
192 private:
193  typedef std::shared_ptr<control_toolbox::Pid> PidPtr;
194  std::vector<PidPtr> pids_;
195 
196  std::vector<double> velocity_ff_;
197 
198  std::vector<ur_controllers::ScaledJointHandle>* joint_handles_ptr_;
199 };
200 } // namespace ur_controllers
201 
225 template <class State>
226 class HardwareInterfaceAdapter<ur_controllers::ScaledVelocityJointInterface, State>
228 {
229 };
230 
231 #endif // ifndef UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
void updateCommand(const ros::Time &, const ros::Duration &period, const State &desired_state, const State &state_error)
std::vector< ur_controllers::ScaledJointHandle > * joint_handles_ptr_
Helper base class template for closed loop HardwareInterfaceAdapter implementations.
bool init(std::vector< typename HardwareInterface::ResourceHandleType > &, ros::NodeHandle &)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSLIB_DECL std::string command(const std::string &cmd)
void updateCommand(const ros::Time &, const ros::Duration &, const State &desired_state, const State &)
#define ROS_WARN_STREAM(args)
bool init(std::vector< ur_controllers::ScaledJointHandle > &joint_handles, ros::NodeHandle &)
bool init(std::vector< ur_controllers::ScaledJointHandle > &joint_handles, ros::NodeHandle &controller_nh)


ur_controllers
Author(s):
autogenerated on Sun Aug 22 2021 02:38:05