Skip to content

Commit

Permalink
Added fuzzy for MISO and KF with multiple update
Browse files Browse the repository at this point in the history
  • Loading branch information
alexeysp11 committed May 9, 2021
1 parent 980d350 commit 585546f
Show file tree
Hide file tree
Showing 13 changed files with 724 additions and 207 deletions.
10 changes: 7 additions & 3 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,14 @@ image_recognition
snippets
tests

# docs
docs
README.md

# Unfinished files
sensors/gyro.py
sensors/accelerometer.py

# Notes and Docs snippets
docs
README.md
#
signal_processing/gps_kf.py
signal_processing/imu_kf.py
52 changes: 32 additions & 20 deletions application/invoke.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,10 @@

from console.console import Console as console
from physical_models.car import Car
from signal_processing.imu_kf import ImuKF
from signal_processing.gps_kf import GpsKF
from control_algorithms.fuzzy_driver import FuzzyDriver
from signal_processing.spa import SignalProcessingAlgorithm as SPA
from control_algorithms.fuzzy_driver_miso import FuzzyDriverMiso
from control_algorithms.fuzzy_driver_siso import FuzzyDriverSiso


class Invoke:
"""
Expand All @@ -18,6 +19,15 @@ class Invoke:
"""

def imu(mode):
"""
Allows to invoke all required modules in order to execute IMT module
that consists of GPS, speedometer, accelerometer.
Takes `mode` as an input parameter that indicates car's motion pattern
(for example, constant position `p`, constant speed `v` or random
acceleration `a`).
"""

try:
car = Car()
dim = 2
Expand All @@ -33,16 +43,15 @@ def imu(mode):
init_velocity=velocity,
mode=mode,
is_accel=is_accel,
is_mock=is_default)
is_default=is_default)

# invoke Kalman filter for processing IMU data.
imu_kf = ImuKF()
imu_kf.callkf(dimension=dim, init_data=init_data)

spa = SPA()
spa.imu_kf(dimension=dim, init_data=init_data)
except Exception as e:
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)
init_data = None
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)
init_data = None


def gps(mode):
Expand All @@ -69,23 +78,26 @@ def gps(mode):
init_velocity=velocity,
mode=mode,
is_accel=is_accel,
is_mock=is_default)
is_default=is_default)

# invoke Kalman filter for processing GPS data.
gps_kf = GpsKF()
gps_kf.callkf(dimension=dim, init_data=init_data)

spa = SPA()
spa.gps_kf(dimension=dim, init_data=init_data)
except Exception as e:
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)
init_data = None
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)
init_data = None


def fuzzy():
try:
fc = FuzzyDriver()
fc.call()

is_miso = console.is_miso_fuzzy()
if is_miso == True:
fc = FuzzyDriverMiso()
fc.call()
else:
fc = FuzzyDriverSiso()
fc.call()
except Exception as e:
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)
44 changes: 24 additions & 20 deletions console/console.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,51 +28,35 @@ def get_command():
# ignore if user just pressed Enter
if command == '':
pass

elif command == 'sdc':
info.help()
info.commands()

elif command == 'sdc -commands':
info.commands()

elif command == 'sdc -h' or command == 'sdc -help':
info.help()

elif command == 'sdc imu':
info.imu()

elif command == 'sdc imu --p':
return 'imu', 'p'

elif command == 'sdc imu --v':
return 'imu', 'v'

elif command == 'sdc imu --a':
return 'imu', 'a'

elif command == 'sdc gps':
info.gps()

elif command == 'sdc gps --p':
return 'gps', 'p'

elif command == 'sdc gps --v':
return 'gps', 'v'
invoke.gps(mode='v')

elif command == 'sdc gps --a':
return 'gps', 'a'

elif command == 'sdc fuzzy':
return 'fuzzy', '0'

elif command == 'sdc exit':
sys.exit()

else:
print('Incorrect command!')

except Exception as e:
print('Info for developer:'.upper)
print(e)
Expand All @@ -93,16 +77,36 @@ def is_default(dimension):

while(True):
is_default = input('Default parameters? ')
try:
if is_default == 'y' or is_default == 'yes':
return True
elif is_default == 'n' or is_default == 'no':
return False
except Exception as e:
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)


def is_miso_fuzzy():
"""
Asks user if fuzzy controller should be MISO.
Returns:
`True`: if fuzzy controller should be MISO.
`False`: if fuzzy controller should be SISO.
"""

print('Fuzzy controller module'.upper())

while(True):
is_default = input('MISO fuzzy controller? ')
try:
if is_default == 'y' or is_default == 'yes':
return True

elif is_default == 'n' or is_default == 'no':
return False

except Exception as e:
print('Exception: '.upper(), e)
traceback.print_tb(e.__traceback__)

return init_data
158 changes: 158 additions & 0 deletions control_algorithms/fuzzy_driver_miso.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
import sys, traceback

import numpy as np
import matplotlib
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D

sys.path.append('../maths')
from maths.fc_miso import FcMiso as FuzzyController


