00001 00028 #ifndef _SRH_JOINT_VELOCITY_CONTROLLER_HPP_ 00029 #define _SRH_JOINT_VELOCITY_CONTROLLER_HPP_ 00030 00031 #include <sr_mechanism_controllers/sr_controller.hpp> 00032 #include <sr_mechanism_controllers/sr_friction_compensation.hpp> 00033 00034 00035 namespace controller 00036 { 00037 class SrhJointVelocityController : public SrController 00038 { 00039 public: 00040 00041 SrhJointVelocityController(); 00042 00043 bool init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n); 00044 00045 virtual void starting(const ros::Time& time); 00046 00050 virtual void update(const ros::Time& time, const ros::Duration& period); 00051 00052 virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min); 00053 virtual bool resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp); 00054 bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp); 00055 00056 private: 00057 boost::scoped_ptr<control_toolbox::Pid> pid_controller_velocity_; 00059 00060 double velocity_deadband; 00061 00063 sr_deadband::HysteresisDeadband<double> hysteresis_deadband; 00064 00066 void read_parameters(); 00067 00069 void setCommandCB(const std_msgs::Float64ConstPtr& msg); 00070 00071 void resetJointState(); 00072 }; 00073 } // namespace 00074 00075 /* For the emacs weenies in the crowd. 00076 Local Variables: 00077 c-basic-offset: 2 00078 End: 00079 */ 00080 00081 00082 #endif