This repository has been archived by the owner on Dec 24, 2021. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 0
/
simulator.py
269 lines (226 loc) · 11.2 KB
/
simulator.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
# Python simulator class for MCU
import random
import standardcalc
import os
import math
import threading
import sys
import time
from drivers import interface
import global_vars as gVars
import static_vars as sVars
from datatype import BoatData
from datatype import ControlData
from datatype import GPSCoordinate
# This will be the format of the file output
# The file will be a space delimited file.
# The first line will be a header, depicting which variable is where
# hog awa sog windSpeed latitude longitude rudderAngle sheetPercentage
# |--------------------------------------------------------------|
# | hog | awa | sog | wSpd | lat | long | rud | sheet|
# |--------------------------------------------------------------|
# | oldHog| oldAwa| oldSog|oldWSpd| oldLat|oldLong| oldRud| oldSh|
# |--------------------------------------------------------------|
# Assumes the mcu repository is in the parent directory of simulator.
MCU_DIRECTORY = os.path.join(os.path.pardir, "mcu", "build")
# for self closed loop, change to read from "simulatorOutput"
# otherwise, use "mcuOutput"
LINK_FILE = os.path.join(MCU_DIRECTORY, "simuLink")
ROUTE_FILE = os.path.join(MCU_DIRECTORY, "routeLink")
DUMMY_BOAT_INPUTS_FILE = os.path.join(MCU_DIRECTORY,"dummy_boat_inputs.txt")
class Simulator():
# maximum wind speed (20 knots; typical is 6 - 12 knots)
MAX_WIND_SPEED = 15.0
# minimum wind speed
MIN_WIND_SPEED = 3.0
# maximum current speed (~1 knot; max current speed in English Bay: 0.75 knots)
MAX_CURRENT_SPEED = 1e9
# runtime for the mcu
CLOCK_INTERVAL = 0.25 # was 0.01
# Time scale for calculations, if equal to clock interval the simulation will run in real time.
TIME_SCALE = CLOCK_INTERVAL
# Change in HOG for max rudder setting in 1 meter
MAX_RUDDER_HOG_CHANGE = 10.0
# Max rudder angle possible (angle between -45 to 45)
MAX_RUDDER_ANGLE = 45.0
# This affects how fast the boat reaches the ideal SOG
# SOW_DECAY_FACTOR = (3 / CLOCK_INTERVAL)
# How likely a gust is to occur every virtual second (Higher => Less probable)
GUST_PROBABILITY = 100
# Actual seconds between every time data is sent to the server
DATA_DELAY = 0.1
# This is the centerboard to rudder distance L in metres
L_CENTERBOARD_TO_RUDDER = 0.2
# Maximum tail angle
MAX_TAIL_ANGLE = 15.0
# Time constant for exponential decay of SOW
SOW_TIME_CONSTANT = 1.0
# HOG change constant
HOG_CHANGE_FACTOR = 7.07
def __init__(self, verbose, reset, gust, data_to_ui):
random.seed()
# Choose Random Wind Angle between -180 and 180
# self.trueWindAngle = random.randint(-180, 180)
self.trueWindAngle = 90
# Choose random wind speed (between typical values of 6 - 10 m/s)
self.trueWindSpeed = float(random.uniform(6, 7))
# self.trueWindSpeed = 3.0
self.windVector = standardcalc.Vector2D.zero()
self.windVector = standardcalc.Vector2D.create_from_angle(self.trueWindAngle, self.trueWindSpeed)
self.apparentWindVector = standardcalc.Vector2D.zero()
self.currentFlowAngle = random.randint(-180, 180)
# self.currentFlowSpeed = float(random.uniform(0.1, 0.3))
self.currentFlowSpeed = 0.0
self.currentFlowVector = standardcalc.Vector2D.zero()
self.boatVector = standardcalc.Vector2D.zero()
self.verbose = verbose
self.gust = gust
self.dataToUI = data_to_ui
self.displacementVector = standardcalc.Vector2D.zero()
self.gustTimer = 0
self.dataTimer = 0
self.preGustTrueWindSpeed = 0
self.preGustTrueWindAngle = 0
self.dest_coords = GPSCoordinate.GPSCoordinate(0, 0)
self.boatData = BoatData.BoatData()
self.boatData.hog = 0
self.boatData.sow = 1.0
# self.boatData.sog = self.boatData.sow
self.controlData = ControlData.ControlData()
self.oldBoatData = BoatData.BoatData()
self.oldBoatDataString = ""
self.distanceToWaypoint = 0
self.acceptDist = 5
self.arrivedAtPointFlag = 0
def update(self):
self.read_data()
self.update_old_data()
self.adjust_true_wind()
self.adjust_current()
if self.gust:
self.gust_manager()
self.adjust_aw()
self.adjust_sow()
self.adjust_hog()
self.update_vectors()
self.update_sailAngles()
self.adjust_position()
self.write_data()
gVars.boatVars = self.boatData
def read_data(self):
data = gVars.bus.getData()
ctrl_data = gVars.bus.getCtrlData()
self.boatData.rudder = data.rudder
tailAngle = data.tailAngle
if tailAngle > self.MAX_TAIL_ANGLE:
self.boatData.tailAngle = self.MAX_TAIL_ANGLE
elif tailAngle < -self.MAX_TAIL_ANGLE:
self.boatData.tailAngle = -self.MAX_TAIL_ANGLE
else:
self.boatData.tailAngle = tailAngle
self.controlData.steer_scheme = ctrl_data.steer_scheme
self.controlData.steer_setpoint = ctrl_data.steer_setpoint
self.controlData.prop_scheme = ctrl_data.prop_scheme
self.controlData.prop_setpoint = ctrl_data.prop_setpoint
def update_old_data(self):
self.oldBoatDataString = self.boatData.__repr__() + self.controlData.__repr__()
def adjust_true_wind(self):
# True wind angle is allowed to fluctuate
self.trueWindAngle += random.gauss(0, 1) * self.CLOCK_INTERVAL
self.trueWindSpeed += random.gauss(0, 0.3) * self.CLOCK_INTERVAL
if self.trueWindSpeed > self.MAX_WIND_SPEED:
self.trueWindSpeed = self.MAX_WIND_SPEED
if self.trueWindSpeed < self.MIN_WIND_SPEED:
self.trueWindSpeed = self.MIN_WIND_SPEED
self.trueWindAngle = standardcalc.bound_to_180(self.trueWindAngle)
self.trueWindSpeed = abs(self.trueWindSpeed)
self.windVector = -standardcalc.Vector2D.create_from_angle(self.trueWindAngle, self.trueWindSpeed)
def adjust_current(self):
self.currentFlowAngle += random.gauss(0, 1) * self.CLOCK_INTERVAL
self.currentFlowSpeed += random.gauss(0, 0.3) * self.CLOCK_INTERVAL
self.currentFlowAngle = standardcalc.bound_to_180(self.currentFlowAngle)
if self.currentFlowSpeed > self.MAX_CURRENT_SPEED:
self.currentFlowSpeed = self.MAX_CURRENT_SPEED
self.currentFlowSpeed = abs(self.currentFlowSpeed)
self.currentFlowVector = standardcalc.Vector2D.create_from_angle(self.currentFlowAngle, self.currentFlowSpeed)
def gust_manager(self):
if self.gustTimer <= 0:
if random.randint(1, self.GUST_PROBABILITY / self.CLOCK_INTERVAL) == 2:
self.preGustTrueWindAngle = self.trueWindAngle
self.preGustTrueWindSpeed = self.trueWindSpeed
self.trueWindSpeed = random.randint(20, 30)
self.trueWindAngle += random.randint(-5, 5)
self.gustTimer = random.randint(5, 80) / self.CLOCK_INTERVAL
else:
self.gustTimer -= 1
if self.verbose:
print "Gust is active. Timer: " + str(self.gustTimer)
if self.gustTimer <= 0:
self.trueWindSpeed = abs(self.preGustTrueWindSpeed + random.randint(-2, 2))
self.trueWindAngle = standardcalc.bound_to_180(self.preGustTrueWindAngle + random.randint(-1, 1))
def adjust_aw(self):
self.boatVector = standardcalc.Vector2D.create_from_angle(self.boatData.hog, self.boatData.sow) \
- self.currentFlowVector
# Update COG and SOG
self.boatData.cog = self.boatVector.angle()
self.boatData.sog = self.boatVector.length()
self.apparentWindVector = self.windVector - self.boatVector
# print str(self.apparentWindVector.angle()) + " " + str(self.apparentWindVector.length())
self.boatData.awa = standardcalc.bound_to_180(
standardcalc.Vector2D.angle_between(self.boatVector, -self.apparentWindVector))
self.boatData.windspeed = self.apparentWindVector.length()
def adjust_sow(self):
# v_b = w_a*f(phi_aw)*beta where w_a is the apparent wind speed, f(phi_aw) is the norm. BSPD and beta is
# the control parameter setting (e.g. sheet setting)
next_sow = standardcalc.calculate_sog_BSPD(self.boatData.awa, self.boatData.windspeed) \
* abs(self.boatData.tailAngle / self.MAX_TAIL_ANGLE) * 0.6
max_sow = standardcalc.calculate_max_sog(self.boatData.awa, self.boatData.windspeed)
sow_change = (next_sow - self.boatData.sow)*math.exp(-self.SOW_TIME_CONSTANT / self.CLOCK_INTERVAL)
self.boatData.sow += sow_change
if self.boatData.sow > max_sow:
self.boatData.sow = max_sow
def adjust_hog(self):
# Update HOG from rudder change
hogChange = (self.boatData.sow * math.sin(self.boatData.rudder * math.pi / 180.0)
* self.CLOCK_INTERVAL) * self.HOG_CHANGE_FACTOR
self.boatData.hog += hogChange
self.boatData.hog = standardcalc.bound_to_180(self.boatData.hog)
def update_vectors(self):
pass
def update_sailAngles(self):
# Using 2 right now, but this should be the factor relating tail Angle and angle of attack
# wingAngle is defined in the same way as AWA, relative to the boat
self.boatData.wingAngle = self.boatData.awa - self.boatData.tailAngle * 2
def adjust_position(self):
# Vector addition
self.displacementVector = self.CLOCK_INTERVAL * standardcalc.Vector2D.create_from_angle(self.boatData.cog,
self.boatData.sog)
self.boatData.gps_coord.lat, self.boatData.gps_coord.long = standardcalc.shift_coordinates(
self.boatData.gps_coord.lat,
self.boatData.gps_coord.long,
self.displacementVector
)
self.arrivedAtPointFlag = self.arrivedAtPoint()
# print str(self.arrivedAtPointFlag)
def arrivedAtPoint(self):
self.distanceToWaypoint = standardcalc.distBetweenTwoCoords(self.boatData.gps_coord, self.dest_coords)
return self.distanceToWaypoint < self.acceptDist
def write_data(self):
# Publish GPS and AW data to the bus.
gVars.bus.publish("GPS", self.boatData.gps_coord.lat, self.boatData.gps_coord.long,
self.boatData.hog, self.boatData.sog, self.boatData.cog, self.boatData.sow)
gVars.bus.publish("AW", self.boatData.windspeed, self.boatData.awa)
gVars.bus.publish("GUI", self.dest_coords.lat, self.dest_coords.long)
if self.verbose:
# Debug printer
print "===================="
print self.oldBoatDataString
print self.boatData.__repr__()
print "\n"
print "TRUE WIND SPEED: " + '%.8f' % self.trueWindSpeed
print "TRUE WIND ANGLE: " + '%.8f' % self.trueWindAngle
print "CURRENT SPEED: " + '%.8f' % self.currentFlowSpeed
print "CURRENT ANGLE: " + '%.8f' % self.currentFlowAngle
else:
print self.boatData.__repr__() + ", CFS:" + str(round(self.currentFlowSpeed,2)) + \
", CFA:" + str(round(self.currentFlowAngle,2)) + " " + self.controlData.__repr__()