class FuzzyDriverMiso:
"""
This class allows you to configure interaction with `FuzzyController` class
from the console application.
"""
def call(self):
"""
Calls `FuzzyController` from the console application.
"""

# Declare an instance of `FuzzyController` class
fc = FuzzyController()

print("""VARIABLES:
In: Distance to next point.
In: Distance to previous point.
In: Angle.
Out: Speed.""")

print("""Select one of these options:
1) Enter input variables and get output variable only once,
2) Describe relationship between input and output variable using a graph.
""")

while(True):
command = input('Please, enter 1 or 2: ')
if command == '1':
speed = self.get_speed_console(fc)
print(f'Speed = {speed} km/h')
break
elif command == '2':
self.relationship(fc)
break


def draw_plot(self, input1, input2, input3, output, view):
"""
Allows to visualize relationship between 3 input variables of fuzzy
controller (distance to the previous point `dpp`, distance to
the next point `dnp` and angle of rotation `angle` in degrees)
and its output variable (speed of a car `speed`).
Graph is drawn as 3D plot of 3 input variables, output variable
is shown using colorbar.
"""
if view == 'subplots':
pass
if view == '3d':
# convert to 2d matrices
input1, input2 = np.meshgrid(input1, input2) # 10x10
input3 = np.outer(input3.T, input3) / np.max(input3) # 10x10
output = np.outer(output.T, output) / np.max(output) # 10x10

# fourth dimention - colormap
mappable = plt.cm.ScalarMappable(cmap='seismic')
mappable.set_array(output)

fig = plt.figure()
ax = fig.add_subplot(111, projection='3d')
ax.plot_surface(input1, input2, input3,
cmap=mappable.cmap, norm=mappable.norm,
linewidth=0, antialiased=False)
fig.colorbar(mappable)

ax.set_xlabel('DPP (m)')
ax.set_ylabel('DNP (m)')
ax.set_zlabel('Angle (deg)')
plt.title('Three variable fuzzy controller')
plt.grid()
plt.show()
else:
raise f'Incorrect parameter of view: {view}'


def relationship(self, fuzzy_controller):
"""
Print out and plot the relationship between `distance` and `speed`
initiated in the rulebase.
Plot a diagram of the relationship by calling `draw_plot()` method.
"""

dstnce_prev = np.arange(0.0, 50.0, 5.0)
dstnce_next = np.arange(0.0, 50.0, 5.0)
angle = np.arange(-45.0, 45.0, 9.0)
speed = []
try:
for x in dstnce_prev:
for y in dstnce_next:
for z in angle:
result = fuzzy_controller.inference(x, y, z)
speed.append(result)
print(f'x: {x}\ty: {y}\tz: {z}\tresult: {result}')
speed = np.asarray(speed)
self.draw_plot(input1=dstnce_prev, input2=dstnce_next,
input3=angle, output=speed, view='3d')
except Exception:
pass


def get_speed_console(self, fc):
"""
This method allows you to write value of `distance` in the console and
get value of `speed` corresponding to the `distance`.
Variable `distance` is measured in meters, and `speed` is measured
in km/h.
:returns: floating point `distance`, floating point `speed`.
"""
while (1):
dstnce_prev = input('Distance to previous point (m): ')
try:
dstnce_prev = float(dstnce_prev)
if dstnce_prev < 0:
raise 'Distance cannot be negative'
else:
break
except Exception:
print('Incorrect input')

while (1):
dstnce_next = input('Distance to next point (m): ')
try:
dstnce_next = float(dstnce_next)
if dstnce_next < 0:
raise 'Distance cannot be negative'
else:
break
except Exception:
print('Incorrect input')

while (1):
angle = input('Angle of rotation (deg): ')
try:
angle = float(angle)
if angle < -90 and angle > 90:
raise 'Angle is out of range'
else:
break
except Exception:
print('Incorrect input')

speed = fc.inference(dpp_in=dstnce_prev,
dnp_in=dstnce_next,
angle_in=angle)
return float(speed)
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@

sys.path.append('../maths')

from maths.fuzzy_controller import FuzzyController
from maths.fc_siso import FcSiso as FuzzyController
import matplotlib.pyplot as plt


class FuzzyDriver:
class FuzzyDriverSiso:
"""
This class allows you to configure interaction with `FuzzyController` class
from the console application.
Expand All @@ -22,7 +22,6 @@ def call(self):

# Declare instances of considered classes
fc = FuzzyController()
self = FuzzyDriver()

print("""Select one of these options:
1) Enter distance and get speed once,
Expand Down Expand Up @@ -87,10 +86,12 @@ def draw_plot(self, speed_axis, distance_axis):

# naming the x axis and the y axis
plt.xlabel('Distance (m)')
plt.ylabel('Speed (km/h')
plt.ylabel('Speed (km/h)')

# giving a title to my graph
plt.title('Relationship between distance and speed')
plt.title('Distance vs speed')

plt.grid()

# function to show the plot
plt.show()
Expand Down
Loading

0 comments on commit 585546f

Please sign in to comment.