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