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     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::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp);
00053 
00054   private:
00056     void read_parameters();
00057 
00059     void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00060   };
00061 } // namespace
00062 
00063 /* For the emacs weenies in the crowd.
00064 Local Variables:
00065    c-basic-offset: 2
00066 End:
00067 */
00068 
00069 
00070 #endif


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14