pid_controller.py
Go to the documentation of this file.
00001 import numpy as np, math
00002 
00003 import roslib
00004 roslib.load_manifest('rospy')
00005 roslib.load_manifest('std_msgs')
00006 
00007 import rospy
00008 from std_msgs.msg import Float64, Float64MultiArray
00009 
00010 ##
00011 # Classic PID controller with maximum integral thresholding to
00012 # prevent windup.
00013 class PIDController(object):
00014     def __init__(self, rate=100., k_p=0., k_i=0., k_d=0., i_max=None, feed_forward=0.,
00015                  init_integ=0., saturation=None, name=None):
00016         self.y = 0.
00017         self.k_p = k_p
00018         self.k_i = k_i
00019         self.k_d = k_d
00020         self.i_max = i_max
00021         self.feed_forward = feed_forward
00022         self.rate = rate
00023         self.saturation = saturation
00024         self.err_last = None
00025         self.integral = init_integ
00026         self.name = name
00027         if self.name is not None:
00028             self.err_pub = rospy.Publisher("/pid_controller/" + name + "_error", Float64)
00029             self.out_pub = rospy.Publisher("/pid_controller/" + name + "_output", Float64)
00030             self.diag_pub = rospy.Publisher("/pid_controller/" + name + "_diag", Float64MultiArray)
00031 
00032     ##
00033     # Updates the controller state and returns the current output.
00034     def update_state(self, err):
00035         last_integral = self.integral
00036         self.integral += err / self.rate
00037         if self.i_max is not None:
00038             self.integral = np.clip(self.integral, -self.i_max, self.i_max)
00039         if self.err_last is None:
00040             self.err_last = err
00041         propr = self.k_p * err
00042         integ = self.k_i * self.integral
00043         deriv = self.k_d * (err - self.err_last) * self.rate
00044         feedf = self.feed_forward
00045         raw_y = propr + integ + deriv + feedf
00046         self.err_last = err
00047         if self.saturation is not None:
00048             self.y = np.clip(raw_y, -self.saturation, self.saturation)
00049             if self.y in [-self.saturation, self.saturation]:
00050                 self.integral = last_integral
00051         if self.name is not None:
00052             self.err_pub.publish(err)
00053             self.out_pub.publish(self.y)
00054             diag_msg = Float64MultiArray()
00055             diag_msg.data = [self.y, propr, integ, deriv, feedf, raw_y, self.saturation]
00056             self.diag_pub.publish(diag_msg)
00057         return self.y
00058 
00059     def reset_controller(self):
00060         self.err_last = None
00061         self.integral = 0


hrl_pr2_ar_servo
Author(s): Kelsey Hawkins, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab
autogenerated on Wed Nov 27 2013 11:43:43