srh_mixed_position_velocity_controller.hpp
Go to the documentation of this file.
00001 
00030 #ifndef SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H
00031 #define SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H
00032 
00033 #include <sr_mechanism_controllers/sr_controller.hpp>
00034 #include <sr_robot_msgs/SetMixedPositionVelocityPidGains.h>
00035 #include <sr_robot_msgs/JointControllerState.h>
00036 
00037 namespace controller
00038 {
00039   class SrhMixedPositionVelocityJointController : public SrController
00040   {
00041   public:
00042 
00043     SrhMixedPositionVelocityJointController();
00044 
00045     bool init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n);
00046 
00047     virtual void starting(const ros::Time& time);
00048 
00052     virtual void update(const ros::Time& time, const ros::Duration& period);
00053 
00054     virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00055     virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min);
00056     virtual bool resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
00057     bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp);
00058 
00059   private:
00060     boost::scoped_ptr<control_toolbox::Pid> pid_controller_position_;       
00061     boost::scoped_ptr<control_toolbox::Pid> pid_controller_velocity_;       
00063     //publish our joint controller state
00064     boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller_state_publisher_;
00065 
00067     double max_velocity_, min_velocity_;
00068 
00069 #ifdef DEBUG_PUBLISHER
00070     ros::Publisher debug_pub;
00071 #endif
00072 
00073     //ros::Subscriber sub_command_;
00074     //void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00075 
00076     ros::ServiceServer serve_set_gains_;
00077 
00079     double position_deadband;
00080 
00082     sr_deadband::HysteresisDeadband<double> hysteresis_deadband;
00083 
00085     void read_parameters();
00086 
00088     int motor_min_force_threshold;
00089 
00091     void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00092 
00093     void resetJointState();
00094   };
00095 } // namespace
00096 
00097 /* For the emacs weenies in the crowd.
00098 Local Variables:
00099    c-basic-offset: 2
00100 End:
00101 */
00102 
00103 
00104 #endif


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