srh_joint_effort_controller.hpp
Go to the documentation of this file.
00001 
00030 #ifndef _SRH_EFFORT_CONTROLLER_HPP_
00031 #define _SRH_EFFORT_CONTROLLER_HPP_
00032 
00033 #include <sr_mechanism_controllers/sr_controller.hpp>
00034 #include <sr_robot_msgs/SetEffortControllerGains.h>
00035 
00036 namespace controller
00037 {
00038   class SrhEffortJointController : public SrController
00039   {
00040   public:
00041     SrhEffortJointController();
00042     virtual ~SrhEffortJointController();
00043 
00044     bool init( pr2_mechanism_model::RobotState *robot, const std::string &joint_name);
00045     bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00046 
00047     virtual void starting();
00048 
00052     virtual void update();
00053 
00054     virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00055     virtual bool resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
00056     bool setGains(sr_robot_msgs::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp);
00057 
00058   private:
00060     void read_parameters();
00061   };
00062 } // namespace
00063 
00064 /* For the emacs weenies in the crowd.
00065 Local Variables:
00066    c-basic-offset: 2
00067 End:
00068 */
00069 
00070 
00071 #endif


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