Browse Source

added motor controller

subDesTagesMitExtraKaese 4 years ago
parent
commit
91bd23137c

+ 13 - 4
software/appWindow.py

@@ -6,6 +6,8 @@ from analogPressure.sdpArray import SdpArray
 from analogPressure.mcp3008 import MCP3008
 from digitalPressure.sdp610Array import Spd610Array
 from wirelessLoadCell.loadCells import LoadCells
+from motorController.pwmOutput import PWM
+from motorController.pidController import PID
 from ui import *
 
 import tkinter as tk
@@ -22,7 +24,8 @@ class Main(tk.Tk, Table):
     self.pressureSensors = Spd610Array()
     self.forceSensors = LoadCells()
     self.forceSensors.start()
-    self.motorController = None
+    self.motorController = PWM(32)
+    self.pid = PID()
     
     Table.__init__(self, 
     ["time", "windspeed", "motor_pwm"] + 
@@ -94,13 +97,19 @@ class Main(tk.Tk, Table):
       label.pack(side="top", fill="x", pady=10)
       b1 = tk.Button(popup, text="Okay", command=popup.destroy)
       b1.pack()
+      
   def interval(self):
-    adcValues = self.adc.read()
+    adcValue = self.adc.getVoltage(0)
+    windSpeed = adcValue * 1337
+    pwmValue = self.PID.update(windSpeed)
+    if not self.motorEnabled:
+      pwmValue = 0
+    self.pwm.setDutyCycle(pwmValue)
 
     self.addRow(
-      [time.time(), 0, 0] + 
+      [time.time(), windSpeed, pwmValue] + 
       self.pressureSensors.getValues() +
-      [self.adc.getVoltage(0)] +
+      [adcValue] +
       self.forceSensors.getForces(0) +
       self.forceSensors.getForces(1) +
       self.forceSensors.getForces(2)

+ 129 - 0
software/motorController/pidController.py

@@ -0,0 +1,129 @@
+#!/usr/bin/python
+#
+# This file is part of IvPID.
+# Copyright (C) 2015 Ivmech Mechatronics Ltd. <bilgi@ivmech.com>
+#
+# IvPID is free software: you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation, either version 3 of the License, or
+# (at your option) any later version.
+#
+# IvPID is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+# GNU General Public License for more details.
+#
+# You should have received a copy of the GNU General Public License
+# along with this program.  If not, see <http://www.gnu.org/licenses/>.
+
+# title           :PID.py
+# description     :python pid controller
+# author          :Caner Durmusoglu
+# date            :20151218
+# version         :0.1
+# notes           :
+# python_version  :2.7
+# ==============================================================================
+
+"""Ivmech PID Controller is simple implementation of a Proportional-Integral-Derivative (PID) Controller in the Python Programming Language.
+More information about PID Controller: http://en.wikipedia.org/wiki/PID_controller
+"""
+import time
+
+class PID:
+    """PID Controller
+    """
+
+    def __init__(self, P=0.2, I=0.0, D=0.0, current_time=None):
+
+        self.Kp = P
+        self.Ki = I
+        self.Kd = D
+
+        self.sample_time = 0.00
+        self.current_time = current_time if current_time is not None else time.time()
+        self.last_time = self.current_time
+
+        self.clear()
+
+    def clear(self):
+        """Clears PID computations and coefficients"""
+        self.SetPoint = 0.0
+
+        self.PTerm = 0.0
+        self.ITerm = 0.0
+        self.DTerm = 0.0
+        self.last_error = 0.0
+
+        # Windup Guard
+        self.int_error = 0.0
+        self.windup_guard = 20.0
+
+        self.output = 0.0
+
+    def update(self, feedback_value, current_time=None):
+        """Calculates PID value for given reference feedback
+
+        .. math::
+            u(t) = K_p e(t) + K_i \int_{0}^{t} e(t)dt + K_d {de}/{dt}
+
+        .. figure:: images/pid_1.png
+           :align:   center
+
+           Test PID with Kp=1.2, Ki=1, Kd=0.001 (test_pid.py)
+
+        """
+        error = self.SetPoint - feedback_value
+
+        self.current_time = current_time if current_time is not None else time.time()
+        delta_time = self.current_time - self.last_time
+        delta_error = error - self.last_error
+
+        if (delta_time >= self.sample_time):
+            self.PTerm = self.Kp * error
+            self.ITerm += error * delta_time
+
+            if (self.ITerm < -self.windup_guard):
+                self.ITerm = -self.windup_guard
+            elif (self.ITerm > self.windup_guard):
+                self.ITerm = self.windup_guard
+
+            self.DTerm = 0.0
+            if delta_time > 0:
+                self.DTerm = delta_error / delta_time
+
+            # Remember last time and last error for next calculation
+            self.last_time = self.current_time
+            self.last_error = error
+
+            self.output = self.PTerm + (self.Ki * self.ITerm) + (self.Kd * self.DTerm)
+
+    def setKp(self, proportional_gain):
+        """Determines how aggressively the PID reacts to the current error with setting Proportional Gain"""
+        self.Kp = proportional_gain
+
+    def setKi(self, integral_gain):
+        """Determines how aggressively the PID reacts to the current error with setting Integral Gain"""
+        self.Ki = integral_gain
+
+    def setKd(self, derivative_gain):
+        """Determines how aggressively the PID reacts to the current error with setting Derivative Gain"""
+        self.Kd = derivative_gain
+
+    def setWindup(self, windup):
+        """Integral windup, also known as integrator windup or reset windup,
+        refers to the situation in a PID feedback controller where
+        a large change in setpoint occurs (say a positive change)
+        and the integral terms accumulates a significant error
+        during the rise (windup), thus overshooting and continuing
+        to increase as this accumulated error is unwound
+        (offset by errors in the other direction).
+        The specific problem is the excess overshooting.
+        """
+        self.windup_guard = windup
+
+    def setSampleTime(self, sample_time):
+        """PID that should be updated at a regular interval.
+        Based on a pre-determined sampe time, the PID decides if it should compute or return immediately.
+        """
+        self.sample_time = sample_time

+ 26 - 0
software/motorController/pwmOutput.py

@@ -0,0 +1,26 @@
+
+import RPi.GPIO as GPIO
+import time
+import sys
+
+class PWM:
+  def __init__(self, pin):
+    self.pin = pin
+    GPIO.setup(self.pin, GPIO.OUT)
+    GPIO.output(self.pin, 0)
+    self.pwm = GPIO.PWM(self.pin, 100)
+    self.pwm.start(0)
+
+  def setDutyCycle(self, val):
+    self.pwm.ChangeDutyCycle(val)
+
+if __name__ == '__main__':
+  try:
+    GPIO.setmode(GPIO.BCM)
+    p = PWM(32)
+    while True:
+      p.setDutyCycle(int(time.time()*100 % 100))
+      time.sleep(.03)
+  except KeyboardInterrupt:
+    GPIO.cleanup()
+    sys.exit(0)

+ 4 - 1
software/ui/Page_1.py

@@ -14,6 +14,7 @@ class Page_1(tk.Frame):
   def __init__(self, parent, controller):
     tk.Frame.__init__(self, parent)
     self.t = 0
+    self.controller = controller
 
     # graph
     self.serialPlot = Plot(20)
@@ -42,6 +43,8 @@ class Page_1(tk.Frame):
     label2.pack()
     label3.pack()
 
+    controller.pid.SetPoint = 0.4 # m/s
+
   def update(self):
-    self.serialPlot.update(controller.getLastValue("force_X_1"))
+    self.serialPlot.update(self.controller.getLastValue("force_X_1"))
     self.label4.config(text="{:3d} Nm".format(3))