hardware_interface_adapter.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #ifndef JOINT_TRAJECTORY_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H
31 #define JOINT_TRAJECTORY_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H
32 
33 #include <cassert>
34 #include <string>
35 #include <vector>
36 
37 #include <boost/shared_ptr.hpp>
38 
39 #include <ros/node_handle.h>
40 #include <ros/time.h>
41 
42 #include <control_toolbox/pid.h>
46 
56 template <class HardwareInterface, class State>
58 {
59 public:
60  bool init(std::vector<typename HardwareInterface::ResourceHandleType>& /*joint_handles*/, ros::NodeHandle& /*controller_nh*/)
61  {
62  return false;
63  }
64 
65  void starting(const ros::Time& /*time*/) {}
66  void stopping(const ros::Time& /*time*/) {}
67 
68  void updateCommand(const ros::Time& /*time*/,
69  const ros::Duration& /*period*/,
70  const State& /*desired_state*/,
71  const State& /*state_error*/) {}
72 };
73 
94 template <class State>
95 class HardwareInterfaceAdapter<hardware_interface::PositionJointInterface, State>
96 {
97 public:
98  HardwareInterfaceAdapter() : joint_handles_ptr_(0) {}
99 
100  bool init(std::vector<hardware_interface::JointHandle>& joint_handles, ros::NodeHandle& /*controller_nh*/)
101  {
102  // Store pointer to joint handles
103  joint_handles_ptr_ = &joint_handles;
104 
105  return true;
106  }
107 
108  void starting(const ros::Time& /*time*/)
109  {
110  if (!joint_handles_ptr_) {return;}
111 
112  // Semantic zero for commands
113  for (unsigned int i = 0; i < joint_handles_ptr_->size(); ++i)
114  {
115  (*joint_handles_ptr_)[i].setCommand((*joint_handles_ptr_)[i].getPosition());
116  }
117  }
118 
119  void stopping(const ros::Time& /*time*/) {}
120 
121  void updateCommand(const ros::Time& /*time*/,
122  const ros::Duration& /*period*/,
123  const State& desired_state,
124  const State& /*state_error*/)
125  {
126  // Forward desired position to command
127  const unsigned int n_joints = joint_handles_ptr_->size();
128  for (unsigned int i = 0; i < n_joints; ++i) {(*joint_handles_ptr_)[i].setCommand(desired_state.position[i]);}
129  }
130 
131 private:
132  std::vector<hardware_interface::JointHandle>* joint_handles_ptr_;
133 };
134 
144 template <class State>
146 {
147 public:
148  ClosedLoopHardwareInterfaceAdapter() : joint_handles_ptr_(0) {}
149 
150  bool init(std::vector<hardware_interface::JointHandle>& joint_handles, ros::NodeHandle& controller_nh)
151  {
152  // Store pointer to joint handles
153  joint_handles_ptr_ = &joint_handles;
154 
155  // Initialize PIDs
156  pids_.resize(joint_handles.size());
157  for (unsigned int i = 0; i < pids_.size(); ++i)
158  {
159  // Node handle to PID gains
160  ros::NodeHandle joint_nh(controller_nh, std::string("gains/") + joint_handles[i].getName());
161 
162  // Init PID gains from ROS parameter server
163  pids_[i].reset(new control_toolbox::Pid());
164  if (!pids_[i]->init(joint_nh))
165  {
166  ROS_WARN_STREAM("Failed to initialize PID gains from ROS parameter server.");
167  return false;
168  }
169  }
170 
171  // Load velocity feedforward gains from parameter server
172  velocity_ff_.resize(joint_handles.size());
173  for (unsigned int i = 0; i < velocity_ff_.size(); ++i)
174  {
175  controller_nh.param(std::string("velocity_ff/") + joint_handles[i].getName(), velocity_ff_[i], 0.0);
176  }
177 
178  return true;
179  }
180 
181  void starting(const ros::Time& /*time*/)
182  {
183  if (!joint_handles_ptr_) {return;}
184 
185  // Reset PIDs, zero commands
186  for (unsigned int i = 0; i < pids_.size(); ++i)
187  {
188  pids_[i]->reset();
189  (*joint_handles_ptr_)[i].setCommand(0.0);
190  }
191  }
192 
193  void stopping(const ros::Time& /*time*/) {}
194 
195  void updateCommand(const ros::Time& /*time*/,
196  const ros::Duration& period,
197  const State& desired_state,
198  const State& state_error)
199  {
200  const unsigned int n_joints = joint_handles_ptr_->size();
201 
202  // Preconditions
203  if (!joint_handles_ptr_)
204  return;
205  assert(n_joints == state_error.position.size());
206  assert(n_joints == state_error.velocity.size());
207 
208  // Update PIDs
209  for (unsigned int i = 0; i < n_joints; ++i)
210  {
211  const double command = (desired_state.velocity[i] * velocity_ff_[i]) + pids_[i]->computeCommand(state_error.position[i], state_error.velocity[i], period);
212  (*joint_handles_ptr_)[i].setCommand(command);
213  }
214  }
215 
216 private:
218  std::vector<PidPtr> pids_;
219 
220  std::vector<double> velocity_ff_;
221 
222  std::vector<hardware_interface::JointHandle>* joint_handles_ptr_;
223 };
224 
252 template <class State>
253 class HardwareInterfaceAdapter<hardware_interface::VelocityJointInterface, State> : public ClosedLoopHardwareInterfaceAdapter<State>
254 {};
255 
283 template <class State>
284 class HardwareInterfaceAdapter<hardware_interface::EffortJointInterface, State> : public ClosedLoopHardwareInterfaceAdapter<State>
285 {};
286 
290 template <class State>
291 class HardwareInterfaceAdapter<hardware_interface::PosVelJointInterface, State>
292 {
293 public:
294  HardwareInterfaceAdapter() : joint_handles_ptr_(0) {}
295 
296  bool init(std::vector<hardware_interface::PosVelJointHandle>& joint_handles, ros::NodeHandle& /*controller_nh*/)
297  {
298  // Store pointer to joint handles
299  joint_handles_ptr_ = &joint_handles;
300 
301  return true;
302  }
303 
304  void starting(const ros::Time& /*time*/) {}
305  void stopping(const ros::Time& /*time*/) {}
306 
307  void updateCommand(const ros::Time& /*time*/,
308  const ros::Duration& /*period*/,
309  const State& desired_state,
310  const State& /*state_error*/)
311  {
312  // Forward desired position to command
313  const unsigned int n_joints = joint_handles_ptr_->size();
314  for (unsigned int i = 0; i < n_joints; ++i)
315  {
316  (*joint_handles_ptr_)[i].setCommand(desired_state.position[i], desired_state.velocity[i]);
317  }
318  }
319 
320 private:
321  std::vector<hardware_interface::PosVelJointHandle>* joint_handles_ptr_;
322 };
323 
327 template <class State>
328 class HardwareInterfaceAdapter<hardware_interface::PosVelAccJointInterface, State>
329 {
330 public:
331  HardwareInterfaceAdapter() : joint_handles_ptr_(0) {}
332 
333  bool init(std::vector<hardware_interface::PosVelAccJointHandle>& joint_handles, ros::NodeHandle& /*controller_nh*/)
334  {
335  // Store pointer to joint handles
336  joint_handles_ptr_ = &joint_handles;
337 
338  return true;
339  }
340 
341  void starting(const ros::Time& /*time*/) {}
342  void stopping(const ros::Time& /*time*/) {}
343 
344  void updateCommand(const ros::Time& /*time*/,
345  const ros::Duration& /*period*/,
346  const State& desired_state,
347  const State& /*state_error*/)
348  {
349  // Forward desired position to command
350  const unsigned int n_joints = joint_handles_ptr_->size();
351  for (unsigned int i = 0; i < n_joints; ++i)
352  {
353  (*joint_handles_ptr_)[i].setCommand(desired_state.position[i], desired_state.velocity[i], desired_state.acceleration[i]);
354  }
355  }
356 
357 private:
358  std::vector<hardware_interface::PosVelAccJointHandle>* joint_handles_ptr_;
359 };
360 
361 #endif // header guard
boost::shared_ptr< control_toolbox::Pid > PidPtr
void updateCommand(const ros::Time &, const ros::Duration &, const State &desired_state, const State &)
bool init(std::vector< typename HardwareInterface::ResourceHandleType > &, ros::NodeHandle &)
std::vector< hardware_interface::PosVelAccJointHandle > * joint_handles_ptr_
void stopping(const ros::Time &)
std::string getName(void *handle)
bool init(std::vector< hardware_interface::JointHandle > &joint_handles, ros::NodeHandle &controller_nh)
bool init(std::vector< hardware_interface::JointHandle > &joint_handles, ros::NodeHandle &)
std::vector< hardware_interface::JointHandle > * joint_handles_ptr_
std::vector< hardware_interface::PosVelJointHandle > * joint_handles_ptr_
void updateCommand(const ros::Time &, const ros::Duration &period, const State &desired_state, const State &state_error)
ROSLIB_DECL std::string command(const std::string &cmd)
Helper base class template for closed loop HardwareInterfaceAdapter implementations.
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 &, const State &)
void updateCommand(const ros::Time &, const ros::Duration &, const State &desired_state, const State &)
#define ROS_WARN_STREAM(args)
Helper class to simplify integrating the JointTrajectoryController with different hardware interfaces...
void starting(const ros::Time &)
bool init(std::vector< hardware_interface::PosVelAccJointHandle > &joint_handles, ros::NodeHandle &)
bool init(std::vector< hardware_interface::PosVelJointHandle > &joint_handles, ros::NodeHandle &)
void updateCommand(const ros::Time &, const ros::Duration &, const State &desired_state, const State &)


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Apr 11 2019 03:08:37