00001 00028 #ifndef _SRH_MUSCLE_JOINT_POSITION_CONTROLLER_HPP_ 00029 #define _SRH_MUSCLE_JOINT_POSITION_CONTROLLER_HPP_ 00030 00031 #include <sr_mechanism_controllers/sr_controller.hpp> 00032 #include <sr_robot_msgs/JointMusclePositionControllerState.h> 00033 00034 namespace controller 00035 { 00036 class SrhMuscleJointPositionController : public SrController 00037 { 00038 public: 00039 SrhMuscleJointPositionController(); 00040 ~SrhMuscleJointPositionController(); 00041 00042 bool init( pr2_mechanism_model::RobotState *robot, const std::string &joint_name, 00043 boost::shared_ptr<control_toolbox::Pid> pid_position); 00044 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00045 00046 virtual void starting(); 00047 00051 virtual void update(); 00052 00053 virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min); 00054 virtual bool resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp); 00055 bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp); 00056 00057 private: 00058 boost::shared_ptr<control_toolbox::Pid> pid_controller_position_; 00060 //publish our joint controller state 00061 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointMusclePositionControllerState> > controller_state_publisher_; 00062 00064 double max_force_demand; 00065 00067 double position_deadband; 00068 00070 sr_deadband::HysteresisDeadband<double> hysteresis_deadband; 00071 00073 int command_acc_; 00074 00076 void read_parameters(); 00077 00078 std::string joint_name_; 00079 }; 00080 } // namespace 00081 00082 /* For the emacs weenies in the crowd. 00083 Local Variables: 00084 c-basic-offset: 2 00085 End: 00086 */ 00087 00088 00089 #endif