|
@@ -15,7 +15,6 @@ import rospy
|
|
|
import time
|
|
|
import roslib; roslib.load_manifest('ros_arduino_python')
|
|
|
import dynamic_reconfigure.client
|
|
|
-import queue
|
|
|
|
|
|
from math import sin, cos, pi, sqrt
|
|
|
import numpy as np
|
|
@@ -30,27 +29,27 @@ class SimplePID:
|
|
|
def __init__(self, target, P, I, D):
|
|
|
'''Create a discrete PID controller
|
|
|
each of the parameters may be a vector if they have the same length
|
|
|
-
|
|
|
+
|
|
|
Args:
|
|
|
target (double) -- the target value(s)
|
|
|
P, I, D (double)-- the PID parameter
|
|
|
|
|
|
'''
|
|
|
|
|
|
-
|
|
|
+
|
|
|
self.Kp =np.array(P)
|
|
|
self.Ki =np.array(I)
|
|
|
self.Kd =np.array(D)
|
|
|
self.setPoint =np.array(target)
|
|
|
-
|
|
|
+
|
|
|
self.last_error=0
|
|
|
self.integrator = 0
|
|
|
self.integrator_max = float('inf')
|
|
|
- self.timeOfLastCall = None
|
|
|
-
|
|
|
-
|
|
|
+ self.timeOfLastCall = None
|
|
|
+
|
|
|
+
|
|
|
def update(self, current_value):
|
|
|
- '''Updates the PID controller.
|
|
|
+ '''Updates the PID controller.
|
|
|
|
|
|
Args:
|
|
|
current_value (double): vector/number of same legth as the target given in the constructor
|
|
@@ -66,23 +65,23 @@ class SimplePID:
|
|
|
self.timeOfLastCall = time.clock()
|
|
|
return np.zeros(np.size(current_value))
|
|
|
|
|
|
-
|
|
|
+
|
|
|
error = self.setPoint - current_value
|
|
|
P = error
|
|
|
-
|
|
|
+
|
|
|
currentTime = time.clock()
|
|
|
deltaT = (currentTime-self.timeOfLastCall)
|
|
|
|
|
|
|
|
|
self.integrator = self.integrator + (error*deltaT)
|
|
|
I = self.integrator
|
|
|
-
|
|
|
+
|
|
|
|
|
|
D = (error-self.last_error)/deltaT
|
|
|
-
|
|
|
+
|
|
|
self.last_error = error
|
|
|
self.timeOfLastCall = currentTime
|
|
|
-
|
|
|
+
|
|
|
|
|
|
return self.Kp*P + self.Ki*I + self.Kd*D
|
|
|
|
|
@@ -459,11 +458,11 @@ class BaseController:
|
|
|
|
|
|
def get_yaw(self):
|
|
|
rospy.wait_for_service(self.yaw_data_service)
|
|
|
- try:
|
|
|
+ try:
|
|
|
yaw_data = rospy.ServiceProxy(self.yaw_data_service, GetYawData)
|
|
|
resp = yaw_data()
|
|
|
- return resp.yaw
|
|
|
- except rospy.ServiceException, e:
|
|
|
+ return resp.yaw
|
|
|
+ except rospy.ServiceException, e:
|
|
|
print "Service call failed: %s"%e
|
|
|
|
|
|
def reset_pid_controller(self):
|
|
@@ -472,7 +471,7 @@ class BaseController:
|
|
|
self.pid_controller.timeOfLastCall = None
|
|
|
|
|
|
def cmdVelCallback(self, req):
|
|
|
-
|
|
|
+
|
|
|
|
|
|
self.last_cmd_time = rospy.Time.now()
|
|
|
|
|
@@ -494,7 +493,7 @@ class BaseController:
|
|
|
|
|
|
else:
|
|
|
self.correction_yaw_flag = 0
|
|
|
- self.reset_pid_controller()
|
|
|
+ self.reset_pid_controller()
|
|
|
|
|
|
|
|
|
tmpX = sqrt(3)/2.0
|