00001 00030 #ifndef _SRH_MUSCLE_VALVE_CONTROLLER_HPP_ 00031 #define _SRH_MUSCLE_VALVE_CONTROLLER_HPP_ 00032 00033 #include <sr_mechanism_controllers/sr_controller.hpp> 00034 #include <sr_robot_msgs/JointMuscleValveControllerState.h> 00035 #include <sr_robot_msgs/JointMuscleValveControllerCommand.h> 00036 00037 namespace controller 00038 { 00039 class SrhJointMuscleValveController : public SrController 00040 { 00041 public: 00042 SrhJointMuscleValveController(); 00043 00044 bool init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n); 00045 00046 virtual void starting(const ros::Time& time); 00047 00051 virtual void update(const ros::Time& time, const ros::Duration& period); 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::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp); 00056 00057 int8_t cmd_valve_muscle_[2]; 00058 unsigned int cmd_duration_ms_[2]; 00059 unsigned int current_duration_ms_[2]; // These are the actual counters used to maintain the commanded value for the valve during the commanded time 00060 00061 int8_t cmd_valve_muscle_min_; 00062 int8_t cmd_valve_muscle_max_; 00063 00064 private: 00065 //publish our joint controller state 00066 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointMuscleValveControllerState> > controller_state_publisher_; 00067 00068 ros::Subscriber sub_command_; 00069 void setCommandCB(const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr& msg); 00070 00072 void read_parameters(); 00073 00075 int8_t clamp_command( int8_t cmd ); 00076 }; 00077 } // namespace 00078 00079 /* For the emacs weenies in the crowd. 00080 Local Variables: 00081 c-basic-offset: 2 00082 End: 00083 */ 00084 00085 00086 #endif