hardware_interface_adapter.h
Go to the documentation of this file.
1 // Copyright (C) 2014, SRI International
3 // Copyright (C) 2013, PAL Robotics S.L.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of SRI International nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #pragma once
32 
33 
34 #include <cassert>
35 #include <string>
36 #include <vector>
37 #include <memory>
38 
39 #include <ros/node_handle.h>
40 #include <ros/time.h>
41 
42 #include <control_toolbox/pid.h>
44 
52 template <class HardwareInterface>
54 {
55 public:
56  bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
57  {
58  return false;
59  }
60 
61  void starting(const ros::Time& time) {}
62  void stopping(const ros::Time& time) {}
63 
64  double updateCommand(const ros::Time& time,
65  const ros::Duration& period,
66  double desired_position,
67  double desired_velocity,
68  double error_position,
69  double error_velocity,
70  double max_allowed_effort) { return 0.0;}
71 
72 };
73 
77 template<>
78 class HardwareInterfaceAdapter<hardware_interface::PositionJointInterface>
79 {
80 public:
81  HardwareInterfaceAdapter() : joint_handle_ptr_(nullptr) {}
82 
83  bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
84  {
85  // Store pointer to joint handles
86  joint_handle_ptr_ = &joint_handle;
87 
88  return true;
89  }
90 
91  void starting(const ros::Time& time) {}
92  void stopping(const ros::Time& time) {}
93 
94  double updateCommand(const ros::Time& /*time*/,
95  const ros::Duration& period,
96  double desired_position,
97  double desired_velocity,
98  double error_position,
99  double error_velocity,
100  double max_allowed_effort)
101  {
102  // Forward desired position to command
103  (*joint_handle_ptr_).setCommand(desired_position);
104  return max_allowed_effort;
105  }
106 
107 private:
109 };
110 
127 template<>
128 class HardwareInterfaceAdapter<hardware_interface::EffortJointInterface>
129 {
130 public:
131  HardwareInterfaceAdapter() : joint_handle_ptr_(nullptr) {}
132 
133  bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
134  {
135  // Store pointer to joint handles
136  joint_handle_ptr_ = &joint_handle;
137 
138  // Initialize PIDs
139  ros::NodeHandle joint_nh(controller_nh, std::string("gains/") + joint_handle.getName());
140 
141  // Init PID gains from ROS parameter server
142  pid_.reset(new control_toolbox::Pid());
143  if (!pid_->init(joint_nh))
144  {
145  ROS_WARN_STREAM("Failed to initialize PID gains from ROS parameter server.");
146  return false;
147  }
148 
149  return true;
150  }
151 
152  void starting(const ros::Time& time)
153  {
154  if (!joint_handle_ptr_)
155  {
156  return;
157  }
158  // Reset PIDs, zero effort commands
159  pid_->reset();
160  (*joint_handle_ptr_).setCommand(0.0);
161  }
162 
163  void stopping(const ros::Time& time) {}
164 
165  double updateCommand(const ros::Time& /*time*/,
166  const ros::Duration& period,
167  double desired_position,
168  double desired_velocity,
169  double error_position,
170  double error_velocity,
171  double max_allowed_effort)
172  {
173  // Preconditions
174  if (!joint_handle_ptr_) {return 0.0;}
175 
176  // Update PIDs
177  double command = pid_->computeCommand(error_position, error_velocity, period);
178  command = std::min<double>(fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
179  (*joint_handle_ptr_).setCommand(command);
180  return command;
181  }
182 
183 private:
184  typedef std::shared_ptr<control_toolbox::Pid> PidPtr;
187 };
HardwareInterfaceAdapter::stopping
void stopping(const ros::Time &time)
Definition: hardware_interface_adapter.h:62
node_handle.h
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::updateCommand
double updateCommand(const ros::Time &, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
Definition: hardware_interface_adapter.h:165
command
ROSLIB_DECL std::string command(const std::string &cmd)
time.h
HardwareInterfaceAdapter::init
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
Definition: hardware_interface_adapter.h:56
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::updateCommand
double updateCommand(const ros::Time &, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
Definition: hardware_interface_adapter.h:94
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::joint_handle_ptr_
hardware_interface::JointHandle * joint_handle_ptr_
Definition: hardware_interface_adapter.h:186
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::joint_handle_ptr_
hardware_interface::JointHandle * joint_handle_ptr_
Definition: hardware_interface_adapter.h:108
HardwareInterfaceAdapter::starting
void starting(const ros::Time &time)
Definition: hardware_interface_adapter.h:61
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::starting
void starting(const ros::Time &time)
Definition: hardware_interface_adapter.h:152
hardware_interface
joint_command_interface.h
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::stopping
void stopping(const ros::Time &time)
Definition: hardware_interface_adapter.h:163
HardwareInterfaceAdapter::updateCommand
double updateCommand(const ros::Time &time, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
Definition: hardware_interface_adapter.h:64
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::HardwareInterfaceAdapter
HardwareInterfaceAdapter()
Definition: hardware_interface_adapter.h:131
hardware_interface::JointStateHandle::getName
std::string getName() const
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::starting
void starting(const ros::Time &time)
Definition: hardware_interface_adapter.h:91
hardware_interface::JointHandle
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::init
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
Definition: hardware_interface_adapter.h:83
ros::Time
HardwareInterfaceAdapter
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition: hardware_interface_adapter.h:53
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::HardwareInterfaceAdapter
HardwareInterfaceAdapter()
Definition: hardware_interface_adapter.h:81
control_toolbox::Pid
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::PidPtr
std::shared_ptr< control_toolbox::Pid > PidPtr
Definition: hardware_interface_adapter.h:184
pid.h
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface >::stopping
void stopping(const ros::Time &time)
Definition: hardware_interface_adapter.h:92
ros::Duration
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::pid_
PidPtr pid_
Definition: hardware_interface_adapter.h:185
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::init
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
Definition: hardware_interface_adapter.h:133
ros::NodeHandle


gripper_action_controller
Author(s): Sachin Chitta
autogenerated on Fri May 24 2024 02:41:17