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


scaled_joint_trajectory_controller
Author(s):
autogenerated on Wed May 18 2022 02:43:18