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     virtual ~SrhMixedPositionVelocityJointController();
00045 
00046     bool init( pr2_mechanism_model::RobotState *robot, const std::string &joint_name,
00047                boost::shared_ptr<control_toolbox::Pid> pid_position,
00048                boost::shared_ptr<control_toolbox::Pid> pid_velocity);
00049     bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00050 
00051     virtual void starting();
00052 
00056     virtual void update();
00057 
00058     virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00059     virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min);
00060     virtual bool resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
00061     bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp);
00062 
00063   private:
00064     boost::shared_ptr<control_toolbox::Pid> pid_controller_position_;       
00065     boost::shared_ptr<control_toolbox::Pid> pid_controller_velocity_;       
00067     //publish our joint controller state
00068     boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller_state_publisher_;
00069 
00071     double max_velocity_, min_velocity_;
00072 
00073 #ifdef DEBUG_PUBLISHER
00074     ros::Publisher debug_pub;
00075 #endif
00076 
00077     //ros::Subscriber sub_command_;
00078     //void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00079 
00080     ros::ServiceServer serve_set_gains_;
00081 
00083     double position_deadband;
00084 
00086     sr_deadband::HysteresisDeadband<double> hysteresis_deadband;
00087 
00089     void read_parameters();
00090 
00092     int motor_min_force_threshold;
00093   };
00094 } // namespace
00095 
00096 /* For the emacs weenies in the crowd.
00097 Local Variables:
00098    c-basic-offset: 2
00099 End:
00100 */
00101 
00102 
00103 #endif


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