Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00028
00030
00031 #ifndef GRIPPER_ACTION_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H
00032 #define GRIPPER_ACTION_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H
00033
00034 #include <cassert>
00035 #include <string>
00036 #include <vector>
00037
00038 #include <boost/shared_ptr.hpp>
00039
00040 #include <ros/node_handle.h>
00041 #include <ros/time.h>
00042
00043 #include <control_toolbox/pid.h>
00044 #include <hardware_interface/joint_command_interface.h>
00045
00053 template <class HardwareInterface>
00054 class HardwareInterfaceAdapter
00055 {
00056 public:
00057 bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
00058 {
00059 return false;
00060 }
00061
00062 void starting(const ros::Time& time) {}
00063 void stopping(const ros::Time& time) {}
00064
00065 double updateCommand(const ros::Time& time,
00066 const ros::Duration& period,
00067 double desired_position,
00068 double desired_velocity,
00069 double error_position,
00070 double error_velocity,
00071 double max_allowed_effort) { return 0.0;}
00072
00073 };
00074
00078 template<>
00079 class HardwareInterfaceAdapter<hardware_interface::PositionJointInterface>
00080 {
00081 public:
00082 HardwareInterfaceAdapter() : joint_handle_ptr_(0) {}
00083
00084 bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
00085 {
00086
00087 joint_handle_ptr_ = &joint_handle;
00088
00089 return true;
00090 }
00091
00092 void starting(const ros::Time& time) {}
00093 void stopping(const ros::Time& time) {}
00094
00095 double updateCommand(const ros::Time& ,
00096 const ros::Duration& period,
00097 double desired_position,
00098 double desired_velocity,
00099 double error_position,
00100 double error_velocity,
00101 double max_allowed_effort)
00102 {
00103
00104 (*joint_handle_ptr_).setCommand(desired_position);
00105 return max_allowed_effort;
00106 }
00107
00108 private:
00109 hardware_interface::JointHandle* joint_handle_ptr_;
00110 };
00111
00128 template<>
00129 class HardwareInterfaceAdapter<hardware_interface::EffortJointInterface>
00130 {
00131 public:
00132 HardwareInterfaceAdapter() : joint_handle_ptr_(0) {}
00133
00134 bool init(hardware_interface::JointHandle& joint_handle, ros::NodeHandle& controller_nh)
00135 {
00136
00137 joint_handle_ptr_ = &joint_handle;
00138
00139
00140 ros::NodeHandle joint_nh(controller_nh, std::string("gains/") + joint_handle.getName());
00141
00142
00143 pid_.reset(new control_toolbox::Pid());
00144 if (!pid_->init(joint_nh))
00145 {
00146 ROS_WARN_STREAM("Failed to initialize PID gains from ROS parameter server.");
00147 return false;
00148 }
00149
00150 return true;
00151 }
00152
00153 void starting(const ros::Time& time)
00154 {
00155 if (!joint_handle_ptr_)
00156 {
00157 return;
00158 }
00159
00160 pid_->reset();
00161 (*joint_handle_ptr_).setCommand(0.0);
00162 }
00163
00164 void stopping(const ros::Time& time) {}
00165
00166 double updateCommand(const ros::Time& ,
00167 const ros::Duration& period,
00168 double desired_position,
00169 double desired_velocity,
00170 double error_position,
00171 double error_velocity,
00172 double max_allowed_effort)
00173 {
00174
00175 if (!joint_handle_ptr_) {return 0.0;}
00176
00177
00178 double command = pid_->computeCommand(error_position, error_velocity, period);
00179 command = std::min<double>(fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
00180 (*joint_handle_ptr_).setCommand(command);
00181 return command;
00182 }
00183
00184 private:
00185 typedef boost::shared_ptr<control_toolbox::Pid> PidPtr;
00186 PidPtr pid_;
00187 hardware_interface::JointHandle* joint_handle_ptr_;
00188 };
00189
00190 #endif // header guard