srh_joint_position_controller.hpp
Go to the documentation of this file.
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     virtual ~SrhJointPositionController();
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 
00061     double max_force_demand;
00062 
00064     double position_deadband;
00065 
00067     sr_deadband::HysteresisDeadband<double> hysteresis_deadband;
00068 
00070     void read_parameters();
00071 
00072     std::string joint_name_;
00073   };
00074 } // namespace
00075 
00076 /* For the emacs weenies in the crowd.
00077 Local Variables:
00078    c-basic-offset: 2
00079 End:
00080 */
00081 
00082 
00083 #endif


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:56