From 7556cd730879f60510853a64ca00ac2e80ab085f Mon Sep 17 00:00:00 2001 From: zCoCo Date: Fri, 30 Dec 2022 14:23:29 -0500 Subject: [PATCH 01/39] GDS: Fixed bug in WD Flight Heartbeat decoding of ADC Temp (fixed a bitshift). --- .../packet_classes/watchdog_heartbeat.py | 6 +- ...ssion__01GJD7DN8HYX8M8775ZMH3AKNJ.log.ansi | 507 ++++++++++++++++++ 2 files changed, 512 insertions(+), 1 deletion(-) create mode 100644 Apps/GroundSoftware/out/___bgapi_passthrough_programming_session__01GJD7DN8HYX8M8775ZMH3AKNJ.log.ansi diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py index 52d80e5f5..4bd1b0335 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py @@ -179,6 +179,7 @@ def CurrentMilliamps(self) -> float: @property def BattAdcTempKelvin(self) -> float: + # ! TODO: This is wrong. return self.despan(self._BattAdcTempRaw, 8, 75, -12.31, span_max=233) # Make public get, private set to signal that you can freely use these values @@ -248,8 +249,11 @@ def decode(cls, f"Expected {cls.START_FLAG}, Got: {flag} ." ) # TODO: use `bitstruct.compile` on first run to speed processing time. + bitfields = [*bitstruct.unpack('u7u1u7u1u8', core_data)] + # Unshift fields: + bitfields[-1] = bitfields[-1] << 4 custom_payload = WatchdogHeartbeatPacket.CustomPayload( - *bitstruct.unpack('u7u1u7u1u8', core_data) + *bitfields ) return WatchdogHeartbeatPacket( custom_payload=custom_payload, diff --git a/Apps/GroundSoftware/out/___bgapi_passthrough_programming_session__01GJD7DN8HYX8M8775ZMH3AKNJ.log.ansi b/Apps/GroundSoftware/out/___bgapi_passthrough_programming_session__01GJD7DN8HYX8M8775ZMH3AKNJ.log.ansi new file mode 100644 index 000000000..d754275d3 --- /dev/null +++ b/Apps/GroundSoftware/out/___bgapi_passthrough_programming_session__01GJD7DN8HYX8M8775ZMH3AKNJ.log.ansi @@ -0,0 +1,507 @@ +11-21 08:53:09.f NOTICE Starting Iris BGAPI Passthrough Programmer . . . +11-21 08:53:09.f INFO Loading and Compiling DFU file ../FlightSoftware/Radio/build/iris_wifi_radio__auto_connect.dfu . . . +11-21 08:53:12.f VERBOSE Compiled 512000B into 4000 chunks of 128B with a total ICP transmission size of 628000B. +11-21 08:53:12.f INFO Starting Serial using A7035PDL at 9600baud . . . +11-21 08:53:12.f ERROR Failed to connect to serial device. Is the device name right? Check the connection? Original error: list index out of range +11-21 08:53:12.f INFO Waiting for data from Hercules . . . +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Can't read data, serial connection not started. Try `connect_serial()`. +11-21 08:53:12.f SPAM Got: +UnsupportedPacket[0B]: + + +11-21 08:53:12.f ERROR Haven't heard anything from Hercules. Aborting. From bfb5b0505045164ef74433e1979bde69233edcbe Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 09:53:04 -0500 Subject: [PATCH 02/39] GDS: Added voltage scaling corrections in ADC conversions based on FM1 observations during RCs. --- .../watchdog_detailed_status.py | 89 +++++++++++++++---- 1 file changed, 72 insertions(+), 17 deletions(-) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py index 9a6ffbfd8..a72665108 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py @@ -5,7 +5,7 @@ detailed replacement for Heartbeat. @author: Connor W. Colombo (CMU) -@last-updated: 05/01/2022 +@last-updated: 12/31/2022 """ from __future__ import annotations # Activate postponed annotations (for using classes as return type in their own methods) @@ -62,9 +62,38 @@ class CustomPayload(): 'degC': np.asarray([-55, -50, -45, -40, -35, -30, -25, -20, -15, -10, -5, 0, 5, 10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60, 65, 70, 75, 80, 85, 90, 95, 100, 105, 110, 115, 120, 125, 130, 135, 140, 145, 150, 155]), 'RTH_R25': np.asarray([96.3, 67.01, 47.17, 33.65, 24.26, 17.7, 13.04, 9.707, 7.293, 5.533, 4.232, 3.265, 2.539, 1.99, 1.571, 1.249, 1.0000, 0.8057, 0.6531, 0.5327, 0.4369, 0.3603, 0.2986, 0.2488, 0.2083, 0.1752, 0.1481, 0.1258, 0.1072, 0.09177, 0.07885, 0.068, 0.05886, 0.05112, 0.04454, 0.03893, 0.03417, 0.03009, 0.02654, 0.02348, 0.02083, 0.01853, 0.01653]) } + V_LANDER_MAX = 1.10*28.0 # Maximum possible lander voltage (allowed) V_HEATER_NOM = 28.0 # NOMINAL Heater Voltage R_HEATER = 628.245 # Heater resistance (ohms) + # Correction factor for Vcc28 ADC conversion on FM1 in the cleanroom + # during RC6 at 28.0V input: + # upper 6bits = +-64ADC = +-0.567V + # At 28.0V, an ADC reading of 3158.6777 would be expected. Since only + # upper 6b are being sent, this needs to be rounded to nearest 64: 3136. + VCC28_ADC_FM1_CORRECTION_FACTOR = 3136 / 2944 + # Correction factor for VL ADC conversion on FM1 in the cleanroom + # during RC6 at 28.0V input: + # upper 7bits = +-32ADC = +-0.248V + # At 28.0V, an ADC reading of 3611.5347 would be expected. Since only + # upper 7b are being sent, this needs to be rounded to nearest 32: 3616. + VL_ADC_FM1_CORRECTION_FACTOR = 3616 / 3104 + + # Correction factor for VSA ADC conversion on FM1 in the cleanroom + # during RC6 at 28.0V input: + # upper 5bits = +-128ADC = +-0.992V + # At 28.0V, an ADC reading of 3611.5347 would be expected. Since only + # upper 5b are being sent, this needs to be rounded to nearest 128: 3584. + # yes, 2944 was observed here too (large jumps b/c so few bits) + VSA_ADC_FM1_CORRECTION_FACTOR = 3584 / 2944 + + # Correction factor for VBS ADC conversion on FM1 in the cleanroom + # during RC5 at 23.80V VBS: + # upper 9bits = +-8ADC = +-0.054V + # At 23.80V, an ADC reading of 3558.5824 would be expected. Since only + # upper 9b are being sent, this needs to be rounded to nearest 8: 3560. + VBS_ADC_FM1_CORRECTION_FACTOR = 3560 / 2928 + __slots__: List[str] = [ '_Io_ChargingStatus1', '_Io_ChargingStatus2', @@ -167,10 +196,29 @@ def fused_est_lander_voltage(self) -> float: # TODO: Update these weights from empirical measurements of their accuracies and uncertainties dLander = 0.25 # [Volts] (uncertainty in LanderVoltage reading) dVcc28 = 0.5 # [Volts] (uncertainty in Vcc28Voltage reading) + + VLander = self.Adc_LanderVoltage + Vcc28 = self.Adc_Vcc28Voltage + + # If a significant difference exists (i.e. one sensor is likely faulty)...: + if (abs(Vcc28 - VLander) / max(abs(VLander), abs(Vcc28))) > 0.5: + # If one of them is significantly greater (50%) than the max + # possible lander voltage (i.e. way to large -- failed high), + # take the other one: + if (VLander > 1.5 * self.V_LANDER_MAX) and (Vcc28 <= 1.5 * self.V_LANDER_MAX): + return Vcc28 + if (Vcc28 > 1.5 * self.V_LANDER_MAX) and (VLander <= 1.5 * self.V_LANDER_MAX): + return VLander + # otherwise, just use the larger of the two (since the lower + # one likely failed low): + return max(VLander, Vcc28) + + # Guard against poor uncertainty settings: if (dLander+dVcc28) == 0: return 0 - else: - return self.Adc_LanderVoltage * (1.0-dLander/(dLander+dVcc28)) + self.Adc_Vcc28Voltage * (1.0-dVcc28/(dLander+dVcc28)) + + # Both sensors have consistent values, so fuse the results: + return VLander * (1.0-dLander/(dLander+dVcc28)) + Vcc28 * (1.0-dVcc28/(dLander+dVcc28)) # Computed properties for Computed Telemetry Channels: @property @@ -405,7 +453,7 @@ def Watchdog_ResetEventsList(self) -> List[str]: @property def Adc_LanderVoltage(self) -> float: - return float(self.Adc_LanderVoltageRaw) / 4095.0 * 3.3 * (232.0+2000.0)/232.0 + return self.VL_ADC_FM1_CORRECTION_FACTOR * float(self.Adc_LanderVoltageRaw) / 4095.0 * 3.3 * (232.0+2000.0)/232.0 @property def Adc_BatteryChargingTempKelvin(self) -> float: @@ -447,7 +495,7 @@ def Adc_BatteryTempUncertaintyKelvin(self) -> float: @property def Adc_FullSystemVoltage(self) -> float: - return float(self.Adc_FullSystemVoltageRaw) / 4095.0 * 3.3 * (232.0+2000.0)/232.0 + return self.VSA_ADC_FM1_CORRECTION_FACTOR * float(self.Adc_FullSystemVoltageRaw) / 4095.0 * 3.3 * (232.0+2000.0)/232.0 @property def Adc_FullSystemCurrent(self) -> float: @@ -457,7 +505,7 @@ def Adc_FullSystemCurrent(self) -> float: @property def Adc_SwitchedBatteryVoltage(self) -> float: - return float(self.Adc_SwitchedBatteryVoltageRaw) / 4095.0 * 3.3 * (274.0+2000.0)/274.0 + return self.VBS_ADC_FM1_CORRECTION_FACTOR * float(self.Adc_SwitchedBatteryVoltageRaw) / 4095.0 * 3.3 * (274.0+2000.0)/274.0 @property def Adc_2V5Voltage(self) -> float: @@ -471,7 +519,7 @@ def Adc_2V8Voltage(self) -> float: @property def Adc_Vcc28Voltage(self) -> float: - return float(self.Adc_Vcc28VoltageRaw) / 4095.0 * 3.3 * (47.0+470.0)/47.0 + return self.VCC28_ADC_FM1_CORRECTION_FACTOR * float(self.Adc_Vcc28VoltageRaw) / 4095.0 * 3.3 * (47.0+470.0)/47.0 @property def Adc_Vcc24Voltage(self) -> float: @@ -499,6 +547,7 @@ def Adc_DataFrame(self) -> DataFrame: @property def Heater_PwmLimit_DutyCyclePercent(self) -> float: + # NOTE: PwmLimit is deprecated if self.Heater_DutyCyclePeriodCycles == 0: return float('Inf') else: @@ -506,7 +555,7 @@ def Heater_PwmLimit_DutyCyclePercent(self) -> float: @property def Heater_EffectivePowerLimit(self) -> float: - # TODO: consider using V_HEATER_NOM instead of `fused_est_lander_voltage` in case `fused_est_lander_voltage` isn't accurate + # NOTE: PwmLimit is deprecated max_avail_voltage = self.fused_est_lander_voltage * \ self.Heater_PwmLimit_DutyCyclePercent / 100.0 if self.R_HEATER == 0: @@ -514,6 +563,14 @@ def Heater_EffectivePowerLimit(self) -> float: else: return max_avail_voltage**2 / self.R_HEATER + @property + def Heater_MaxPossiblePower(self) -> float: + # Maximum possible heater power + if self.R_HEATER == 0: + return float('Inf') + else: + return self.fused_est_lander_voltage**2 / self.R_HEATER + @property def Heater_SetpointKelvin(self) -> float: # ! TODO: Why are we sending 16b if Adc maxes out at 12b... Strongly consider revising. @@ -547,7 +604,6 @@ def Heater_DutyCyclePercent(self) -> float: @property def Heater_EffectiveVoltage(self) -> float: - # TODO: consider using V_HEATER_NOM instead of `fused_est_lander_voltage` in case `fused_est_lander_voltage` isn't accurate return self.fused_est_lander_voltage * self.Heater_DutyCyclePercent / 100.0 @property @@ -861,13 +917,12 @@ def __repr__(self) -> str: f"ISA: {self.Adc_FullSystemCurrent*1000:.1f}mA" "\n" "HEATER " - f"[{self.Heater_OnTempKelvin:.0f}K |" - f"{self.Heater_SetpointKelvin:.0f}K |" - f"{self.Heater_OffTempKelvin:.0f}K] \t" + f"[↑{self.Heater_OnTempKelvin:.0f}K ({self.Heater_OnValue}) | " + f"↓{self.Heater_OffTempKelvin:.0f}K ({self.Heater_OffValue})] \t" f" is {self.getEnumName('Heater_IsHeating')}, " f"Control: {self.getEnumName('Heater_ControlEnabled')} \t" - f"@ {self.Heater_EffectivePower:.3f}W / {self.Heater_EffectivePowerLimit:.3f}W \t" - f"Period: {self.Heater_DutyCyclePeriodMs:.1f}ms" + f"@ {self.Heater_EffectivePower:.3f}W / {self.Heater_MaxPossiblePower:.3f}W \t" + f"Period: {self.Heater_DutyCyclePeriodMs:.2f}ms" "\n" f"Tbatt: {self.Adc_BatteryTempKelvin:.1f}K ± {self.Adc_BatteryTempUncertaintyKelvin}K \t" f"Tchrg: {self.Adc_BatteryChargingTempKelvin:.1f}K ± {self.Adc_BatteryChargingTempUncertaintyKelvin}K \t" @@ -930,9 +985,9 @@ class WatchdogDetailedStatusPacket(WDS_PI[WDS_PI, WDS_CP]): ('Adc_2V5VoltageRaw', (5, True, 5, WD_ADC_BITS)), ('Adc_2V8VoltageRaw', (5, True, 5, WD_ADC_BITS)), ('Adc_Vcc28VoltageRaw', (6, True, 6, WD_ADC_BITS)), - ('Heater_Kp', (16, False, 0, 0)), - ('Heater_PwmLimit_DutyCycleCounter', (16, False, 0, 0)), - ('Heater_SetpointValue', (16, False, 0, 0)), + ('Heater_Kp', (16, False, 0, 0)), # Deprecated + ('Heater_PwmLimit_DutyCycleCounter', (16, False, 0, 0)), # Deprecated + ('Heater_SetpointValue', (16, False, 0, 0)), # Deprecated ('Heater_OnValue', (16, False, 0, 0)), ('Heater_OffValue', (16, False, 0, 0)), ('Heater_DutyCyclePeriodCycles', (16, False, 0, 0)), From db522e34b667a4cab2641c3c21900ba171757779 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 09:57:23 -0500 Subject: [PATCH 03/39] WD: Added notes to flags.h and applied linter. --- Apps/FlightSoftware/Watchdog/include/flags.h | 284 +++++++++---------- 1 file changed, 142 insertions(+), 142 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/flags.h b/Apps/FlightSoftware/Watchdog/include/flags.h index 2059082c8..f668c1a3a 100644 --- a/Apps/FlightSoftware/Watchdog/include/flags.h +++ b/Apps/FlightSoftware/Watchdog/include/flags.h @@ -15,10 +15,10 @@ extern "C" #define FLAG_UART0_RX_PACKET 0x1 #define FLAG_UART1_RX_PACKET 0x2 -#define FLAG_TIMER_TICK 0x8 -#define FLAG_TEMP_LOW 0x10 -#define FLAG_TEMP_HIGH 0x20 -#define FLAG_POWER_ISSUE 0x40 +#define FLAG_TIMER_TICK 0x8 +#define FLAG_TEMP_LOW 0x10 +#define FLAG_TEMP_HIGH 0x20 +#define FLAG_POWER_ISSUE 0x40 #define FLAG_I2C_GAUGE_READING_ACTIVE 0x80 #define WDFLAG_RADIO_KICK 0x0001 @@ -30,102 +30,102 @@ extern "C" #define WDFLAG_UNRESET_MOTOR2 0x0040 #define WDFLAG_UNRESET_MOTOR3 0x0080 #define WDFLAG_UNRESET_MOTOR4 0x0100 -#define WDFLAG_UNRESET_FPGA 0x0200 -#define WDFLAG_UNRESET_3V3 0x0400 -#define WDFLAG_POWER_ON_V_SYS_ALL 0x0800 -#define WDFLAG_HERCULES_KICK 0x1000 -#define WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE 0x2000 +#define WDFLAG_UNRESET_FPGA 0x0200 +#define WDFLAG_UNRESET_3V3 0x0400 +#define WDFLAG_POWER_ON_V_SYS_ALL 0x0800 +#define WDFLAG_HERCULES_KICK 0x1000 +#define WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE 0x2000 -#define WDOPT_MONITOR_HERCULES 0x0001 +#define WDOPT_MONITOR_HERCULES 0x0001 #define ENTER_DEFAULT_LPM LPM1 #define EXIT_DEFAULT_LPM LPM1_EXIT -typedef struct HeaterParams -{ - uint16_t m_kpHeater; - uint16_t m_pwmLimit; - uint16_t m_heaterSetpoint; - uint16_t m_heaterWindow; - uint16_t m_heaterOnVal; - uint16_t m_heaterOffVal; - BOOL m_heating; - BOOL m_heatingControlEnabled; - uint16_t m_heaterDutyCyclePeriod; - uint16_t m_heaterDutyCycle; -} HeaterParams; - -#define DEFAULT_KP_HEATER 500 -#define DEFAULT_PWM_LIMIT 8500 -#define DEFAULT_HEATER_SETPOINT 3325 -#define DEFAULT_HEATER_WINDOW 60 -// 3670 is the -5 deg C thermistor voltage ADC reading + typedef struct HeaterParams + { + uint16_t m_kpHeater; + uint16_t m_pwmLimit; + uint16_t m_heaterSetpoint; + uint16_t m_heaterWindow; + uint16_t m_heaterOnVal; // heater transitions to ON when T ADC < this value + uint16_t m_heaterOffVal; // heater transitions to OFF when T ADC > this value + BOOL m_heating; + BOOL m_heatingControlEnabled; + uint16_t m_heaterDutyCyclePeriod; + uint16_t m_heaterDutyCycle; + } HeaterParams; + +#define DEFAULT_KP_HEATER 500 // deprecated +#define DEFAULT_PWM_LIMIT 8500 // deprecated +#define DEFAULT_HEATER_SETPOINT 3325 // deprecated +#define DEFAULT_HEATER_WINDOW 60 // deprecated +// 3670 is the -5 deg C thermistor voltage ADC reading - heater transitions to ON when T ADC < this value: #define DEFAULT_HEATER_ON_VAL 3670 -// 3670 is the 0 deg C thermistor voltage ADC reading +// 3670 is the 0 deg C thermistor voltage ADC reading - heater transitions to OFF when T ADC > this value: #define DEFAULT_HEATER_OFF_VAL 3352 #define DEFAULT_HEATING_CONTROL_ENABLED TRUE #define DEFAULT_HEATER_DUTY_CYCLE_PERIOD 10000 #define DEFAULT_HEATER_DUTY_CYCLE 0 -#define GENERIC_BIT_INDEX_TO_TYPE_MASK(type, index) (((type) 1) << ((type) (index))) +#define GENERIC_BIT_INDEX_TO_TYPE_MASK(type, index) (((type)1) << ((type)(index))) #define GENERIC_BIT_INDEX_TO_UINT8_MASK(index) GENERIC_BIT_INDEX_TO_TYPE_MASK(uint8_t, index) #define GENERIC_BIT_INDEX_TO_UINT16_MASK(index) GENERIC_BIT_INDEX_TO_TYPE_MASK(uint16_t, index) #define GENERIC_BIT_INDEX_TO_UINT32_MASK(index) GENERIC_BIT_INDEX_TO_TYPE_MASK(uint32_t, index) #define GENERIC_BIT_INDEX_TO_UINT64_MASK(index) GENERIC_BIT_INDEX_TO_TYPE_MASK(uint64_t, index) #define GENERIC_SET_BIT_IN_UINT8(uintVal, index) \ - uintVal |= ((uint8_t) GENERIC_BIT_INDEX_TO_UINT8_MASK(index)) + uintVal |= ((uint8_t)GENERIC_BIT_INDEX_TO_UINT8_MASK(index)) #define GENERIC_SET_BIT_IN_UINT16(uintVal, index) \ - uintVal |= ((uint16_t) GENERIC_BIT_INDEX_TO_UINT16_MASK(index)) + uintVal |= ((uint16_t)GENERIC_BIT_INDEX_TO_UINT16_MASK(index)) #define GENERIC_SET_BIT_IN_UINT32(uintVal, index) \ - uintVal |= ((uint32_t) GENERIC_BIT_INDEX_TO_UINT32_MASK(index)) + uintVal |= ((uint32_t)GENERIC_BIT_INDEX_TO_UINT32_MASK(index)) #define GENERIC_SET_BIT_IN_UINT64(uintVal, index) \ - uintVal |= ((uint64_t) GENERIC_BIT_INDEX_TO_UINT64_MASK(index)) + uintVal |= ((uint64_t)GENERIC_BIT_INDEX_TO_UINT64_MASK(index)) #define GENERIC_CLEAR_BIT_IN_UINT8(uintVal, index) \ - uintVal &= ~((uint8_t) GENERIC_BIT_INDEX_TO_UINT8_MASK(index)) + uintVal &= ~((uint8_t)GENERIC_BIT_INDEX_TO_UINT8_MASK(index)) #define GENERIC_CLEAR_BIT_IN_UINT16(uintVal, index) \ - uintVal &= ~((uint16_t) GENERIC_BIT_INDEX_TO_UINT16_MASK(index)) + uintVal &= ~((uint16_t)GENERIC_BIT_INDEX_TO_UINT16_MASK(index)) #define GENERIC_CLEAR_BIT_IN_UINT32(uintVal, index) \ - uintVal &= ~((uint32_t) GENERIC_BIT_INDEX_TO_UINT32_MASK(index)) + uintVal &= ~((uint32_t)GENERIC_BIT_INDEX_TO_UINT32_MASK(index)) #define GENERIC_CLEAR_BIT_IN_UINT64(uintVal, index) \ - uintVal &= ~((uint64_t) GENERIC_BIT_INDEX_TO_UINT64_MASK(index)) - -typedef enum OutputPinStatusBitIndices -{ - // These are digital outputs. If the corresponding bit is set, these should be high - OPSBI__V_LANDER_REG_EN = 0, - OPSBI__HEATER, - OPSBI__DEPLOYMENT, - OPSBI__FPGA_KICK_AKA_CAM_SELECT, - OPSBI__LATCH_BATT, - OPSBI__3V3_EN, - OPSBI__HERCULES_ON, - OPSBI__FPGA_ON, - OPSBI__MOTOR_ON, - OPSBI__CHRG_EN, - OPSBI__CHRG_EN_FORCE_HIGH, - OPSBI__BATTERY_EN, - OPSBI__V_SYS_ALL_EN, - OPSBI__V_SYS_ALL_EN_FORCE_LOW, - OPSBI__HERCULES_N_RST, - OPSBI__HERCULES_N_PORRST, - OPSBI__FPGA_N_RST, - OPSBI__RADIO_N_RST, - OPSBI__RADIO_ON, - OPSBI__BMS_BOOT, - OPSBI__LATCH_SET, - OPSBI__LATCH_RESET, - OPSBI__BATT_STAT, - - OPSBI__RADIO_N_RESET_IS_INPUT, - OPSBI__HERCULES_N_RST_IS_INPUT, - OPSBI__HERCULES_N_PORRST_IS_INPUT, - OPSBI__FPGA_N_RST_IS_INPUT, - OPSBI__LATCH_SET_IS_INPUT, - OPSBI__LATCH_RESET_IS_INPUT, - OPSBI__BATT_STAT_IS_INPUT, -} OutputPinStatusBitIndices; + uintVal &= ~((uint64_t)GENERIC_BIT_INDEX_TO_UINT64_MASK(index)) + + typedef enum OutputPinStatusBitIndices + { + // These are digital outputs. If the corresponding bit is set, these should be high + OPSBI__V_LANDER_REG_EN = 0, + OPSBI__HEATER, + OPSBI__DEPLOYMENT, + OPSBI__FPGA_KICK_AKA_CAM_SELECT, + OPSBI__LATCH_BATT, + OPSBI__3V3_EN, + OPSBI__HERCULES_ON, + OPSBI__FPGA_ON, + OPSBI__MOTOR_ON, + OPSBI__CHRG_EN, + OPSBI__CHRG_EN_FORCE_HIGH, + OPSBI__BATTERY_EN, + OPSBI__V_SYS_ALL_EN, + OPSBI__V_SYS_ALL_EN_FORCE_LOW, + OPSBI__HERCULES_N_RST, + OPSBI__HERCULES_N_PORRST, + OPSBI__FPGA_N_RST, + OPSBI__RADIO_N_RST, + OPSBI__RADIO_ON, + OPSBI__BMS_BOOT, + OPSBI__LATCH_SET, + OPSBI__LATCH_RESET, + OPSBI__BATT_STAT, + + OPSBI__RADIO_N_RESET_IS_INPUT, + OPSBI__HERCULES_N_RST_IS_INPUT, + OPSBI__HERCULES_N_PORRST_IS_INPUT, + OPSBI__FPGA_N_RST_IS_INPUT, + OPSBI__LATCH_SET_IS_INPUT, + OPSBI__LATCH_RESET_IS_INPUT, + OPSBI__BATT_STAT_IS_INPUT, + } OutputPinStatusBitIndices; #define OPSBI_MASK(opsbi_index_enum) GENERIC_BIT_INDEX_TO_UINT32_MASK(opsbi_index_enum) #define SET_OPSBI_IN_UINT(opsbiUint, opsbi_index_enum) GENERIC_SET_BIT_IN_UINT32(opsbiUint, opsbi_index_enum) @@ -133,24 +133,24 @@ typedef enum OutputPinStatusBitIndices #define CLEAR_OPSBI_IN_UINT(opsbiUint, opsbi_index_enum) GENERIC_CLEAR_BIT_IN_UINT32(opsbiUint, opsbi_index_enum) #define CLEAR_OPSBI_IN_UINT_PTR(opsbiUintPtr, opsbi_index_enum) CLEAR_OPSBI_IN_UINT(*opsbiUintPtr, opsbi_index_enum) -typedef enum InputPinAndStateBitIndices -{ - // State related things - IPASBI__UART0_INITIALIZED = 0, - IPASBI__UART1_INITIALIZED, - IPASBI__DEPLOYED, - IPASBI__DEPLOYING, - - // These are digital inputs. If the corresponding bit is set, then the input reads high - IPASBI__CHARGE_STAT1, - IPASBI__CHARGE_STAT2, - IPASBI__BATT_STAT, - IPASBI__LATCH_STAT, - IPASBI__PG12, - IPASBI__PG18, - IPASBI__PG33, - IPASBI__PG50, -} InputPinAndStateBitIndices; + typedef enum InputPinAndStateBitIndices + { + // State related things + IPASBI__UART0_INITIALIZED = 0, + IPASBI__UART1_INITIALIZED, + IPASBI__DEPLOYED, + IPASBI__DEPLOYING, + + // These are digital inputs. If the corresponding bit is set, then the input reads high + IPASBI__CHARGE_STAT1, + IPASBI__CHARGE_STAT2, + IPASBI__BATT_STAT, + IPASBI__LATCH_STAT, + IPASBI__PG12, + IPASBI__PG18, + IPASBI__PG33, + IPASBI__PG50, + } InputPinAndStateBitIndices; #define IPASBI_MASK(ipasbi_index_enum) GENERIC_BIT_INDEX_TO_UINT16_MASK(ipasbi_index_enum) #define SET_IPASBI_IN_UINT(ipasbiUint, ipasbi_index_enum) GENERIC_SET_BIT_IN_UINT16(ipasbiUint, ipasbi_index_enum) @@ -158,47 +158,47 @@ typedef enum InputPinAndStateBitIndices #define CLEAR_IPASBI_IN_UINT(ipasbiUint, ipasbi_index_enum) GENERIC_CLEAR_BIT_IN_UINT16(ipasbiUint, ipasbi_index_enum) #define CLEAR_IPASBI_IN_UINT_PTR(ipasbiUintPtr, ipasbi_index_enum) CLEAR_IPASBI_IN_UINT(*ipasbiUintPtr, ipasbi_index_enum) -typedef enum ResetActionBitIndices -{ - RABI__NO_RESET = 0, - RABI__HERCULES_RESET, - RABI__HERCULES_UNRESET, - RABI__HERCULES_POWER_ON, - RABI__HERCULES_POWER_OFF, - RABI__RADIO_RESET, - RABI__RADIO_UNRESET, - RABI__RADIO_POWER_ON, - RABI__RADIO_POWER_OFF, - RABI__CAM_FPGA_RESET, - RABI__CAM_FPGA_UNRESET, - RABI__CAM_FPGA_POWER_ON, - RABI__CAM_FPGA_POWER_OFF, - RABI__ALL_MOTORS_POWER_ON, - RABI__ALL_MOTORS_POWER_OFF, - RABI__3V3_EN_RESET, - RABI__3V3_EN_UNRESET, - RABI__3V3_EN_POWER_ON, - RABI__3V3_EN_POWER_OFF, - RABI__V_SYS_ALL_OFF__RESET, - RABI__V_SYS_ALL_ON__UNRESET, - RABI__V_SYS_ALL_POWER_ON, - RABI__V_SYS_ALL_POWER_OFF, - RABI__HDRM_DEPLOY_SIGNAL_POWER_OFF, - RABI__FPGA_CAM_0_SELECT, - RABI__FPGA_CAM_1_SELECT, - RABI__BATTERY_CHARGE_START, - RABI__BATTERY_CHARGE_STOP, - RABI__RS422_UART_ENABLE, - RABI__RS422_UART_DISABLE, - RABI__AUTO_HEATER_CONTROLLER_ENABLE, - RABI__AUTO_HEATER_CONTROLLER_DISABLE, - RABI__HERCULES_WATCHDOG_ENABLE, - RABI__HERCULES_WATCHDOG_DISABLE, - RABI__BATTERIES_ENABLE, - RABI__BATTERIES_DISABLE, - RABI__HDRM_DEPLOY_SIGNAL_POWER_ON, - RABI__HERCULES_WATCHDOG_RESET -} ResetActionBitIndices; + typedef enum ResetActionBitIndices + { + RABI__NO_RESET = 0, + RABI__HERCULES_RESET, + RABI__HERCULES_UNRESET, + RABI__HERCULES_POWER_ON, + RABI__HERCULES_POWER_OFF, + RABI__RADIO_RESET, + RABI__RADIO_UNRESET, + RABI__RADIO_POWER_ON, + RABI__RADIO_POWER_OFF, + RABI__CAM_FPGA_RESET, + RABI__CAM_FPGA_UNRESET, + RABI__CAM_FPGA_POWER_ON, + RABI__CAM_FPGA_POWER_OFF, + RABI__ALL_MOTORS_POWER_ON, + RABI__ALL_MOTORS_POWER_OFF, + RABI__3V3_EN_RESET, + RABI__3V3_EN_UNRESET, + RABI__3V3_EN_POWER_ON, + RABI__3V3_EN_POWER_OFF, + RABI__V_SYS_ALL_OFF__RESET, + RABI__V_SYS_ALL_ON__UNRESET, + RABI__V_SYS_ALL_POWER_ON, + RABI__V_SYS_ALL_POWER_OFF, + RABI__HDRM_DEPLOY_SIGNAL_POWER_OFF, + RABI__FPGA_CAM_0_SELECT, + RABI__FPGA_CAM_1_SELECT, + RABI__BATTERY_CHARGE_START, + RABI__BATTERY_CHARGE_STOP, + RABI__RS422_UART_ENABLE, + RABI__RS422_UART_DISABLE, + RABI__AUTO_HEATER_CONTROLLER_ENABLE, + RABI__AUTO_HEATER_CONTROLLER_DISABLE, + RABI__HERCULES_WATCHDOG_ENABLE, + RABI__HERCULES_WATCHDOG_DISABLE, + RABI__BATTERIES_ENABLE, + RABI__BATTERIES_DISABLE, + RABI__HDRM_DEPLOY_SIGNAL_POWER_ON, + RABI__HERCULES_WATCHDOG_RESET + } ResetActionBitIndices; #define RABI_MASK(rabi_index_enum) GENERIC_BIT_INDEX_TO_UINT64_MASK(rabi_index_enum) #define SET_RABI_IN_UINT(rabiUint, rabi_index_enum) GENERIC_SET_BIT_IN_UINT64(rabiUint, rabi_index_enum) @@ -206,14 +206,14 @@ typedef enum ResetActionBitIndices #define CLEAR_RABI_IN_UINT(rabiUint, rabi_index_enum) GENERIC_CLEAR_BIT_IN_UINT64(rabiUint, rabi_index_enum) #define CLEAR_RABI_IN_UINT_PTR(rabiUintPtr, rabi_index_enum) CLEAR_RABI_IN_UINT(*rabiUintPtr, rabi_index_enum) -typedef struct WatchdogStateDetails -{ - uint32_t m_outputPinBits; - uint16_t m_inputPinAndStateBits; - uint64_t m_resetActionBits; - uint8_t m_stateAsUint; - HeaterParams m_hParams; -} WatchdogStateDetails; + typedef struct WatchdogStateDetails + { + uint32_t m_outputPinBits; + uint16_t m_inputPinAndStateBits; + uint64_t m_resetActionBits; + uint8_t m_stateAsUint; + HeaterParams m_hParams; + } WatchdogStateDetails; #ifdef __cplusplus } /* close extern "C" */ From ec74e413195e066f31d5617f458df9d538577f49 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 09:58:34 -0500 Subject: [PATCH 04/39] WD: Added notes to ground_msgs.h and applied linter. --- .../Watchdog/include/comms/ground_msgs.h | 306 +++++++++--------- 1 file changed, 153 insertions(+), 153 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h b/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h index 9924b8cb7..d54bcdb6d 100644 --- a/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h +++ b/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h @@ -15,159 +15,159 @@ extern "C" #define MANUALLY_CONSTRUCT_REPORT -typedef enum GroundMsgs__Status -{ - GND_MSGS__STATUS__SUCCESS = 0, /* Operation succeeded. */ - GND_MSGS__STATUS__ERROR_NULL = -1, /* A required argument or a member of an argument was NULL */ - GND_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL = -2, - GND_MSGS__STATUS__ERROR_SERIALIZATION_ERROR = -3, - GND_MSGS__STATUS__ERROR_UNKNOWN_MESSAGE_ID = -4, - GND_MSGS__STATUS__ERROR_UNKNOWN_MAGIC_NUMBER = -5, - GND_MSGS__STATUS__ERROR_WRONG_STATE = -6, - GND_MSGS__STATUS__ERROR_UNKNOWN_RESET_VALUE = -7, - - GND_MSGS__STATUS__ERROR__INTERNAL = -255 /* An unexpected internal error occurred. */ -} GroundMsgs__Status; - -typedef struct __attribute__((packed)) FlightEarthHeartbeat -{ - uint8_t magicNumber; - uint8_t batt_charge_telem : 7; - uint8_t heating : 1; - uint8_t batt_curr_telem : 7; - uint8_t battery_voltage_good : 1; - uint8_t battTemp; -} FlightEarthHeartbeat; - -typedef struct __attribute__((packed)) FullEarthHeartbeat -{ - uint8_t magicNumber; // always equal to 0xFF - uint16_t battTemp; - uint8_t raw_battery_charge[2]; - uint8_t raw_battery_voltage[2]; - uint8_t raw_battery_current[2]; - uint8_t raw_fuel_gauge_temp[2]; - uint16_t kpHeater; - uint16_t heaterSetpoint; - uint16_t heaterWindow; - uint16_t pwmLimit; - uint8_t stateAsUint; - uint8_t heating; - uint8_t heatingControlEnabled; -uint16_t pwmValue; -} FullEarthHeartbeat; - -typedef struct __attribute__((packed)) DetailedReport -{ - uint8_t magic; // Should always be 0xD5 - - uint8_t chargeStat1 : 1; - uint8_t chargeStat2 : 1; - uint8_t battStat : 1; - uint8_t latchStat : 1; - uint8_t pg12 : 1; - uint8_t pg18 : 1; - uint8_t pg33 : 1; - uint8_t pg50 : 1; - - uint8_t state; - - uint16_t deploymentStatus : 2; // 00 = not deployed, 01 = deploying, 10 = deployed - uint16_t uart0Initialized : 1; - uint16_t uart1Initialized : 1; - uint16_t adcBattRT : 12; - - uint8_t sequenceNumber; - - uint32_t outputPinStateBits; - - uint32_t lowerResetActionBits; - uint8_t upperResetActionBits; - - uint16_t vLanderSense : 7; // upper 7 bits (from 12-bit resolution data) - uint16_t battTemp : 9; // upper 9 bits (from 12-bit resolution data) - - uint32_t vSysAllSens : 5; // upper 5 bits (from 12-bit resolution data) - uint32_t iSysAllSense : 9; // LOWER 9 bits (from 12-bit resolution data) - uint32_t vBattSense : 9; // upper 9 bits (from 12-bit resolution data) - uint32_t vcc24 : 7; // upper 7 bits (from 12-bit resolution data) - uint32_t heatingControlEnabled : 1; - uint32_t heating : 1; - - uint16_t vcc2Point5 : 5; // upper 5 bits (from 12-bit resolution data) - uint16_t vcc2Point8 : 5; // upper 5 bits (from 12-bit resolution data) - uint16_t vcc28 : 6; // upper 6 bits (from 12-bit resolution data) - - uint16_t kpHeater; - - uint16_t heaterPwmLimit; - - uint16_t heaterSetpoint; - - uint16_t heaterOnValue; - - uint16_t heaterOffValue; - - uint16_t heaterDutyCyclePeriod; - - uint16_t heaterPwmValue; - - uint8_t rawBatteryCharge[2]; - - uint8_t rawBatteryVoltage[2]; - - uint8_t rawBatteryCurrent[2]; - - uint8_t rawFuelGaugeTemp[2]; - - uint8_t battChargeTelem; - - uint8_t battCurrTelem; -} DetailedReport; - -/** - * @brief Generates a transit heartbeat message for transmission to ground. - * - * Since the struct is packed, we want to serialize with little endianness, and the MSP430 has little endianness, - * serializing this message it is as simple as casting the struct to uint8_t*. - * - * @param i2cReadings - * @param adcValues - * @param hParams - * @param hb - * @return - */ -GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - HeaterParams* hParams, - FlightEarthHeartbeat* hb); - -/** - * @brief Generates a serialized full heartbeat message for transmission to ground. - * - * Since the struct is packed, we want to serialize with little endianness, and the MSP430 has little endianness, - * serializing this message it is as simple as casting the struct to uint8_t*. - * - * Note that all uint16_t values are serialized with little endianness. - * - * @param i2cReadings - * @param adcValues - * @param hParams - * @param stateAsUint - * @param hb - * @return - */ -GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - HeaterParams* hParams, - uint8_t stateAsUint, - FullEarthHeartbeat* hb); - -GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - WatchdogStateDetails* details, - DetailedReport* hb, - uint8_t* reportBuffer); + typedef enum GroundMsgs__Status + { + GND_MSGS__STATUS__SUCCESS = 0, /* Operation succeeded. */ + GND_MSGS__STATUS__ERROR_NULL = -1, /* A required argument or a member of an argument was NULL */ + GND_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL = -2, + GND_MSGS__STATUS__ERROR_SERIALIZATION_ERROR = -3, + GND_MSGS__STATUS__ERROR_UNKNOWN_MESSAGE_ID = -4, + GND_MSGS__STATUS__ERROR_UNKNOWN_MAGIC_NUMBER = -5, + GND_MSGS__STATUS__ERROR_WRONG_STATE = -6, + GND_MSGS__STATUS__ERROR_UNKNOWN_RESET_VALUE = -7, + + GND_MSGS__STATUS__ERROR__INTERNAL = -255 /* An unexpected internal error occurred. */ + } GroundMsgs__Status; + + typedef struct __attribute__((packed)) FlightEarthHeartbeat + { + uint8_t magicNumber; + uint8_t batt_charge_telem : 7; + uint8_t heating : 1; + uint8_t batt_curr_telem : 7; + uint8_t battery_voltage_good : 1; + uint8_t battTemp; + } FlightEarthHeartbeat; + + typedef struct __attribute__((packed)) FullEarthHeartbeat + { + uint8_t magicNumber; // always equal to 0xFF + uint16_t battTemp; + uint8_t raw_battery_charge[2]; + uint8_t raw_battery_voltage[2]; + uint8_t raw_battery_current[2]; + uint8_t raw_fuel_gauge_temp[2]; + uint16_t kpHeater; + uint16_t heaterSetpoint; + uint16_t heaterWindow; + uint16_t pwmLimit; + uint8_t stateAsUint; + uint8_t heating; + uint8_t heatingControlEnabled; + uint16_t pwmValue; + } FullEarthHeartbeat; + + typedef struct __attribute__((packed)) DetailedReport + { + uint8_t magic; // Should always be 0xD5 + + uint8_t chargeStat1 : 1; + uint8_t chargeStat2 : 1; + uint8_t battStat : 1; + uint8_t latchStat : 1; + uint8_t pg12 : 1; + uint8_t pg18 : 1; + uint8_t pg33 : 1; + uint8_t pg50 : 1; + + uint8_t state; + + uint16_t deploymentStatus : 2; // 00 = not deployed, 01 = deploying, 10 = deployed + uint16_t uart0Initialized : 1; + uint16_t uart1Initialized : 1; + uint16_t adcBattRT : 12; + + uint8_t sequenceNumber; + + uint32_t outputPinStateBits; + + uint32_t lowerResetActionBits; + uint8_t upperResetActionBits; + + uint16_t vLanderSense : 7; // upper 7 bits (from 12-bit resolution data) + uint16_t battTemp : 9; // upper 9 bits (from 12-bit resolution data) + + uint32_t vSysAllSens : 5; // upper 5 bits (from 12-bit resolution data) + uint32_t iSysAllSense : 9; // LOWER 9 bits (from 12-bit resolution data) + uint32_t vBattSense : 9; // upper 9 bits (from 12-bit resolution data) + uint32_t vcc24 : 7; // upper 7 bits (from 12-bit resolution data) + uint32_t heatingControlEnabled : 1; + uint32_t heating : 1; + + uint16_t vcc2Point5 : 5; // upper 5 bits (from 12-bit resolution data) + uint16_t vcc2Point8 : 5; // upper 5 bits (from 12-bit resolution data) + uint16_t vcc28 : 6; // upper 6 bits (from 12-bit resolution data) + + uint16_t kpHeater; + + uint16_t heaterPwmLimit; + + uint16_t heaterSetpoint; + + uint16_t heaterOnValue; + + uint16_t heaterOffValue; + + uint16_t heaterDutyCyclePeriod; + + uint16_t heaterPwmValue; + + uint8_t rawBatteryCharge[2]; + + uint8_t rawBatteryVoltage[2]; + + uint8_t rawBatteryCurrent[2]; + + uint8_t rawFuelGaugeTemp[2]; + + uint8_t battChargeTelem; + + uint8_t battCurrTelem; + } DetailedReport; + + /** + * @brief Generates a transit heartbeat message for transmission to ground. + * + * Since the struct is packed, we want to serialize with little endianness, and the MSP430 has little endianness, + * serializing this message it is as simple as casting the struct to uint8_t*. + * + * @param i2cReadings + * @param adcValues + * @param hParams + * @param hb + * @return + */ + GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + HeaterParams *hParams, + FlightEarthHeartbeat *hb); + + /** + * @brief Generates a serialized full heartbeat message for transmission to ground. + * + * Since the struct is packed, we want to serialize with little endianness, and the MSP430 has little endianness, + * serializing this message it is as simple as casting the struct to uint8_t*. + * + * Note that all uint16_t values are serialized with little endianness. + * + * @param i2cReadings + * @param adcValues + * @param hParams + * @param stateAsUint + * @param hb + * @return + */ + GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + HeaterParams *hParams, + uint8_t stateAsUint, + FullEarthHeartbeat *hb); + + GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + WatchdogStateDetails *details, + DetailedReport *hb, + uint8_t *reportBuffer); #ifdef __cplusplus } /* close extern "C" */ From 46181d016f852a5cab5e9a5a1f3625f5d5733ada Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:02:09 -0500 Subject: [PATCH 05/39] WD: Applied linter. --- .../Watchdog/src/comms/ground_msgs.c | 197 ++++++++++-------- .../FlightSoftware/Watchdog/src/drivers/adc.c | 63 +++--- 2 files changed, 138 insertions(+), 122 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c index 0dc915785..09287d847 100644 --- a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c +++ b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c @@ -15,40 +15,43 @@ #define ENABLE_DEBUGGING_PRINT_OF_FAKE_REPORT 0 #define ENABLE_FORMATTED_DEBUG_PRINT 0 -#define CHECK_SERIALIZATION_RESULT(RESULT_VAR) \ - if (0 > RESULT_VAR) { \ +#define CHECK_SERIALIZATION_RESULT(RESULT_VAR) \ + if (0 > RESULT_VAR) \ + { \ return GND_MSGS__STATUS__ERROR__INTERNAL; \ } -GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - HeaterParams* hParams, - FlightEarthHeartbeat* hb) +GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + HeaterParams *hParams, + FlightEarthHeartbeat *hb) { - if (NULL == i2cReadings || NULL == adcValues || NULL == hb) { + if (NULL == i2cReadings || NULL == adcValues || NULL == hb) + { return GND_MSGS__STATUS__ERROR_NULL; } hb->magicNumber = 0xFF; - hb->batt_charge_telem = (uint8_t) (i2cReadings->batt_charge_telem & 0x7F); + hb->batt_charge_telem = (uint8_t)(i2cReadings->batt_charge_telem & 0x7F); hb->heating = hParams->m_heating ? 1 : 0; - hb->batt_curr_telem = (uint8_t) (i2cReadings->batt_curr_telem & 0x7F); + hb->batt_curr_telem = (uint8_t)(i2cReadings->batt_curr_telem & 0x7F); // send voltage nominal status (1=good, 0=too low) // check if batt voltage is above 16.59 V (~10% above discharge cutoff) /** @todo Update this threshold **/ - hb->battery_voltage_good = (i2cReadings->raw_battery_voltage[0] > 0x3B) ? 1 : 0; - hb->battTemp = (uint8_t) (adcValues->battTemp >> 4); + hb->battery_voltage_good = (i2cReadings->raw_battery_voltage[0] > 0x3B) ? 1 : 0; + hb->battTemp = (uint8_t)(adcValues->battTemp >> 4); return GND_MSGS__STATUS__SUCCESS; } -GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - HeaterParams* hParams, +GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + HeaterParams *hParams, uint8_t stateAsUint, - FullEarthHeartbeat* hb) + FullEarthHeartbeat *hb) { - if (NULL == i2cReadings || NULL == adcValues || NULL == hParams || NULL == hb) { + if (NULL == i2cReadings || NULL == adcValues || NULL == hParams || NULL == hb) + { return GND_MSGS__STATUS__ERROR_NULL; } @@ -100,32 +103,33 @@ GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings* } #define BYTE_TO_BINARY_PATTERN "%c%c%c%c%c%c%c%c" -#define BYTE_TO_BINARY(byte) \ - (byte & 0x80 ? '1' : '0'), \ - (byte & 0x40 ? '1' : '0'), \ - (byte & 0x20 ? '1' : '0'), \ - (byte & 0x10 ? '1' : '0'), \ - (byte & 0x08 ? '1' : '0'), \ - (byte & 0x04 ? '1' : '0'), \ - (byte & 0x02 ? '1' : '0'), \ - (byte & 0x01 ? '1' : '0') - -GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2cReadings, - AdcValues* adcValues, - WatchdogStateDetails* details, - DetailedReport* report, - uint8_t* reportBuffer) +#define BYTE_TO_BINARY(byte) \ + (byte & 0x80 ? '1' : '0'), \ + (byte & 0x40 ? '1' : '0'), \ + (byte & 0x20 ? '1' : '0'), \ + (byte & 0x10 ? '1' : '0'), \ + (byte & 0x08 ? '1' : '0'), \ + (byte & 0x04 ? '1' : '0'), \ + (byte & 0x02 ? '1' : '0'), \ + (byte & 0x01 ? '1' : '0') + +GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings *i2cReadings, + AdcValues *adcValues, + WatchdogStateDetails *details, + DetailedReport *report, + uint8_t *reportBuffer) { static uint8_t sequenceNumber = 0; - if (NULL == i2cReadings || NULL == adcValues || NULL == details || NULL == report) { + if (NULL == i2cReadings || NULL == adcValues || NULL == details || NULL == report) + { return GND_MSGS__STATUS__ERROR_NULL; } // Update values read from digital inputs on WD chip itself (not on I/O expander) readOnChipInputs(); - uint8_t* dstIntPtr = (uint8_t*) reportBuffer; + uint8_t *dstIntPtr = (uint8_t *)reportBuffer; report->magic = 0xD5; @@ -144,14 +148,14 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c report->pg50 = (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG50)) ? 1 : 0; uint8_t data = 0; - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__CHARGE_STAT1)) ? 1 : 0) & 0x1) << 7); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__CHARGE_STAT2)) ? 1 : 0) & 0x1) << 6); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__BATT_STAT)) ? 1 : 0) & 0x1) << 5); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__LATCH_STAT)) ? 1 : 0) & 0x1) << 4); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG12)) ? 1 : 0) & 0x1) << 3); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG18)) ? 1 : 0) & 0x1) << 2); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG33)) ? 1 : 0) & 0x1) << 1); - data |= (uint8_t) ((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG50)) ? 1 : 0) & 0x1) << 0); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__CHARGE_STAT1)) ? 1 : 0) & 0x1) << 7); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__CHARGE_STAT2)) ? 1 : 0) & 0x1) << 6); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__BATT_STAT)) ? 1 : 0) & 0x1) << 5); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__LATCH_STAT)) ? 1 : 0) & 0x1) << 4); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG12)) ? 1 : 0) & 0x1) << 3); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG18)) ? 1 : 0) & 0x1) << 2); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG33)) ? 1 : 0) & 0x1) << 1); + data |= (uint8_t)((((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__PG50)) ? 1 : 0) & 0x1) << 0); serializationResult = Serialization__serializeAs8Bit(&(data), dstIntPtr, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); @@ -163,28 +167,32 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c CHECK_SERIALIZATION_RESULT(serializationResult); dstIntPtr += sizeof(details->m_stateAsUint); - uint8_t deploymentStatus; - if (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__DEPLOYED)) { + if (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__DEPLOYED)) + { report->deploymentStatus = 2; deploymentStatus = 2; - } else if (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__DEPLOYING)) { + } + else if (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__DEPLOYING)) + { report->deploymentStatus = 1; deploymentStatus = 1; - } else { + } + else + { report->deploymentStatus = 0; deploymentStatus = 0; } report->uart0Initialized = (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART0_INITIALIZED)) ? 1 : 0; report->uart1Initialized = (details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART1_INITIALIZED)) ? 1 : 0; - report->adcBattRT = (uint16_t) (adcValues->battRT && 0x0FFF); + report->adcBattRT = (uint16_t)(adcValues->battRT && 0x0FFF); uint16_t data16 = 0; - data16 |= (uint16_t) (((uint16_t) (((uint8_t) deploymentStatus) & 0x3)) << 14); - data16 |= (uint16_t) (((uint16_t) (((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART0_INITIALIZED)) ? 1 : 0) & 0x1)) << 13); - data16 |= (uint16_t) (((uint16_t) (((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART1_INITIALIZED)) ? 1 : 0) & 0x1)) << 12); - data16 |= (uint16_t) (adcValues->battRT && 0x0FFF); + data16 |= (uint16_t)(((uint16_t)(((uint8_t)deploymentStatus) & 0x3)) << 14); + data16 |= (uint16_t)(((uint16_t)(((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART0_INITIALIZED)) ? 1 : 0) & 0x1)) << 13); + data16 |= (uint16_t)(((uint16_t)(((details->m_inputPinAndStateBits & IPASBI_MASK(IPASBI__UART1_INITIALIZED)) ? 1 : 0) & 0x1)) << 12); + data16 |= (uint16_t)(adcValues->battRT && 0x0FFF); serializationResult = Serialization__serializeAs16Bit(&(data16), dstIntPtr, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); @@ -202,56 +210,57 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c CHECK_SERIALIZATION_RESULT(serializationResult); dstIntPtr += sizeof(details->m_outputPinBits); - report->lowerResetActionBits = (uint32_t) (0xFFFFFFFF & (details->m_resetActionBits)); - report->upperResetActionBits = (uint8_t) (((details->m_resetActionBits) >> 32) & 0xFF); + report->lowerResetActionBits = (uint32_t)(0xFFFFFFFF & (details->m_resetActionBits)); + report->upperResetActionBits = (uint8_t)(((details->m_resetActionBits) >> 32) & 0xFF); - uint8_t buffer64bit[8] = { 0 }; + uint8_t buffer64bit[8] = {0}; serializationResult = Serialization__serializeAs64Bit(&(details->m_resetActionBits), buffer64bit, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); - for (int i = 5; i >= 0; i--) { + for (int i = 5; i >= 0; i--) + { *dstIntPtr = buffer64bit[i]; dstIntPtr++; } - report->vLanderSense = (uint8_t) (((adcValues->vLanderSense) >> 5) & 0x7F); // Top 7 bits of 12 - report->battTemp = (uint16_t) (((adcValues->battTemp) >> 3) & 0x1FF); // Top 9 bits of 12 + report->vLanderSense = (uint8_t)(((adcValues->vLanderSense) >> 5) & 0x7F); // Top 7 bits of 12 + report->battTemp = (uint16_t)(((adcValues->battTemp) >> 3) & 0x1FF); // Top 9 bits of 12 data16 = 0; - data16 |= (uint16_t) (((uint16_t) (((adcValues->vLanderSense) >> 5) & 0x7F)) << 9); - data16 |= (uint16_t) (((adcValues->battTemp) >> 3) & 0x1FF); + data16 |= (uint16_t)(((uint16_t)(((adcValues->vLanderSense) >> 5) & 0x7F)) << 9); + data16 |= (uint16_t)(((adcValues->battTemp) >> 3) & 0x1FF); serializationResult = Serialization__serializeAs16Bit(&(data16), dstIntPtr, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); dstIntPtr += sizeof(data16); - report->vSysAllSens = (uint8_t) (((adcValues->vSysAllSense) >> 7) & 0x1F); // Top 5 bits of 12 - report->iSysAllSense = (uint16_t) ((adcValues->iSysAllSense) & 0x1FF); // Bottom 9 bits of 12 - report->vBattSense = (uint16_t) (((adcValues->vBattSense) >> 3) & 0x1FF); // Top 9 bits of 12 - report->vcc24 = (uint8_t) (((adcValues->vcc24) >> 5) & 0x7F); // Top 7 bits of 12 + report->vSysAllSens = (uint8_t)(((adcValues->vSysAllSense) >> 7) & 0x1F); // Top 5 bits of 12 + report->iSysAllSense = (uint16_t)((adcValues->iSysAllSense) & 0x1FF); // Bottom 9 bits of 12 + report->vBattSense = (uint16_t)(((adcValues->vBattSense) >> 3) & 0x1FF); // Top 9 bits of 12 + report->vcc24 = (uint8_t)(((adcValues->vcc24) >> 5) & 0x7F); // Top 7 bits of 12 report->heatingControlEnabled = (details->m_hParams.m_heatingControlEnabled) ? 1 : 0; report->heating = (details->m_hParams.m_heating) ? 1 : 0; uint32_t data32 = 0; - data32 |= (uint32_t) (((uint32_t) (((adcValues->vSysAllSense) >> 7) & 0x1F)) << 27); - data32 |= (uint32_t) (((uint32_t) ((adcValues->iSysAllSense) & 0x1FF)) << 18); - data32 |= (uint32_t) (((uint32_t) (((adcValues->vBattSense) >> 3) & 0x1FF)) << 9); - data32 |= (uint32_t) (((uint32_t) (((adcValues->vcc24) >> 5) & 0x7F)) << 2); - data32 |= (uint32_t) (((details->m_hParams.m_heatingControlEnabled) ? 1 : 0) << 1); - data32 |= (uint32_t) ((details->m_hParams.m_heating) ? 1 : 0); + data32 |= (uint32_t)(((uint32_t)(((adcValues->vSysAllSense) >> 7) & 0x1F)) << 27); + data32 |= (uint32_t)(((uint32_t)((adcValues->iSysAllSense) & 0x1FF)) << 18); + data32 |= (uint32_t)(((uint32_t)(((adcValues->vBattSense) >> 3) & 0x1FF)) << 9); + data32 |= (uint32_t)(((uint32_t)(((adcValues->vcc24) >> 5) & 0x7F)) << 2); + data32 |= (uint32_t)(((details->m_hParams.m_heatingControlEnabled) ? 1 : 0) << 1); + data32 |= (uint32_t)((details->m_hParams.m_heating) ? 1 : 0); serializationResult = Serialization__serializeAs32Bit(&(data32), dstIntPtr, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); dstIntPtr += sizeof(data32); - report->vcc2Point5 = (uint8_t) (((adcValues->vcc2Point5) >> 7) & 0x1F); // Top 5 bits of 12 - report->vcc2Point8 = (uint8_t) (((adcValues->vcc2Point8) >> 7) & 0x1F); // Top 5 bits of 12 - report->vcc28 = (uint8_t) (((adcValues->vcc28) >> 6) & 0x3F); // Top 6 bits of 12 + report->vcc2Point5 = (uint8_t)(((adcValues->vcc2Point5) >> 7) & 0x1F); // Top 5 bits of 12 + report->vcc2Point8 = (uint8_t)(((adcValues->vcc2Point8) >> 7) & 0x1F); // Top 5 bits of 12 + report->vcc28 = (uint8_t)(((adcValues->vcc28) >> 6) & 0x3F); // Top 6 bits of 12 data16 = 0; - data16 |= (uint16_t) (((uint16_t) (((adcValues->vcc2Point5) >> 7) & 0x1F)) << 11); - data16 |= (uint16_t) (((uint16_t) (((adcValues->vcc2Point8) >> 7) & 0x1F)) << 6); - data16 |= (uint16_t) (((adcValues->vcc28) >> 6) & 0x3F); + data16 |= (uint16_t)(((uint16_t)(((adcValues->vcc2Point5) >> 7) & 0x1F)) << 11); + data16 |= (uint16_t)(((uint16_t)(((adcValues->vcc2Point8) >> 7) & 0x1F)) << 6); + data16 |= (uint16_t)(((adcValues->vcc28) >> 6) & 0x3F); serializationResult = Serialization__serializeAs16Bit(&(data16), dstIntPtr, SERIALIZATION__LITTLE_ENDIAN); CHECK_SERIALIZATION_RESULT(serializationResult); @@ -319,7 +328,7 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c dstIntPtr += sizeof(i2cReadings->batt_curr_telem); #if defined(ENABLE_DEBUG_ONLY_CODE) && ENABLE_DEBUGGING_PRINT_OF_FAKE_REPORT - DetailedReport report2 = { 0 }; + DetailedReport report2 = {0}; report2.magic = 0xD5; report2.chargeStat1 = 1; @@ -345,18 +354,18 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c report2.upperResetActionBits = 0; report2.vLanderSense = 0b1111111; // Top 7 bits of 12 - report2.battTemp = 0b110010011; // Top 9 bits of 12 + report2.battTemp = 0b110010011; // Top 9 bits of 12 - report2.vSysAllSens = 0b01110; // Top 5 bits of 12 + report2.vSysAllSens = 0b01110; // Top 5 bits of 12 report2.iSysAllSense = 0b100000111; // Bottom 9 bits of 12 - report2.vBattSense = 0b001100110; // Top 9 bits of 12 - report2.vcc24 = 0b0011100; // Top 7 bits of 12 + report2.vBattSense = 0b001100110; // Top 9 bits of 12 + report2.vcc24 = 0b0011100; // Top 7 bits of 12 report2.heatingControlEnabled = 0; report2.heating = 0; report2.vcc2Point5 = 0b10101; // Top 5 bits of 12 report2.vcc2Point8 = 0b01010; // Top 5 bits of 12 - report2.vcc28 = 0b110011; // Top 6 bits of 12 + report2.vcc28 = 0b110011; // Top 6 bits of 12 report2.kpHeater = 0x0A0B; report2.heaterPwmLimit = 0x0C0D; @@ -381,21 +390,25 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c report2.battChargeTelem = 0x5A; report2.battCurrTelem = 0x5B; - uint8_t *reportView = (uint8_t*) &report2; + uint8_t *reportView = (uint8_t *)&report2; size_t rowLen = 4; size_t numRows = sizeof(report2) / rowLen; - if (sizeof(report2) % rowLen > 0) { + if (sizeof(report2) % rowLen > 0) + { numRows++; } - for (size_t r = 0; r < numRows; ++r) { - DPRINTF_ERR("%s%d: ", (((rowLen * r) <= 9) ? "0" : ""), (int) (rowLen * r)); + for (size_t r = 0; r < numRows; ++r) + { + DPRINTF_ERR("%s%d: ", (((rowLen * r) <= 9) ? "0" : ""), (int)(rowLen * r)); - for (size_t c = 0; c < rowLen; ++c) { + for (size_t c = 0; c < rowLen; ++c) + { size_t i = (rowLen * r) + c; - if (i >= sizeof(report2)) { + if (i >= sizeof(report2)) + { break; } @@ -405,13 +418,16 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c } DPRINTF_ERR("\n"); - for (size_t r = 0; r < numRows; ++r) { - DPRINTF_ERR("%s%d: ", (((rowLen * r) <= 9) ? "0" : ""), (int) (rowLen * r)); + for (size_t r = 0; r < numRows; ++r) + { + DPRINTF_ERR("%s%d: ", (((rowLen * r) <= 9) ? "0" : ""), (int)(rowLen * r)); - for (size_t c = 0; c < rowLen; ++c) { + for (size_t c = 0; c < rowLen; ++c) + { size_t i = (rowLen * r) + c; - if (i >= sizeof(report2)) { + if (i >= sizeof(report2)) + { break; } @@ -425,4 +441,3 @@ GroundMsgs__Status GroundMsgs__generateDetailedReport(I2C_Sensors__Readings* i2c return GND_MSGS__STATUS__SUCCESS; } - diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/adc.c b/Apps/FlightSoftware/Watchdog/src/drivers/adc.c index deceaa80a..83a03c650 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/adc.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/adc.c @@ -30,10 +30,11 @@ * 12-bit: LSB = 0.0008056640625V */ -static AdcValues* outputValues = NULL; -static volatile uint16_t* watchdogFlagsPtr = NULL; +static AdcValues *outputValues = NULL; +static volatile uint16_t *watchdogFlagsPtr = NULL; -void adc_init(volatile uint16_t* watchdogFlags) { +void adc_init(volatile uint16_t *watchdogFlags) +{ watchdogFlagsPtr = watchdogFlags; // configure the ADC module @@ -100,14 +101,16 @@ BOOL isAdcSampleDone(void) /** * @brief take one sample of the ADC */ -BOOL adcCheckVoltageLevels(AdcValues* output) +BOOL adcCheckVoltageLevels(AdcValues *output) { - if (NULL == output) { + if (NULL == output) + { return FALSE; } // If existing sample isn't done, then we can't trigger a new sample - if (!isAdcSampleDone()) { + if (!isAdcSampleDone()) + { return FALSE; } @@ -126,37 +129,35 @@ BOOL adcCheckVoltageLevels(AdcValues* output) #pragma vector = ADC12_VECTOR __interrupt void ADC12_ISR(void) #elif defined(__GNUC__) -void __attribute__ ((interrupt(ADC12_VECTOR))) ADC12_ISR (void) +void __attribute__((interrupt(ADC12_VECTOR))) ADC12_ISR(void) #else #error Compiler not supported! #endif { - if (NULL == outputValues) { + if (NULL == outputValues) + { return; } - switch (__even_in_range(ADC12IV, ADC12IV_ADC12RDYIFG)) { - case ADC12IV_ADC12IFG9: // ADC12IE9 interrupt - outputValues->vLanderSense = ADC12MEM0; - outputValues->battTemp = ADC12MEM1; - outputValues->battRT = ADC12MEM2; - outputValues->vSysAllSense = ADC12MEM3; - outputValues->iSysAllSense = ADC12MEM4; - outputValues->vBattSense = ADC12MEM5; - outputValues->vcc2Point5 = ADC12MEM6; - outputValues->vcc2Point8 = ADC12MEM7; - outputValues->vcc28 = ADC12MEM8; - outputValues->vcc24 = ADC12MEM9; - outputValues->sampleComplete = TRUE; // update output struct to signal sample is complete. - - *watchdogFlagsPtr |= WDFLAG_ADC_READY; // signal ready to main loop - __low_power_mode_off_on_exit(); - break; - default: - break; + switch (__even_in_range(ADC12IV, ADC12IV_ADC12RDYIFG)) + { + case ADC12IV_ADC12IFG9: // ADC12IE9 interrupt + outputValues->vLanderSense = ADC12MEM0; + outputValues->battTemp = ADC12MEM1; + outputValues->battRT = ADC12MEM2; + outputValues->vSysAllSense = ADC12MEM3; + outputValues->iSysAllSense = ADC12MEM4; + outputValues->vBattSense = ADC12MEM5; + outputValues->vcc2Point5 = ADC12MEM6; + outputValues->vcc2Point8 = ADC12MEM7; + outputValues->vcc28 = ADC12MEM8; + outputValues->vcc24 = ADC12MEM9; + outputValues->sampleComplete = TRUE; // update output struct to signal sample is complete. + + *watchdogFlagsPtr |= WDFLAG_ADC_READY; // signal ready to main loop + __low_power_mode_off_on_exit(); + break; + default: + break; } } - - - - From 3cb7b6bbcdd44771f16bf8ff699b4f0f8d0c5785 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:03:49 -0500 Subject: [PATCH 06/39] WD: Added note to ADC after double checking VeRef+- sources. --- Apps/FlightSoftware/Watchdog/src/drivers/adc.c | 1 + 1 file changed, 1 insertion(+) diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/adc.c b/Apps/FlightSoftware/Watchdog/src/drivers/adc.c index 83a03c650..cbaeddb1f 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/adc.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/adc.c @@ -60,6 +60,7 @@ void adc_init(volatile uint16_t *watchdogFlags) ADC12CTL3 = 0; // MEM0: P1.4 == V_LANDER_SENS == A4. Use VR+ = VeRef+ buffered, VR- = VeRef- + // ADC12VRSEL_15 is listed in `adc12_b.h` as `ADC12_B_VREFPOS_EXTBUF_VREFNEG_EXTNEG`, so seems right... ADC12MCTL0 = ADC12INCH_4 | ADC12VRSEL_15; // MEM1: P2.4 == BATT_TEMP == A7. Use VR+ = VeRef+ buffered, VR- = VeRef- From bab6fb9c8469f73a45e8710890b3d6bb08d994d4 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:10:11 -0500 Subject: [PATCH 07/39] WD: Corrected Heartbeat Packets to use main battery heater thermistor (RT) instead of charging thermistor (battTemp). --- .../Watchdog/include/comms/ground_msgs.h | 4 +- .../Watchdog/include/drivers/adc.h | 48 +++++++++---------- .../Watchdog/src/comms/ground_msgs.c | 4 +- 3 files changed, 28 insertions(+), 28 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h b/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h index d54bcdb6d..dc7a49146 100644 --- a/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h +++ b/Apps/FlightSoftware/Watchdog/include/comms/ground_msgs.h @@ -75,7 +75,7 @@ extern "C" uint16_t deploymentStatus : 2; // 00 = not deployed, 01 = deploying, 10 = deployed uint16_t uart0Initialized : 1; uint16_t uart1Initialized : 1; - uint16_t adcBattRT : 12; + uint16_t adcBattRT : 12; // main heater thermistor uint8_t sequenceNumber; @@ -85,7 +85,7 @@ extern "C" uint8_t upperResetActionBits; uint16_t vLanderSense : 7; // upper 7 bits (from 12-bit resolution data) - uint16_t battTemp : 9; // upper 9 bits (from 12-bit resolution data) + uint16_t battTemp : 9; // upper 9 bits (from 12-bit resolution data) - charging thermistor uint32_t vSysAllSens : 5; // upper 5 bits (from 12-bit resolution data) uint32_t iSysAllSense : 9; // LOWER 9 bits (from 12-bit resolution data) diff --git a/Apps/FlightSoftware/Watchdog/include/drivers/adc.h b/Apps/FlightSoftware/Watchdog/include/drivers/adc.h index 19a71f55e..e3d370d45 100644 --- a/Apps/FlightSoftware/Watchdog/include/drivers/adc.h +++ b/Apps/FlightSoftware/Watchdog/include/drivers/adc.h @@ -16,30 +16,30 @@ extern "C" { #endif -typedef struct AdcValues -{ - volatile uint16_t vLanderSense; - volatile uint16_t battTemp; - volatile uint16_t battRT; - volatile uint16_t vSysAllSense; - volatile uint16_t iSysAllSense; - volatile uint16_t vBattSense; - volatile uint16_t vcc2Point5; - volatile uint16_t vcc2Point8; - volatile uint16_t vcc28; - volatile uint16_t vcc24; - volatile BOOL sampleComplete; -} AdcValues; - -/** - * @brief Initialize ADC hardware. - * Sets up the interrupts and whatnot for ADC. - */ -void adc_init(volatile uint16_t* watchdogFlags); - -BOOL isAdcSampleDone(void); - -BOOL adcCheckVoltageLevels(AdcValues* output); + typedef struct AdcValues + { + volatile uint16_t vLanderSense; + volatile uint16_t battTemp; // charging thermistor + volatile uint16_t battRT; // main heater thermistor + volatile uint16_t vSysAllSense; + volatile uint16_t iSysAllSense; + volatile uint16_t vBattSense; + volatile uint16_t vcc2Point5; + volatile uint16_t vcc2Point8; + volatile uint16_t vcc28; + volatile uint16_t vcc24; + volatile BOOL sampleComplete; + } AdcValues; + + /** + * @brief Initialize ADC hardware. + * Sets up the interrupts and whatnot for ADC. + */ + void adc_init(volatile uint16_t *watchdogFlags); + + BOOL isAdcSampleDone(void); + + BOOL adcCheckVoltageLevels(AdcValues *output); #ifdef __cplusplus } /* close extern "C" */ diff --git a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c index 09287d847..8a45c66a3 100644 --- a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c +++ b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c @@ -39,7 +39,7 @@ GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Reading // check if batt voltage is above 16.59 V (~10% above discharge cutoff) /** @todo Update this threshold **/ hb->battery_voltage_good = (i2cReadings->raw_battery_voltage[0] > 0x3B) ? 1 : 0; - hb->battTemp = (uint8_t)(adcValues->battTemp >> 4); + hb->battRT = (uint8_t)(adcValues->battRT >> 4); return GND_MSGS__STATUS__SUCCESS; } @@ -59,7 +59,7 @@ GroundMsgs__Status GroundMsgs__generateFullEarthHeartbeat(I2C_Sensors__Readings hb->magicNumber = 0xFF; // send adc value temperature - hb->battTemp = adcValues->battTemp; + hb->battTemp = adcValues->battRT; // send adc value temperature hb->raw_battery_charge[0] = i2cReadings->raw_battery_charge[0]; From 69c4e8af5ce58c9f3e8391fe7b3109c865855466 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:18:40 -0500 Subject: [PATCH 08/39] WD: Fix heaterbeat battery status flag threshold (I was in the neighborhood). --- Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c index 8a45c66a3..f0ee666af 100644 --- a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c +++ b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c @@ -37,8 +37,11 @@ GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Reading hb->batt_curr_telem = (uint8_t)(i2cReadings->batt_curr_telem & 0x7F); // send voltage nominal status (1=good, 0=too low) // check if batt voltage is above 16.59 V (~10% above discharge cutoff) - /** @todo Update this threshold **/ - hb->battery_voltage_good = (i2cReadings->raw_battery_voltage[0] > 0x3B) ? 1 : 0; + // 16.59 * 4095.0 / 3.3 / (274.0+2000.0)*274.0 (NOTE: this thresh is likely + // too high since FM1 RC testing on Earth showed that at 23.80V-VBS, the + // divider was reading low by a factor of 2928/3560, meaning the voltage + // could actually be as high as 20.17V when this alarm sounds). + hb->battery_voltage_good = (adcValues->vBattSense > 2480) ? 1 : 0; hb->battRT = (uint8_t)(adcValues->battRT >> 4); return GND_MSGS__STATUS__SUCCESS; From 787f6ffd6a698d805ea48a568633d96fd8be94d1 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:19:40 -0500 Subject: [PATCH 09/39] WD: Fix heaterbeat battery status flag threshold (I was in the neighborhood) - added a note. --- Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c index f0ee666af..5d029debf 100644 --- a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c +++ b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c @@ -41,6 +41,8 @@ GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Reading // too high since FM1 RC testing on Earth showed that at 23.80V-VBS, the // divider was reading low by a factor of 2928/3560, meaning the voltage // could actually be as high as 20.17V when this alarm sounds). + // Also, note, this is mostly meaningless in KA since the battery is + // disconnected anyway, so we won't be able to read it. hb->battery_voltage_good = (adcValues->vBattSense > 2480) ? 1 : 0; hb->battRT = (uint8_t)(adcValues->battRT >> 4); From 32580aebcd53177296c539c55ef67b867676aba2 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:23:07 -0500 Subject: [PATCH 10/39] WD: Updated some comments and applied linter. --- .../src/stateMachine/RoverStateBase.cpp | 1965 +++++++++-------- .../RoverStateEnteringKeepAlive.cpp | 158 +- .../RoverStateEnteringMission.cpp | 438 ++-- .../src/stateMachine/RoverStateMission.cpp | 214 +- .../src/stateMachine/RoverStateService.cpp | 137 +- 5 files changed, 1556 insertions(+), 1356 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 8f7566ebf..db8a3999c 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -26,17 +26,17 @@ namespace iris struct CallbackUserArg { - RoverStateBase& m_state; - RoverContext& m_context; + RoverStateBase &m_state; + RoverContext &m_context; - explicit CallbackUserArg(RoverStateBase& state, RoverContext& context) - : m_state(state), m_context(context) - { - } + explicit CallbackUserArg(RoverStateBase &state, RoverContext &context) + : m_state(state), m_context(context) + { + } }; RoverStateBase::RoverStateBase(RoverState state) - : m_state(state) + : m_state(state) { } @@ -45,49 +45,49 @@ namespace iris return m_state; } - bool RoverStateBase::canEnterLowPowerMode(RoverContext& /*theContext*/) + bool RoverStateBase::canEnterLowPowerMode(RoverContext & /*theContext*/) { return true; } - RoverState RoverStateBase::handleHighTemp(RoverContext& theContext) + RoverState RoverStateBase::handleHighTemp(RoverContext &theContext) { return getState(); } - RoverState RoverStateBase::handleWdIntEdge(bool rising, RoverContext& theContext) + RoverState RoverStateBase::handleWdIntEdge(bool rising, RoverContext &theContext) { uint16_t flatDuration = watchdog_get_wd_int_flat_duration(); WdIntMpsm__Status status = WdIntMpsm__processEdge(rising ? TRUE : FALSE, flatDuration); switch (status) { - case WD_INT_MPSM__STATUS__POWER_CYCLE_RADIO: - return handleRadioPowerCycleRadioCommand(theContext); - case WD_INT_MPSM__STATUS__POWER_CYCLE_HERCULES: - return handleRadioPowerCycleHerculesCommand(theContext); - case WD_INT_MPSM__STATUS__PARSED_EXIT_STASIS: - return handleRadioExitStasisCommand(theContext); - case WD_INT_MPSM__STATUS__PARSED_ENTER_STASIS: - return handleRadioEnterStasisCommand(theContext); - case WD_INT_MPSM__STATUS__PARSED_GOT_WIFI: - return handleRadioGotWifiCommand(theContext); + case WD_INT_MPSM__STATUS__POWER_CYCLE_RADIO: + return handleRadioPowerCycleRadioCommand(theContext); + case WD_INT_MPSM__STATUS__POWER_CYCLE_HERCULES: + return handleRadioPowerCycleHerculesCommand(theContext); + case WD_INT_MPSM__STATUS__PARSED_EXIT_STASIS: + return handleRadioExitStasisCommand(theContext); + case WD_INT_MPSM__STATUS__PARSED_ENTER_STASIS: + return handleRadioEnterStasisCommand(theContext); + case WD_INT_MPSM__STATUS__PARSED_GOT_WIFI: + return handleRadioGotWifiCommand(theContext); } return getState(); } - RoverState RoverStateBase::handleWdIntRisingEdge(RoverContext& theContext) + RoverState RoverStateBase::handleWdIntRisingEdge(RoverContext &theContext) { return handleWdIntEdge(true, theContext); } - RoverState RoverStateBase::handleWdIntFallingEdge(RoverContext& theContext) + RoverState RoverStateBase::handleWdIntFallingEdge(RoverContext &theContext) { return handleWdIntEdge(false, theContext); } - RoverState RoverStateBase::handleRadioPowerCycleRadioCommand(RoverContext&) + RoverState RoverStateBase::handleRadioPowerCycleRadioCommand(RoverContext &) { setRadioReset(); powerOffRadio(); @@ -99,7 +99,7 @@ namespace iris return getState(); } - RoverState RoverStateBase::handleRadioPowerCycleHerculesCommand(RoverContext&) + RoverState RoverStateBase::handleRadioPowerCycleHerculesCommand(RoverContext &) { setHerculesReset(); powerOffHercules(); @@ -111,41 +111,42 @@ namespace iris return getState(); } - RoverState RoverStateBase::handleRadioExitStasisCommand(RoverContext&) + RoverState RoverStateBase::handleRadioExitStasisCommand(RoverContext &) { return getState(); } - RoverState RoverStateBase::handleRadioEnterStasisCommand(RoverContext&) + RoverState RoverStateBase::handleRadioEnterStasisCommand(RoverContext &) { return RoverState::ENTERING_STASIS; } - RoverState RoverStateBase::handleRadioGotWifiCommand(RoverContext& theContext) + RoverState RoverStateBase::handleRadioGotWifiCommand(RoverContext &theContext) { DPRINTF("Got WiFi Event.\n"); theContext.gotWifi = true; return getState(); } - LanderComms__Status RoverStateBase::txDownlinkData(RoverContext& theContext, void* data, size_t dataSize, + LanderComms__Status RoverStateBase::txDownlinkData(RoverContext &theContext, void *data, size_t dataSize, bool fromHercules) { LanderComms__Status lcStatus = LANDER_COMMS__STATUS__SUCCESS; // !! TODO !!: Is this the condition we want here? - if (*(theContext.m_persistentDeployed) && HerculesComms__isInitialized(theContext.m_hcState) && !fromHercules) { + if (*(theContext.m_persistentDeployed) && HerculesComms__isInitialized(theContext.m_hcState) && !fromHercules) + { HerculesComms__Status hcStatus = HerculesComms__txDownlinkData(theContext.m_hcState, - (uint8_t *) data, + (uint8_t *)data, dataSize); - lcStatus = (LanderComms__Status) hcStatus; + lcStatus = (LanderComms__Status)hcStatus; } - LanderComms__Status lcStatus2 = LanderComms__txData(theContext.m_lcState, (uint8_t *) data, dataSize); + LanderComms__Status lcStatus2 = LanderComms__txData(theContext.m_lcState, (uint8_t *)data, dataSize); return lcStatus; } - void RoverStateBase::initiateNextI2cAction(RoverContext& theContext) + void RoverStateBase::initiateNextI2cAction(RoverContext &theContext) { // A static value so that we remember the index of the last action we performed. By doing this, we can rotate // through all possibles actions to make sure that a single action repeated with a high frequency doesn't @@ -153,80 +154,87 @@ namespace iris static size_t i = static_cast(I2C_SENSORS__ACTIONS__INACTIVE); // Exit early if we have no queued actions - if (theContext.m_queuedI2cActions == 0) { + if (theContext.m_queuedI2cActions == 0) + { return; } // See what, if anything, is the next action to be performed - for (size_t j = 0; j < static_cast(I2C_SENSORS__ACTIONS__COUNT); ++j) { + for (size_t j = 0; j < static_cast(I2C_SENSORS__ACTIONS__COUNT); ++j) + { size_t actionIndex = i + j; // Wrap around if necessary (in theory only an if should be necessary, but a while loop seems safer) - while (actionIndex >= static_cast(I2C_SENSORS__ACTIONS__COUNT)) { + while (actionIndex >= static_cast(I2C_SENSORS__ACTIONS__COUNT)) + { actionIndex -= static_cast(I2C_SENSORS__ACTIONS__COUNT); } uint16_t actionMask = 1 << actionIndex; // If the corresponding bit in m_queuedI2cActions is set, then we want to perform that action - if ((theContext.m_queuedI2cActions & actionMask) != 0) { + if ((theContext.m_queuedI2cActions & actionMask) != 0) + { // First, initiate the action I2C_Sensors__Action actionEnum = static_cast(actionIndex); I2C_Sensors__Status i2cStatus = I2C_SENSORS__STATUS__SUCCESS_DONE; - switch (actionEnum) { - case I2C_SENSORS__ACTIONS__INACTIVE: - // This is always false in this case, but rechecking this condition makes the resulting output - // more descriptive. - DEBUG_ASSERT_NOT_EQUAL(actionEnum, I2C_SENSORS__ACTIONS__INACTIVE); - break; - - case I2C_SENSORS__ACTIONS__GAUGE_READING: - i2cStatus = I2C_Sensors__initiateGaugeReadings(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__GAUGE_INIT: - i2cStatus = I2C_Sensors__initiateFuelGaugeInitialization(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__WRITE_GAUGE_LOW_POWER: - i2cStatus = I2C_Sensors__initiateWriteLowPower(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__READ_GAUGE_CONTROL_REGISTER: - i2cStatus = I2C_Sensors__initiateReadControl(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__INIT_IO_EXPANDER: - i2cStatus = I2C_Sensors__initiateIoExpanderInitialization(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER: - if (theContext.m_writeCustomIoExpanderValues) { - i2cStatus = I2C_Sensors__initiateWriteIoExpander(theContext.m_queuedIOWritePort0Value, - theContext.m_queuedIOWritePort1Value); - } else { - i2cStatus = I2C_Sensors__initiateWriteIoExpanderCurrentValues(); - } - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - case I2C_SENSORS__ACTIONS__READ_IO_EXPANDER: - i2cStatus = I2C_Sensors__initiateReadIoExpander(); - DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); - break; - - default: - // This is always false in this case, but rechecking this condition makes the resulting output - // more descriptive. - DEBUG_ASSERT(actionEnum >= I2C_SENSORS__ACTIONS__INACTIVE - && actionEnum < I2C_SENSORS__ACTIONS__COUNT); + switch (actionEnum) + { + case I2C_SENSORS__ACTIONS__INACTIVE: + // This is always false in this case, but rechecking this condition makes the resulting output + // more descriptive. + DEBUG_ASSERT_NOT_EQUAL(actionEnum, I2C_SENSORS__ACTIONS__INACTIVE); + break; + + case I2C_SENSORS__ACTIONS__GAUGE_READING: + i2cStatus = I2C_Sensors__initiateGaugeReadings(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__GAUGE_INIT: + i2cStatus = I2C_Sensors__initiateFuelGaugeInitialization(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__WRITE_GAUGE_LOW_POWER: + i2cStatus = I2C_Sensors__initiateWriteLowPower(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__READ_GAUGE_CONTROL_REGISTER: + i2cStatus = I2C_Sensors__initiateReadControl(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__INIT_IO_EXPANDER: + i2cStatus = I2C_Sensors__initiateIoExpanderInitialization(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER: + if (theContext.m_writeCustomIoExpanderValues) + { + i2cStatus = I2C_Sensors__initiateWriteIoExpander(theContext.m_queuedIOWritePort0Value, + theContext.m_queuedIOWritePort1Value); + } + else + { + i2cStatus = I2C_Sensors__initiateWriteIoExpanderCurrentValues(); + } + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + case I2C_SENSORS__ACTIONS__READ_IO_EXPANDER: + i2cStatus = I2C_Sensors__initiateReadIoExpander(); + DEBUG_ASSERT_EQUAL(i2cStatus, I2C_SENSORS__STATUS__SUCCESS_DONE); + break; + + default: + // This is always false in this case, but rechecking this condition makes the resulting output + // more descriptive. + DEBUG_ASSERT(actionEnum >= I2C_SENSORS__ACTIONS__INACTIVE && actionEnum < I2C_SENSORS__ACTIONS__COUNT); } // Then, clear the queued action bit so we don't repeat this action until it is requeued elsewhere @@ -243,26 +251,30 @@ namespace iris } } - void RoverStateBase::heaterControl(RoverContext& theContext) + void RoverStateBase::heaterControl(RoverContext &theContext) { // voltage, where LSB = 0.0008056640625V unsigned short thermReading = theContext.m_adcValues.battRT; - HeaterParams& hParams = theContext.m_details.m_hParams; + HeaterParams &hParams = theContext.m_details.m_hParams; - if (thermReading > hParams.m_heaterOnVal) { + if (thermReading > hParams.m_heaterOnVal) + { // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a // configured (either via the default value or a value commanded from ground) ADC reading. enableHeater(); - } else if (thermReading < hParams.m_heaterOffVal) { + } + else if (thermReading < hParams.m_heaterOffVal) + { // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a // configured (either via the default value or a value commanded from ground) ADC reading. disableHeater(); } } - void RoverStateBase::enableHerculesComms(RoverContext& theContext) + void RoverStateBase::enableHerculesComms(RoverContext &theContext) { - if (!UART__isInitialized(theContext.m_uart0State)) { + if (!UART__isInitialized(theContext.m_uart0State)) + { UART__Status uartStatus = UART__init0(&(theContext.m_uartConfig), &(theContext.m_uart0State)); @@ -270,7 +282,8 @@ namespace iris DEBUG_ASSERT_EQUAL(UART__STATUS__SUCCESS, uartStatus); } - if (!HerculesComms__isInitialized(theContext.m_hcState)) { + if (!HerculesComms__isInitialized(theContext.m_hcState)) + { HerculesComms__Status hcStatus = HerculesComms__init(&(theContext.m_hcState), theContext.m_uart0State); DEBUG_LOG_CHECK_STATUS(HERCULES_COMMS__STATUS__SUCCESS, hcStatus, "Failed to init Hercules Comms"); DEBUG_ASSERT_EQUAL(HERCULES_COMMS__STATUS__SUCCESS, hcStatus); @@ -279,69 +292,72 @@ namespace iris DebugComms__registerHerculesComms(theContext.m_hcState); } - RoverState RoverStateBase::handleLanderData(RoverContext& theContext) + RoverState RoverStateBase::handleLanderData(RoverContext &theContext) { return pumpMsgsFromLander(theContext); } - RoverState RoverStateBase::handleHerculesData(RoverContext& theContext) + RoverState RoverStateBase::handleHerculesData(RoverContext &theContext) { return pumpMsgsFromHercules(theContext); } - void RoverStateBase::herculesMsgCallback(HercMsgs__Header* header, - uint8_t* payloadBuffer, + void RoverStateBase::herculesMsgCallback(HercMsgs__Header *header, + uint8_t *payloadBuffer, size_t payloadSize, - void* userArg) + void *userArg) { - if (nullptr == userArg || nullptr == header || (payloadSize > 0 && NULL == payloadBuffer)) { + if (nullptr == userArg || nullptr == header || (payloadSize > 0 && NULL == payloadBuffer)) + { return; } - CallbackUserArg* args = reinterpret_cast(userArg); + CallbackUserArg *args = reinterpret_cast(userArg); args->m_context.m_watchdogFlags |= WDFLAG_HERCULES_KICK; - switch (header->lowerOpCode) { - case HERCULES_COMMS__MSG_OPCODE__STROKE: - args->m_state.handleStrokeFromHercules(args->m_context, header); - break; - - case HERCULES_COMMS__MSG_OPCODE__DOWNLINK: - args->m_state.handleDownlinkFromHercules(args->m_context, - header, - payloadBuffer, - payloadSize); - break; - - case HERCULES_COMMS__MSG_OPCODE__DEBUG: - args->m_state.handleDebugFromHercules(args->m_context, - header, - payloadBuffer, - payloadSize); - break; - - default: // We assume this is a reset command - args->m_state.handleResetFromHercules(args->m_context, header); - break; + switch (header->lowerOpCode) + { + case HERCULES_COMMS__MSG_OPCODE__STROKE: + args->m_state.handleStrokeFromHercules(args->m_context, header); + break; + + case HERCULES_COMMS__MSG_OPCODE__DOWNLINK: + args->m_state.handleDownlinkFromHercules(args->m_context, + header, + payloadBuffer, + payloadSize); + break; + + case HERCULES_COMMS__MSG_OPCODE__DEBUG: + args->m_state.handleDebugFromHercules(args->m_context, + header, + payloadBuffer, + payloadSize); + break; + + default: // We assume this is a reset command + args->m_state.handleResetFromHercules(args->m_context, header); + break; } } - void RoverStateBase::landerMsgCallback(uint8_t* rxDataBuffer, size_t rxDataLen, void* userArg) + void RoverStateBase::landerMsgCallback(uint8_t *rxDataBuffer, size_t rxDataLen, void *userArg) { // Statically allocate the message structure so that it's not allocated on the stack - static WdCmdMsgs__Message wdMessage = { 0 }; - static WdCmdMsgs__Response response = { 0 }; - static WdCmdMsgs__Response deployNotificationResponse = { 0 }; + static WdCmdMsgs__Message wdMessage = {0}; + static WdCmdMsgs__Response response = {0}; + static WdCmdMsgs__Response deployNotificationResponse = {0}; #pragma diag_push #pragma diag_suppress 770 DEBUG_ASSERT_NOT_EQUAL(nullptr, userArg); #pragma diag_pop - CallbackUserArg* args = reinterpret_cast(userArg); + CallbackUserArg *args = reinterpret_cast(userArg); - if (nullptr == rxDataBuffer) { + if (nullptr == rxDataBuffer) + { //!< @todo reply to lander with this error return; } @@ -351,7 +367,8 @@ namespace iris CmdMsgs__Status cmdStatus = CmdMsgs__deserializeHeader(rxDataBuffer, rxDataLen, &(wdMessage.commonHeader)); DEBUG_ASSERT_EQUAL(CMD_MSGS__STATUS__SUCCESS, cmdStatus); - if (CMD_MSGS__STATUS__SUCCESS != cmdStatus) { + if (CMD_MSGS__STATUS__SUCCESS != cmdStatus) + { // This should only really happen if rxDataLen is the wrong size //!< @todo reply to lander with this error return; @@ -360,7 +377,8 @@ namespace iris // We identify a ground command for WD by checking the "Type Magic" field in the FSW common header. // If the magic number in that field indicates the command is for Watchdog, then it is a ground // command for us. - if (HEADER__TYPE_MAGIC_NUM__WATCHDOG_COMMAND == wdMessage.commonHeader.typeMagicNumber) { + if (HEADER__TYPE_MAGIC_NUM__WATCHDOG_COMMAND == wdMessage.commonHeader.typeMagicNumber) + { // This is a watchdog command. Parse it as such WdCmdMsgs__Status wdCmdStatus = WdCmdMsgs__deserializeMessage(rxDataBuffer, rxDataLen, @@ -368,7 +386,8 @@ namespace iris FALSE); // Don't reparse the header DEBUG_ASSERT_EQUAL(WD_CMD_MSGS__STATUS__SUCCESS, wdCmdStatus); - if (WD_CMD_MSGS__STATUS__SUCCESS != wdCmdStatus) { + if (WD_CMD_MSGS__STATUS__SUCCESS != wdCmdStatus) + { // This should only really happen if rxDataLen is the wrong size //!< @todo reply to lander with this error return; @@ -376,18 +395,21 @@ namespace iris bool sendDeployNotificationResponse = false; args->m_state.m_pumpMsgsFromLanderReturnState = - args->m_state.performWatchdogCommand(args->m_context, - wdMessage, - response, - deployNotificationResponse, - sendDeployNotificationResponse); + args->m_state.performWatchdogCommand(args->m_context, + wdMessage, + response, + deployNotificationResponse, + sendDeployNotificationResponse); - if (sendDeployNotificationResponse) { + if (sendDeployNotificationResponse) + { args->m_state.sendLanderResponse(args->m_context, deployNotificationResponse); } args->m_state.sendLanderResponse(args->m_context, response); - } else { + } + else + { // Anything with "Type Magic" field value that isn't for Watchdog is treated as uplink for Hercules args->m_state.m_pumpMsgsFromLanderReturnState = args->m_state.handleUplinkFromLander(args->m_context, rxDataBuffer, @@ -395,11 +417,11 @@ namespace iris } } - RoverState RoverStateBase::performWatchdogCommand(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::performWatchdogCommand(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // Make sure that by default we don't want to send the deploy notification response sendDeployNotificationResponse = false; @@ -408,256 +430,283 @@ namespace iris response.magicNumber = WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER; response.commandId = msg.commandId; - switch (msg.commandId) { - case WD_CMD_MSGS__CMD_ID__RESET_SPECIFIC: - return doGndCmdResetSpecific(theContext, + switch (msg.commandId) + { + case WD_CMD_MSGS__CMD_ID__RESET_SPECIFIC: + return doGndCmdResetSpecific(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__PREP_FOR_DEPLOY: + /* power on all systems */ + if (msg.body.prepForDeploy.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdPrepForDeploy(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__PREP_FOR_DEPLOY: - /* power on all systems */ - if (msg.body.prepForDeploy.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdPrepForDeploy(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; + case WD_CMD_MSGS__CMD_ID__DEPLOY: + if (msg.body.deploy.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdDeploy(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__DEPLOY: - if (msg.body.deploy.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdDeploy(theContext, + case WD_CMD_MSGS__CMD_ID__SWITCH_CONN_MODE: + return doGndCmdSwitchConnMode(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); - } - break; - case WD_CMD_MSGS__CMD_ID__SWITCH_CONN_MODE: - return doGndCmdSwitchConnMode(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - - case WD_CMD_MSGS__CMD_ID__SET_DEBUG_COMMS_STATE: - if (msg.body.setDebugCommsState.magic != WD_CMD_MSGS__SET_DEBUG_COMMS_STATE_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdSetDebugCommsState(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; - - case WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_ON_VALUE: - return doGndCmdSetAutoHeaterOnValue(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - - case WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_OFF_VALUE: - return doGndCmdSetAutoHeaterOffValue(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - - case WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE: - return doGndCmdSetHeaterDutyCycle(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); + case WD_CMD_MSGS__CMD_ID__SET_DEBUG_COMMS_STATE: + if (msg.body.setDebugCommsState.magic != WD_CMD_MSGS__SET_DEBUG_COMMS_STATE_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdSetDebugCommsState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE_PERIOD: - return doGndCmdSetHeaterDutyCyclePeriod(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - - case WD_CMD_MSGS__CMD_ID__SET_VSAE_STATE: - if (msg.body.setVSAEState.magic != WD_CMD_MSGS__SET_VSAE_STATE_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdSetVSAEState(theContext, + case WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_ON_VALUE: + return doGndCmdSetAutoHeaterOnValue(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); - } - break; - - case WD_CMD_MSGS__CMD_ID__ENTER_SLEEP_MODE: - /* Enter sleep mode */ - if (msg.body.enterSleepMode.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdEnterSleepMode(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; - case WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE: - /* Enter keepalive mode */ - if (msg.body.enterKeepAliveMode.confirmationMagicNumber - != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdEnterKeepAliveMode(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; + case WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_OFF_VALUE: + return doGndCmdSetAutoHeaterOffValue(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); - case WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE: - /* Enter service mode */ - if (msg.body.enterServiceMode.confirmationMagicNumber - != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdEnterServiceMode(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; + case WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE: + return doGndCmdSetHeaterDutyCycle(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); - case WD_CMD_MSGS__CMD_ID__CLEAR_RESET_MEMORY: - if ((msg.body.clearResetMem.magicOne != WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_ONE) || - (msg.body.clearResetMem.magicTwo != WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_TWO)) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdClearResetMemory(theContext, + case WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE_PERIOD: + return doGndCmdSetHeaterDutyCyclePeriod(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); - } - break; - - case WD_CMD_MSGS__CMD_ID__DANGEROUS_FORCE_BATT_STATE: - if ((msg.body.dangForceBattState.confirmationMagicNumberOne - != WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_ONE) || - (msg.body.dangForceBattState.confirmationMagicNumberTwo - != WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_TWO)) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdDangForceBattState(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; - - case WD_CMD_MSGS__CMD_ID__ECHO: - return doGndCmdEcho(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - - case WD_CMD_MSGS__CMD_ID__REQUEST_DETAILED_REPORT: - /* Enter service mode */ - if (msg.body.reqDetReport.magic != WD_CMD_MSGS__CONFIRM_REQ_DET_REPORT_MAGIC_NUMBER) { - /* magic bad */ - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - } else { - return doGndCmdRequestDetailedReport(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - } - break; - - case WD_CMD_MSGS__CMD_ID__SET_CHARGE_EN_STATE: - return doGndCmdSetChargeEnState(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); - case WD_CMD_MSGS__CMD_ID__SET_CHARGE_REG_EN_STATE: - return doGndCmdSetChargeRegEnState(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); + case WD_CMD_MSGS__CMD_ID__SET_VSAE_STATE: + if (msg.body.setVSAEState.magic != WD_CMD_MSGS__SET_VSAE_STATE_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdSetVSAEState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__SET_BATT_EN_STATE: - return doGndCmdSetBattEnState(theContext, + case WD_CMD_MSGS__CMD_ID__ENTER_SLEEP_MODE: + /* Enter sleep mode */ + if (msg.body.enterSleepMode.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdEnterSleepMode(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__SET_BATT_CTRL_EN_STATE: - return doGndCmdSetBattCtrlEnState(theContext, + case WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE: + /* Enter keepalive mode */ + if (msg.body.enterKeepAliveMode.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdEnterKeepAliveMode(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__SET_LATCH_BATT_STATE: - return doGndCmdSetLatchBattState(theContext, - msg, - response, - deployNotificationResponse, - sendDeployNotificationResponse); + case WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE: + /* Enter service mode */ + if (msg.body.enterServiceMode.confirmationMagicNumber != WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdEnterServiceMode(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__LATCH_SET_PULSE_LOW: - return doGndCmdLatchSetPulseLow(theContext, + case WD_CMD_MSGS__CMD_ID__CLEAR_RESET_MEMORY: + if ((msg.body.clearResetMem.magicOne != WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_ONE) || + (msg.body.clearResetMem.magicTwo != WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_TWO)) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdClearResetMemory(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); + } + break; - case WD_CMD_MSGS__CMD_ID__LATCH_RESET_PULSE_LOW: - return doGndCmdLatchResetPulseLow(theContext, + case WD_CMD_MSGS__CMD_ID__DANGEROUS_FORCE_BATT_STATE: + if ((msg.body.dangForceBattState.confirmationMagicNumberOne != WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_ONE) || + (msg.body.dangForceBattState.confirmationMagicNumberTwo != WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_TWO)) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdDangForceBattState(theContext, msg, response, deployNotificationResponse, sendDeployNotificationResponse); + } + break; + + case WD_CMD_MSGS__CMD_ID__ECHO: + return doGndCmdEcho(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__REQUEST_DETAILED_REPORT: + /* Enter service mode */ + if (msg.body.reqDetReport.magic != WD_CMD_MSGS__CONFIRM_REQ_DET_REPORT_MAGIC_NUMBER) + { + /* magic bad */ + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + } + else + { + return doGndCmdRequestDetailedReport(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + } + break; + + case WD_CMD_MSGS__CMD_ID__SET_CHARGE_EN_STATE: + return doGndCmdSetChargeEnState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__SET_CHARGE_REG_EN_STATE: + return doGndCmdSetChargeRegEnState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__SET_BATT_EN_STATE: + return doGndCmdSetBattEnState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_ID; - break; + case WD_CMD_MSGS__CMD_ID__SET_BATT_CTRL_EN_STATE: + return doGndCmdSetBattCtrlEnState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__SET_LATCH_BATT_STATE: + return doGndCmdSetLatchBattState(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__LATCH_SET_PULSE_LOW: + return doGndCmdLatchSetPulseLow(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + case WD_CMD_MSGS__CMD_ID__LATCH_RESET_PULSE_LOW: + return doGndCmdLatchResetPulseLow(theContext, + msg, + response, + deployNotificationResponse, + sendDeployNotificationResponse); + + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_ID; + break; } return getState(); } - RoverState RoverStateBase::handleUplinkFromLander(RoverContext& theContext, - uint8_t* rxDataBuffer, + RoverState RoverStateBase::handleUplinkFromLander(RoverContext &theContext, + uint8_t *rxDataBuffer, size_t rxDataLen) { // Anything with "Type Magic" field value that isn't for Watchdog is treated as uplink for Hercules @@ -665,17 +714,18 @@ namespace iris rxDataBuffer, rxDataLen); - if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) { + if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) + { //!< @todo handling? Send response to lander maybe? } return getState(); } - RoverState RoverStateBase::handleStrokeFromHercules(RoverContext& theContext, - HercMsgs__Header* header) + RoverState RoverStateBase::handleStrokeFromHercules(RoverContext &theContext, + HercMsgs__Header *header) { - static uint8_t telemetrySerializationBuffer[16] = { 0 }; + static uint8_t telemetrySerializationBuffer[16] = {0}; #pragma diag_push #pragma diag_suppress 770 @@ -693,20 +743,21 @@ namespace iris telemetrySerializationBuffer, sizeof(telemetrySerializationBuffer)); - if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) { + if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) + { DebugComms__tryPrintfToLanderNonblocking("HerculesComms__txResponseMsg failed with error: %d in " - "RoverStateBase::handleStrokeFromHercules\n", - hcStatus); + "RoverStateBase::handleStrokeFromHercules\n", + hcStatus); } - //HerculesComms__flushTx(theContext.m_hcState); + // HerculesComms__flushTx(theContext.m_hcState); return getState(); } - RoverState RoverStateBase::handleDownlinkFromHercules(RoverContext& theContext, - HercMsgs__Header* header, - uint8_t* payloadBuffer, + RoverState RoverStateBase::handleDownlinkFromHercules(RoverContext &theContext, + HercMsgs__Header *header, + uint8_t *payloadBuffer, size_t payloadSize) { #pragma diag_push @@ -724,10 +775,11 @@ namespace iris nullptr, 0); - if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) { + if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) + { DebugComms__tryPrintfToLanderNonblocking("HerculesComms__txResponseMsg failed with error: %d in " - "RoverStateBase::handleDownlinkFromHercules\n", - hcStatus); + "RoverStateBase::handleDownlinkFromHercules\n", + hcStatus); } // 2) Send data to lander @@ -735,14 +787,14 @@ namespace iris DEBUG_LOG_CHECK_STATUS(LANDER_COMMS__STATUS__SUCCESS, lcStatus, "Downlink failed"); - //LanderComms__flushTx(theContext.m_lcState); + // LanderComms__flushTx(theContext.m_lcState); return getState(); } - RoverState RoverStateBase::handleDebugFromHercules(RoverContext& theContext, - HercMsgs__Header* header, - uint8_t* payloadBuffer, + RoverState RoverStateBase::handleDebugFromHercules(RoverContext &theContext, + HercMsgs__Header *header, + uint8_t *payloadBuffer, size_t payloadSize) { #pragma diag_push @@ -758,8 +810,8 @@ namespace iris return getState(); } - RoverState RoverStateBase::handleResetFromHercules(RoverContext& theContext, - HercMsgs__Header* header) + RoverState RoverStateBase::handleResetFromHercules(RoverContext &theContext, + HercMsgs__Header *header) { #pragma diag_push #pragma diag_suppress 770 @@ -767,7 +819,7 @@ namespace iris #pragma diag_pop // For Reset_Specific we want to do the reset, then reply to Hercules - WdCmdMsgs__ResetSpecificId resetValue = (WdCmdMsgs__ResetSpecificId) header->resetValue; + WdCmdMsgs__ResetSpecificId resetValue = (WdCmdMsgs__ResetSpecificId)header->resetValue; RoverState result = performResetCommand(theContext, resetValue, nullptr); @@ -776,54 +828,57 @@ namespace iris nullptr, 0); - if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) { + if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) + { DebugComms__tryPrintfToLanderNonblocking("HerculesComms__txResponseMsg failed with error: %d in " - "RoverStateBase::handleResetFromHercules\n", - hcStatus); + "RoverStateBase::handleResetFromHercules\n", + hcStatus); } return result; } - RoverState RoverStateBase::pumpMsgsFromLander(RoverContext& theContext) + RoverState RoverStateBase::pumpMsgsFromLander(RoverContext &theContext) { m_pumpMsgsFromLanderReturnState = getState(); CallbackUserArg args(*this, theContext); LanderComms__Status lcStatus = LanderComms__tryGetMessage(theContext.m_lcState, RoverStateBase::landerMsgCallback, - (void*) &args); + (void *)&args); DEBUG_ASSERT_EQUAL(LANDER_COMMS__STATUS__SUCCESS, lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo logging? } return m_pumpMsgsFromLanderReturnState; } - RoverState RoverStateBase::pumpMsgsFromHercules(RoverContext& theContext) + RoverState RoverStateBase::pumpMsgsFromHercules(RoverContext &theContext) { m_pumpMsgsFromHerculesReturnState = getState(); CallbackUserArg args(*this, theContext); HerculesComms__Status hcStatus = HerculesComms__tryGetMessage(theContext.m_hcState, RoverStateBase::herculesMsgCallback, - (void*) &args); + (void *)&args); - //DEBUG_ASSERT_EQUAL(HERCULES_COMMS__STATUS__SUCCESS, hcStatus); - if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) { + // DEBUG_ASSERT_EQUAL(HERCULES_COMMS__STATUS__SUCCESS, hcStatus); + if (HERCULES_COMMS__STATUS__SUCCESS != hcStatus) + { DebugComms__tryPrintfToLanderNonblocking("HerculesComms__tryGetMessage failed with error: %d in " - "RoverStateBase::pumpMsgsFromHercules\n", - hcStatus); + "RoverStateBase::pumpMsgsFromHercules\n", + hcStatus); } return m_pumpMsgsFromHerculesReturnState; } - void RoverStateBase::sendLanderResponse(RoverContext& theContext, WdCmdMsgs__Response& response) + void RoverStateBase::sendLanderResponse(RoverContext &theContext, WdCmdMsgs__Response &response) { - static uint8_t responseSerializationBuffer[WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG] = { 0 }; + static uint8_t responseSerializationBuffer[WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG] = {0}; WdCmdMsgs__Status wdCmdStatus = WdCmdMsgs__serializeGroundResponse(&response, responseSerializationBuffer, @@ -832,445 +887,458 @@ namespace iris DEBUG_ASSERT_EQUAL(WD_CMD_MSGS__STATUS__SUCCESS, wdCmdStatus); LanderComms__Status lcStatus = txDownlinkData(theContext, - responseSerializationBuffer, - sizeof(responseSerializationBuffer)); + responseSerializationBuffer, + sizeof(responseSerializationBuffer)); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo handling? } } // Specific watchdog command handling - RoverState RoverStateBase::doGndCmdResetSpecific(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdResetSpecific(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { return performResetCommand(theContext, msg.body.resetSpecific.resetId, &response); } - RoverState RoverStateBase::doGndCmdPrepForDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdPrepForDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Default to not being in the right state to transition to mission mode */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Default to not being in the right state to transition to deploy */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdSwitchConnMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSwitchConnMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { //!< @todo IMPLEMENT! response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdSetDebugCommsState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetDebugCommsState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setDebugCommsState.selection) { - case WD_CMD_MSGS__DEBUG_COMMS__ON: - DebugComms__setEnabled(TRUE); - DebugComms__tryPrintfToLanderNonblocking("Debug comms enabled\n"); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setDebugCommsState.selection) + { + case WD_CMD_MSGS__DEBUG_COMMS__ON: + DebugComms__setEnabled(TRUE); + DebugComms__tryPrintfToLanderNonblocking("Debug comms enabled\n"); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__DEBUG_COMMS__OFF: - DebugComms__tryPrintfToLanderNonblocking("Disabling debug comms\n"); - DebugComms__setEnabled(FALSE); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__DEBUG_COMMS__OFF: + DebugComms__tryPrintfToLanderNonblocking("Disabling debug comms\n"); + DebugComms__setEnabled(FALSE); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetAutoHeaterOnValue(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetAutoHeaterOnValue(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { theContext.m_details.m_hParams.m_heaterOnVal = msg.body.setAutoHeaterOnValue.heaterOnValue; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdSetAutoHeaterOffValue(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetAutoHeaterOffValue(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { theContext.m_details.m_hParams.m_heaterOffVal = msg.body.setAutoHeaterOffValue.heaterOffValue; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdSetHeaterDutyCycle(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetHeaterDutyCycle(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - const uint16_t& newDutyCycle = msg.body.setHeaterDutyCycle.dutyCycle; - if (newDutyCycle <= theContext.m_details.m_hParams.m_heaterDutyCyclePeriod) { + const uint16_t &newDutyCycle = msg.body.setHeaterDutyCycle.dutyCycle; + if (newDutyCycle <= theContext.m_details.m_hParams.m_heaterDutyCyclePeriod) + { TB0CCR2 = newDutyCycle; theContext.m_details.m_hParams.m_heaterDutyCycle = newDutyCycle; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - } else { + } + else + { response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetHeaterDutyCyclePeriod(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetHeaterDutyCyclePeriod(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { TB0CCR0 = msg.body.setHeaterDutyCyclePeriod.dutyCyclePeriod; theContext.m_details.m_hParams.m_heaterDutyCyclePeriod = - msg.body.setHeaterDutyCyclePeriod.dutyCyclePeriod; + msg.body.setHeaterDutyCyclePeriod.dutyCyclePeriod; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdSetVSAEState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetVSAEState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setVSAEState.selection) { - case WD_CMD_MSGS__VSAE__ON: - blimp_vSysAllEnOn(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setVSAEState.selection) + { + case WD_CMD_MSGS__VSAE__ON: + blimp_vSysAllEnOn(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__VSAE__OFF: - blimp_vSysAllEnOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__VSAE__OFF: + blimp_vSysAllEnOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__VSAE__FORCE_LOW: - blimp_vSysAllEnForceLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__VSAE__FORCE_LOW: + blimp_vSysAllEnForceLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdEnterSleepMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdEnterSleepMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // Sleep mode is deprecated so always return that we're in the wrong state to transition to sleep. response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdEnterKeepAliveMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdEnterKeepAliveMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Default to not being in the right state to transition to keep alive mode */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdEnterServiceMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdEnterServiceMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Default to not being in the right state to transition to service mode */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdDangForceBattState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdDangForceBattState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.dangForceBattState.state) { - case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__LOW: - blimp_bstat_dangerous_forceLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.dangForceBattState.state) + { + case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__LOW: + blimp_bstat_dangerous_forceLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__HIGH: - blimp_bstat_dangerous_forceHigh(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__HIGH: + blimp_bstat_dangerous_forceHigh(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__RESTORE: - blimp_bstat_safe_restoreInput(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__DANG_FORCE_BATT_STATE__RESTORE: + blimp_bstat_safe_restoreInput(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetChargeEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetChargeEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setChargeEnState.selection) { - case WD_CMD_MSGS__CHARGE_EN__ON: - blimp_chargerEnOn(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setChargeEnState.selection) + { + case WD_CMD_MSGS__CHARGE_EN__ON: + blimp_chargerEnOn(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__CHARGE_EN__OFF: - blimp_chargerEnOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__CHARGE_EN__OFF: + blimp_chargerEnOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__CHARGE_EN__FORCE_HIGH: - blimp_chargerEnForceHigh(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__CHARGE_EN__FORCE_HIGH: + blimp_chargerEnForceHigh(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetChargeRegEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetChargeRegEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setChargeRegEnState.selection) { - case WD_CMD_MSGS__CHARGE_REG_EN__ON: - blimp_regEnOn(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setChargeRegEnState.selection) + { + case WD_CMD_MSGS__CHARGE_REG_EN__ON: + blimp_regEnOn(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__CHARGE_REG_EN__OFF: - blimp_regEnOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__CHARGE_REG_EN__OFF: + blimp_regEnOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetBattEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetBattEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setBattEnState.selection) { - case WD_CMD_MSGS__BATT_EN__ON: - blimp_battEnOn(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setBattEnState.selection) + { + case WD_CMD_MSGS__BATT_EN__ON: + blimp_battEnOn(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__BATT_EN__OFF: - blimp_battEnOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__BATT_EN__OFF: + blimp_battEnOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdSetBattCtrlEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetBattCtrlEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; return getState(); } - RoverState RoverStateBase::doGndCmdSetLatchBattState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdSetLatchBattState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.setLatchBattState.selection) { - case WD_CMD_MSGS__LATCH_BATT__ON: - blimp_latchBattOn(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.setLatchBattState.selection) + { + case WD_CMD_MSGS__LATCH_BATT__ON: + blimp_latchBattOn(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_BATT__OFF: - blimp_latchBattOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_BATT__OFF: + blimp_latchBattOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_BATT__UPDATE: - blimp_latchBattUpdate(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_BATT__UPDATE: + blimp_latchBattUpdate(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdLatchSetPulseLow(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdLatchSetPulseLow(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.latchSetPulseLow.selection) { - case WD_CMD_MSGS__LATCH_SET_RESET__OFF: - blimp_latchSetOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.latchSetPulseLow.selection) + { + case WD_CMD_MSGS__LATCH_SET_RESET__OFF: + blimp_latchSetOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__PULSE: - blimp_latchSetPulseLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__PULSE: + blimp_latchSetPulseLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH: - blimp_latchSetHigh(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH: + blimp_latchSetHigh(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW: - blimp_latchSetLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW: + blimp_latchSetLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdLatchResetPulseLow(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdLatchResetPulseLow(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (msg.body.latchResetPulseLow.selection) { - case WD_CMD_MSGS__LATCH_SET_RESET__OFF: - blimp_latchResetOff(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + switch (msg.body.latchResetPulseLow.selection) + { + case WD_CMD_MSGS__LATCH_SET_RESET__OFF: + blimp_latchResetOff(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__PULSE: - blimp_latchResetPulseLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__PULSE: + blimp_latchResetPulseLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH: - blimp_latchResetHigh(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH: + blimp_latchResetHigh(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW: - blimp_latchResetLow(); - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - break; + case WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW: + blimp_latchResetLow(); + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + break; - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; } return getState(); } - RoverState RoverStateBase::doGndCmdClearResetMemory(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdClearResetMemory(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { theContext.m_details.m_resetActionBits = 0; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdEcho(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdEcho(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { echoToLander(theContext, msg.body.echo.numBytesToEcho, msg.body.echo.bytesToEcho); response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - RoverState RoverStateBase::doGndCmdRequestDetailedReport(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateBase::doGndCmdRequestDetailedReport(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { theContext.m_sendDetailedReport = true; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } - void RoverStateBase::echoToLander(RoverContext& theContext, uint8_t numBytesToEcho, const uint8_t* bytesToEcho) + void RoverStateBase::echoToLander(RoverContext &theContext, uint8_t numBytesToEcho, const uint8_t *bytesToEcho) { /* settings */ static const char ECHO_HEADER[] = "ECHO: "; @@ -1289,41 +1357,43 @@ namespace iris /* send echo */ LanderComms__Status lcStatus = txDownlinkData(theContext, ECHO_BUFFER, - (ECHO_HEADER_SIZE+numBytesToEcho)); + (ECHO_HEADER_SIZE + numBytesToEcho)); DEBUG_ASSERT_EQUAL(LANDER_COMMS__STATUS__SUCCESS, lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? // just an echo so we can probably just ignore it. Ground will just try again. } } - void RoverStateBase::sendDetailedReportToLander(RoverContext& theContext) + void RoverStateBase::sendDetailedReportToLander(RoverContext &theContext) { /* send detailed report */ - static DetailedReport report = { 0 }; - static uint8_t reportBuffer[sizeof(DetailedReport)] = { 0 }; + static DetailedReport report = {0}; + static uint8_t reportBuffer[sizeof(DetailedReport)] = {0}; GroundMsgs__Status gcStatus = - GroundMsgs__generateDetailedReport(&(theContext.m_i2cReadings), - &(theContext.m_adcValues), - &(theContext.m_details), - &report, - reportBuffer); + GroundMsgs__generateDetailedReport(&(theContext.m_i2cReadings), + &(theContext.m_adcValues), + &(theContext.m_details), + &report, + reportBuffer); DEBUG_ASSERT_EQUAL(GND_MSGS__STATUS__SUCCESS, gcStatus); LanderComms__Status lcStatus = txDownlinkData(theContext, - (uint8_t*) &report, - sizeof(report)); + (uint8_t *)&report, + sizeof(report)); DEBUG_ASSERT_EQUAL(LANDER_COMMS__STATUS__SUCCESS, lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? } #if DEBUG_REPORT DebugComms_printfToLander("\n"); - DebugComms__printDataAsHexToLander((uint8_t*) &report, sizeof(DetailedReport), FALSE); + DebugComms__printDataAsHexToLander((uint8_t *)&report, sizeof(DetailedReport), FALSE); DebugComms_printfToLander("chargeStat1: %u, ", report.chargeStat1); DebugComms_printfToLander("chargeStat2: %u, ", report.chargeStat2); DebugComms_printfToLander("battStat: %u, ", report.battStat); @@ -1367,311 +1437,350 @@ namespace iris #endif // DEBUG_REPORT } - void RoverStateBase::doConditionalResetSpecific(RoverContext& theContext, + void RoverStateBase::doConditionalResetSpecific(RoverContext &theContext, WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response, + WdCmdMsgs__Response *response, bool allowPowerOn, bool allowDisableRs422, bool allowDeploy, bool allowUndeploy, - bool& writeIoExpander) + bool &writeIoExpander) { - if (nullptr != response) { + if (nullptr != response) + { // Default to success, change if necessary response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; } writeIoExpander = false; - switch (resetValue) { - case WD_CMD_MSGS__RESET_ID__NO_RESET: - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__NO_RESET); - break; - - case WD_CMD_MSGS__RESET_ID__HERCULES_RESET: - //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. - setHerculesReset(); - writeIoExpander = true; - // queue up hercules unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_HERCULES; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_RESET); - break; - - case WD_CMD_MSGS__RESET_ID__HERCULES_POWER_ON: - if (allowPowerOn) { - powerOnHercules(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__HERCULES_POWER_OFF: - powerOffHercules(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_POWER_OFF); - break; - - case WD_CMD_MSGS__RESET_ID__RADIO_RESET: - //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. - setRadioReset(); - writeIoExpander = true; - // queue up an radio unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_RADIO1; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_RESET); - break; - - case WD_CMD_MSGS__RESET_ID__RADIO_POWER_ON: - if (allowPowerOn) { - powerOnRadio(); - writeIoExpander = true; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__RADIO_POWER_OFF: - powerOffRadio(); - writeIoExpander = true; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_POWER_OFF); - break; - - case WD_CMD_MSGS__RESET_ID__CAM_FPGA_RESET: - //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. - setFPGAReset(); - writeIoExpander = true; - // queue up the fpga unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_FPGA; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_RESET); - break; - - case WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_ON: - if (allowPowerOn) { - powerOnFpga(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_OFF: - powerOffFpga(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_POWER_OFF); - break; - - case WD_CMD_MSGS__RESET_ID__MOTOR_1_RESET: - setMotor1Reset(); - writeIoExpander = true; - // queue up the motor 1 unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR1; - break; - - case WD_CMD_MSGS__RESET_ID__MOTOR_2_RESET: - setMotor2Reset(); - writeIoExpander = true; - // queue up the motor 2 unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR2; - break; - - case WD_CMD_MSGS__RESET_ID__MOTOR_3_RESET: - setMotor3Reset(); - writeIoExpander = true; - // queue up the motor 3 unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR3; - break; - - case WD_CMD_MSGS__RESET_ID__MOTOR_4_RESET: - setMotor4Reset(); - writeIoExpander = true; - // queue up the motor 4 unreset - theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR4; - break; - - case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_RESET: - setMotorsReset(); + switch (resetValue) + { + case WD_CMD_MSGS__RESET_ID__NO_RESET: + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__NO_RESET); + break; + + case WD_CMD_MSGS__RESET_ID__HERCULES_RESET: + //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. + setHerculesReset(); + writeIoExpander = true; + // queue up hercules unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_HERCULES; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_RESET); + break; + + case WD_CMD_MSGS__RESET_ID__HERCULES_POWER_ON: + if (allowPowerOn) + { + powerOnHercules(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; + + case WD_CMD_MSGS__RESET_ID__HERCULES_POWER_OFF: + powerOffHercules(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_POWER_OFF); + break; + + case WD_CMD_MSGS__RESET_ID__RADIO_RESET: + //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. + setRadioReset(); + writeIoExpander = true; + // queue up an radio unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_RADIO1; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_RESET); + break; + + case WD_CMD_MSGS__RESET_ID__RADIO_POWER_ON: + if (allowPowerOn) + { + powerOnRadio(); writeIoExpander = true; - // queue up all the motor unresets - theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR1 | WDFLAG_UNRESET_MOTOR2 | - WDFLAG_UNRESET_MOTOR3 | WDFLAG_UNRESET_MOTOR4; - break; - - case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_ON: - if (allowPowerOn) { - powerOnMotors(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__ALL_MOTORS_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_OFF: - powerOffMotors(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__ALL_MOTORS_POWER_OFF); - break; - - case WD_CMD_MSGS__RESET_ID__3_3V_EN_RESET: - if (allowPowerOn) { - disable3V3PowerRail(); - // queue up 3V3 rail on again - theContext.m_watchdogFlags |= WDFLAG_UNRESET_3V3; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_RESET); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; + + case WD_CMD_MSGS__RESET_ID__RADIO_POWER_OFF: + powerOffRadio(); + writeIoExpander = true; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RADIO_POWER_OFF); + break; + + case WD_CMD_MSGS__RESET_ID__CAM_FPGA_RESET: + //!< @todo Should reset be allowed in KeepAlive? It's not technically powering on, but its similar. + setFPGAReset(); + writeIoExpander = true; + // queue up the fpga unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_FPGA; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_RESET); + break; + + case WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_ON: + if (allowPowerOn) + { + powerOnFpga(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; + + case WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_OFF: + powerOffFpga(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__CAM_FPGA_POWER_OFF); + break; + + case WD_CMD_MSGS__RESET_ID__MOTOR_1_RESET: + setMotor1Reset(); + writeIoExpander = true; + // queue up the motor 1 unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR1; + break; + + case WD_CMD_MSGS__RESET_ID__MOTOR_2_RESET: + setMotor2Reset(); + writeIoExpander = true; + // queue up the motor 2 unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR2; + break; + + case WD_CMD_MSGS__RESET_ID__MOTOR_3_RESET: + setMotor3Reset(); + writeIoExpander = true; + // queue up the motor 3 unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR3; + break; + + case WD_CMD_MSGS__RESET_ID__MOTOR_4_RESET: + setMotor4Reset(); + writeIoExpander = true; + // queue up the motor 4 unreset + theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR4; + break; + + case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_RESET: + setMotorsReset(); + writeIoExpander = true; + // queue up all the motor unresets + theContext.m_watchdogFlags |= WDFLAG_UNRESET_MOTOR1 | WDFLAG_UNRESET_MOTOR2 | + WDFLAG_UNRESET_MOTOR3 | WDFLAG_UNRESET_MOTOR4; + break; + + case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_ON: + if (allowPowerOn) + { + powerOnMotors(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__ALL_MOTORS_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_ON: - if (allowPowerOn) { - blimp_vSysAllEnOn(); - enable3V3PowerRail(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + case WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_OFF: + powerOffMotors(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__ALL_MOTORS_POWER_OFF); + break; - case WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_OFF: + case WD_CMD_MSGS__RESET_ID__3_3V_EN_RESET: + if (allowPowerOn) + { disable3V3PowerRail(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_POWER_OFF); - break; + // queue up 3V3 rail on again + theContext.m_watchdogFlags |= WDFLAG_UNRESET_3V3; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_RESET); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_POWER_CYCLE: - if (allowPowerOn) { - disableVSysAllPowerRail(); - // queue up VSA rail on again - theContext.m_watchdogFlags |= WDFLAG_POWER_ON_V_SYS_ALL; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_OFF__RESET); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + case WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_ON: + if (allowPowerOn) + { + blimp_vSysAllEnOn(); + enable3V3PowerRail(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_ON: - if (allowPowerOn) { - enableVSysAllPowerRail(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + case WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_OFF: + disable3V3PowerRail(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__3V3_EN_POWER_OFF); + break; - case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_OFF: + case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_POWER_CYCLE: + if (allowPowerOn) + { disableVSysAllPowerRail(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_POWER_OFF); - break; - - case WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_OFF: - if (allowUndeploy) { - unsetDeploy(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HDRM_DEPLOY_SIGNAL_POWER_OFF); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__FPGA_CAM_0_SELECT: - fpgaCameraSelectLo(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__FPGA_CAM_0_SELECT); - break; - - case WD_CMD_MSGS__RESET_ID__FPGA_CAM_1_SELECT: - fpgaCameraSelectHi(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__FPGA_CAM_1_SELECT); - break; + // queue up VSA rail on again + theContext.m_watchdogFlags |= WDFLAG_POWER_ON_V_SYS_ALL; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_OFF__RESET); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_START: - startChargingBatteries(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERY_CHARGE_START); - break; + case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_ON: + if (allowPowerOn) + { + enableVSysAllPowerRail(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_STOP: - stopChargingBatteries(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERY_CHARGE_STOP); - break; + case WD_CMD_MSGS__RESET_ID__V_SYS_ALL_OFF: + disableVSysAllPowerRail(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__V_SYS_ALL_POWER_OFF); + break; - case WD_CMD_MSGS__RESET_ID__RS422_UART_ENABLE: + case WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_OFF: + if (allowUndeploy) + { + unsetDeploy(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HDRM_DEPLOY_SIGNAL_POWER_OFF); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; + + case WD_CMD_MSGS__RESET_ID__FPGA_CAM_0_SELECT: + fpgaCameraSelectLo(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__FPGA_CAM_0_SELECT); + break; + + case WD_CMD_MSGS__RESET_ID__FPGA_CAM_1_SELECT: + fpgaCameraSelectHi(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__FPGA_CAM_1_SELECT); + break; + + case WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_START: + startChargingBatteries(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERY_CHARGE_START); + break; + + case WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_STOP: + stopChargingBatteries(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERY_CHARGE_STOP); + break; + + case WD_CMD_MSGS__RESET_ID__RS422_UART_ENABLE: + //!< @todo IMPLEMENT + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RS422_UART_ENABLE); + break; + + case WD_CMD_MSGS__RESET_ID__RS422_UART_DISABLE: + if (allowDisableRs422) + { //!< @todo IMPLEMENT - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RS422_UART_ENABLE); - break; - - case WD_CMD_MSGS__RESET_ID__RS422_UART_DISABLE: - if (allowDisableRs422) { - //!< @todo IMPLEMENT - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RS422_UART_DISABLE); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; - - case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_ENABLE: - theContext.m_details.m_hParams.m_heatingControlEnabled = true; - enableHeater(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__AUTO_HEATER_CONTROLLER_ENABLE); - break; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__RS422_UART_DISABLE); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_DISABLE: - theContext.m_details.m_hParams.m_heatingControlEnabled = false; - /** - * @warning TB0CCR2 should ~NOT~ be set here. It should only be set in two places: when Timer_B is - * initialized (where TB0CCR2 is set to its default value), and in the handler for the - * "Set Heater Duty Cycle" ground command. By respecting this, TB0CCR2 keeps whatever value it - * was set with by the ground command and the heater is interacted with (by this command and - * the auto heater control loop) simply by enabling/disabling the heater pin. - * - * @note Similar to the TB0CC2, the m_heating field should not be set here. Instead, it should only be - * modified via calls to enableHeater() and disableHeater(). - */ - disableHeater(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__AUTO_HEATER_CONTROLLER_DISABLE); - break; + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_ENABLE: + theContext.m_details.m_hParams.m_heatingControlEnabled = true; + enableHeater(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__AUTO_HEATER_CONTROLLER_ENABLE); + break; + + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_DISABLE: + theContext.m_details.m_hParams.m_heatingControlEnabled = false; + /** + * @warning TB0CCR2 should ~NOT~ be set here. It should only be set in two places: when Timer_B is + * initialized (where TB0CCR2 is set to its default value), and in the handler for the + * "Set Heater Duty Cycle" ground command. By respecting this, TB0CCR2 keeps whatever value it + * was set with by the ground command and the heater is interacted with (by this command and + * the auto heater control loop) simply by enabling/disabling the heater pin. + * + * @note Similar to the TB0CC2, the m_heating field should not be set here. Instead, it should only be + * modified via calls to enableHeater() and disableHeater(). + */ + disableHeater(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__AUTO_HEATER_CONTROLLER_DISABLE); + break; - case WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_ENABLE: - theContext.m_watchdogOpts |= WDOPT_MONITOR_HERCULES; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_WATCHDOG_ENABLE); - break; + case WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_ENABLE: + theContext.m_watchdogOpts |= WDOPT_MONITOR_HERCULES; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_WATCHDOG_ENABLE); + break; - case WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_DISABLE: - theContext.m_watchdogOpts &= ~WDOPT_MONITOR_HERCULES; - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_WATCHDOG_DISABLE); - break; + case WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_DISABLE: + theContext.m_watchdogOpts &= ~WDOPT_MONITOR_HERCULES; + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_WATCHDOG_DISABLE); + break; - case WD_CMD_MSGS__RESET_ID__BATTERIES_ENABLE: - if (allowPowerOn) { - enableBatteries(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERIES_ENABLE); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + case WD_CMD_MSGS__RESET_ID__BATTERIES_ENABLE: + if (allowPowerOn) + { + enableBatteries(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERIES_ENABLE); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - case WD_CMD_MSGS__RESET_ID__BATTERIES_DISABLE: - disableBatteries(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERIES_DISABLE); - break; + case WD_CMD_MSGS__RESET_ID__BATTERIES_DISABLE: + disableBatteries(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__BATTERIES_DISABLE); + break; - case WD_CMD_MSGS__RESET_ID__CLEAR_PERSISTENT_DEPLOY: - *(theContext.m_persistentDeployed) = false; - break; + case WD_CMD_MSGS__RESET_ID__CLEAR_PERSISTENT_DEPLOY: + *(theContext.m_persistentDeployed) = false; + break; - case WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_ON: - if (allowPowerOn && allowDeploy) { - /* WOOT WOOT! WE ARE ON TO THE MOON, FOLKS */ - /* ref: https://docs.google.com/document/d/1dKLlBcIIVo8t1bGu3jNiHobGMavA3I2al0cncj3ZAhE/edit */ - setDeploy(); - SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HDRM_DEPLOY_SIGNAL_POWER_ON); - } else if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - } - break; + case WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_ON: + if (allowPowerOn && allowDeploy) + { + /* WOOT WOOT! WE ARE ON TO THE MOON, FOLKS */ + /* ref: https://docs.google.com/document/d/1dKLlBcIIVo8t1bGu3jNiHobGMavA3I2al0cncj3ZAhE/edit */ + setDeploy(); + SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HDRM_DEPLOY_SIGNAL_POWER_ON); + } + else if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + } + break; - default: - /* invalid command */ - if (nullptr != response) { - response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; - // If we can respond indicating there was a bad parameter, then return - // that this function finished "successfully," since we have a valid way - // of communicating something didn't work - } + default: + /* invalid command */ + if (nullptr != response) + { + response->statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER; + // If we can respond indicating there was a bad parameter, then return + // that this function finished "successfully," since we have a valid way + // of communicating something didn't work + } } } diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringKeepAlive.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringKeepAlive.cpp index cbc07b551..5506712f7 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringKeepAlive.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringKeepAlive.cpp @@ -14,16 +14,16 @@ namespace iris { RoverStateEnteringKeepAlive::RoverStateEnteringKeepAlive() - : RoverStateBase(RoverState::ENTERING_KEEP_ALIVE) + : RoverStateBase(RoverState::ENTERING_KEEP_ALIVE) { } RoverStateEnteringKeepAlive::RoverStateEnteringKeepAlive(RoverState overridingState) - : RoverStateBase(overridingState) + : RoverStateBase(overridingState) { } - bool RoverStateEnteringKeepAlive::canEnterLowPowerMode(RoverContext& /*theContext*/) + bool RoverStateEnteringKeepAlive::canEnterLowPowerMode(RoverContext & /*theContext*/) { // Don't allow entering low power mode while entering keep alive. The only non-instant thing this state // does is to wait for the previous ADC transaction to complete. Since we don't wake from LPM after an ADC @@ -31,7 +31,7 @@ namespace iris return false; } - RoverState RoverStateEnteringKeepAlive::handleHerculesData(RoverContext& /*theContext*/) + RoverState RoverStateEnteringKeepAlive::handleHerculesData(RoverContext & /*theContext*/) { /** * @todo Should we re-enter this state upon this occurring, in order to re-set the bit that should power off @@ -42,38 +42,41 @@ namespace iris return getState(); } - RoverState RoverStateEnteringKeepAlive::handleTimerTick(RoverContext& theContext) + RoverState RoverStateEnteringKeepAlive::handleTimerTick(RoverContext &theContext) { theContext.m_keepAliveTickCount++; theContext.m_keepAliveTickCountForDetailedReport++; /* only send every 4 timer ticks (28s) */ - if (theContext.m_keepAliveTickCount >= 4) { + if (theContext.m_keepAliveTickCount >= 4) + { theContext.m_keepAliveTickCount = 0; /* send heartbeat with collected data */ - static FlightEarthHeartbeat hb = { 0 }; + static FlightEarthHeartbeat hb = {0}; GroundMsgs__Status gcStatus = - GroundMsgs__generateFlightEarthHeartbeat(&(theContext.m_i2cReadings), - &(theContext.m_adcValues), - &(theContext.m_details.m_hParams), - &hb); + GroundMsgs__generateFlightEarthHeartbeat(&(theContext.m_i2cReadings), + &(theContext.m_adcValues), + &(theContext.m_details.m_hParams), + &hb); assert(GND_MSGS__STATUS__SUCCESS == gcStatus); LanderComms__Status lcStatus = txDownlinkData(theContext, - (uint8_t*) &hb, - sizeof(hb)); + (uint8_t *)&hb, + sizeof(hb)); assert(LANDER_COMMS__STATUS__SUCCESS == lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? } } /* only send every 70 timer ticks (490s) */ // NOTE: This is just the base rate for ENTERING KeepAlive (if stuck here). Actual KeepAlive also sends its own detailed status packets. - if (theContext.m_keepAliveTickCountForDetailedReport >= 70) { + if (theContext.m_keepAliveTickCountForDetailedReport >= 70) + { theContext.m_keepAliveTickCountForDetailedReport = 0; sendDetailedReportToLander(theContext); } @@ -84,78 +87,84 @@ namespace iris UART__Status uStatus = UART__checkRxRbErrors(theContext.m_uart1State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Lander UART Rx Rb Error count"); - if (changed) { + if (changed) + { DebugComms__tryPrintfToLanderNonblocking("New Lander UART Rx Rb failures, total count = %u\n", count); } - if (theContext.m_details.m_hParams.m_heatingControlEnabled) { - // calculate PWM duty cycle (if any) to apply to heater + if (theContext.m_details.m_hParams.m_heatingControlEnabled) + { + // Update the Heater State (PWM remains unchanged here): heaterControl(theContext); } // Queue up a read of the IO Expander, and initiate it if no other I2C action is active - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } return getState(); } - RoverState RoverStateEnteringKeepAlive::handlePowerIssue(RoverContext& /*theContext*/) + RoverState RoverStateEnteringKeepAlive::handlePowerIssue(RoverContext & /*theContext*/) { //!< @todo Implement RoverStateEnteringKeepAlive::handlePowerIssue return getState(); } - RoverState RoverStateEnteringKeepAlive::spinOnce(RoverContext& theContext) + RoverState RoverStateEnteringKeepAlive::spinOnce(RoverContext &theContext) { - switch (m_currentSubstate) { - case SubState::WAITING_FOR_IO_EXPANDER_WRITE: + switch (m_currentSubstate) + { + case SubState::WAITING_FOR_IO_EXPANDER_WRITE: + { + I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; + uint8_t readValue = 0; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, + &(theContext.m_i2cReadings), + &readValue); + + // Sanity check + assert(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action); + + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; - uint8_t readValue = 0; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, - &(theContext.m_i2cReadings), - &readValue); - - // Sanity check - assert(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action); - - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - } + theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; + } - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; - // Start the next I2C action if one is queued, if nothing queued this will return quickly - initiateNextI2cAction(theContext); + // Start the next I2C action if one is queued, if nothing queued this will return quickly + initiateNextI2cAction(theContext); - return transitionToFinishUpSetup(theContext); - } - } - break; - - case SubState::FINISH_UP_SETUP: - // Fall through - default: - // We should only ever spin in this state when the SubState is WAITING_FOR_IO_EXPANDER_WRITE. Really we - // don't need the substates, but I've kept them because they are representative of the stages of this - // state. - assert(!"In spinOnce() not in WAITING_FOR_IO_EXPANDER_WRITE substate, which shouldn't be possible"); - break; + return transitionToFinishUpSetup(theContext); + } + } + break; + + case SubState::FINISH_UP_SETUP: + // Fall through + default: + // We should only ever spin in this state when the SubState is WAITING_FOR_IO_EXPANDER_WRITE. Really we + // don't need the substates, but I've kept them because they are representative of the stages of this + // state. + assert(!"In spinOnce() not in WAITING_FOR_IO_EXPANDER_WRITE substate, which shouldn't be possible"); + break; } // Last ADC sample still not done, so remain in the current state. return getState(); } - RoverState RoverStateEnteringKeepAlive::transitionTo(RoverContext& theContext) + RoverState RoverStateEnteringKeepAlive::transitionTo(RoverContext &theContext) { *(theContext.m_persistentInMission) = false; theContext.m_keepAliveTickCount = 0; @@ -168,9 +177,9 @@ namespace iris return RoverState::KEEP_ALIVE; } - RoverState RoverStateEnteringKeepAlive::performResetCommand(RoverContext& theContext, + RoverState RoverStateEnteringKeepAlive::performResetCommand(RoverContext &theContext, WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response) + WdCmdMsgs__Response *response) { bool writeIOExpander = false; RoverStateBase::doConditionalResetSpecific(theContext, @@ -182,12 +191,14 @@ namespace iris false, // whether or not to allow undeploy writeIOExpander); - if (writeIOExpander) { - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + if (writeIOExpander) + { + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; theContext.m_watchdogFlags |= WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } } @@ -195,8 +206,8 @@ namespace iris return getState(); } - RoverState RoverStateEnteringKeepAlive::handleUplinkFromLander(RoverContext& theContext, - uint8_t* rxDataBuffer, + RoverState RoverStateEnteringKeepAlive::handleUplinkFromLander(RoverContext &theContext, + uint8_t *rxDataBuffer, size_t rxDataLen) { // Ignore any uplink because the Hercules shouldn't be powered on. @@ -204,11 +215,11 @@ namespace iris return getState(); } - RoverState RoverStateEnteringKeepAlive::doGndCmdEnterKeepAliveMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateEnteringKeepAlive::doGndCmdEnterKeepAliveMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // We're already entering keep alive mode, but we can still re-transition into keep alive // once we receive this command. @@ -216,7 +227,7 @@ namespace iris return transitionTo(theContext); } - RoverState RoverStateEnteringKeepAlive::transitionToWaitingForIoExpanderWrite(RoverContext& theContext) + RoverState RoverStateEnteringKeepAlive::transitionToWaitingForIoExpanderWrite(RoverContext &theContext) { // Clear all queued I2C actions and stop any active one. This allows us to immediately perform the IO expander // write @@ -243,7 +254,8 @@ namespace iris blimp_normalBoot(); // Restore BLiMP state if returning to KA from a higher state. Shouldn't do anything if we're pushing straight through KA the first time. // Turn off Herc comms (used if returning to KA from a higher state): - if (HerculesComms__isInitialized(theContext.m_hcState)) { + if (HerculesComms__isInitialized(theContext.m_hcState)) + { DebugComms__registerHerculesComms(NULL); HerculesComms__Status hcStatus = HerculesComms__uninitialize(&(theContext.m_hcState)); DEBUG_ASSERT_EQUAL(HERCULES_COMMS__STATUS__SUCCESS, hcStatus); @@ -252,7 +264,7 @@ namespace iris // Make sure to disable the Hercules uart so we don't dump current through that tx pin UART__uninit0(&(theContext.m_uart0State)); - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; initiateNextI2cAction(theContext); @@ -260,7 +272,7 @@ namespace iris return getState(); } - RoverState RoverStateEnteringKeepAlive::transitionToFinishUpSetup(RoverContext& theContext) + RoverState RoverStateEnteringKeepAlive::transitionToFinishUpSetup(RoverContext &theContext) { // These are simply setting/clearing bits, so they are instant. enableHeater(); diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringMission.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringMission.cpp index 6cd93e801..2337f3c26 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringMission.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateEnteringMission.cpp @@ -18,11 +18,11 @@ namespace iris { RoverStateEnteringMission::RoverStateEnteringMission() - : RoverStateBase(RoverState::ENTERING_MISSION) + : RoverStateBase(RoverState::ENTERING_MISSION) { } - bool RoverStateEnteringMission::canEnterLowPowerMode(RoverContext& /*theContext*/) + bool RoverStateEnteringMission::canEnterLowPowerMode(RoverContext & /*theContext*/) { // Don't allow entering low power mode while entering mission. Waiting for ADC transaction to complete, waiting // for wifi to be ready, and the I2C transactions involved with initializing the fuel gauge are all things that @@ -30,7 +30,7 @@ namespace iris return false; } - RoverState RoverStateEnteringMission::handleTimerTick(RoverContext& theContext) + RoverState RoverStateEnteringMission::handleTimerTick(RoverContext &theContext) { // Check for UART errors to report size_t count = 0; @@ -38,31 +38,34 @@ namespace iris UART__Status uStatus = UART__checkRxRbErrors(theContext.m_uart1State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Lander UART Rx Rb Error count"); - if (changed) { + if (changed) + { DebugComms__tryPrintfToLanderNonblocking("New Lander UART Rx Rb failures, total count = %u\n", count); } /* send heartbeat with collected data */ - static FullEarthHeartbeat hb = { 0 }; + static FullEarthHeartbeat hb = {0}; GroundMsgs__Status gcStatus = GroundMsgs__generateFullEarthHeartbeat(&(theContext.m_i2cReadings), - &(theContext.m_adcValues), - &(theContext.m_details.m_hParams), - static_cast(getState()), - &hb); + &(theContext.m_adcValues), + &(theContext.m_details.m_hParams), + static_cast(getState()), + &hb); DEBUG_ASSERT_EQUAL(GND_MSGS__STATUS__SUCCESS, gcStatus); LanderComms__Status lcStatus = LanderComms__txDataUntilSendOrTimeout(theContext.m_lcState, - (uint8_t*) &hb, + (uint8_t *)&hb, sizeof(hb), 200); DEBUG_ASSERT_EQUAL(LANDER_COMMS__STATUS__SUCCESS, lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? } - if (theContext.m_details.m_hParams.m_heatingControlEnabled) { - // calculate PWM duty cycle (if any) to apply to heater + if (theContext.m_details.m_hParams.m_heatingControlEnabled) + { + // Update the Heater State (PWM remains unchanged here): heaterControl(theContext); } @@ -95,248 +98,272 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::handlePowerIssue(RoverContext& /*theContext*/) + RoverState RoverStateEnteringMission::handlePowerIssue(RoverContext & /*theContext*/) { //!< @todo Implement RoverStateEnteringMission::handlePowerIssue return getState(); } - RoverState RoverStateEnteringMission::spinOnce(RoverContext& theContext) + RoverState RoverStateEnteringMission::spinOnce(RoverContext &theContext) { - switch (m_currentSubstate) { - case SubState::WAITING_FOR_I2C_DONE: - if (theContext.m_i2cActive) { - I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; - uint8_t readValue = 0; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, - &(theContext.m_i2cReadings), - &readValue); - - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; - initiateNextI2cAction(theContext); - - // If m_i2cActive is still false after calling initiateNextI2cAction, it means all queued i2c - // actions have been performed and there is no active i2c action - if (!(theContext.m_i2cActive)) { - return transitionToWaitingForIoExpanderWrite1(theContext); - } + switch (m_currentSubstate) + { + case SubState::WAITING_FOR_I2C_DONE: + if (theContext.m_i2cActive) + { + I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; + uint8_t readValue = 0; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, + &(theContext.m_i2cReadings), + &readValue); + + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; + initiateNextI2cAction(theContext); + + // If m_i2cActive is still false after calling initiateNextI2cAction, it means all queued i2c + // actions have been performed and there is no active i2c action + if (!(theContext.m_i2cActive)) + { + return transitionToWaitingForIoExpanderWrite1(theContext); } - } else { - return transitionToWaitingForIoExpanderWrite1(theContext); } - break; + } + else + { + return transitionToWaitingForIoExpanderWrite1(theContext); + } + break; + + case SubState::WAITING_FOR_IO_EXPANDER_WRITE_1: + { + I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; + uint8_t readValue = 0; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, + &(theContext.m_i2cReadings), + &readValue); + + // Sanity check + DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); - case SubState::WAITING_FOR_IO_EXPANDER_WRITE_1: + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; - uint8_t readValue = 0; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, - &(theContext.m_i2cReadings), - &readValue); + theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; + } - // Sanity check - DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + return transitionToWaitingForIoExpanderWrite2(theContext); + } + } + break; - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - } + case SubState::WAITING_FOR_IO_EXPANDER_WRITE_2: + { + I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; + uint8_t readValue = 0; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, + &(theContext.m_i2cReadings), + &readValue); - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; + // Sanity check + DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); - return transitionToWaitingForIoExpanderWrite2(theContext); - } - } - break; + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - case SubState::WAITING_FOR_IO_EXPANDER_WRITE_2: + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; - uint8_t readValue = 0; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, - &(theContext.m_i2cReadings), - &readValue); + theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; + } - // Sanity check - DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + return transitionToWaitingForFuelGaugeOrTimeout(theContext); + } + } + break; + + case SubState::WAITING_FOR_FUEL_GAUGE_OR_TIMEOUT: + { + // First of all, if we've timed out we can simply move forward. + uint16_t timePassed = Time__getTimeInCentiseconds() - m_startFuelGaugeInitTimeCentiseconds; + // DPRINTF_ERR("%d\n", Time__getTimeInCentiseconds()); + if (timePassed > FUEL_GAUGE_INIT_TIMEOUT_CENTISECONDS) + { + DPRINTF_ERR("Setting up fuel gauge timed out\n"); + I2C_Sensors__stop(); + theContext.m_queuedI2cActions = 0; + theContext.m_i2cActive = false; + + return transitionToWatitingForWifiReadyOrTimeout(theContext); + } - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - } + // Next, check if initializing the fuel gauge is complete (either due to success or failure). + I2C_Sensors__Action currentAction = I2C_SENSORS__ACTIONS__INACTIVE; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(¤tAction, NULL, NULL); - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; + // First of all, we should always be doing the action to initialize the fuel gauges at this point + DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__GAUGE_INIT, currentAction); - return transitionToWaitingForFuelGaugeOrTimeout(theContext); - } - } - break; + if (I2C_SENSORS__STATUS__SUCCESS_DONE == i2cStatus) + { + // Gauge initialization completed successfully, so move forward - case SubState::WAITING_FOR_FUEL_GAUGE_OR_TIMEOUT: - { - // First of all, if we've timed out we can simply move forward. - uint16_t timePassed = Time__getTimeInCentiseconds() - m_startFuelGaugeInitTimeCentiseconds; - //DPRINTF_ERR("%d\n", Time__getTimeInCentiseconds()); - if (timePassed > FUEL_GAUGE_INIT_TIMEOUT_CENTISECONDS) { - DPRINTF_ERR("Setting up fuel gauge timed out\n"); - I2C_Sensors__stop(); - theContext.m_queuedI2cActions = 0; - theContext.m_i2cActive = false; - - return transitionToWatitingForWifiReadyOrTimeout(theContext); - } + // First clear the last I2C_Sensors action so we can start a new one later + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; - // Next, check if initializing the fuel gauge is complete (either due to success or failure). - I2C_Sensors__Action currentAction = I2C_SENSORS__ACTIONS__INACTIVE; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(¤tAction, NULL, NULL); - - // First of all, we should always be doing the action to initialize the fuel gauges at this point - DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__GAUGE_INIT, currentAction); - - if (I2C_SENSORS__STATUS__SUCCESS_DONE == i2cStatus) { - // Gauge initialization completed successfully, so move forward - - // First clear the last I2C_Sensors action so we can start a new one later - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; - - // Then move forward - return transitionToWatitingForWifiReadyOrTimeout(theContext); - } else if (I2C_SENSORS__STATUS__ERROR__DONE_WITH_NACKS == i2cStatus) { - // Gauge initialization failed, but we haven't timed out yet. Therefore we retry the - // initialization action. - - // First clear the current (completed) action from the I2C_Sensors module so we can start a new - // one. - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; - - // Kick off the series of I2C transactions to initialize the fuel gauge. - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__GAUGE_INIT); - initiateNextI2cAction(theContext); - } else if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, - i2cStatus, - "Unexpected failure while getting I2C status"); - // I guess retry entering mission? - //!< @todo What to do here? Enter FAULT? - return transitionToWaitingForI2cDone(theContext); - } + // Then move forward + return transitionToWatitingForWifiReadyOrTimeout(theContext); + } + else if (I2C_SENSORS__STATUS__ERROR__DONE_WITH_NACKS == i2cStatus) + { + // Gauge initialization failed, but we haven't timed out yet. Therefore we retry the + // initialization action. + + // First clear the current (completed) action from the I2C_Sensors module so we can start a new + // one. + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; + + // Kick off the series of I2C transactions to initialize the fuel gauge. + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__GAUGE_INIT); + initiateNextI2cAction(theContext); + } + else if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, + i2cStatus, + "Unexpected failure while getting I2C status"); + // I guess retry entering mission? + //!< @todo What to do here? Enter FAULT? + return transitionToWaitingForI2cDone(theContext); + } - break; - } + break; + } - case SubState::WAITING_FOR_WIFI_READY_OR_TIMEOUT: - { - // First of all, if we've timed out we can simply move forward. - uint16_t timePassed = Time__getTimeInCentiseconds() - m_startWifiReadyTimeCentiseconds; - bool transition = false; - - if(!m_sentWaitingForWifiMessage){ - // Let Ground know why they'll not hear anything from us for a bit: - DPRINTF("Awaiting Wifi for %d cs\n", WIFI_READY_TIMEOUT_CENTISECONDS); - m_sentWaitingForWifiMessage = true; - } + case SubState::WAITING_FOR_WIFI_READY_OR_TIMEOUT: + { + // First of all, if we've timed out we can simply move forward. + uint16_t timePassed = Time__getTimeInCentiseconds() - m_startWifiReadyTimeCentiseconds; + bool transition = false; + + if (!m_sentWaitingForWifiMessage) + { + // Let Ground know why they'll not hear anything from us for a bit: + DPRINTF("Awaiting Wifi for %d cs\n", WIFI_READY_TIMEOUT_CENTISECONDS); + m_sentWaitingForWifiMessage = true; + } - if (timePassed > WIFI_READY_TIMEOUT_CENTISECONDS) { - DPRINTF_ERR("Wait for Wifi timed out\n"); - transition = true; - } + if (timePassed > WIFI_READY_TIMEOUT_CENTISECONDS) + { + DPRINTF_ERR("Wait for Wifi timed out\n"); + transition = true; + } - if (theContext.gotWifi) { - DPRINTF("Got Wifi\n"); - transition = true; - } + if (theContext.gotWifi) + { + DPRINTF("Got Wifi\n"); + transition = true; + } - if (transition) { - // At this point the only thing that may be using I2C would be the read/write from the timer tick, - // and transitioning to mission has priority over that. If it was a write, the changes being written - // should be picked up and written in IoExpanderWrite3. If it was a read, then all that we lose by - // canceling it is a short delay in updating the input values on the IO expander - I2C_Sensors__stop(); - theContext.m_queuedI2cActions = 0; - theContext.m_i2cActive = false; - return transitionToWaitingForIoExpanderWrite3(theContext); - } - break; - } + if (transition) + { + // At this point the only thing that may be using I2C would be the read/write from the timer tick, + // and transitioning to mission has priority over that. If it was a write, the changes being written + // should be picked up and written in IoExpanderWrite3. If it was a read, then all that we lose by + // canceling it is a short delay in updating the input values on the IO expander + I2C_Sensors__stop(); + theContext.m_queuedI2cActions = 0; + theContext.m_i2cActive = false; + return transitionToWaitingForIoExpanderWrite3(theContext); + } + break; + } - case SubState::WAITING_FOR_IO_EXPANDER_WRITE_3: - { - I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; - uint8_t readValue = 0; - I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, - &(theContext.m_i2cReadings), - &readValue); + case SubState::WAITING_FOR_IO_EXPANDER_WRITE_3: + { + I2C_Sensors__Action action = I2C_SENSORS__ACTIONS__INACTIVE; + uint8_t readValue = 0; + I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, + &(theContext.m_i2cReadings), + &readValue); - // Sanity check - DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); + // Sanity check + DEBUG_ASSERT_EQUAL(I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER, action); - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { - DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { + DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { - theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - } + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) + { + theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; + } - I2C_Sensors__clearLastAction(); - theContext.m_i2cActive = false; + I2C_Sensors__clearLastAction(); + theContext.m_i2cActive = false; - // Start the next I2C action if one is queued, if nothing queued this will return quickly - initiateNextI2cAction(theContext); + // Start the next I2C action if one is queued, if nothing queued this will return quickly + initiateNextI2cAction(theContext); - enableHerculesComms(theContext); + enableHerculesComms(theContext); - return RoverState::MISSION; - } - } - break; + return RoverState::MISSION; + } + } + break; - default: - assert(!"In spinOnce() in default case, which shouldn't be possible"); - break; + default: + assert(!"In spinOnce() in default case, which shouldn't be possible"); + break; } // Remain in the current state. return getState(); } - RoverState RoverStateEnteringMission::transitionTo(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionTo(RoverContext &theContext) { m_sentWaitingForWifiMessage = false; // reset flag return transitionToWaitingForI2cDone(theContext); } - RoverState RoverStateEnteringMission::performResetCommand(RoverContext& theContext, + RoverState RoverStateEnteringMission::performResetCommand(RoverContext &theContext, WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response) + WdCmdMsgs__Response *response) { bool writeIOExpander = false; RoverStateBase::doConditionalResetSpecific(theContext, resetValue, response, - true, // whether or not to allow power on + true, // whether or not to allow power on false, // whether or not to allow disabling RS422 false, // whether or not to allow deploy false, // whether or not to allow undeploy writeIOExpander); - if (writeIOExpander) { - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + if (writeIOExpander) + { + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; theContext.m_watchdogFlags |= WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } } @@ -344,17 +371,20 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::transitionToWaitingForI2cDone(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWaitingForI2cDone(RoverContext &theContext) { - if (theContext.m_i2cActive) { + if (theContext.m_i2cActive) + { m_currentSubstate = SubState::WAITING_FOR_I2C_DONE; return getState(); - } else { + } + else + { return transitionToWaitingForIoExpanderWrite1(theContext); } } - RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite1(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite1(RoverContext &theContext) { /* bootup process - enable all rails */ blimp_vSysAllEnOn(); // [CWC] new. desired behavior. @@ -369,7 +399,7 @@ namespace iris releaseRadioReset(); releaseFPGAReset(); - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; // I2C being inactive should be a prerequisite of entering this state @@ -381,7 +411,7 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite2(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite2(RoverContext &theContext) { // Power stuff on. These are simply setting/clearing bits, so they are instant. However, powering on the radio // requires writing the I/O Expander. @@ -390,7 +420,7 @@ namespace iris powerOnRadio(); stopChargingBatteries(); - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; // I2C being inactive should be a prerequisite of entering this state @@ -402,7 +432,7 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::transitionToWaitingForFuelGaugeOrTimeout(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWaitingForFuelGaugeOrTimeout(RoverContext &theContext) { // I2C being inactive should be a prerequisite of entering this state DEBUG_ASSERT(!(theContext.m_i2cActive)); @@ -413,7 +443,7 @@ namespace iris m_startFuelGaugeInitTimeCentiseconds = Time__getTimeInCentiseconds(); // Kick off the series of I2C transactions to initialize the fuel gauge. - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__GAUGE_INIT); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__GAUGE_INIT); initiateNextI2cAction(theContext); // We're done transitioning. The spinOnce() for this substate will monitor for completion of initialization @@ -423,7 +453,7 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::transitionToWatitingForWifiReadyOrTimeout(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWatitingForWifiReadyOrTimeout(RoverContext &theContext) { // Record the start time for the time period in which we'll wait for the wifi to become ready for use. If it // isn't ready by the end of the timeout period, then we'll move forward without wifi. @@ -442,14 +472,14 @@ namespace iris return getState(); } - RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite3(RoverContext& theContext) + RoverState RoverStateEnteringMission::transitionToWaitingForIoExpanderWrite3(RoverContext &theContext) { // These are simply setting/clearing bits, so they are instant powerOnHercules(); releaseMotorsReset(); releaseHerculesReset(); - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; // I2C being inactive should be a prerequisite of entering this state diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp index 2427a1d7a..9ce428f18 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp @@ -14,13 +14,13 @@ namespace iris { RoverStateMission::RoverStateMission() - : RoverStateBase(RoverState::MISSION), - m_currentSubState(SubState::MISSION_NORMAL), - m_currentDeployState(DeployState::NOT_DEPLOYED) + : RoverStateBase(RoverState::MISSION), + m_currentSubState(SubState::MISSION_NORMAL), + m_currentDeployState(DeployState::NOT_DEPLOYED) { } - bool RoverStateMission::canEnterLowPowerMode(RoverContext& theContext) + bool RoverStateMission::canEnterLowPowerMode(RoverContext &theContext) { // The only thing that is done in this state that requires us to stay out of LPM is processing an I2C // transaction. Therefore in this state allowing entering LPM is conditional on whether or not we're actively @@ -28,10 +28,11 @@ namespace iris return !theContext.m_i2cActive; } - RoverState RoverStateMission::handleTimerTick(RoverContext& theContext) + RoverState RoverStateMission::handleTimerTick(RoverContext &theContext) { // Trigger a new ADC sample if the previous one is done - if (isAdcSampleDone()) { + if (isAdcSampleDone()) + { adcCheckVoltageLevels(&(theContext.m_adcValues)); } @@ -43,8 +44,9 @@ namespace iris UART__Status uStatus = UART__checkRxRbErrors(theContext.m_uart0State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Hercules UART Rx Rb Error count"); - if (changed) { - DebugComms__tryPrintfToLanderNonblocking("New Hercules UART Rx Rb failures, total count = %d\n", (int) count); + if (changed) + { + DebugComms__tryPrintfToLanderNonblocking("New Hercules UART Rx Rb failures, total count = %d\n", (int)count); } // Lander UART @@ -53,13 +55,14 @@ namespace iris uStatus = UART__checkRxRbErrors(theContext.m_uart1State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Lander UART Rx Rb Error count"); - if (changed) { - DebugComms__tryPrintfToLanderNonblocking("New Lander UART Rx Rb failures, total count = %d\n", (int) count); + if (changed) + { + DebugComms__tryPrintfToLanderNonblocking("New Lander UART Rx Rb failures, total count = %d\n", (int)count); } // Enable Hercules UART if Hercules is ON: - if ((theContext.m_details.m_outputPinBits & OPSBI__HERCULES_ON) - && !(HerculesComms__isInitialized(theContext.m_hcState))) { + if ((theContext.m_details.m_outputPinBits & OPSBI__HERCULES_ON) && !(HerculesComms__isInitialized(theContext.m_hcState))) + { // We should hopefully never be here during Mission... DebugComms__tryPrintfToLanderNonblocking("Trying to establish UART between WD and Hercules\n"); enableHerculesComms(theContext); @@ -70,7 +73,7 @@ namespace iris * @todo Check if we've deployed or if we shouldn't be able to communicate with lander for any other * reason, and don't send this if that is the case. */ - static FullEarthHeartbeat hb = { 0 }; + static FullEarthHeartbeat hb = {0}; GroundMsgs__Status gcStatus = GroundMsgs__generateFullEarthHeartbeat(&(theContext.m_i2cReadings), &(theContext.m_adcValues), &(theContext.m_details.m_hParams), @@ -79,25 +82,26 @@ namespace iris DEBUG_ASSERT_EQUAL(GND_MSGS__STATUS__SUCCESS, gcStatus); - - LanderComms__Status lcStatus = txDownlinkData(theContext, - (uint8_t*) &hb, - sizeof(hb)); + (uint8_t *)&hb, + sizeof(hb)); DEBUG_ASSERT_EQUAL(LANDER_COMMS__STATUS__SUCCESS, lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? } - if (theContext.m_details.m_hParams.m_heatingControlEnabled) { - // calculate PWM duty cycle (if any) to apply to heater + if (theContext.m_details.m_hParams.m_heatingControlEnabled) + { + // Update the Heater State (PWM remains unchanged here): heaterControl(theContext); } - //theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__GAUGE_READING); + // theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__GAUGE_READING); - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } @@ -108,63 +112,74 @@ namespace iris &writeIOExpander, &(theContext.m_details)); - - - if (writeIOExpander) { - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + if (writeIOExpander) + { + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; theContext.m_watchdogFlags |= WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } } // Queue up a read of the IO Expander, and initiate it if no other I2C action is active - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } return getState(); } - RoverState RoverStateMission::handlePowerIssue(RoverContext& /*theContext*/) + RoverState RoverStateMission::handlePowerIssue(RoverContext & /*theContext*/) { //!< @todo Implement RoverStateMission::handlePowerIssue return getState(); } - RoverState RoverStateMission::spinOnce(RoverContext& theContext) + RoverState RoverStateMission::spinOnce(RoverContext &theContext) { - if (theContext.m_i2cActive) { + if (theContext.m_i2cActive) + { I2C_Sensors__Action action = {}; uint8_t readValue = 0; I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, &(theContext.m_i2cReadings), &readValue); - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) + { theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; } - if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) + { bool chargeStat2 = (readValue & I2C_SENSORS__IOE_P1_BIT__CHARGE_STAT2 != 0); bool latchStat = (readValue & I2C_SENSORS__IOE_P1_BIT__LATCH_STAT != 0); - if (chargeStat2) { + if (chargeStat2) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); } - if (latchStat) { + if (latchStat) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); } } @@ -173,26 +188,26 @@ namespace iris theContext.m_i2cActive = false; initiateNextI2cAction(theContext); } - } - if (theContext.m_sendDetailedReport) { + if (theContext.m_sendDetailedReport) + { theContext.m_sendDetailedReport = false; sendDetailedReportToLander(theContext); - } return getState(); } - RoverState RoverStateMission::transitionTo(RoverContext& theContext) + RoverState RoverStateMission::transitionTo(RoverContext &theContext) { // Nothing to do on this transition, which should always be from ENTERING_MISSION. m_currentSubState = SubState::MISSION_NORMAL; *(theContext.m_persistentInMission) = true; - if (*(theContext.m_persistentDeployed)) { + if (*(theContext.m_persistentDeployed)) + { m_currentDeployState = DeployState::DEPLOYED; disableHeater(); } @@ -200,20 +215,23 @@ namespace iris return getState(); } - void RoverStateMission::heaterControl(RoverContext& theContext) { + void RoverStateMission::heaterControl(RoverContext &theContext) + { // Only use heater when connected to the lander - if (m_currentDeployState != DeployState::NOT_DEPLOYED) { + if (m_currentDeployState != DeployState::NOT_DEPLOYED) + { disableHeater(); - } else { + } + else + { RoverStateBase::heaterControl(theContext); } - } - RoverState RoverStateMission::performResetCommand(RoverContext& theContext, + RoverState RoverStateMission::performResetCommand(RoverContext &theContext, WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response) + WdCmdMsgs__Response *response) { bool writeIOExpander = false; RoverStateBase::doConditionalResetSpecific(theContext, @@ -228,12 +246,14 @@ namespace iris m_currentDeployState != DeployState::NOT_DEPLOYED, writeIOExpander); - if (writeIOExpander) { - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + if (writeIOExpander) + { + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; theContext.m_watchdogFlags |= WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } } @@ -241,16 +261,16 @@ namespace iris return getState(); } - RoverState RoverStateMission::performWatchdogCommand(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateMission::performWatchdogCommand(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // If we're in the SERVICE_ALIVE_HOLDING substate and we receive any command other than EnterService, then we // switch to the MISSION_NORMAL substate. - if (SubState::SERVICE_HOLDING == m_currentSubState - && msg.commandId != WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE) { + if (SubState::SERVICE_HOLDING == m_currentSubState && msg.commandId != WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE) + { m_currentSubState = SubState::MISSION_NORMAL; } @@ -262,51 +282,55 @@ namespace iris sendDeployNotificationResponse); } - RoverState RoverStateMission::doGndCmdDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateMission::doGndCmdDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { - switch (m_currentDeployState) { - case DeployState::NOT_DEPLOYED: - setDeploy(); - m_currentDeployState = DeployState::DEPLOYING; - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; - - deployNotificationResponse.magicNumber = WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER; - deployNotificationResponse.commandId = msg.commandId; - deployNotificationResponse.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__DEPLOY; - sendDeployNotificationResponse = true; - *(theContext.m_persistentDeployed) = true; - - // Don't allow DebugComms to write to lander anymore - DebugComms__registerLanderComms(NULL); - break; - - case DeployState::DEPLOYING: - // fall through - case DeployState::DEPLOYED: - // fall through - default: - response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; - break; + switch (m_currentDeployState) + { + case DeployState::NOT_DEPLOYED: + setDeploy(); + m_currentDeployState = DeployState::DEPLOYING; + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; + + deployNotificationResponse.magicNumber = WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER; + deployNotificationResponse.commandId = msg.commandId; + deployNotificationResponse.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__DEPLOY; + sendDeployNotificationResponse = true; + *(theContext.m_persistentDeployed) = true; + + // Don't allow DebugComms to write to lander anymore + DebugComms__registerLanderComms(NULL); + break; + + case DeployState::DEPLOYING: + // fall through + case DeployState::DEPLOYED: + // fall through + default: + response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE; + break; } return getState(); } - RoverState RoverStateMission::doGndCmdEnterServiceMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateMission::doGndCmdEnterServiceMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // We only want to actually enter keep alive if we receive it twice in a row - if (SubState::SERVICE_HOLDING == m_currentSubState) { + if (SubState::SERVICE_HOLDING == m_currentSubState) + { response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return RoverState::ENTERING_SERVICE; - } else { + } + else + { // Update the substate so that we know to actually transition to keep alive mode if we receive the command // again as the next command. m_currentSubState = SubState::SERVICE_HOLDING; diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp index 49f072a2c..8e4b858a7 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp @@ -12,21 +12,22 @@ namespace iris { RoverStateService::RoverStateService() - : RoverStateEnteringService(RoverState::SERVICE) + : RoverStateEnteringService(RoverState::SERVICE) { } - bool RoverStateService::canEnterLowPowerMode(RoverContext& theContext) + bool RoverStateService::canEnterLowPowerMode(RoverContext &theContext) { // Receiving data from lander or hercules and timer ticks will both wake us up out of LPM, so we can enter LPM // while in this state as long as there are no active I2C transactions occurring return !(theContext.m_i2cActive); } - RoverState RoverStateService::handleTimerTick(RoverContext& theContext) + RoverState RoverStateService::handleTimerTick(RoverContext &theContext) { // Trigger a new ADC sample if the previous one is done - if (isAdcSampleDone()) { + if (isAdcSampleDone()) + { adcCheckVoltageLevels(&(theContext.m_adcValues)); } @@ -38,22 +39,27 @@ namespace iris UART__Status uStatus = UART__checkRxRbErrors(theContext.m_uart1State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Lander UART Rx Rb Error count"); - if (changed) { + if (changed) + { DebugComms__tryPrintfToLanderNonblocking("New Lander UART Rx Rb failures, total count = %u\n", count); } // Hercules UART - if (HerculesComms__isInitialized(theContext.m_hcState)) { + if (HerculesComms__isInitialized(theContext.m_hcState)) + { // Hercules Comms initialized size_t count = 0; BOOL changed = FALSE; UART__Status uStatus = UART__checkRxRbErrors(theContext.m_uart0State, &count, &changed); DEBUG_LOG_CHECK_STATUS(UART__STATUS__SUCCESS, uStatus, "Failed to get Hercules UART Rx Rb Error count"); - if (changed) { - DebugComms__tryPrintfToLanderNonblocking("New Hercules UART Rx Rb failures, total count = %d\n", (int) count); + if (changed) + { + DebugComms__tryPrintfToLanderNonblocking("New Hercules UART Rx Rb failures, total count = %d\n", (int)count); } - } else if ((theContext.m_details.m_outputPinBits & OPSBI__HERCULES_ON)) { + } + else if ((theContext.m_details.m_outputPinBits & OPSBI__HERCULES_ON)) + { // Enable Hercules UART if Hercules is ON: // Hercules Power ON but Comms not initialized DebugComms__tryPrintfToLanderNonblocking("Trying to establish UART between WD and Hercules\n"); @@ -61,7 +67,7 @@ namespace iris } /* send heartbeat with collected data */ - static FullEarthHeartbeat hb = { 0 }; + static FullEarthHeartbeat hb = {0}; GroundMsgs__Status gcStatus = GroundMsgs__generateFullEarthHeartbeat(&(theContext.m_i2cReadings), &(theContext.m_adcValues), &(theContext.m_details.m_hParams), @@ -71,16 +77,18 @@ namespace iris assert(GND_MSGS__STATUS__SUCCESS == gcStatus); LanderComms__Status lcStatus = txDownlinkData(theContext, - (uint8_t*) &hb, - sizeof(hb)); + (uint8_t *)&hb, + sizeof(hb)); assert(LANDER_COMMS__STATUS__SUCCESS == lcStatus); - if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) { + if (LANDER_COMMS__STATUS__SUCCESS != lcStatus) + { //!< @todo Handling? } - if (theContext.m_details.m_hParams.m_heatingControlEnabled) { - // calculate PWM duty cycle (if any) to apply to heater + if (theContext.m_details.m_hParams.m_heatingControlEnabled) + { + // Update the Heater State (PWM remains unchanged here): heaterControl(theContext); } @@ -91,61 +99,74 @@ namespace iris &writeIOExpander, &(theContext.m_details)); - if (writeIOExpander) { - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); + if (writeIOExpander) + { + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER); theContext.m_writeCustomIoExpanderValues = false; theContext.m_watchdogFlags |= WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } } // Queue up a read of the IO Expander, and initiate it if no other I2C action is active - theContext.m_queuedI2cActions |= 1 << ((uint16_t) I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); + theContext.m_queuedI2cActions |= 1 << ((uint16_t)I2C_SENSORS__ACTIONS__READ_IO_EXPANDER); - if (!theContext.m_i2cActive) { + if (!theContext.m_i2cActive) + { initiateNextI2cAction(theContext); } return getState(); } - RoverState RoverStateService::handlePowerIssue(RoverContext& /*theContext*/) + RoverState RoverStateService::handlePowerIssue(RoverContext & /*theContext*/) { //!< @todo Implement RoverStateService::handlePowerIssue return getState(); } - RoverState RoverStateService::spinOnce(RoverContext& theContext) + RoverState RoverStateService::spinOnce(RoverContext &theContext) { - if (theContext.m_i2cActive) { + if (theContext.m_i2cActive) + { I2C_Sensors__Action action = {}; uint8_t readValue = 0; I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, &(theContext.m_i2cReadings), &readValue); - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) + { theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; } - if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) + { bool chargeStat2 = (readValue & I2C_SENSORS__IOE_P1_BIT__CHARGE_STAT2 != 0); bool latchStat = (readValue & I2C_SENSORS__IOE_P1_BIT__LATCH_STAT != 0); - if (chargeStat2) { + if (chargeStat2) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); } - if (latchStat) { + if (latchStat) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); } } @@ -156,7 +177,8 @@ namespace iris } } - if (theContext.m_sendDetailedReport) { + if (theContext.m_sendDetailedReport) + { theContext.m_sendDetailedReport = false; sendDetailedReportToLander(theContext); } @@ -164,23 +186,23 @@ namespace iris return getState(); } - RoverState RoverStateService::transitionTo(RoverContext& theContext) + RoverState RoverStateService::transitionTo(RoverContext &theContext) { // Nothing to do on this transition, which should always be from ENTERING_SERVICE. m_currentSubState = SubState::SERVICE_NORMAL; return getState(); } - RoverState RoverStateService::performWatchdogCommand(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateService::performWatchdogCommand(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // If we're in the KEEP_ALIVE_HOLDING substate and we receive any command other than EnterKeepAlive, then we // switch to the SERVICE_NORMAL substate. - if (SubState::KEEP_ALIVE_HOLDING == m_currentSubState - && msg.commandId != WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE) { + if (SubState::KEEP_ALIVE_HOLDING == m_currentSubState && msg.commandId != WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE) + { m_currentSubState = SubState::SERVICE_NORMAL; } @@ -192,28 +214,31 @@ namespace iris sendDeployNotificationResponse); } - RoverState RoverStateService::doGndCmdPrepForDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateService::doGndCmdPrepForDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Can transition directly to mission mode from service */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return RoverState::ENTERING_MISSION; } - RoverState RoverStateService::doGndCmdEnterKeepAliveMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateService::doGndCmdEnterKeepAliveMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // We only want to actually enter keep alive if we receive it twice in a row - if (SubState::KEEP_ALIVE_HOLDING == m_currentSubState) { + if (SubState::KEEP_ALIVE_HOLDING == m_currentSubState) + { response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return RoverState::ENTERING_KEEP_ALIVE; - } else { + } + else + { // Update the substate so that we know to actually transition to keep alive mode if we receive the command // againas the next command. m_currentSubState = SubState::KEEP_ALIVE_HOLDING; @@ -229,11 +254,11 @@ namespace iris } } - RoverState RoverStateService::doGndCmdEnterServiceMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateService::doGndCmdEnterServiceMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // Do the default behavior of complaining about being in the wrong state. return RoverStateBase::doGndCmdEnterServiceMode(theContext, From c4ecea54b3acb0227a2ce47afd73f3246bdd8002 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:24:20 -0500 Subject: [PATCH 11/39] WD: Applied linter. --- Apps/FlightSoftware/Watchdog/src/watchdog.c | 205 +++++++++++--------- 1 file changed, 116 insertions(+), 89 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/watchdog.c b/Apps/FlightSoftware/Watchdog/src/watchdog.c index bd5e66e2c..dbd414f28 100644 --- a/Apps/FlightSoftware/Watchdog/src/watchdog.c +++ b/Apps/FlightSoftware/Watchdog/src/watchdog.c @@ -22,8 +22,8 @@ static volatile uint16_t shouldBeUnusedWatchdogFlags = 0; static volatile uint16_t shouldBeUnusedTimeCount = 0; -//static volatile uint16_t* watchdogFlagsPtr = &shouldBeUnusedWatchdogFlags; -static volatile uint16_t* timeCountCentisecondsPtr = &shouldBeUnusedTimeCount; +// static volatile uint16_t* watchdogFlagsPtr = &shouldBeUnusedWatchdogFlags; +static volatile uint16_t *timeCountCentisecondsPtr = &shouldBeUnusedTimeCount; static volatile BOOL lookingForWdIntFallingEdge = TRUE; static volatile uint16_t wdIntLastEdgeTime = 0; @@ -32,15 +32,15 @@ static volatile uint16_t wdIntTimeBetweenLastEdges = 0; /** * Set up the ISRs for the watchdog */ -int watchdog_init(volatile uint16_t* watchdogFlags, - volatile uint16_t* timeCountCentiseconds, - const HeaterParams* hParams) +int watchdog_init(volatile uint16_t *watchdogFlags, + volatile uint16_t *timeCountCentiseconds, + const HeaterParams *hParams) { DEBUG_LOG_NULL_CHECK_RETURN(watchdogFlags, "Parameter is NULL", -1); DEBUG_LOG_NULL_CHECK_RETURN(timeCountCentiseconds, "Parameter is NULL", -1); DEBUG_LOG_NULL_CHECK_RETURN(hParams, "Parameter is NULL", -1); -// watchdogFlagsPtr = watchdogFlags; + // watchdogFlagsPtr = watchdogFlags; timeCountCentisecondsPtr = timeCountCentiseconds; /* ===================================================== @@ -49,7 +49,7 @@ int watchdog_init(volatile uint16_t* watchdogFlags, // Use ACLK (which has a frequency of about 9.4 kHz (typ.)) as Timer_A clock source. This also ensures // that the timer is stopped, as all bits in TA0CTL other than TASSEL will be cleared. This means the - // MC bits will be set to zero, which means that the timer is stopped. + // MC bits will be set to zero, which means that the timer is stopped. TA0CTL = TASSEL_1; // The input divider for the input clock is determined by the ID bits in TAxCTL and the TAIDEX bits @@ -57,9 +57,9 @@ int watchdog_init(volatile uint16_t* watchdogFlags, // the clock divisor determined by the ID bits is d_ID, and the clock divisor determined by the TAIDEX // bits is d_TAIDEX, then their relationship is: // - // f_timer = (f_clk / d_ID ) / d_TAIDEX + // f_timer = (f_clk / d_ID ) / d_TAIDEX // f_timer = f_clk / (d_ID * d_TAIDEX) - // + // // Here, we use f_clk = 9.4 kHz, d_ID = 1, and d_TAIDEX = 1, so f_timer = 9.4 kHz // Sets ID to 00b, making it divide by 1 (i.e. does not divide). @@ -69,7 +69,7 @@ int watchdog_init(volatile uint16_t* watchdogFlags, TA0EX0 = TAIDEX_0; // Per the note in section 25.2.1.1 (pg 645) of the user guide, TACLR should be set after modifying - // the ID or TAIDEX bits. Doing so resets the clock divider logic, and the new settings are + // the ID or TAIDEX bits. Doing so resets the clock divider logic, and the new settings are // used once the TACLR bit is cleared. We do not need to manually clear this bit after setting it, // as it is reset automatically. TA0CTL |= TACLR; @@ -89,18 +89,18 @@ int watchdog_init(volatile uint16_t* watchdogFlags, // that we will get the TAIFG interrupt once about every 7 seconds (2^16 = 65536, and // 65536 / 9400 = ~6.97 seconds) TA0CTL |= TAIE; - + // Finished setting up Timer_A, so start the timer in "Continuous" mode (i.e. timer will count up to 0xFFFF, // then overflow to zero) - TA0CTL |= MC_2; + TA0CTL |= MC_2; - /* ===================================================== + /* ===================================================== Timer_B setup (used to generate PWM for heater control) ===================================================== */ // Use SMCLK (which has a frequency of 8 MHz) as Timer_B clock source. This also ensures // that the timer is stopped, as all bits in TB0CTL other than TBSSEL will be cleared. This means the - // MC bits will be set to zero, which means that the timer is stopped. + // MC bits will be set to zero, which means that the timer is stopped. TB0CTL = TBSSEL__SMCLK; // The input divier for the input clock is determined by the ID bits in TBxCTL and the TBIDEX bits @@ -108,9 +108,9 @@ int watchdog_init(volatile uint16_t* watchdogFlags, // the clock divisor determined by the ID bits is d_ID, and the clock divisor determined by the TBIDEX // bits is d_TBIDEX, then their relationship is: // - // f_timer = (f_clk / d_ID ) / d_TBIDEX + // f_timer = (f_clk / d_ID ) / d_TBIDEX // f_timer = f_clk / (d_ID * d_TBIDEX) - // + // // Here, we use f_clk = 8 MHz, d_ID = 1, and d_TBIDEX = 1, so f_timer = 8 MHz // ID bits in TB0CTL will have been set to 00b in the previous assignment, making it divide by 1 (i.e. @@ -120,9 +120,9 @@ int watchdog_init(volatile uint16_t* watchdogFlags, TB0EX0 = TAIDEX_0; // Per the note in section 25.2.1.1 (pg 645) of the user guide, TBCLR should be set after modifying - // the ID or TBIDEX bits. Doing so resets the clock divider logic, and the new settings are + // the ID or TBIDEX bits. Doing so resets the clock divider logic, and the new settings are // used once the TBCLR bit is cleared. We do not need to manually clear this bit after setting it, - // as it is reset automatically. More specifically, the state of the output changes when the + // as it is reset automatically. More specifically, the state of the output changes when the TB0CTL |= TBCLR; // Set the maximum count value of Timer_B (when it is set to "Up" mode) to 10000. @@ -133,11 +133,11 @@ int watchdog_init(volatile uint16_t* watchdogFlags, // Set the output mode of capture/compare block 2 to "Reset/Set". This means that the output is // reset (i.e. made low) when Timer_B counts to the value in TB0CCR2, and the output is set (i.e. - // made high) when Timer_B counts to TB0CL0 (which is set from the value in TB0CCR0). + // made high) when Timer_B counts to TB0CL0 (which is set from the value in TB0CCR0). TB0CCTL2 = OUTMOD_7; // Set the initial duty cycle of the PWM. Specifically, this is the counter value at which the output - // will reset, or go low. When this has a value of zero, it means that the heater is effectively + // will reset, or go low. When this has a value of zero, it means that the heater is effectively // disabled. TB0CCR2 = hParams->m_heaterDutyCycle; @@ -157,11 +157,11 @@ int watchdog_init(volatile uint16_t* watchdogFlags, * * Function called every ~5s */ -int watchdog_monitor(HerculesComms__State* hState, - volatile uint16_t* watchdogFlags, - uint8_t* watchdogOpts, - BOOL* writeIOExpander, - WatchdogStateDetails* details) +int watchdog_monitor(HerculesComms__State *hState, + volatile uint16_t *watchdogFlags, + uint8_t *watchdogOpts, + BOOL *writeIOExpander, + WatchdogStateDetails *details) { // NOTE: hState can be NULL if the Hercules comm link isn't up DEBUG_LOG_NULL_CHECK_RETURN(watchdogFlags, "Parameter is NULL", -1); @@ -173,15 +173,19 @@ int watchdog_monitor(HerculesComms__State* hState, __disable_interrupt(); /* check that kicks have been received */ - if (*watchdogFlags & WDFLAG_RADIO_KICK) { + if (*watchdogFlags & WDFLAG_RADIO_KICK) + { /* radio kick received, all ok! */ *watchdogFlags ^= WDFLAG_RADIO_KICK; - } else { + } + else + { /* MISSING radio kick! don't bother resetting, though */ } /* unreset wifi chip */ - if (*watchdogFlags & WDFLAG_UNRESET_RADIO2) { + if (*watchdogFlags & WDFLAG_UNRESET_RADIO2) + { releaseRadioReset(); *watchdogFlags ^= WDFLAG_UNRESET_RADIO2; *writeIOExpander = TRUE; @@ -189,13 +193,15 @@ int watchdog_monitor(HerculesComms__State* hState, } /* unreset wifi chip */ - if ((*watchdogFlags & WDFLAG_UNRESET_RADIO1) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_RADIO1) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { *watchdogFlags |= WDFLAG_UNRESET_RADIO2; *watchdogFlags ^= WDFLAG_UNRESET_RADIO1; } /* unreset hercules */ - if ((*watchdogFlags & WDFLAG_UNRESET_HERCULES) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_HERCULES) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseHerculesReset(); *watchdogFlags ^= WDFLAG_UNRESET_HERCULES; *writeIOExpander = TRUE; @@ -203,35 +209,40 @@ int watchdog_monitor(HerculesComms__State* hState, } /* unreset motor 1 */ - if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR1) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR1) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseMotor1Reset(); *watchdogFlags ^= WDFLAG_UNRESET_MOTOR1; *writeIOExpander = TRUE; } /* unreset motor 2 */ - if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR2) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR2) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseMotor2Reset(); *watchdogFlags ^= WDFLAG_UNRESET_MOTOR2; *writeIOExpander = TRUE; } /* unreset motor 3 */ - if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR3) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR3) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseMotor3Reset(); *watchdogFlags ^= WDFLAG_UNRESET_MOTOR3; *writeIOExpander = TRUE; } /* unreset motor 4 */ - if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR4) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_MOTOR4) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseMotor4Reset(); *watchdogFlags ^= WDFLAG_UNRESET_MOTOR4; *writeIOExpander = TRUE; } /* unreset FPGA */ - if ((*watchdogFlags & WDFLAG_UNRESET_FPGA) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) { + if ((*watchdogFlags & WDFLAG_UNRESET_FPGA) && !(*watchdogFlags & WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE)) + { releaseFPGAReset(); *watchdogFlags ^= WDFLAG_UNRESET_FPGA; *writeIOExpander = TRUE; @@ -239,30 +250,37 @@ int watchdog_monitor(HerculesComms__State* hState, } /* bring 3V3 on again */ - if (*watchdogFlags & WDFLAG_UNRESET_3V3) { + if (*watchdogFlags & WDFLAG_UNRESET_3V3) + { enable3V3PowerRail(); *watchdogFlags ^= WDFLAG_UNRESET_3V3; SET_RABI_IN_UINT(details->m_resetActionBits, RABI__3V3_EN_UNRESET); } /* turn VSA on again */ - if (*watchdogFlags & WDFLAG_POWER_ON_V_SYS_ALL) { + if (*watchdogFlags & WDFLAG_POWER_ON_V_SYS_ALL) + { enableVSysAllPowerRail(); *watchdogFlags ^= WDFLAG_POWER_ON_V_SYS_ALL; SET_RABI_IN_UINT(details->m_resetActionBits, RABI__V_SYS_ALL_ON__UNRESET); } /* check ADC values */ - if (*watchdogFlags & WDFLAG_ADC_READY) { + if (*watchdogFlags & WDFLAG_ADC_READY) + { /* ensure ADC values are in spec */ *watchdogFlags ^= WDFLAG_ADC_READY; } /* check if hercules has given a valid kick */ - if (*watchdogFlags & WDFLAG_HERCULES_KICK) { + if (*watchdogFlags & WDFLAG_HERCULES_KICK) + { *watchdogFlags ^= WDFLAG_HERCULES_KICK; - } else { - if (*watchdogOpts & WDOPT_MONITOR_HERCULES) { + } + else + { + if (*watchdogOpts & WDOPT_MONITOR_HERCULES) + { // reset the hercules setHerculesReset(); @@ -272,7 +290,8 @@ int watchdog_monitor(HerculesComms__State* hState, *watchdogFlags |= WDFLAG_UNRESET_HERCULES; // if the issue was due to a comms breakdown, reset the comms state - if (NULL != hState) { + if (NULL != hState) + { HerculesComms__Status hcStatus = HerculesComms__resetState(hState); //!< @todo Replace with returning watchdog error code once that is implemented. @@ -280,7 +299,9 @@ int watchdog_monitor(HerculesComms__State* hState, } *writeIOExpander = TRUE; - } else { + } + else + { // missed a kick, but don't reset the hercules. } } @@ -290,19 +311,18 @@ int watchdog_monitor(HerculesComms__State* hState, return 0; } - - void watchdog_build_hercules_telem(const I2C_Sensors__Readings *i2cReadings, - const AdcValues* adcValues, + const AdcValues *adcValues, BOOL hasDeployed, - uint8_t* telbuf, + uint8_t *telbuf, size_t telbufSize) { DEBUG_LOG_NULL_CHECK_RETURN(i2cReadings, "Parameter is NULL", /* nothing, b/c void return */); DEBUG_LOG_NULL_CHECK_RETURN(adcValues, "Parameter is NULL", /* nothing, b/c void return */); DEBUG_LOG_NULL_CHECK_RETURN(telbuf, "Parameter is NULL", /* nothing, b/c void return */); - if (telbufSize < 16) { + if (telbufSize < 16) + { DPRINTF_ERR("telbufSize is too small: required = %d, actual = %d\n", 16, telbufSize); return; } @@ -331,7 +351,6 @@ uint16_t watchdog_get_wd_int_flat_duration(void) return wdIntTimeBetweenLastEdges; } - /* * Pins that need an ISR: * @@ -356,42 +375,48 @@ uint16_t watchdog_get_wd_int_flat_duration(void) /* Port 1 handler */ #if 1 #if defined(__TI_COMPILER_VERSION__) || defined(__IAR_SYSTEMS_ICC__) -#pragma vector=PORT1_VECTOR -__interrupt void port1_isr_handler(void) { +#pragma vector = PORT1_VECTOR +__interrupt void port1_isr_handler(void) +{ #elif defined(__GNUC__) -void __attribute__ ((interrupt(PORT1_VECTOR))) port1_isr_handler (void) { +void __attribute__((interrupt(PORT1_VECTOR))) port1_isr_handler(void) +{ #else #error Compiler not supported! #endif uint16_t now = *timeCountCentisecondsPtr; - switch(__even_in_range(P1IV, P1IV__P1IFG7)) { - case P1IV__P1IFG3: // P1.3: WD_INT - if (lookingForWdIntFallingEdge) { - EventQueue__put(EVENT__TYPE__WD_INT_FALLING_EDGE); - lookingForWdIntFallingEdge = FALSE; - enableWdIntRisingEdgeInterrupt(); - } else { - EventQueue__put(EVENT__TYPE__WD_INT_RISING_EDGE); - lookingForWdIntFallingEdge = TRUE; - enableWdIntFallingEdgeInterrupt(); - } + switch (__even_in_range(P1IV, P1IV__P1IFG7)) + { + case P1IV__P1IFG3: // P1.3: WD_INT + if (lookingForWdIntFallingEdge) + { + EventQueue__put(EVENT__TYPE__WD_INT_FALLING_EDGE); + lookingForWdIntFallingEdge = FALSE; + enableWdIntRisingEdgeInterrupt(); + } + else + { + EventQueue__put(EVENT__TYPE__WD_INT_RISING_EDGE); + lookingForWdIntFallingEdge = TRUE; + enableWdIntFallingEdgeInterrupt(); + } - wdIntTimeBetweenLastEdges = now - wdIntLastEdgeTime; - wdIntLastEdgeTime = now; + wdIntTimeBetweenLastEdges = now - wdIntLastEdgeTime; + wdIntLastEdgeTime = now; - // exit LPM - __low_power_mode_off_on_exit(); - break; - default: // default: ignore - break; + // exit LPM + __low_power_mode_off_on_exit(); + break; + default: // default: ignore + break; } } #endif #if 0 /* Port 3 handler */ #if defined(__TI_COMPILER_VERSION__) || defined(__IAR_SYSTEMS_ICC__) -#pragma vector=PORT3_VECTOR +#pragma vector = PORT3_VECTOR __interrupt void port3_isr_handler(void) { #elif defined(__GNUC__) void __attribute__ ((interrupt(PORT3_VECTOR))) port3_isr_handler (void) { @@ -408,27 +433,29 @@ void __attribute__ ((interrupt(PORT3_VECTOR))) port3_isr_handler (void) { /* Timer 1 handler */ #if defined(__TI_COMPILER_VERSION__) || defined(__IAR_SYSTEMS_ICC__) #pragma vector = TIMER0_A1_VECTOR -__interrupt void Timer0_A1_ISR(void) { +__interrupt void Timer0_A1_ISR(void) +{ #elif defined(__GNUC__) -void __attribute__ ((interrupt(TIMER0_A1_VECTOR))) Timer0_A1_ISR (void) { +void __attribute__((interrupt(TIMER0_A1_VECTOR))) Timer0_A1_ISR(void) +{ #else #error Compiler not supported! #endif - switch (__even_in_range(TA0IV, TAIV__TAIFG)) { - case TAIV__TACCR1: - *timeCountCentisecondsPtr = *timeCountCentisecondsPtr + 1; - - // Offset the count value we're looking for by by the number of timer ticks in one centisecond - TA0CCR1 += 94; - break; - - case TAIV__TAIFG: /* timer tick overflowed */ - EventQueue__put(EVENT__TYPE__TIMER_TICK); - __low_power_mode_off_on_exit(); - break; - - default: - break; + switch (__even_in_range(TA0IV, TAIV__TAIFG)) + { + case TAIV__TACCR1: + *timeCountCentisecondsPtr = *timeCountCentisecondsPtr + 1; + + // Offset the count value we're looking for by by the number of timer ticks in one centisecond + TA0CCR1 += 94; + break; + + case TAIV__TAIFG: /* timer tick overflowed */ + EventQueue__put(EVENT__TYPE__TIMER_TICK); + __low_power_mode_off_on_exit(); + break; + + default: + break; } } - From 386900f90e869f211f83b302050d035111d66a02 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:26:03 -0500 Subject: [PATCH 12/39] WD: Corrected which thermistor data is being fed to Hercules (RT instead of charging now). --- Apps/FlightSoftware/Watchdog/src/watchdog.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Apps/FlightSoftware/Watchdog/src/watchdog.c b/Apps/FlightSoftware/Watchdog/src/watchdog.c index dbd414f28..fb4a0106a 100644 --- a/Apps/FlightSoftware/Watchdog/src/watchdog.c +++ b/Apps/FlightSoftware/Watchdog/src/watchdog.c @@ -336,7 +336,7 @@ void watchdog_build_hercules_telem(const I2C_Sensors__Readings *i2cReadings, // [6,7] won't be able to read lander power in mission mode telbuf[6] = (uint8_t)(adcValues->vLanderSense); telbuf[7] = (uint8_t)(adcValues->vLanderSense >> 8); - telbuf[8] = (uint8_t)(adcValues->battTemp >> 4); + telbuf[8] = (uint8_t)(adcValues->battRT >> 4); telbuf[9] = hasDeployed ? 1 : 0; telbuf[10] = (uint8_t)(i2cReadings->raw_battery_charge[0]); telbuf[11] = (uint8_t)(i2cReadings->raw_battery_charge[1]); From fe0c1ed5a7160cf95a93fa0a9dbe73a5893a03bb Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 10:27:33 -0500 Subject: [PATCH 13/39] WD: Updated default heater power to 85% - value used in EM3 TVAC - (from 0%) so heater control can actually control the heater. --- Apps/FlightSoftware/Watchdog/include/flags.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/flags.h b/Apps/FlightSoftware/Watchdog/include/flags.h index f668c1a3a..0885aa3f6 100644 --- a/Apps/FlightSoftware/Watchdog/include/flags.h +++ b/Apps/FlightSoftware/Watchdog/include/flags.h @@ -56,7 +56,7 @@ extern "C" } HeaterParams; #define DEFAULT_KP_HEATER 500 // deprecated -#define DEFAULT_PWM_LIMIT 8500 // deprecated +#define DEFAULT_PWM_LIMIT 9999 // deprecated #define DEFAULT_HEATER_SETPOINT 3325 // deprecated #define DEFAULT_HEATER_WINDOW 60 // deprecated // 3670 is the -5 deg C thermistor voltage ADC reading - heater transitions to ON when T ADC < this value: @@ -65,7 +65,7 @@ extern "C" #define DEFAULT_HEATER_OFF_VAL 3352 #define DEFAULT_HEATING_CONTROL_ENABLED TRUE #define DEFAULT_HEATER_DUTY_CYCLE_PERIOD 10000 -#define DEFAULT_HEATER_DUTY_CYCLE 0 +#define DEFAULT_HEATER_DUTY_CYCLE 8500 #define GENERIC_BIT_INDEX_TO_TYPE_MASK(type, index) (((type)1) << ((type)(index))) #define GENERIC_BIT_INDEX_TO_UINT8_MASK(index) GENERIC_BIT_INDEX_TO_TYPE_MASK(uint8_t, index) From 24579de4b5df93fe42c8befee281222b3f378cab Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 11:16:27 -0500 Subject: [PATCH 14/39] WD: Applied linter to bsp.c --- .../FlightSoftware/Watchdog/src/drivers/bsp.c | 136 +++++++++++------- 1 file changed, 81 insertions(+), 55 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c index 0e442b2c7..70178b520 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c @@ -8,7 +8,7 @@ #include // uncomment to program MC -//#define PROGRAM_MOTOR_CONTROLLERS +// #define PROGRAM_MOTOR_CONTROLLERS #define PORT1_ENABLED 1 #define PORT2_ENABLED 1 @@ -16,48 +16,70 @@ #define PORT4_ENABLED 1 #define PORTJ_ENABLED 1 -static WatchdogStateDetails* detailsPtr = NULL; +static WatchdogStateDetails *detailsPtr = NULL; -const char* getResetReasonString(void) +const char *getResetReasonString(void) { switch (__even_in_range(SYSRSTIV, SYSRSTIV_MPUSEG3IFG)) { - case SYSRSTIV_NONE: return "None"; - case SYSRSTIV_BOR: return "Brownout (BOR)"; - case SYSRSTIV_RSTNMI: return "RSTIFG RST/NMI (BOR)"; - case SYSRSTIV_DOBOR: return "PMMSWBOR software BOR (BOR)"; - case SYSRSTIV_LPM5WU: return "LPMx.5 wake up (BOR)"; - case SYSRSTIV_SECYV: return "Security violation (BOR)"; - case SYSRSTIV_SVSHIFG: return "SCSHIFG SVSH event (BOR)"; - case SYSRSTIV_DOPOR: return "PMMSWPOR software POR (POR)"; - case SYSRSTIV_WDTTO: return "WDTIFG watchdog timeout (PUC)"; - case SYSRSTIV_WDTPW: return "WDTPW password violation (PUC)"; - case SYSRSTIV_FRCTLPW: return "FRCTLPW password violation (PUC)"; - case SYSRSTIV_UBDIFG: return "Uncorrectable FRAM bit error detection (PUC)"; - case SYSRSTIV_PERF: return "Peripheral area fetch (PUC)"; - case SYSRSTIV_PMMPW: return "PMMPW PMM password violation (PUC)"; - case SYSRSTIV_MPUPW: return "MPUPW MPU password violation (PUC)"; - case SYSRSTIV_CSPW: return "CSPW CS password violation (PUC)"; - case SYSRSTIV_MPUSEGPIFG: return "MPUSEGIPIFG encapsulated IP memory segment violation (PUC)"; - case SYSRSTIV_MPUSEGIIFG: return "MPUSEGIIFG information memory segment violation (PUC)"; - case SYSRSTIV_MPUSEG1IFG: return "MPUSEG1IFG segment 1 memory violation (PUC)"; - case SYSRSTIV_MPUSEG2IFG: return "MPUSEG2IFG segment 2 memory violation (PUC)"; - case SYSRSTIV_MPUSEG3IFG: return "MPUSEG3IFG segment 3 memory violation (PUC)"; - default: return "Unknown"; + case SYSRSTIV_NONE: + return "None"; + case SYSRSTIV_BOR: + return "Brownout (BOR)"; + case SYSRSTIV_RSTNMI: + return "RSTIFG RST/NMI (BOR)"; + case SYSRSTIV_DOBOR: + return "PMMSWBOR software BOR (BOR)"; + case SYSRSTIV_LPM5WU: + return "LPMx.5 wake up (BOR)"; + case SYSRSTIV_SECYV: + return "Security violation (BOR)"; + case SYSRSTIV_SVSHIFG: + return "SCSHIFG SVSH event (BOR)"; + case SYSRSTIV_DOPOR: + return "PMMSWPOR software POR (POR)"; + case SYSRSTIV_WDTTO: + return "WDTIFG watchdog timeout (PUC)"; + case SYSRSTIV_WDTPW: + return "WDTPW password violation (PUC)"; + case SYSRSTIV_FRCTLPW: + return "FRCTLPW password violation (PUC)"; + case SYSRSTIV_UBDIFG: + return "Uncorrectable FRAM bit error detection (PUC)"; + case SYSRSTIV_PERF: + return "Peripheral area fetch (PUC)"; + case SYSRSTIV_PMMPW: + return "PMMPW PMM password violation (PUC)"; + case SYSRSTIV_MPUPW: + return "MPUPW MPU password violation (PUC)"; + case SYSRSTIV_CSPW: + return "CSPW CS password violation (PUC)"; + case SYSRSTIV_MPUSEGPIFG: + return "MPUSEGIPIFG encapsulated IP memory segment violation (PUC)"; + case SYSRSTIV_MPUSEGIIFG: + return "MPUSEGIIFG information memory segment violation (PUC)"; + case SYSRSTIV_MPUSEG1IFG: + return "MPUSEG1IFG segment 1 memory violation (PUC)"; + case SYSRSTIV_MPUSEG2IFG: + return "MPUSEG2IFG segment 2 memory violation (PUC)"; + case SYSRSTIV_MPUSEG3IFG: + return "MPUSEG3IFG segment 3 memory violation (PUC)"; + default: + return "Unknown"; } } /** * @brief Initializes the gpios. */ -void initializeGpios(WatchdogStateDetails* details) +void initializeGpios(WatchdogStateDetails *details) { DEBUG_LOG_NULL_CHECK_RETURN(details, "Parameter is NULL", /* nothing, b/c void return */); detailsPtr = details; - //######################################################################## - // P1 configuration. - //######################################################################## + // ######################################################################## + // P1 configuration. + // ######################################################################## #if PORT1_ENABLED // Start with all as GPIO output (which is the recommended default config for unused pins) P1DIR = 0xFFu; @@ -87,7 +109,6 @@ void initializeGpios(WatchdogStateDetails* details) // Used when the Radio wants to send information to the Watchdog. P1DIR &= ~BIT3; - // P1.4 is connected to the V_LANDER_SENS signal (output of voltage divider for measuring lander voltage being // supplied to us), and is used as an ADC analog input (specifically it is ADC analog input A4). This is the // tertiary function (SEL1 and SEL0 are 1). @@ -113,9 +134,9 @@ void initializeGpios(WatchdogStateDetails* details) P1SEL1 |= BIT7; #endif // PORT1_ENABLED - //######################################################################## - // P2 configuration. - //######################################################################## + // ######################################################################## + // P2 configuration. + // ######################################################################## #if PORT2_ENABLED // Start with all as GPIO input. Unused pins are supposed to be configured as outputs, but due to current draw // issues with P2.0, we initialize all as inputs so that they are high-z and don't allow current draw. We configure @@ -132,7 +153,7 @@ void initializeGpios(WatchdogStateDetails* details) // // TODO >> Don't set this here, as we see large current draw when this mode is set and Hercules is off. << // - //P2SEL1 |= BIT0; + // P2SEL1 |= BIT0; CLEAR_IPASBI_IN_UINT(detailsPtr->m_inputPinAndStateBits, IPASBI__UART0_INITIALIZED); // P2.1 is used as the UART0 (UCA0) RX data line (RXD). This is the secondary function (SEL1 is 1 and SEL0 is 0). @@ -170,7 +191,7 @@ void initializeGpios(WatchdogStateDetails* details) // TODO >> Don't set this here, as we could see large current draw if this mode is set while disconnected from // lander. << // - //P2SEL1 |= BIT5; + // P2SEL1 |= BIT5; CLEAR_IPASBI_IN_UINT(detailsPtr->m_inputPinAndStateBits, IPASBI__UART1_INITIALIZED); // P2.6 is used as the UART1 (UCA1) RX data line (RXD). This is the secondary function (SEL1 is 1 and SEL0 is 0). @@ -187,9 +208,9 @@ void initializeGpios(WatchdogStateDetails* details) P2REN &= ~BIT7; #endif // PORT2_ENABLED - //######################################################################## - // P3 configuration. - //######################################################################## + // ######################################################################## + // P3 configuration. + // ######################################################################## #if PORT3_ENABLED // Start with all as GPIO output (which is the recommended default config for unused pins) P3DIR = 0xFFu; @@ -248,9 +269,9 @@ void initializeGpios(WatchdogStateDetails* details) CLEAR_OPSBI_IN_UINT(detailsPtr->m_outputPinBits, OPSBI__3V3_EN); #endif // PORT3_ENABLED - //######################################################################## - // P4 configuration. - //######################################################################## + // ######################################################################## + // P4 configuration. + // ######################################################################## #if PORT4_ENABLED // Start with all as GPIO output (which is the recommended default config for unused pins) P4DIR = 0xFFu; @@ -317,9 +338,9 @@ void initializeGpios(WatchdogStateDetails* details) P4REN &= ~BIT7; #endif // PORT4_ENABLED - //######################################################################## - // PJ configuration. - //######################################################################## + // ######################################################################## + // PJ configuration. + // ######################################################################## #if PORTJ_ENABLED // Start with all as GPIO output (which is the recommended default config for unused pins) PJDIR = 0xFFu; @@ -410,7 +431,8 @@ void disableWdIntInterrupt(void) } // Return the *current* state of the WD_INT pin: -uint8_t getWdIntState(void){ +uint8_t getWdIntState(void) +{ return P1IN & BIT3; } @@ -883,7 +905,8 @@ inline void startChargingBatteries(void) { // Turn on batteries before charging if not on yet: // (not safe to start charging on an open circuit) - if(!blimp_batteryState()){ + if (!blimp_batteryState()) + { blimp_battEnOn(); } // Enable the charging regulator: @@ -903,15 +926,18 @@ inline void stopChargingBatteries(void) blimp_regEnOff(); } -#define UPDATE_INPUT(detPtr, ipasbi_enum, port, bit) \ - do { \ - if (port & bit) { \ - SET_IPASBI_IN_UINT(detPtr->m_inputPinAndStateBits, ipasbi_enum); \ - } else { \ - CLEAR_IPASBI_IN_UINT(detPtr->m_inputPinAndStateBits, ipasbi_enum); \ - } \ - } while (0) - +#define UPDATE_INPUT(detPtr, ipasbi_enum, port, bit) \ + do \ + { \ + if (port & bit) \ + { \ + SET_IPASBI_IN_UINT(detPtr->m_inputPinAndStateBits, ipasbi_enum); \ + } \ + else \ + { \ + CLEAR_IPASBI_IN_UINT(detPtr->m_inputPinAndStateBits, ipasbi_enum); \ + } \ + } while (0) void readOnChipInputs(void) { From c8f019e3613b2da847c5e4a6c50b38634f5108d6 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 11:16:53 -0500 Subject: [PATCH 15/39] WD: Validated heater control logic. --- Apps/FlightSoftware/Watchdog/src/drivers/bsp.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c index 70178b520..ea059103c 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c @@ -547,10 +547,13 @@ void clockInit(void) /** * @brief Enables the heater. (HI = ON) - * TB0CCTL2 is register that toggles PWM output on heater pin + * Lets the TB0.2 timer take control (SEL0=1, SEL1=0) + * TB0CCTL2 is register that toggles PWM output on heater pin. + * Per Table 9-23 in https://www.ti.com/lit/ds/symlink/msp430fr5994.pdf. */ inline void enableHeater(void) { + P2DIR |= BIT2; P2OUT &= ~BIT2; P2SEL0 |= BIT2; P2SEL1 &= ~BIT2; @@ -560,6 +563,7 @@ inline void enableHeater(void) /** * @brief Disables the heater. (LO = OFF) + * Sets pin back to GPIO output (SEL0=0, SEL1=0) low (OFF). */ inline void disableHeater(void) { From 2b2938ca22a02b3e7c18904db952a93039a631b0 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 11:28:06 -0500 Subject: [PATCH 16/39] GDS: Fixed div 0 bug introduced in recent Detailed Status Packet changes. --- .../codec/packet_classes/watchdog_detailed_status.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py index a72665108..66d2b6d71 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py @@ -200,6 +200,10 @@ def fused_est_lander_voltage(self) -> float: VLander = self.Adc_LanderVoltage Vcc28 = self.Adc_Vcc28Voltage + # Guard against 0: + if max(abs(VLander), abs(Vcc28)) == 0: + return 0 + # If a significant difference exists (i.e. one sensor is likely faulty)...: if (abs(Vcc28 - VLander) / max(abs(VLander), abs(Vcc28))) > 0.5: # If one of them is significantly greater (50%) than the max From bd885eab8995b7d7caf36dc1f814ab15d7c9abb3 Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Sat, 31 Dec 2022 11:31:51 -0500 Subject: [PATCH 17/39] WD: Typo fix. --- Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c index 5d029debf..4cc798035 100644 --- a/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c +++ b/Apps/FlightSoftware/Watchdog/src/comms/ground_msgs.c @@ -44,7 +44,7 @@ GroundMsgs__Status GroundMsgs__generateFlightEarthHeartbeat(I2C_Sensors__Reading // Also, note, this is mostly meaningless in KA since the battery is // disconnected anyway, so we won't be able to read it. hb->battery_voltage_good = (adcValues->vBattSense > 2480) ? 1 : 0; - hb->battRT = (uint8_t)(adcValues->battRT >> 4); + hb->battTemp = (uint8_t)(adcValues->battRT >> 4); return GND_MSGS__STATUS__SUCCESS; } From 3cfccb7da4155ad7e24edc79042813be64f54680 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 11:48:51 -0500 Subject: [PATCH 18/39] GDS: Fixed thermistor conversion bug in HB. --- .../packet_classes/watchdog_detailed_status.py | 7 ++++--- .../codec/packet_classes/watchdog_heartbeat.py | 16 +++++++++------- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py index 66d2b6d71..d972dd419 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py @@ -480,11 +480,12 @@ def Adc_BatteryChargingTempUncertaintyKelvin(self) -> float: # ! TODO: (pull from BACK HAL code + supporting samsung notes) return 0.0 - def battery_adc_reading_to_kelvin(self, adc_reading) -> float: + @classmethod + def battery_adc_reading_to_kelvin(cls, adc_reading) -> float: return float(np.interp( float(adc_reading), - self.BATT_5K_THERMISTOR_LOOKUP_TABLE['adc'][::-1], - self.BATT_5K_THERMISTOR_LOOKUP_TABLE['degC'][::-1] + cls.BATT_5K_THERMISTOR_LOOKUP_TABLE['adc'][::-1], + cls.BATT_5K_THERMISTOR_LOOKUP_TABLE['degC'][::-1] )) + 273.15 @property diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py index 4bd1b0335..9953893ec 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_heartbeat.py @@ -4,7 +4,7 @@ important Watchdog statuses during cis-lunar transit. @author: Connor W. Colombo (CMU) -@last-updated: 05/01/2022 +@last-updated: 12/31/2022 """ from __future__ import annotations # Activate postponed annotations (for using classes as return type in their own methods) @@ -20,6 +20,9 @@ from ..settings import ENDIANNESS_CODE from ..exceptions import PacketDecodingException +# Borrow conversions from Detailed status: +from .watchdog_detailed_status import WatchdogDetailedStatusPacketInterface + from IrisBackendv3.data_standards.module import Module @@ -62,7 +65,7 @@ class CustomPayload(): _BatteryVoltageOk: bool _BattAdcTempRaw: int - @ staticmethod + @staticmethod def despan(span: int, num_bits: int, min_val: float, @@ -112,7 +115,7 @@ def despan(span: int, return (span-span_min)/(span_max-span_min) * (max_val-min_val) + min_val - @ staticmethod + @staticmethod def span(val: float, num_bits: int, min_val: float, @@ -179,8 +182,7 @@ def CurrentMilliamps(self) -> float: @property def BattAdcTempKelvin(self) -> float: - # ! TODO: This is wrong. - return self.despan(self._BattAdcTempRaw, 8, 75, -12.31, span_max=233) + return WatchdogDetailedStatusPacketInterface.CustomPayload.battery_adc_reading_to_kelvin(self._BattAdcTempRaw) # Make public get, private set to signal that you can freely use these values # but modifying them directly can yield undefined behavior (specifically @@ -236,7 +238,7 @@ class WatchdogHeartbeatPacket(WHB_PI[WHB_PI, WHB_CP]): def __repr__(self) -> str: return self.custom_payload.__repr__() - @ classmethod + @classmethod def decode(cls, data: bytes, endianness_code: str = ENDIANNESS_CODE @@ -266,7 +268,7 @@ def encode(self, **kwargs: Any) -> bytes: #!! TODO: IS NECESSARY FOR IPC (OR JUST ENCODE THAT STUFF IN A STATE) <- Not with new `Packet`-specific `__reduce__` strategy raise NotImplementedError() - @ classmethod + @classmethod def is_valid(cls, data: bytes, endianness_code: str = ENDIANNESS_CODE) -> bool: """ Determines whether the given bytes constitute a valid packet of this type. From d125ddcc4f59b103a03754cb38a4ff8f73a6e3f7 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 20:35:28 -0500 Subject: [PATCH 19/39] WD: Heater control logic debounced. --- Apps/FlightSoftware/Watchdog/src/drivers/bsp.c | 6 ++++++ .../Watchdog/src/stateMachine/RoverStateBase.cpp | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c index ea059103c..b59def7cc 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c @@ -553,6 +553,12 @@ void clockInit(void) */ inline void enableHeater(void) { + // For safety against some register having been bitflipped, just reaffirm + // all heater (P2.2) related settings when turning on: + TB0CCR0 = detailsPtr->hParams->m_heaterDutyCyclePeriod - 1; + TB0CCTL2 = OUTMOD_7; + TB0CCR2 = detailsPtr->hParams->m_heaterDutyCycle; + TB0CTL |= MC__UP; P2DIR |= BIT2; P2OUT &= ~BIT2; P2SEL0 |= BIT2; diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index db8a3999c..08c87b29c 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -257,13 +257,13 @@ namespace iris unsigned short thermReading = theContext.m_adcValues.battRT; HeaterParams &hParams = theContext.m_details.m_hParams; - if (thermReading > hParams.m_heaterOnVal) + if (!m_hParams.m_heating && thermReading > hParams.m_heaterOnVal) { // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a // configured (either via the default value or a value commanded from ground) ADC reading. enableHeater(); } - else if (thermReading < hParams.m_heaterOffVal) + else if (m_hParams.m_heating && thermReading < hParams.m_heaterOffVal) { // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a // configured (either via the default value or a value commanded from ground) ADC reading. From 8385965c3f1e3a7d767463fa797683d156764a35 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 20:58:08 -0500 Subject: [PATCH 20/39] WD: Applied linter. --- .../include/stateMachine/RoverStateBase.hpp | 474 +++++++++--------- 1 file changed, 237 insertions(+), 237 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp b/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp index 8083bed00..ad96fe60e 100644 --- a/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp +++ b/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp @@ -11,251 +11,251 @@ namespace iris { class RoverStateBase { - public: - explicit RoverStateBase(RoverState state); + public: + explicit RoverStateBase(RoverState state); - RoverState getState(); + RoverState getState(); - virtual bool canEnterLowPowerMode(RoverContext& theContext); + virtual bool canEnterLowPowerMode(RoverContext &theContext); - // The functions to handle events - virtual RoverState handleLanderData(RoverContext& theContext); - virtual RoverState handleHerculesData(RoverContext& theContext); - virtual RoverState handleHighTemp(RoverContext& theContext); - virtual RoverState handleWdIntRisingEdge(RoverContext& theContext); - virtual RoverState handleWdIntFallingEdge(RoverContext& theContext); + // The functions to handle events + virtual RoverState handleLanderData(RoverContext &theContext); + virtual RoverState handleHerculesData(RoverContext &theContext); + virtual RoverState handleHighTemp(RoverContext &theContext); + virtual RoverState handleWdIntRisingEdge(RoverContext &theContext); + virtual RoverState handleWdIntFallingEdge(RoverContext &theContext); - virtual RoverState handleTimerTick(RoverContext& theContext) = 0; - virtual RoverState handlePowerIssue(RoverContext& theContext) = 0; - virtual RoverState spinOnce(RoverContext& theContext) = 0; + virtual RoverState handleTimerTick(RoverContext &theContext) = 0; + virtual RoverState handlePowerIssue(RoverContext &theContext) = 0; + virtual RoverState spinOnce(RoverContext &theContext) = 0; - virtual RoverState transitionTo(RoverContext& theContext) = 0; + virtual RoverState transitionTo(RoverContext &theContext) = 0; - virtual void enableHerculesComms(RoverContext& theContext); + virtual void enableHerculesComms(RoverContext &theContext); - static void herculesMsgCallback(HercMsgs__Header* header, - uint8_t* payloadBuffer, - size_t payloadSize, - void* userArg); + static void herculesMsgCallback(HercMsgs__Header *header, + uint8_t *payloadBuffer, + size_t payloadSize, + void *userArg); - static void landerMsgCallback(uint8_t* rxDataBuffer, size_t rxDataLen, void* userArg); - - protected: - virtual LanderComms__Status txDownlinkData(RoverContext& theContext, void* data, size_t dataSize, - bool fromHercules=false); - - virtual RoverState handleWdIntEdge(bool rising, RoverContext& theContext); - - virtual void initiateNextI2cAction(RoverContext& theContext); - - virtual void heaterControl(RoverContext& theContext); - - virtual RoverState performWatchdogCommand(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState performResetCommand(RoverContext& theContext, - WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response) = 0; - - virtual RoverState handleUplinkFromLander(RoverContext& theContext, - uint8_t* rxDataBuffer, - size_t rxDataLen); - - virtual RoverState handleStrokeFromHercules(RoverContext& theContext, - HercMsgs__Header* header); - - virtual RoverState handleDownlinkFromHercules(RoverContext& theContext, - HercMsgs__Header* header, - uint8_t* payloadBuffer, - size_t payloadSize); - - virtual RoverState handleDebugFromHercules(RoverContext& theContext, - HercMsgs__Header* header, - uint8_t* payloadBuffer, - size_t payloadSize); - - virtual RoverState handleResetFromHercules(RoverContext& theContext, - HercMsgs__Header* header); - - virtual RoverState pumpMsgsFromLander(RoverContext& theContext); - - virtual RoverState pumpMsgsFromHercules(RoverContext& theContext); - - void sendLanderResponse(RoverContext& theContext, WdCmdMsgs__Response& response); - - // Specific watchdog command handling - virtual RoverState doGndCmdResetSpecific(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdPrepForDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdDeploy(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSwitchConnMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetDebugCommsState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetAutoHeaterOnValue(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetAutoHeaterOffValue(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetHeaterDutyCycle(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetHeaterDutyCyclePeriod(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetVSAEState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdEnterSleepMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdEnterKeepAliveMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdEnterServiceMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdDangForceBattState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetChargeEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetChargeRegEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetBattEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetBattCtrlEnState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdSetLatchBattState(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdLatchSetPulseLow(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdLatchResetPulseLow(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdClearResetMemory(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdEcho(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual RoverState doGndCmdRequestDetailedReport(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse); - - virtual void echoToLander(RoverContext& theContext, uint8_t numBytesToEcho, const uint8_t* bytesToEcho); - - virtual void sendDetailedReportToLander(RoverContext& theContext); - - // Specific reset command handling - void doConditionalResetSpecific(RoverContext& theContext, - WdCmdMsgs__ResetSpecificId resetValue, - WdCmdMsgs__Response* response, - bool allowPowerOn, - bool allowDisableRs422, - bool allowDeploy, - bool allowUndeploy, - bool& needToWriteIoExpander); - - - virtual RoverState handleRadioPowerCycleRadioCommand(RoverContext& theContext); - virtual RoverState handleRadioPowerCycleHerculesCommand(RoverContext& theContext); - virtual RoverState handleRadioExitStasisCommand(RoverContext& theContext); - virtual RoverState handleRadioEnterStasisCommand(RoverContext& theContext); - virtual RoverState handleRadioGotWifiCommand(RoverContext& theContext); - private: - RoverState m_state; - - RoverState m_pumpMsgsFromLanderReturnState; - RoverState m_pumpMsgsFromHerculesReturnState; + static void landerMsgCallback(uint8_t *rxDataBuffer, size_t rxDataLen, void *userArg); + + protected: + virtual LanderComms__Status txDownlinkData(RoverContext &theContext, void *data, size_t dataSize, + bool fromHercules = false); + + virtual RoverState handleWdIntEdge(bool rising, RoverContext &theContext); + + virtual void initiateNextI2cAction(RoverContext &theContext); + + virtual void heaterControl(RoverContext &theContext); + + virtual RoverState performWatchdogCommand(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState performResetCommand(RoverContext &theContext, + WdCmdMsgs__ResetSpecificId resetValue, + WdCmdMsgs__Response *response) = 0; + + virtual RoverState handleUplinkFromLander(RoverContext &theContext, + uint8_t *rxDataBuffer, + size_t rxDataLen); + + virtual RoverState handleStrokeFromHercules(RoverContext &theContext, + HercMsgs__Header *header); + + virtual RoverState handleDownlinkFromHercules(RoverContext &theContext, + HercMsgs__Header *header, + uint8_t *payloadBuffer, + size_t payloadSize); + + virtual RoverState handleDebugFromHercules(RoverContext &theContext, + HercMsgs__Header *header, + uint8_t *payloadBuffer, + size_t payloadSize); + + virtual RoverState handleResetFromHercules(RoverContext &theContext, + HercMsgs__Header *header); + + virtual RoverState pumpMsgsFromLander(RoverContext &theContext); + + virtual RoverState pumpMsgsFromHercules(RoverContext &theContext); + + void sendLanderResponse(RoverContext &theContext, WdCmdMsgs__Response &response); + + // Specific watchdog command handling + virtual RoverState doGndCmdResetSpecific(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdPrepForDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdDeploy(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSwitchConnMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetDebugCommsState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetAutoHeaterOnValue(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetAutoHeaterOffValue(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetHeaterDutyCycle(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetHeaterDutyCyclePeriod(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetVSAEState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdEnterSleepMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdEnterKeepAliveMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdEnterServiceMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdDangForceBattState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetChargeEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetChargeRegEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetBattEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetBattCtrlEnState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdSetLatchBattState(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdLatchSetPulseLow(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdLatchResetPulseLow(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdClearResetMemory(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdEcho(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual RoverState doGndCmdRequestDetailedReport(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse); + + virtual void echoToLander(RoverContext &theContext, uint8_t numBytesToEcho, const uint8_t *bytesToEcho); + + virtual void sendDetailedReportToLander(RoverContext &theContext); + + // Specific reset command handling + void doConditionalResetSpecific(RoverContext &theContext, + WdCmdMsgs__ResetSpecificId resetValue, + WdCmdMsgs__Response *response, + bool allowPowerOn, + bool allowDisableRs422, + bool allowDeploy, + bool allowUndeploy, + bool &needToWriteIoExpander); + + virtual RoverState handleRadioPowerCycleRadioCommand(RoverContext &theContext); + virtual RoverState handleRadioPowerCycleHerculesCommand(RoverContext &theContext); + virtual RoverState handleRadioExitStasisCommand(RoverContext &theContext); + virtual RoverState handleRadioEnterStasisCommand(RoverContext &theContext); + virtual RoverState handleRadioGotWifiCommand(RoverContext &theContext); + + private: + RoverState m_state; + + RoverState m_pumpMsgsFromLanderReturnState; + RoverState m_pumpMsgsFromHerculesReturnState; }; } From efe301d7ec5ab845c6499ee467a891ffe8077e94 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 20:59:34 -0500 Subject: [PATCH 21/39] WD: Applied linter. --- .../src/stateMachine/RoverStateKeepAlive.cpp | 67 +++++++++++-------- 1 file changed, 40 insertions(+), 27 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp index 4b2112d0b..f61f046c3 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp @@ -17,22 +17,23 @@ namespace iris { } - bool RoverStateKeepAlive::canEnterLowPowerMode(RoverContext& theContext) + bool RoverStateKeepAlive::canEnterLowPowerMode(RoverContext &theContext) { // Handling lander data and timer ticks will both wake us up out of LPM, so it's ok for us to enter it. return !(theContext.m_i2cActive); } - RoverState RoverStateKeepAlive::handleHerculesData(RoverContext& /*theContext*/) + RoverState RoverStateKeepAlive::handleHerculesData(RoverContext & /*theContext*/) { assert(!"Got hercules data event in KeepAlive, which shouldn't be possible"); return getState(); } - RoverState RoverStateKeepAlive::handleTimerTick(RoverContext& theContext) + RoverState RoverStateKeepAlive::handleTimerTick(RoverContext &theContext) { // Trigger a new ADC sample if the previous one is done - if (isAdcSampleDone()) { + if (isAdcSampleDone()) + { adcCheckVoltageLevels(&(theContext.m_adcValues)); } @@ -42,41 +43,51 @@ namespace iris return getState(); } - RoverState RoverStateKeepAlive::handlePowerIssue(RoverContext& /*theContext*/) + RoverState RoverStateKeepAlive::handlePowerIssue(RoverContext & /*theContext*/) { //!< @todo Implement RoverStateKeepAlive::handlePowerIssue return getState(); } - RoverState RoverStateKeepAlive::spinOnce(RoverContext& theContext) + RoverState RoverStateKeepAlive::spinOnce(RoverContext &theContext) { - if (theContext.m_i2cActive) { + if (theContext.m_i2cActive) + { I2C_Sensors__Action action = {}; uint8_t readValue = 0; I2C_Sensors__Status i2cStatus = I2C_Sensors__getActionStatus(&action, &(theContext.m_i2cReadings), &readValue); - if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) { + if (I2C_SENSORS__STATUS__INCOMPLETE != i2cStatus) + { DEBUG_LOG_CHECK_STATUS(I2C_SENSORS__STATUS__SUCCESS_DONE, i2cStatus, "I2C action failed"); - if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__WRITE_IO_EXPANDER == action) + { theContext.m_watchdogFlags &= ~WDFLAG_WAITING_FOR_IO_EXPANDER_WRITE; } - if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) { + if (I2C_SENSORS__ACTIONS__READ_IO_EXPANDER == action) + { bool chargeStat2 = (readValue & I2C_SENSORS__IOE_P1_BIT__CHARGE_STAT2 != 0); bool latchStat = (readValue & I2C_SENSORS__IOE_P1_BIT__LATCH_STAT != 0); - if (chargeStat2) { + if (chargeStat2) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__CHARGE_STAT2); } - if (latchStat) { + if (latchStat) + { SET_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); - } else { + } + else + { CLEAR_IPASBI_IN_UINT(theContext.m_details.m_inputPinAndStateBits, IPASBI__LATCH_STAT); } } @@ -89,12 +100,14 @@ namespace iris uint16_t currentTime = Time__getTimeInCentiseconds(); if (SEND_DETAILED_REPORTS_IN_SPIN_ONCE && - (currentTime - theContext.m_lastDetailedReportSendTime >= CENTISECONDS_BETWEEN_DETAILED_REPORT_SENDS)) { + (currentTime - theContext.m_lastDetailedReportSendTime >= CENTISECONDS_BETWEEN_DETAILED_REPORT_SENDS)) + { theContext.m_lastDetailedReportSendTime = currentTime; sendDetailedReportToLander(theContext); } - if (theContext.m_sendDetailedReport) { + if (theContext.m_sendDetailedReport) + { theContext.m_sendDetailedReport = false; sendDetailedReportToLander(theContext); } @@ -102,7 +115,7 @@ namespace iris return getState(); } - RoverState RoverStateKeepAlive::transitionTo(RoverContext& theContext) + RoverState RoverStateKeepAlive::transitionTo(RoverContext &theContext) { // Nothing to do on this transition, which should always be from ENTERING_KEEP_ALIVE. @@ -129,11 +142,11 @@ namespace iris return getState(); } - RoverState RoverStateKeepAlive::doGndCmdEnterKeepAliveMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateKeepAlive::doGndCmdEnterKeepAliveMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { // We're already in keep alive mode, but we can still re-transition into keep alive // once we receive this command. @@ -141,11 +154,11 @@ namespace iris return RoverState::ENTERING_KEEP_ALIVE; } - RoverState RoverStateKeepAlive::doGndCmdEnterServiceMode(RoverContext& theContext, - const WdCmdMsgs__Message& msg, - WdCmdMsgs__Response& response, - WdCmdMsgs__Response& deployNotificationResponse, - bool& sendDeployNotificationResponse) + RoverState RoverStateKeepAlive::doGndCmdEnterServiceMode(RoverContext &theContext, + const WdCmdMsgs__Message &msg, + WdCmdMsgs__Response &response, + WdCmdMsgs__Response &deployNotificationResponse, + bool &sendDeployNotificationResponse) { /* Can transition directly to service mode from keepalive */ response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; From 52cbe38990cac60d4b14c2eb0a195565483fad84 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sat, 31 Dec 2022 21:01:07 -0500 Subject: [PATCH 22/39] WD: Manual report requests also send KA HBs now (for completeness). --- .../include/stateMachine/RoverStateBase.hpp | 2 +- .../src/stateMachine/RoverStateBase.cpp | 26 +++++++++++++++++-- .../src/stateMachine/RoverStateKeepAlive.cpp | 2 +- .../src/stateMachine/RoverStateMission.cpp | 2 +- .../src/stateMachine/RoverStateService.cpp | 2 +- 5 files changed, 28 insertions(+), 6 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp b/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp index ad96fe60e..9e9b1b4f6 100644 --- a/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp +++ b/Apps/FlightSoftware/Watchdog/include/stateMachine/RoverStateBase.hpp @@ -233,7 +233,7 @@ namespace iris virtual void echoToLander(RoverContext &theContext, uint8_t numBytesToEcho, const uint8_t *bytesToEcho); - virtual void sendDetailedReportToLander(RoverContext &theContext); + virtual void sendDetailedReportToLander(RoverContext &theContext, bool alsoSendHeartbeats = false); // Specific reset command handling void doConditionalResetSpecific(RoverContext &theContext, diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 08c87b29c..5006a59a6 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -632,7 +632,7 @@ namespace iris sendDeployNotificationResponse); case WD_CMD_MSGS__CMD_ID__REQUEST_DETAILED_REPORT: - /* Enter service mode */ + /* Make sure magic is valid: */ if (msg.body.reqDetReport.magic != WD_CMD_MSGS__CONFIRM_REQ_DET_REPORT_MAGIC_NUMBER) { /* magic bad */ @@ -1367,7 +1367,7 @@ namespace iris } } - void RoverStateBase::sendDetailedReportToLander(RoverContext &theContext) + void RoverStateBase::sendDetailedReportToLander(RoverContext &theContext, bool alsoSendHeartbeats) { /* send detailed report */ static DetailedReport report = {0}; @@ -1391,6 +1391,28 @@ namespace iris //!< @todo Handling? } + if (alsoSendHeartbeats) + { + static FlightEarthHeartbeat hb = {0}; + GroundMsgs__Status gcStatus = + GroundMsgs__generateFlightEarthHeartbeat(&(theContext.m_i2cReadings), + &(theContext.m_adcValues), + &(theContext.m_details.m_hParams), + &hb); + + assert(GND_MSGS__STATUS__SUCCESS == gcStatus); + + LanderComms__Status lcHbStatus = txDownlinkData(theContext, + (uint8_t *)&hb, + sizeof(hb)); + + assert(LANDER_COMMS__STATUS__SUCCESS == lcHbStatus); + if (LANDER_COMMS__STATUS__SUCCESS != lcHbStatus) + { + //!< @todo Handling? + } + } + #if DEBUG_REPORT DebugComms_printfToLander("\n"); DebugComms__printDataAsHexToLander((uint8_t *)&report, sizeof(DetailedReport), FALSE); diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp index f61f046c3..ad5661a15 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateKeepAlive.cpp @@ -109,7 +109,7 @@ namespace iris if (theContext.m_sendDetailedReport) { theContext.m_sendDetailedReport = false; - sendDetailedReportToLander(theContext); + sendDetailedReportToLander(theContext, true); } return getState(); diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp index 9ce428f18..47a424ccd 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateMission.cpp @@ -194,7 +194,7 @@ namespace iris { theContext.m_sendDetailedReport = false; - sendDetailedReportToLander(theContext); + sendDetailedReportToLander(theContext, true); } return getState(); diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp index 8e4b858a7..4c890a09b 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateService.cpp @@ -180,7 +180,7 @@ namespace iris if (theContext.m_sendDetailedReport) { theContext.m_sendDetailedReport = false; - sendDetailedReportToLander(theContext); + sendDetailedReportToLander(theContext, true); } return getState(); From 0ca9ae758a529baa7e5e214a439601301b646263 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 01:12:07 -0500 Subject: [PATCH 23/39] WD+GDS: Added Detailed Ack to ResetSpecific Commands. --- .../src/stateMachine/RoverStateBase.cpp | 7 + Apps/GroundSoftware/.vscode/settings.json | 3 + .../IrisBackendv3/codec/packet.py | 1 + .../codec/packet_classes/__init__.py | 1 + .../packet_classes/watchdog_radio_debug.py | 7 +- .../watchdog_reset_specific_ack.py | 211 ++++++++++++++++++ 6 files changed, 227 insertions(+), 3 deletions(-) create mode 100644 Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 5006a59a6..cd849ca1f 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -1804,6 +1804,13 @@ namespace iris // of communicating something didn't work } } + + // Report what we did (and under what conditions): + uint8_t resetConditions = allowPowerOn; + resetConditions = (resetConditions << 1) & allowDisableRs422; + resetConditions = (resetConditions << 1) & allowDeploy; + resetConditions = (resetConditions << 1) & allowUndeploy; + DebugComms__tryPrintfToLanderNonblocking("RESET:%u -> %u with 0x%02x\n", resetValue, response->statusCode, resetConditions); } } // End namespace iris diff --git a/Apps/GroundSoftware/.vscode/settings.json b/Apps/GroundSoftware/.vscode/settings.json index 12bc323c2..0616f66b8 100644 --- a/Apps/GroundSoftware/.vscode/settings.json +++ b/Apps/GroundSoftware/.vscode/settings.json @@ -67,9 +67,12 @@ "d", "dataframe", "dataframes", + "DATASTANDARD", "datastandards", "datastream", "Dataview", + "DEBUGBGP", + "DEBUGRESET", "deser", "deserialization", "dgram", diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet.py index 848bba0ff..e76fb4748 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet.py @@ -50,6 +50,7 @@ def parse_packet( RadioBgApiPacket, RadioUartBytePacket, RadioDirectMessagePacket, + WatchdogResetSpecificAckPacket, WatchdogHelloPacket, WatchdogRadioDebugPacket, WatchdogDebugImportantPacket, diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/__init__.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/__init__.py index 18d8343c8..4b87f9cdc 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/__init__.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/__init__.py @@ -25,3 +25,4 @@ from .watchdog_hello import * from .watchdog_radio_debug import * from .watchdog_debug_important import * +from .watchdog_reset_specific_ack import * diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_radio_debug.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_radio_debug.py index bffb3bafb..5b618662f 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_radio_debug.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_radio_debug.py @@ -9,7 +9,8 @@ """ from __future__ import annotations -from prompt_toolkit import formatted_text # Activate postponed annotations (for using classes as return type in their own methods) +# Activate postponed annotations (for using classes as return type in their own methods) +from prompt_toolkit import formatted_text from .packet import Packet, CT @@ -56,8 +57,8 @@ def __init__(self, if payloads is None: # Except possibly in future subclasses, this should normally be - # empty for an `WatchdogDebugPacket`. `payloads` needs to stay as - # an `__init__` arg to avoid violating the Liskov substitution + # empty for an `WatchdogRadioDebugPacket`. `payloads` needs to stay + # as an `__init__` arg to avoid violating the Liskov substitution # principle. payloads = EnhancedPayloadCollection() diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py new file mode 100644 index 000000000..03567c5be --- /dev/null +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py @@ -0,0 +1,211 @@ +""" +Defines `WatchdogResetSpecificAckPacket`, a `Packet` wrapper for a debug string +acknowledging a reset specific command and providing info about what occurred. +This packet type doesn't contain any telemetry (for now, should get converted +to a `EventPayload` eventually) and is just printed to the console. + +# ! TODO: (WORKING-HERE): Add result field to GSW and FSW then test. + COLOR + +@author: Connor W. Colombo (CMU) +@last-updated: 01/01/2023 +""" +from __future__ import annotations + +# Activate postponed annotations (for using classes as return type in their own methods) +from prompt_toolkit import formatted_text + +from .packet import Packet, CT + +from typing import List, Any, Optional + +from scapy.utils import hexdump # type: ignore +from termcolor import colored + +from ..payload_collection import EnhancedPayloadCollection + +from ..settings import ENDIANNESS_CODE +from ..settings import settings as CodecSettings +from ..logging import logger +from ..exceptions import PacketDecodingException + +# Fixed prefix. All `RadioBgApiPacket`s start with b'DEBUG' then `RESET:`. +# Note the b'DEBUG' prefix is there b/c this is sent from the Watchdog using +# the debug messaging system. +FIXED_PREFIX: bytes = b'DEBUGRESET:' + + +class WatchdogResetSpecificAckPacketInterface(Packet[CT]): + # empty __slots__ preserves parent class __slots__ + __slots__: List[str] = [] + + +class WatchdogResetSpecificAckPacket(WatchdogResetSpecificAckPacketInterface[WatchdogResetSpecificAckPacketInterface]): + """ + Creates a data-structure to allow storing and handling a reset specific ack. + + @author: Connor W. Colombo (CMU) + @last-updated: 01/01/2023 + """ + __slots__: List[str] = [ + '_resetId', + '_resultStatusCode', + '_allowPowerOn', + '_allowDisableRs422', + '_allowDeploy', + '_allowUndeploy' + ] + + _resetId: int + _resultStatusCode: int + _allowPowerOn: bool + _allowDisableRs422: bool + _allowDeploy: bool + _allowUndeploy: bool + + def __init__(self, + payloads: Optional[EnhancedPayloadCollection] = None, + raw: Optional[bytes] = None, + endianness_code: str = ENDIANNESS_CODE + ) -> None: + + if raw is None and (payloads is None or payloads.is_empty()): + # If both `payloads` and `raw` are `None`, what even caused + # this to be generated? + logger.debug( + "A `WatchdogResetSpecificAckPacket` was constructed with no " + "`payloads` and no `raw` data. This suggests it's being " + "created from nothing as a completely empty packet. Was this " + "intentional or is this a bug?" + ) + + if payloads is None: + # Except possibly in future subclasses, this should normally be + # empty for an `WatchdogResetSpecificAckPacket`. `payloads` needs + # to stay as an `__init__` arg to avoid violating the Liskov + # substitution principle. + payloads = EnhancedPayloadCollection() + + super().__init__( + payloads=payloads, + raw=raw, + endianness_code=endianness_code + ) # passthru + + if self._raw is None: + self._raw = self.encode() + + # Strip off fixed prefix: + core_data = self._raw[len(FIXED_PREFIX):] + # Unpack fields from format: "RESET:%u -> %u with 0x%02x\n" + fields = core_data.strip().split(b' ') + bad_formatting = False + if len(fields) != 5: + bad_formatting = True + else: + try: + # Formatting is correct. Extract data: + self._resetId = int(fields[0]) + self._resultStatusCode = int(fields[3]) + resetConditions = int(fields[-1], 16) + self._allowPowerOn = bool(resetConditions & 0b1000) + self._allowDisableRS422 = bool(resetConditions & 0b0100) + self._allowDeploy = bool(resetConditions & 0b0010) + self._allowUndeploy = bool(resetConditions & 0b0001) + except Exception: + bad_formatting = True + if bad_formatting: + # Raise an exception (so this will become an `UnsupportedPacket`): + raise PacketDecodingException( + self._raw, + ( + f"Failed to decode Reset Specific message inside " + f"`WatchdogResetSpecificAckPacket` with data " + f"`{hexdump(raw, dump=True)}` because the formatting did " + f"not match expectations." + ) + ) + + @property + def resetFieldName(self) -> str: + if self._resetId == 0: + return 'NONE' + elif not self._resetId: + return 'BAD' + else: + try: + module = CodecSettings['STANDARDS'].modules['WatchDogInterface'] + command = module.commands['ResetSpecific'] + arg = command.args[0] + name = arg.get_enum_name(self._resetId) + return str(name) + except Exception: + return 'NOT-FOUND' + + @property + def resetResult(self) -> str: + if self._resultStatusCode == 0: + return 'NO_ERROR' + elif not self._resultStatusCode: + return 'BAD' + else: + try: + module = CodecSettings['STANDARDS'].modules['WatchdogCommandResponse'] + channel = module.telemetry['ErrorFlag'] + name = channel.get_enum_name(self._resultStatusCode) + return str(name) + except Exception: + return 'NOT-FOUND' + + @classmethod + def decode(cls, + data: bytes, + endianness_code: str = ENDIANNESS_CODE + ) -> WatchdogResetSpecificAckPacket: + return cls(raw=data, endianness_code=endianness_code) + + def encode(self, **kwargs: Any) -> bytes: + # There's no encoding to do. It's just raw data. + if self._raw is None: + return b'' + else: + return self._raw + + @classmethod + def build_minimum_packet( + cls, + payloads: EnhancedPayloadCollection, + raw: Optional[bytes], + endianness_code: str + ) -> WatchdogResetSpecificAckPacket: + """ Minimum packet is just the packet. """ + return cls( + payloads=payloads, + raw=raw, + endianness_code=endianness_code + ) + + @classmethod + def is_valid(cls, data: bytes, endianness_code: str = ENDIANNESS_CODE) -> bool: + """Valid if the packet starts with `FIXED_PREFIX`.""" + return data[:len(FIXED_PREFIX)] == FIXED_PREFIX + + def __repr__(self) -> str: + if self._raw is None or len(self._raw) < len(FIXED_PREFIX): + msg = '' + else: + msg = self._raw.decode().strip() + return ( + colored(f" {msg} ", 'black', 'on_grey', ['bold']) + + colored(f": {self.resetFieldName} -> {self.resetResult}", 'grey', attrs=['bold']) + + colored( + f", allowing\t " + f"(PowerOn: {'✓' if self._allowPowerOn else '𐄂'},\t " + f"Rs422Off: {'✓' if self._allowDisableRs422 else '𐄂'},\t " + f"Deploy: {'✓' if self._allowDisableRs422 else '𐄂'},\t " + f"Undeploy: {'✓' if self._allowDisableRs422 else '𐄂'}).", + 'grey' + ) + ) + + def __str__(self) -> str: + return self.__repr__() From 9337be2cb9e0764ff3cb309386e31328d36f133b Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Sun, 1 Jan 2023 01:18:58 -0500 Subject: [PATCH 24/39] WD: Typo fix so heater debounding compiles. --- Apps/FlightSoftware/Watchdog/src/drivers/bsp.c | 4 ++-- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c index b59def7cc..02ee63d7b 100644 --- a/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c +++ b/Apps/FlightSoftware/Watchdog/src/drivers/bsp.c @@ -555,9 +555,9 @@ inline void enableHeater(void) { // For safety against some register having been bitflipped, just reaffirm // all heater (P2.2) related settings when turning on: - TB0CCR0 = detailsPtr->hParams->m_heaterDutyCyclePeriod - 1; + TB0CCR0 = detailsPtr->m_hParams.m_heaterDutyCyclePeriod - 1; TB0CCTL2 = OUTMOD_7; - TB0CCR2 = detailsPtr->hParams->m_heaterDutyCycle; + TB0CCR2 = detailsPtr->m_hParams.m_heaterDutyCycle; TB0CTL |= MC__UP; P2DIR |= BIT2; P2OUT &= ~BIT2; diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index cd849ca1f..d3f80502c 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -257,13 +257,13 @@ namespace iris unsigned short thermReading = theContext.m_adcValues.battRT; HeaterParams &hParams = theContext.m_details.m_hParams; - if (!m_hParams.m_heating && thermReading > hParams.m_heaterOnVal) + if (!hParams.m_heating && thermReading > hParams.m_heaterOnVal) { // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a // configured (either via the default value or a value commanded from ground) ADC reading. enableHeater(); } - else if (m_hParams.m_heating && thermReading < hParams.m_heaterOffVal) + else if (hParams.m_heating && thermReading < hParams.m_heaterOffVal) { // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a // configured (either via the default value or a value commanded from ground) ADC reading. From 53919064990becb571d7cbf6febc087b659dd2cf Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 01:31:07 -0500 Subject: [PATCH 25/39] WD: RESET Ack formatting fix (untested). --- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index d3f80502c..d992f1abc 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -1806,11 +1806,11 @@ namespace iris } // Report what we did (and under what conditions): - uint8_t resetConditions = allowPowerOn; + uint16_t resetConditions = allowPowerOn; resetConditions = (resetConditions << 1) & allowDisableRs422; resetConditions = (resetConditions << 1) & allowDeploy; resetConditions = (resetConditions << 1) & allowUndeploy; - DebugComms__tryPrintfToLanderNonblocking("RESET:%u -> %u with 0x%02x\n", resetValue, response->statusCode, resetConditions); + DebugComms__tryPrintfToLanderNonblocking("RESET:%l -> %l with 0x%x\n", uint16_t(resetValue), response->statusCode, resetConditions); } } // End namespace iris From 15ee17df700729fbd9f3c33afe0fa6aee9a58e4a Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Sun, 1 Jan 2023 01:37:54 -0500 Subject: [PATCH 26/39] WD: RESET Ack formatting fix. --- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index d992f1abc..55102f1bf 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -1810,7 +1810,8 @@ namespace iris resetConditions = (resetConditions << 1) & allowDisableRs422; resetConditions = (resetConditions << 1) & allowDeploy; resetConditions = (resetConditions << 1) & allowUndeploy; - DebugComms__tryPrintfToLanderNonblocking("RESET:%l -> %l with 0x%x\n", uint16_t(resetValue), response->statusCode, resetConditions); + DebugComms__tryPrintfToLanderNonblocking("RESET:%d -> %d with 0x%x\n", int(resetValue), int(response->statusCode), resetConditions); } -} // End namespace iris +} // End namespace iris // configured (either via the default value or a value commanded from ground) ADC reading. + From ebd04036ab3596f010a248136692d98f0554b812 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 02:02:21 -0500 Subject: [PATCH 27/39] GDS: Fixed RESET Specific Ack parsing. --- .../watchdog_reset_specific_ack.py | 33 ++++++++++--------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py index 03567c5be..2b6c72a00 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py @@ -4,8 +4,6 @@ This packet type doesn't contain any telemetry (for now, should get converted to a `EventPayload` eventually) and is just printed to the console. -# ! TODO: (WORKING-HERE): Add result field to GSW and FSW then test. + COLOR - @author: Connor W. Colombo (CMU) @last-updated: 01/01/2023 """ @@ -50,7 +48,7 @@ class WatchdogResetSpecificAckPacket(WatchdogResetSpecificAckPacketInterface[Wat '_resetId', '_resultStatusCode', '_allowPowerOn', - '_allowDisableRs422', + '_allowDisableRS422', '_allowDeploy', '_allowUndeploy' ] @@ -58,7 +56,7 @@ class WatchdogResetSpecificAckPacket(WatchdogResetSpecificAckPacketInterface[Wat _resetId: int _resultStatusCode: int _allowPowerOn: bool - _allowDisableRs422: bool + _allowDisableRS422: bool _allowDeploy: bool _allowUndeploy: bool @@ -96,7 +94,7 @@ def __init__(self, # Strip off fixed prefix: core_data = self._raw[len(FIXED_PREFIX):] - # Unpack fields from format: "RESET:%u -> %u with 0x%02x\n" + # Unpack fields from format: "RESET:%d -> %d with 0x%x\n" fields = core_data.strip().split(b' ') bad_formatting = False if len(fields) != 5: @@ -105,16 +103,19 @@ def __init__(self, try: # Formatting is correct. Extract data: self._resetId = int(fields[0]) - self._resultStatusCode = int(fields[3]) + self._resultStatusCode = int(fields[2]) resetConditions = int(fields[-1], 16) self._allowPowerOn = bool(resetConditions & 0b1000) self._allowDisableRS422 = bool(resetConditions & 0b0100) self._allowDeploy = bool(resetConditions & 0b0010) self._allowUndeploy = bool(resetConditions & 0b0001) - except Exception: + except Exception as e: + print(e) + exit() bad_formatting = True if bad_formatting: # Raise an exception (so this will become an `UnsupportedPacket`): + raise PacketDecodingException( self._raw, ( @@ -134,12 +135,12 @@ def resetFieldName(self) -> str: else: try: module = CodecSettings['STANDARDS'].modules['WatchDogInterface'] - command = module.commands['ResetSpecific'] + command = module.commands['WatchDogInterface_ResetSpecific'] arg = command.args[0] name = arg.get_enum_name(self._resetId) return str(name) except Exception: - return 'NOT-FOUND' + return f'NOT-FOUND ({self._resetId})' @property def resetResult(self) -> str: @@ -154,7 +155,7 @@ def resetResult(self) -> str: name = channel.get_enum_name(self._resultStatusCode) return str(name) except Exception: - return 'NOT-FOUND' + return f'NOT-FOUND ({self._resultStatusCode})' @classmethod def decode(cls, @@ -195,15 +196,15 @@ def __repr__(self) -> str: else: msg = self._raw.decode().strip() return ( - colored(f" {msg} ", 'black', 'on_grey', ['bold']) + - colored(f": {self.resetFieldName} -> {self.resetResult}", 'grey', attrs=['bold']) + + colored(f" {msg} ", 'white', 'on_yellow', ['bold']) + + colored(f": {self.resetFieldName} -> {self.resetResult}", 'yellow', attrs=['bold']) + colored( f", allowing\t " f"(PowerOn: {'✓' if self._allowPowerOn else '𐄂'},\t " - f"Rs422Off: {'✓' if self._allowDisableRs422 else '𐄂'},\t " - f"Deploy: {'✓' if self._allowDisableRs422 else '𐄂'},\t " - f"Undeploy: {'✓' if self._allowDisableRs422 else '𐄂'}).", - 'grey' + f"Rs422Off: {'✓' if self._allowDisableRS422 else '𐄂'},\t " + f"Deploy: {'✓' if self._allowDeploy else '𐄂'},\t " + f"Undeploy: {'✓' if self._allowUndeploy else '𐄂'}).", + 'white' ) ) From 78056a973b9aab6e660bd40378044c1ecc18cfef Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 02:03:51 -0500 Subject: [PATCH 28/39] WD: Removed stray comment. --- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 55102f1bf..b6417281b 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -1813,5 +1813,4 @@ namespace iris DebugComms__tryPrintfToLanderNonblocking("RESET:%d -> %d with 0x%x\n", int(resetValue), int(response->statusCode), resetConditions); } -} // End namespace iris // configured (either via the default value or a value commanded from ground) ADC reading. - +} // End namespace iris From dae191f60b786b2c916c0a68122e7e6efc731d2f Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 02:05:47 -0500 Subject: [PATCH 29/39] GDS: Removed accidentally left in break-test code.{ --- .../codec/packet_classes/watchdog_reset_specific_ack.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py index 2b6c72a00..72255bfe2 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py @@ -110,8 +110,6 @@ def __init__(self, self._allowDeploy = bool(resetConditions & 0b0010) self._allowUndeploy = bool(resetConditions & 0b0001) except Exception as e: - print(e) - exit() bad_formatting = True if bad_formatting: # Raise an exception (so this will become an `UnsupportedPacket`): From 54dfd38433b35b61c3b09cf0806cc33c5bb10e9a Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 03:13:03 -0500 Subject: [PATCH 30/39] WD+GDS: Added power level controls to command_aliases (and tested with scope to confirm they work). --- .../src/stateMachine/RoverStateBase.cpp | 3 +- .../watchdog_reset_specific_ack.py | 1 - Apps/GroundSoftware/__command_aliases.py | 166 +++++++++++++++++- 3 files changed, 164 insertions(+), 6 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index b6417281b..74eda1be3 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -995,7 +995,8 @@ namespace iris bool &sendDeployNotificationResponse) { const uint16_t &newDutyCycle = msg.body.setHeaterDutyCycle.dutyCycle; - if (newDutyCycle <= theContext.m_details.m_hParams.m_heaterDutyCyclePeriod) + // NOTE: TB0CCR0 (max count) is set to m_heaterDutyCyclePeriod-1 (so we need to be < that). + if (newDutyCycle < theContext.m_details.m_hParams.m_heaterDutyCyclePeriod) { TB0CCR2 = newDutyCycle; theContext.m_details.m_hParams.m_heaterDutyCycle = newDutyCycle; diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py index 72255bfe2..26bdf8fa5 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_reset_specific_ack.py @@ -113,7 +113,6 @@ def __init__(self, bad_formatting = True if bad_formatting: # Raise an exception (so this will become an `UnsupportedPacket`): - raise PacketDecodingException( self._raw, ( diff --git a/Apps/GroundSoftware/__command_aliases.py b/Apps/GroundSoftware/__command_aliases.py index c4f7f7dec..ea817bb2c 100644 --- a/Apps/GroundSoftware/__command_aliases.py +++ b/Apps/GroundSoftware/__command_aliases.py @@ -6,7 +6,7 @@ `pyenv exec python datastandards_lookup.py`. Created: 10/29/2021 -Last Update: 11/12/2022 +Last Update: 01/01/2023 """ from __future__ import annotations # Support things like OrderedDict[A,B] from enum import Enum @@ -360,15 +360,173 @@ class Parameter(Enum): OrderedDict(confirm='CONFIRM_REQUEST'), DataPathway.WIRED ), - 'disable-heater-control': ( + 'disable-heater-control-via-herc': ( DataPathway.WIRED, # intentionally telling the WD to tell Herc to tell the WD to enable heater control (same path as deployment command but a quick pretest) + Magic.COMMAND, + 'WatchDogInterface_ResetSpecific', + OrderedDict(reset_value='AUTO_HEATER_CONTROLLER_DISABLE'), + DataPathway.WIRED + ), + 'disable-heater-control': ( + DataPathway.WIRED, Magic.WATCHDOG_COMMAND, 'WatchDogInterface_ResetSpecific', - # Change this to whatever you want to reset. - OrderedDict(reset_value='DISABLE_HEATER_CONTROL'), + OrderedDict(reset_value='AUTO_HEATER_CONTROLLER_DISABLE'), + DataPathway.WIRED + ), + 'enable-heater-control': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_ResetSpecific', + OrderedDict(reset_value='AUTO_HEATER_CONTROLLER_ENABLE'), + DataPathway.WIRED + ), + + # Set the heater's "ON" power level to be 10%: + # NOTE: this is actually setting the TB0CCR2 on counter. + # Percentage Voltage is calculated as DutyCycle/DutyCyclePeriod (TB0CCR0), + # which this assumes is fixed at 10000 (1.25ms). + # Note, b/c P = V^2/R, P/Pmax = (V/Vmax)^2, therefore 10% power = 32% voltage = 3162/10000 + 'set-heater-to-power-10': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=3162), DataPathway.WIRED ), + # Set the heater's "ON" power level to be 20%: + # b/c P/Pmax = (V/Vmax)^2, 20% power = 45% voltage = 4472/10000 + 'set-heater-to-power-20': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=4472), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 25%: + # b/c P/Pmax = (V/Vmax)^2, 25% power = 50% voltage = 5000/10000 + 'set-heater-to-power-25': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=5000), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 30%: + # b/c P/Pmax = (V/Vmax)^2, 30% power = 55% voltage = 5477/10000 + 'set-heater-to-power-30': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=5477), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 40%: + # b/c P/Pmax = (V/Vmax)^2, 40% power = 63% voltage = 6325/10000 + 'set-heater-to-power-40': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=6325), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 50%: + # b/c P/Pmax = (V/Vmax)^2, 50% power = 71% voltage = 7071/10000 + 'set-heater-to-power-50': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=7071), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 60%: + # b/c P/Pmax = (V/Vmax)^2, 60% power = 77% voltage = 7746/10000 + 'set-heater-to-power-60': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=7746), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 70%: + # b/c P/Pmax = (V/Vmax)^2, 70% power = 84% voltage = 8367/10000 + 'set-heater-to-power-70': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=8367), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 75%: + # b/c P/Pmax = (V/Vmax)^2, 75% power = 87% voltage = 8660/10000 + 'set-heater-to-power-75': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=8660), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 80%: + # b/c P/Pmax = (V/Vmax)^2, 80% power = 89% voltage = 8944/10000 + 'set-heater-to-power-80': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=8944), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 90%: + # b/c P/Pmax = (V/Vmax)^2, 90% power = 89% voltage = 9486/10000 + 'set-heater-to-power-90': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=9486), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 95%: + # b/c P/Pmax = (V/Vmax)^2, 95% power = 97% voltage = 9746/10000 + 'set-heater-to-power-95': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + OrderedDict(duty=9746), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 100%: + 'set-heater-to-power-100': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + # DON'T set to the full value of 10000 (since cutoff is 1 less) + OrderedDict(duty=9999), + DataPathway.WIRED + ), + # Set the heater's "ON" power level to be 0% (basically, always off no + # matter what): + 'set-heater-to-power-0': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + # DON'T set to the full value of 10000 (since cutoff is 1 less) + OrderedDict(duty=0), + DataPathway.WIRED + ), + # Set the heater's "ON" power level back to its default (8500 duty, which + # was used during EM3 TVAC). This equates to 72.2% max power or 0.889W at + # 27.80V. + 'set-heater-to-power-default': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetHeaterDutyCycle', + # DON'T set to the full value of 10000 (since cutoff is 1 less) + OrderedDict(duty=8500), + DataPathway.WIRED + ), + + + 'reset-motors': ( DataPathway.WIRED, From 35ffca095f7ebe153ea9f6cfd1dfb81a21cd95d7 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 03:43:59 -0500 Subject: [PATCH 31/39] WD: Polished heater threshold controls. --- Apps/FlightSoftware/Watchdog/include/flags.h | 1 + .../src/stateMachine/RoverStateBase.cpp | 30 +++- .../src/stateMachine/RoverStateManager.cpp | 161 ++++++++++-------- 3 files changed, 117 insertions(+), 75 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/flags.h b/Apps/FlightSoftware/Watchdog/include/flags.h index 0885aa3f6..f4fd9d256 100644 --- a/Apps/FlightSoftware/Watchdog/include/flags.h +++ b/Apps/FlightSoftware/Watchdog/include/flags.h @@ -53,6 +53,7 @@ extern "C" BOOL m_heatingControlEnabled; uint16_t m_heaterDutyCyclePeriod; uint16_t m_heaterDutyCycle; + BOOL m_thresholdsChanged; // flag that the on or off thresholds have changed since they were last checked } HeaterParams; #define DEFAULT_KP_HEATER 500 // deprecated diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 74eda1be3..43ba83c1a 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -253,10 +253,34 @@ namespace iris void RoverStateBase::heaterControl(RoverContext &theContext) { - // voltage, where LSB = 0.0008056640625V unsigned short thermReading = theContext.m_adcValues.battRT; HeaterParams &hParams = theContext.m_details.m_hParams; + if (hParams.m_thresholdsChanged) + { + // Ground operators changed the thresholds. Re-evaluate against + // thresholds: + if (thermReading > hParams.m_heaterOnVal) + { + enableHeater(); + } + else if (thermReading < hParams.m_heaterOffVal) + { + disableHeater(); + } + else + { + // We're somewhere in the middle, in which case, for safety, we + // should default to ON. + // NOTE: unless the settings were intentionally configured + // weirdly during mission, there should be no middle ground + // because Toff should be > Ton (that is ADCoff < ADCon b/c NTC) + enableHeater(); + } + hParams.m_thresholdsChanged = false; + } + + // Normal controller operation: if (!hParams.m_heating && thermReading > hParams.m_heaterOnVal) { // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a @@ -973,6 +997,8 @@ namespace iris bool &sendDeployNotificationResponse) { theContext.m_details.m_hParams.m_heaterOnVal = msg.body.setAutoHeaterOnValue.heaterOnValue; + // Flag that the thresholds have changed: + theContext.m_details.m_hParams.m_thresholdsChanged = true; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } @@ -984,6 +1010,8 @@ namespace iris bool &sendDeployNotificationResponse) { theContext.m_details.m_hParams.m_heaterOffVal = msg.body.setAutoHeaterOffValue.heaterOffValue; + // Flag that the thresholds have changed: + theContext.m_details.m_hParams.m_thresholdsChanged = true; response.statusCode = WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS; return getState(); } diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp index 9b4a05193..06d2c401d 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp @@ -11,7 +11,7 @@ #pragma vector = WDT_VECTOR __interrupt void WDT_ISR(void) #elif defined(__GNUC__) -void __attribute__ ((interrupt(WDT_VECTOR))) WDT_ISR (void) +void __attribute__((interrupt(WDT_VECTOR))) WDT_ISR(void) #else #error Compiler not supported! #endif @@ -33,7 +33,7 @@ namespace iris #pragma PERSISTENT static bool persistentDeployed = false; - RoverStateManager::RoverStateManager(const char* resetReasonString) + RoverStateManager::RoverStateManager(const char *resetReasonString) : m_stateEnteringKeepAlive(), m_stateEnteringMission(), m_stateEnteringService(), @@ -74,6 +74,7 @@ namespace iris m_context.m_details.m_hParams.m_heatingControlEnabled = DEFAULT_HEATING_CONTROL_ENABLED; m_context.m_details.m_hParams.m_heaterDutyCyclePeriod = DEFAULT_HEATER_DUTY_CYCLE_PERIOD; m_context.m_details.m_hParams.m_heaterDutyCycle = DEFAULT_HEATER_DUTY_CYCLE; + m_context.m_details.m_hParams.m_thresholdsChanged = true; m_context.m_details.m_stateAsUint = static_cast(RoverState::ENTERING_KEEP_ALIVE); m_context.m_details.m_inputPinAndStateBits = 0; m_context.m_details.m_outputPinBits = 0; @@ -91,7 +92,8 @@ namespace iris void RoverStateManager::spinForever() { - while (true) { + while (true) + { // Sets watchdog timer to be based on ACLK, and in our clock configuration the source of ACLK is VLOCLK // (with no divisions, so f_ACLK == f_VLOCLK) and f_VLOCLK == 9.4 KHz. Also clears the watchdog timer count // and configures the watchdog timer period (i.e. how long the WDT timer will tick before resetting the @@ -115,30 +117,37 @@ namespace iris // source of the WDT, our option jumps from ~3.5 seconds to ~55 seconds. However, if we use SMCLK as the // source of the WDT, since f_SMCLK = 8 MHz we can use the 2^27 divider option to get a WDT interval of // just over 16.7 seconds. The 2^27 divider is selected when WDTIS is 0b001. - //OLD: WDTCTL = WDTPW + WDTCNTCL + WDTSSEL__ACLK + WDTIS2; + // OLD: WDTCTL = WDTPW + WDTCNTCL + WDTSSEL__ACLK + WDTIS2; WDTCTL = WDTPW + WDTCNTCL + WDTSSEL__SMCLK + WDTIS0; Event__Type event = EVENT__TYPE__UNUSED; EventQueue__Status eqStatus = EventQueue__get(&event); - //bool gotEvent = false; + // bool gotEvent = false; - if (EQ__STATUS__SUCCESS == eqStatus) { + if (EQ__STATUS__SUCCESS == eqStatus) + { // We got an event. Have the current state handle it (performing any necessary state transitions as // requested by the state(s)) handleEvent(event); - //gotEvent = true; - } else if (EQ__STATUS__ERROR_EMPTY == eqStatus) { - if (m_currentState->canEnterLowPowerMode(m_context)) { + // gotEvent = true; + } + else if (EQ__STATUS__ERROR_EMPTY == eqStatus) + { + if (m_currentState->canEnterLowPowerMode(m_context)) + { //!< @todo Enter LPM here. Need to figure out how to handle LPM and WDT together. __enable_interrupt(); // Make sure we haven't somehow left interrupts off ENTER_DEFAULT_LPM; } - } else { + } + else + { // Any status other than success or empty is an unexpected failure. DEBUG_LOG_CHECK_STATUS(EQ__STATUS__SUCCESS, eqStatus, "Failed to get event from queue due to error"); } - if (m_context.m_i2cActive) { + if (m_context.m_i2cActive) + { I2C_Sensors__spinOnce(); } @@ -146,55 +155,57 @@ namespace iris m_context.m_details.m_stateAsUint = static_cast(currentState); RoverState desiredNextState = m_currentState->spinOnce(m_context); - if (currentState != desiredNextState) { + if (currentState != desiredNextState) + { transitionUntilSettled(desiredNextState); } } } - RoverStateBase* RoverStateManager::getStateObjectForStateEnum(RoverState stateEnumValue) + RoverStateBase *RoverStateManager::getStateObjectForStateEnum(RoverState stateEnumValue) { - switch (stateEnumValue) { - case RoverState::INIT: - return &m_stateInit; + switch (stateEnumValue) + { + case RoverState::INIT: + return &m_stateInit; - case RoverState::ENTERING_KEEP_ALIVE: - return &m_stateEnteringKeepAlive; + case RoverState::ENTERING_KEEP_ALIVE: + return &m_stateEnteringKeepAlive; - case RoverState::KEEP_ALIVE: - return &m_stateKeepAlive; + case RoverState::KEEP_ALIVE: + return &m_stateKeepAlive; - case RoverState::ENTERING_SERVICE: - return &m_stateEnteringService; + case RoverState::ENTERING_SERVICE: + return &m_stateEnteringService; - case RoverState::SERVICE: - return &m_stateService; + case RoverState::SERVICE: + return &m_stateService; - case RoverState::ENTERING_MISSION: - return &m_stateEnteringMission; + case RoverState::ENTERING_MISSION: + return &m_stateEnteringMission; - case RoverState::MISSION: - return &m_stateMission; + case RoverState::MISSION: + return &m_stateMission; - default: - DebugComms__tryPrintfToLanderNonblocking("Reached default state in getStateObjectForStateEnum\n"); - DebugComms__flush(); - return &m_stateInit; + default: + DebugComms__tryPrintfToLanderNonblocking("Reached default state in getStateObjectForStateEnum\n"); + DebugComms__flush(); + return &m_stateInit; } } void RoverStateManager::transitionUntilSettled(RoverState desiredState) { - while (m_currentState->getState() != desiredState) { + while (m_currentState->getState() != desiredState) + { const char *originalStateStr = stateToString(m_currentState->getState()); - const char *desiredStateStr = stateToString(desiredState); + const char *desiredStateStr = stateToString(desiredState); DebugComms__tryPrintfToLanderNonblocking("Transitioning from %s to %s\n", originalStateStr, desiredStateStr); m_currentState = getStateObjectForStateEnum(desiredState); m_context.m_details.m_stateAsUint = static_cast(m_currentState->getState()); desiredState = m_currentState->transitionTo(m_context); } - } void RoverStateManager::handleEvent(Event__Type event) @@ -202,47 +213,49 @@ namespace iris RoverState currentState = m_currentState->getState(); RoverState desiredNextState = currentState; - switch (event) { - case EVENT__TYPE__UNUSED: - DebugComms__tryPrintfToLanderNonblocking("Trying to handle an UNUSED event type, which indicates programmer error\n"); - DebugComms__flush(); - return; - - case EVENT__TYPE__LANDER_DATA: - desiredNextState = m_currentState->handleLanderData(m_context); - break; - - case EVENT__TYPE__HERCULES_DATA: - desiredNextState = m_currentState->handleHerculesData(m_context); - break; - - case EVENT__TYPE__TIMER_TICK: - desiredNextState = m_currentState->handleTimerTick(m_context); - break; - - case EVENT__TYPE__HIGH_TEMP: - desiredNextState = m_currentState->handleHighTemp(m_context); - break; - - case EVENT__TYPE__POWER_ISSUE: - desiredNextState = m_currentState->handlePowerIssue(m_context); - break; - - case EVENT__TYPE__WD_INT_RISING_EDGE: - desiredNextState = m_currentState->handleWdIntRisingEdge(m_context); - break; - - case EVENT__TYPE__WD_INT_FALLING_EDGE: - desiredNextState = m_currentState->handleWdIntFallingEdge(m_context); - break; - - default: - DebugComms__tryPrintfToLanderNonblocking("In default case trying to handle event, which indicates programmer error\n"); - DebugComms__flush(); - break; + switch (event) + { + case EVENT__TYPE__UNUSED: + DebugComms__tryPrintfToLanderNonblocking("Trying to handle an UNUSED event type, which indicates programmer error\n"); + DebugComms__flush(); + return; + + case EVENT__TYPE__LANDER_DATA: + desiredNextState = m_currentState->handleLanderData(m_context); + break; + + case EVENT__TYPE__HERCULES_DATA: + desiredNextState = m_currentState->handleHerculesData(m_context); + break; + + case EVENT__TYPE__TIMER_TICK: + desiredNextState = m_currentState->handleTimerTick(m_context); + break; + + case EVENT__TYPE__HIGH_TEMP: + desiredNextState = m_currentState->handleHighTemp(m_context); + break; + + case EVENT__TYPE__POWER_ISSUE: + desiredNextState = m_currentState->handlePowerIssue(m_context); + break; + + case EVENT__TYPE__WD_INT_RISING_EDGE: + desiredNextState = m_currentState->handleWdIntRisingEdge(m_context); + break; + + case EVENT__TYPE__WD_INT_FALLING_EDGE: + desiredNextState = m_currentState->handleWdIntFallingEdge(m_context); + break; + + default: + DebugComms__tryPrintfToLanderNonblocking("In default case trying to handle event, which indicates programmer error\n"); + DebugComms__flush(); + break; } - if (currentState != desiredNextState) { + if (currentState != desiredNextState) + { transitionUntilSettled(desiredNextState); } } From 4a099bf595c41d41e1e69caa1a4ee1a505a260ed Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 03:57:32 -0500 Subject: [PATCH 32/39] WD: Primitive Batt_RT thermistor failure handling added. --- .../src/stateMachine/RoverStateBase.cpp | 43 +++++++++++++++---- 1 file changed, 34 insertions(+), 9 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 43ba83c1a..4f6ea132a 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -280,18 +280,43 @@ namespace iris hParams.m_thresholdsChanged = false; } - // Normal controller operation: - if (!hParams.m_heating && thermReading > hParams.m_heaterOnVal) + // Check for failure cases, in which case, turn the heater on: + if (thermReading < 5) { - // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a - // configured (either via the default value or a value commanded from ground) ADC reading. - enableHeater(); + // if the sensor is giving an ADC reading of basically 0, we + // probably have an open circuit. For safety, enable the heater: + if (!hParams.m_heating) + { + // Let Earth know we're turning on the Heat (this might be during an LOS): + DebugComms__tryPrintfToLanderNonblocking("POSSIBLE BATT_RT THERMISTOR FAILURE DETECTED. ADC < 5. ENABLING HEATER FOR SAFETY. RECOMMEND MANUAL HEATER CONTROL."); + enableHeater(); + } } - else if (hParams.m_heating && thermReading < hParams.m_heaterOffVal) + else { - // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a - // configured (either via the default value or a value commanded from ground) ADC reading. - disableHeater(); + // Normal controller state machine operation: + if (hParams.m_heating) + { + // In the HEATER_ON state... + if (thermReading < hParams.m_heaterOffVal) + { + // transition to HEATER_OFF + // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a + // configured (either via the default value or a value commanded from ground) ADC reading. + disableHeater(); + } + } + else + { + // In the HEATER_OFF state... + if (thermReading > hParams.m_heaterOnVal) + { + // transition to HEATER_ON + // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a + // configured (either via the default value or a value commanded from ground) ADC reading. + enableHeater(); + } + } } } From a86d306c1bb779327d2234ab366b2b90f475cae4 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 05:51:52 -0500 Subject: [PATCH 33/39] WD+XML: Added ability to force heater state and change heater controller input thermistor (as well as charing IC power up/down). --- .../include/comms/watchdog_cmd_msgs.h | 1238 +++++++++-------- Apps/FlightSoftware/Watchdog/include/flags.h | 23 +- .../src/stateMachine/RoverStateBase.cpp | 88 +- .../src/stateMachine/RoverStateManager.cpp | 2 + .../WatchDogInterfaceComponentAi.xml | 11 +- 5 files changed, 738 insertions(+), 624 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/comms/watchdog_cmd_msgs.h b/Apps/FlightSoftware/Watchdog/include/comms/watchdog_cmd_msgs.h index 9633efc9e..9c9b7c83f 100644 --- a/Apps/FlightSoftware/Watchdog/include/comms/watchdog_cmd_msgs.h +++ b/Apps/FlightSoftware/Watchdog/include/comms/watchdog_cmd_msgs.h @@ -9,714 +9,720 @@ extern "C" { #endif -/** - * @defgroup watchdogWatchdogCmdMsgs Watchdog Command Messages - * @addtogroup watchdogWatchdogCmdMsgs - * @{ - */ - -/** - * @brief Possible return statuses of CmdMsgs functions. - */ -typedef enum WdCmdMsgs__Status -{ - WD_CMD_MSGS__STATUS__SUCCESS = CMD_MSGS__STATUS__SUCCESS, //!< Operation succeeded. - /** - * @brief A required argument or a member of an argument was NULL + * @defgroup watchdogWatchdogCmdMsgs Watchdog Command Messages + * @addtogroup watchdogWatchdogCmdMsgs + * @{ */ - WD_CMD_MSGS__STATUS__ERROR_NULL = CMD_MSGS__STATUS__ERROR_NULL, /** - * @brief A given buffer was too small. + * @brief Possible return statuses of CmdMsgs functions. */ - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL = CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL, + typedef enum WdCmdMsgs__Status + { + WD_CMD_MSGS__STATUS__SUCCESS = CMD_MSGS__STATUS__SUCCESS, //!< Operation succeeded. + + /** + * @brief A required argument or a member of an argument was NULL + */ + WD_CMD_MSGS__STATUS__ERROR_NULL = CMD_MSGS__STATUS__ERROR_NULL, + + /** + * @brief A given buffer was too small. + */ + WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL = CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL, + + /** + * @brief A serialization error occurred. + */ + WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR = CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR, + WD_CMD_MSGS__STATUS__ERROR_UNKNOWN_MESSAGE_ID = -4, //!< Encountered an unknown command ID. + + /** + * An unexpected error occurred. + */ + WD_CMD_MSGS__STATUS__ERROR__INTERNAL = CMD_MSGS__STATUS__ERROR__INTERNAL + } WdCmdMsgs__Status; + + // ###################################################################################################################### + // Message Field Types + // ###################################################################################################################### /** - * @brief A serialization error occurred. + * @brief Possible response status codes. */ - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR = CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR, - WD_CMD_MSGS__STATUS__ERROR_UNKNOWN_MESSAGE_ID = -4, //!< Encountered an unknown command ID. + typedef enum WdCmdMsgs__ResponseStatusCode + { + WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS = 0, //!< Command performed successfully. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_PACKET_LENGTH = 1, //!< Wrong packet length for this command. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_CHECKSUM = 2, //!< Checksum validation failed. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_MODULE_ID = 3, //!< Unexpected module ID. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_ID = 4, //!< Unexpected command ID. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER = 5, //!< Unexpected parameter value. + WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE = 6, //!< Unexpected sequence of commands. + + WD_CMD_MSGS__RESPONSE_STATUS__DEPLOY = 96, //!< The watchdog just enabled its HDRM. + } WdCmdMsgs__ResponseStatusCode; /** - * An unexpected error occurred. + * @brief Possible watchdog command IDs */ - WD_CMD_MSGS__STATUS__ERROR__INTERNAL = CMD_MSGS__STATUS__ERROR__INTERNAL -} WdCmdMsgs__Status; + typedef enum WdCmdMsgs__CommandId + { + WD_CMD_MSGS__CMD_ID__RESET_SPECIFIC = 0x1000, //!< Reset Specific. + WD_CMD_MSGS__CMD_ID__PREP_FOR_DEPLOY = 0x1001, //!< Prepare to Deploy. + WD_CMD_MSGS__CMD_ID__DEPLOY = 0x1002, //!< Deploy. + WD_CMD_MSGS__CMD_ID__SWITCH_CONN_MODE = 0x1004, //!< Switch Connection Mode. + WD_CMD_MSGS__CMD_ID__SET_DEBUG_COMMS_STATE = 0x10AA, //!< Sets debug comms on or off. + WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_ON_VALUE = 0x10AB, //!< Set heater "ON" value used with auto heater controller. + WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_OFF_VALUE = 0x10AC, //!< Set heater "OFF" value used with auto heater controller. + WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE = 0x10AD, //!< Set duty cycle of heater PWM. + WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE_PERIOD = 0x10AE, //!< Set period of heater PWM. + WD_CMD_MSGS__CMD_ID__SET_VSAE_STATE = 0x10DA, //!< Set VSAE on or off. + WD_CMD_MSGS__CMD_ID__ENTER_SLEEP_MODE = 0x10EA, //!< Enter "Sleep" mode. + WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE = 0x10EB, //!< Enter "Keep Alive" mode. + WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE = 0x10EC, //!< Enter "Service" mode. + WD_CMD_MSGS__CMD_ID__CLEAR_RESET_MEMORY = 0x10F4, //!< Clear the reset memory used in the detailed report. + WD_CMD_MSGS__CMD_ID__DANGEROUS_FORCE_BATT_STATE = 0x10F5, //!< Dangerous: Force battery state. + WD_CMD_MSGS__CMD_ID__REQUEST_DETAILED_REPORT = 0x10F6, //!< Request a detailed report + WD_CMD_MSGS__CMD_ID__SET_CHARGE_EN_STATE = 0x10F7, //!< Set charging IC enable state. + WD_CMD_MSGS__CMD_ID__SET_CHARGE_REG_EN_STATE = 0x10F8, //!< Set charging power 28V regulator enable state. + WD_CMD_MSGS__CMD_ID__SET_BATT_EN_STATE = 0x10F9, //!< Set battery connection state. + WD_CMD_MSGS__CMD_ID__SET_BATT_CTRL_EN_STATE = 0x10FA, //!< Set battery management control state. + WD_CMD_MSGS__CMD_ID__SET_LATCH_BATT_STATE = 0x10FB, //!< Set battery latch state. + WD_CMD_MSGS__CMD_ID__LATCH_SET_PULSE_LOW = 0x10FC, //!< Pulse battery latch "SET" override low. + WD_CMD_MSGS__CMD_ID__LATCH_RESET_PULSE_LOW = 0x10FD, //!< Pulse battery latch "RESET" override low. + WD_CMD_MSGS__CMD_ID__ECHO = 0x10FF, //!< Diagnostic request to echo the given bytes back (with a header attached marking it as an echo) + } WdCmdMsgs__CommandId; -//###################################################################################################################### -// Message Field Types -//###################################################################################################################### - -/** - * @brief Possible response status codes. - */ -typedef enum WdCmdMsgs__ResponseStatusCode -{ - WD_CMD_MSGS__RESPONSE_STATUS__SUCCESS = 0, //!< Command performed successfully. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_PACKET_LENGTH = 1, //!< Wrong packet length for this command. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_CHECKSUM = 2, //!< Checksum validation failed. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_MODULE_ID = 3, //!< Unexpected module ID. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_ID = 4, //!< Unexpected command ID. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_PARAMETER = 5, //!< Unexpected parameter value. - WD_CMD_MSGS__RESPONSE_STATUS__ERROR_BAD_COMMAND_SEQUENCE = 6, //!< Unexpected sequence of commands. - - WD_CMD_MSGS__RESPONSE_STATUS__DEPLOY = 96, //!< The watchdog just enabled its HDRM. -} WdCmdMsgs__ResponseStatusCode; - -/** - * @brief Possible watchdog command IDs - */ -typedef enum WdCmdMsgs__CommandId -{ - WD_CMD_MSGS__CMD_ID__RESET_SPECIFIC = 0x1000, //!< Reset Specific. - WD_CMD_MSGS__CMD_ID__PREP_FOR_DEPLOY = 0x1001, //!< Prepare to Deploy. - WD_CMD_MSGS__CMD_ID__DEPLOY = 0x1002, //!< Deploy. - WD_CMD_MSGS__CMD_ID__SWITCH_CONN_MODE = 0x1004, //!< Switch Connection Mode. - WD_CMD_MSGS__CMD_ID__SET_DEBUG_COMMS_STATE = 0x10AA, //!< Sets debug comms on or off. - WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_ON_VALUE = 0x10AB, //!< Set heater "ON" value used with auto heater controller. - WD_CMD_MSGS__CMD_ID__SET_AUTO_HEATER_OFF_VALUE = 0x10AC, //!< Set heater "OFF" value used with auto heater controller. - WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE = 0x10AD, //!< Set duty cycle of heater PWM. - WD_CMD_MSGS__CMD_ID__SET_HEATER_DUTY_CYCLE_PERIOD = 0x10AE, //!< Set period of heater PWM. - WD_CMD_MSGS__CMD_ID__SET_VSAE_STATE = 0x10DA, //!< Set VSAE on or off. - WD_CMD_MSGS__CMD_ID__ENTER_SLEEP_MODE = 0x10EA, //!< Enter "Sleep" mode. - WD_CMD_MSGS__CMD_ID__ENTER_KEEPALIVE_MODE = 0x10EB, //!< Enter "Keep Alive" mode. - WD_CMD_MSGS__CMD_ID__ENTER_SERVICE_MODE = 0x10EC, //!< Enter "Service" mode. - WD_CMD_MSGS__CMD_ID__CLEAR_RESET_MEMORY = 0x10F4, //!< Clear the reset memory used in the detailed report. - WD_CMD_MSGS__CMD_ID__DANGEROUS_FORCE_BATT_STATE = 0x10F5, //!< Dangerous: Force battery state. - WD_CMD_MSGS__CMD_ID__REQUEST_DETAILED_REPORT = 0x10F6, //!< Request a detailed report - WD_CMD_MSGS__CMD_ID__SET_CHARGE_EN_STATE = 0x10F7, //!< Set charging IC enable state. - WD_CMD_MSGS__CMD_ID__SET_CHARGE_REG_EN_STATE = 0x10F8, //!< Set charging power 28V regulator enable state. - WD_CMD_MSGS__CMD_ID__SET_BATT_EN_STATE = 0x10F9, //!< Set battery connection state. - WD_CMD_MSGS__CMD_ID__SET_BATT_CTRL_EN_STATE = 0x10FA, //!< Set battery management control state. - WD_CMD_MSGS__CMD_ID__SET_LATCH_BATT_STATE = 0x10FB, //!< Set battery latch state. - WD_CMD_MSGS__CMD_ID__LATCH_SET_PULSE_LOW = 0x10FC, //!< Pulse battery latch "SET" override low. - WD_CMD_MSGS__CMD_ID__LATCH_RESET_PULSE_LOW = 0x10FD, //!< Pulse battery latch "RESET" override low. - WD_CMD_MSGS__CMD_ID__ECHO = 0x10FF, //!< Diagnostic request to echo the given bytes back (with a header attached marking it as an echo) -} WdCmdMsgs__CommandId; - -/** - * @brief Possible reset values, given for the reset specific command. - */ -typedef enum WdCmdMsgs__ResetSpecificId -{ /** - * @brief Don't reset anything. - * @todo What is the point of this? + * @brief Possible reset values, given for the reset specific command. */ - WD_CMD_MSGS__RESET_ID__NO_RESET = 0x00, + typedef enum WdCmdMsgs__ResetSpecificId + { + /** + * @brief Don't reset anything. + * @todo What is the point of this? + */ + WD_CMD_MSGS__RESET_ID__NO_RESET = 0x00, - WD_CMD_MSGS__RESET_ID__HERCULES_RESET = 0x01, //!< Reset the Hercules. - WD_CMD_MSGS__RESET_ID__HERCULES_POWER_ON = 0x02, //!< Power on the Hercules. - WD_CMD_MSGS__RESET_ID__HERCULES_POWER_OFF = 0x03, //!< Power off the Hercules. + WD_CMD_MSGS__RESET_ID__HERCULES_RESET = 0x01, //!< Reset the Hercules. + WD_CMD_MSGS__RESET_ID__HERCULES_POWER_ON = 0x02, //!< Power on the Hercules. + WD_CMD_MSGS__RESET_ID__HERCULES_POWER_OFF = 0x03, //!< Power off the Hercules. - WD_CMD_MSGS__RESET_ID__RADIO_RESET = 0x04, //!< Reset the radio (the WiFi). - WD_CMD_MSGS__RESET_ID__RADIO_POWER_ON = 0x05, //!< Power on the radio (the WiFi). - WD_CMD_MSGS__RESET_ID__RADIO_POWER_OFF = 0x06, //!< Power off the radio (the WiFi). + WD_CMD_MSGS__RESET_ID__RADIO_RESET = 0x04, //!< Reset the radio (the WiFi). + WD_CMD_MSGS__RESET_ID__RADIO_POWER_ON = 0x05, //!< Power on the radio (the WiFi). + WD_CMD_MSGS__RESET_ID__RADIO_POWER_OFF = 0x06, //!< Power off the radio (the WiFi). - WD_CMD_MSGS__RESET_ID__CAM_FPGA_RESET = 0x07, //!< Reset the camera FPGA. - WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_ON = 0x08, //!< Power on the camera FPGA. - WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_OFF = 0x09, //!< Power off the camera FPGA. + WD_CMD_MSGS__RESET_ID__CAM_FPGA_RESET = 0x07, //!< Reset the camera FPGA. + WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_ON = 0x08, //!< Power on the camera FPGA. + WD_CMD_MSGS__RESET_ID__CAM_FPGA_POWER_OFF = 0x09, //!< Power off the camera FPGA. - WD_CMD_MSGS__RESET_ID__MOTOR_1_RESET = 0x0A, //!< Reset motor 1. - WD_CMD_MSGS__RESET_ID__MOTOR_2_RESET = 0x0B, //!< Reset motor 2. - WD_CMD_MSGS__RESET_ID__MOTOR_3_RESET = 0x0C, //!< Reset motor 3. - WD_CMD_MSGS__RESET_ID__MOTOR_4_RESET = 0x0D, //!< Reset motor 4. + WD_CMD_MSGS__RESET_ID__MOTOR_1_RESET = 0x0A, //!< Reset motor 1. + WD_CMD_MSGS__RESET_ID__MOTOR_2_RESET = 0x0B, //!< Reset motor 2. + WD_CMD_MSGS__RESET_ID__MOTOR_3_RESET = 0x0C, //!< Reset motor 3. + WD_CMD_MSGS__RESET_ID__MOTOR_4_RESET = 0x0D, //!< Reset motor 4. - WD_CMD_MSGS__RESET_ID__ALL_MOTORS_RESET = 0x0E, //!< Reset all motors. - WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_ON = 0x0F, //!< Power on all motors. - WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_OFF = 0x10, //!< Power off all motors. + WD_CMD_MSGS__RESET_ID__ALL_MOTORS_RESET = 0x0E, //!< Reset all motors. + WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_ON = 0x0F, //!< Power on all motors. + WD_CMD_MSGS__RESET_ID__ALL_MOTORS_POWER_OFF = 0x10, //!< Power off all motors. - WD_CMD_MSGS__RESET_ID__3_3V_EN_RESET = 0x11, //!< Reset the 3.3V line enable. - WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_ON = 0x12, //!< Power on the 3.3V line enable. - WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_OFF = 0x13, //!< Power off the 3.3V line enable. + WD_CMD_MSGS__RESET_ID__3_3V_EN_RESET = 0x11, //!< Reset the 3.3V line enable. + WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_ON = 0x12, //!< Power on the 3.3V line enable. + WD_CMD_MSGS__RESET_ID__3_3V_EN_POWER_OFF = 0x13, //!< Power off the 3.3V line enable. - WD_CMD_MSGS__RESET_ID__V_SYS_ALL_POWER_CYCLE = 0x14, //!< Reset the 24V line enable. - WD_CMD_MSGS__RESET_ID__V_SYS_ALL_ON = 0x15, //!< Power on the 24V line enable. - WD_CMD_MSGS__RESET_ID__V_SYS_ALL_OFF = 0x16, //!< Power off the 24V line enable. + WD_CMD_MSGS__RESET_ID__V_SYS_ALL_POWER_CYCLE = 0x14, //!< Reset the 24V line enable. + WD_CMD_MSGS__RESET_ID__V_SYS_ALL_ON = 0x15, //!< Power on the 24V line enable. + WD_CMD_MSGS__RESET_ID__V_SYS_ALL_OFF = 0x16, //!< Power off the 24V line enable. - WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_OFF = 0x18, //!< Power off the HDRM. + WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_OFF = 0x18, //!< Power off the HDRM. - WD_CMD_MSGS__RESET_ID__FPGA_CAM_0_SELECT = 0x19, //!< Select camera 0. - WD_CMD_MSGS__RESET_ID__FPGA_CAM_1_SELECT = 0x1A, //!< Select camera 1. + WD_CMD_MSGS__RESET_ID__FPGA_CAM_0_SELECT = 0x19, //!< Select camera 0. + WD_CMD_MSGS__RESET_ID__FPGA_CAM_1_SELECT = 0x1A, //!< Select camera 1. - WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_START = 0x1B, //!< Start charging the batteries. - WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_STOP = 0x1C, //!< Stop charging the batteries. + WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_START = 0x1B, //!< Start charging the batteries. + WD_CMD_MSGS__RESET_ID__BATTERY_CHARGE_STOP = 0x1C, //!< Stop charging the batteries. - WD_CMD_MSGS__RESET_ID__RS422_UART_ENABLE = 0x1D, //!< Enable the RS422 UART. - WD_CMD_MSGS__RESET_ID__RS422_UART_DISABLE = 0x1E, //!< Disable the RS422 UART. + WD_CMD_MSGS__RESET_ID__RS422_UART_ENABLE = 0x1D, //!< Enable the RS422 UART. + WD_CMD_MSGS__RESET_ID__RS422_UART_DISABLE = 0x1E, //!< Disable the RS422 UART. - WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_ENABLE = 0x1F, //!< Enable the automatic heater controller. - WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_DISABLE = 0x20, //!< Disable the automatic heater controller. + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_ENABLE = 0x1F, //!< Enable the automatic heater controller. + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_DISABLE = 0x20, //!< Disable the automatic heater controller. - WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_ENABLE = 0x21, //!< Enable the Hercules watchdog. - WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_DISABLE = 0x22, //!< Disable the Hercules watchdog. + WD_CMD_MSGS__RESET_ID__HEATER_FORCE_OFF = 0xC0, //!< Force the heater to always be OFF (at whatever duty cycle) + WD_CMD_MSGS__RESET_ID__HEATER_FORCE_ON = 0xC1, //!< Force the heater to always be ON (at whatever duty cycle) + WD_CMD_MSGS__RESET_ID__HEATER_FORCE_NOTHING = 0xC2, //!< Don't force the heater to do anything (let the controller work its magic) + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_RT_INPUT = 0xCF, //!< Auto Heater Controller should use BattRT as the temperature input + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT_DEACTIVATE = 0xCE, //!< Deactivate charging circuitry used to allow Auto Heater Controller to use Charger Thermistor as the temperature input (for use if returning to BATT_RT from CHRG) + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT_ACTIVATE = 0xCD, //!< Activate charging circuitry but disable charging so the Auto Heater Controller can use Charger Thermistor as the temperature input (needed for `WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT` to work) + WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT = 0xCC, //!< Auto Heater Controller should use Charger Thermistor as the temperature input - WD_CMD_MSGS__RESET_ID__BATTERIES_ENABLE = 0x23, //!< Enable the batteries. - WD_CMD_MSGS__RESET_ID__BATTERIES_DISABLE = 0x24, //!< Disable the batteries. + WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_ENABLE = 0x21, //!< Enable the Hercules watchdog. + WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_DISABLE = 0x22, //!< Disable the Hercules watchdog. - WD_CMD_MSGS__RESET_ID__CLEAR_PERSISTENT_DEPLOY = 0xDD, //!< Clear the persistent "deployed" status. - WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_ON = 0xEE //!< Power on the HDRM. + WD_CMD_MSGS__RESET_ID__BATTERIES_ENABLE = 0x23, //!< Enable the batteries. + WD_CMD_MSGS__RESET_ID__BATTERIES_DISABLE = 0x24, //!< Disable the batteries. -} WdCmdMsgs__ResetSpecificId; + WD_CMD_MSGS__RESET_ID__CLEAR_PERSISTENT_DEPLOY = 0xDD, //!< Clear the persistent "deployed" status. + WD_CMD_MSGS__RESET_ID__HDRM_DEPLOY_SIGNAL_POWER_ON = 0xEE //!< Power on the HDRM. -/** - * @brief Possible values of the parameter of the Switch Connection Mode command. - */ -typedef enum WdCmdMsgs__SwitchConnModeSelection -{ - WD_CMD_MSGS__CONN_MODE__WIRED = 0x01, //!< Wired (RS-422): Watchdog gets data, forwards to Hercules - WD_CMD_MSGS__CONN_MODE__WIRELESS = 0x02 //!< Wireless: Hercules gets data, forwards to watchdog -} WdCmdMsgs__SwitchConnModeSelection; + } WdCmdMsgs__ResetSpecificId; -/** - * @brief Possible values of the parameter of the Dangerous Force Battery State command. - */ -typedef enum WdCmdMsgs__DangForceBattStateSelection -{ - WD_CMD_MSGS__DANG_FORCE_BATT_STATE__LOW = 0x00, //!< Force battery state low - WD_CMD_MSGS__DANG_FORCE_BATT_STATE__HIGH = 0xFF, //!< Force battery state high - WD_CMD_MSGS__DANG_FORCE_BATT_STATE__RESTORE = 0xAA //!< Restore battery state to an input -} WdCmdMsgs__DangForceBattStateSelection; + /** + * @brief Possible values of the parameter of the Switch Connection Mode command. + */ + typedef enum WdCmdMsgs__SwitchConnModeSelection + { + WD_CMD_MSGS__CONN_MODE__WIRED = 0x01, //!< Wired (RS-422): Watchdog gets data, forwards to Hercules + WD_CMD_MSGS__CONN_MODE__WIRELESS = 0x02 //!< Wireless: Hercules gets data, forwards to watchdog + } WdCmdMsgs__SwitchConnModeSelection; -/** - * @brief Possible values of the parameter of the Set Charge EN State command. - */ -typedef enum WdCmdMsgs__SetChargeEnSelection -{ - WD_CMD_MSGS__CHARGE_EN__ON = 0xFF, //!< Enable charging - WD_CMD_MSGS__CHARGE_EN__OFF = 0x00, //!< Disable charging - WD_CMD_MSGS__CHARGE_EN__FORCE_HIGH = 0x99 //!< Force high output on CHRG_EN pin -} WdCmdMsgs__SetChargeEnSelection; + /** + * @brief Possible values of the parameter of the Dangerous Force Battery State command. + */ + typedef enum WdCmdMsgs__DangForceBattStateSelection + { + WD_CMD_MSGS__DANG_FORCE_BATT_STATE__LOW = 0x00, //!< Force battery state low + WD_CMD_MSGS__DANG_FORCE_BATT_STATE__HIGH = 0xFF, //!< Force battery state high + WD_CMD_MSGS__DANG_FORCE_BATT_STATE__RESTORE = 0xAA //!< Restore battery state to an input + } WdCmdMsgs__DangForceBattStateSelection; -/** - * @brief Possible values of the parameter of the Set Charge EN State command. - */ -typedef enum WdCmdMsgs__SetChargeRegEnSelection -{ - WD_CMD_MSGS__CHARGE_REG_EN__ON = 0xFF, //!< Enable charging regulator - WD_CMD_MSGS__CHARGE_REG_EN__OFF = 0x00 //!< Disable charging regulator -} WdCmdMsgs__SetChargeRegEnSelection; + /** + * @brief Possible values of the parameter of the Set Charge EN State command. + */ + typedef enum WdCmdMsgs__SetChargeEnSelection + { + WD_CMD_MSGS__CHARGE_EN__ON = 0xFF, //!< Enable charging + WD_CMD_MSGS__CHARGE_EN__OFF = 0x00, //!< Disable charging + WD_CMD_MSGS__CHARGE_EN__FORCE_HIGH = 0x99 //!< Force high output on CHRG_EN pin + } WdCmdMsgs__SetChargeEnSelection; -/** - * @brief Possible values of the parameter of the Set Battery EN State command. - */ -typedef enum WdCmdMsgs__SetBattEnSelection -{ - WD_CMD_MSGS__BATT_EN__ON = 0xFF, //!< Enable battery connection - WD_CMD_MSGS__BATT_EN__OFF = 0x00 //!< Disable battery connection -} WdCmdMsgs__SetBattEnSelection; + /** + * @brief Possible values of the parameter of the Set Charge EN State command. + */ + typedef enum WdCmdMsgs__SetChargeRegEnSelection + { + WD_CMD_MSGS__CHARGE_REG_EN__ON = 0xFF, //!< Enable charging regulator + WD_CMD_MSGS__CHARGE_REG_EN__OFF = 0x00 //!< Disable charging regulator + } WdCmdMsgs__SetChargeRegEnSelection; -/** - * @brief Possible values of the parameter of the Set Battery Control EN State command. - */ -typedef enum WdCmdMsgs__SetBattCtrlEnSelection -{ - WD_CMD_MSGS__BATT_CTRL_EN__ON = 0xFF, //!< Enable battery connection - WD_CMD_MSGS__BATT_CTRL_EN__OFF = 0x00, //!< Disable battery connection - WD_CMD_MSGS__BATT_CTRL_EN__FORCE_HIGH = 0x99 //!< Force high output on BCTRLE pin -} WdCmdMsgs__SetBattCtrlEnSelection; + /** + * @brief Possible values of the parameter of the Set Battery EN State command. + */ + typedef enum WdCmdMsgs__SetBattEnSelection + { + WD_CMD_MSGS__BATT_EN__ON = 0xFF, //!< Enable battery connection + WD_CMD_MSGS__BATT_EN__OFF = 0x00 //!< Disable battery connection + } WdCmdMsgs__SetBattEnSelection; -/** - * @brief Possible values of the parameter of the Set Battery Control EN State command. - */ -typedef enum WdCmdMsgs__SetLatchBattSelection -{ - WD_CMD_MSGS__LATCH_BATT__ON = 0xFF, //!< Enable battery connection - WD_CMD_MSGS__LATCH_BATT__OFF = 0x00, //!< Disable battery connection - WD_CMD_MSGS__LATCH_BATT__UPDATE = 0xAA//!< Pulse latch low-high-low -} WdCmdMsgs__SetLatchBattSelection; + /** + * @brief Possible values of the parameter of the Set Battery Control EN State command. + */ + typedef enum WdCmdMsgs__SetBattCtrlEnSelection + { + WD_CMD_MSGS__BATT_CTRL_EN__ON = 0xFF, //!< Enable battery connection + WD_CMD_MSGS__BATT_CTRL_EN__OFF = 0x00, //!< Disable battery connection + WD_CMD_MSGS__BATT_CTRL_EN__FORCE_HIGH = 0x99 //!< Force high output on BCTRLE pin + } WdCmdMsgs__SetBattCtrlEnSelection; -/** - * @brief Possible values of the parameter of the Set Battery Control EN State command. - */ -typedef enum WdCmdMsgs__LatchSetResetSelection -{ - WD_CMD_MSGS__LATCH_SET_RESET__OFF = 0x00, //!< - WD_CMD_MSGS__LATCH_SET_RESET__PULSE = 0x15, //!< Pulse high-low-high as an output - WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH = 0xBB, //!< Make an output and drive high - WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW = 0xFF //!< Make an output and drive low -} WdCmdMsgs__LatchSetResetSelection; + /** + * @brief Possible values of the parameter of the Set Battery Control EN State command. + */ + typedef enum WdCmdMsgs__SetLatchBattSelection + { + WD_CMD_MSGS__LATCH_BATT__ON = 0xFF, //!< Enable battery connection + WD_CMD_MSGS__LATCH_BATT__OFF = 0x00, //!< Disable battery connection + WD_CMD_MSGS__LATCH_BATT__UPDATE = 0xAA //!< Pulse latch low-high-low + } WdCmdMsgs__SetLatchBattSelection; -/** - * @brief Possible values of the parameter of the Set Debug Comms State command. - */ -typedef enum WdCmdMsgs__SetDebugCommsSelection -{ - WD_CMD_MSGS__DEBUG_COMMS__ON = 0xFF, //!< Enable Debug Comms - WD_CMD_MSGS__DEBUG_COMMS__OFF = 0x00 //!< Disable Debug Comms -} WdCmdMsgs__SetDebugCommsSelection; + /** + * @brief Possible values of the parameter of the Set Battery Control EN State command. + */ + typedef enum WdCmdMsgs__LatchSetResetSelection + { + WD_CMD_MSGS__LATCH_SET_RESET__OFF = 0x00, //!< + WD_CMD_MSGS__LATCH_SET_RESET__PULSE = 0x15, //!< Pulse high-low-high as an output + WD_CMD_MSGS__LATCH_SET_RESET__FORCE_HIGH = 0xBB, //!< Make an output and drive high + WD_CMD_MSGS__LATCH_SET_RESET__FORCE_LOW = 0xFF //!< Make an output and drive low + } WdCmdMsgs__LatchSetResetSelection; -/** - * @brief Possible values of the parameter of the Set VSAE State command. - */ -typedef enum WdCmdMsgs__SetVSAESelection -{ - WD_CMD_MSGS__VSAE__ON = 0xFF, //!< Enable VSAE - WD_CMD_MSGS__VSAE__OFF = 0x00, //!< Disable VSAE - WD_CMD_MSGS__VSAE__FORCE_LOW = 0x66 //!< Force VSAE low -} WdCmdMsgs__SetVSAESelection; + /** + * @brief Possible values of the parameter of the Set Debug Comms State command. + */ + typedef enum WdCmdMsgs__SetDebugCommsSelection + { + WD_CMD_MSGS__DEBUG_COMMS__ON = 0xFF, //!< Enable Debug Comms + WD_CMD_MSGS__DEBUG_COMMS__OFF = 0x00 //!< Disable Debug Comms + } WdCmdMsgs__SetDebugCommsSelection; -/** - * @brief The magic number that is expected as the parameter of all of the commands that change the mode. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER = 0x77u; + /** + * @brief Possible values of the parameter of the Set VSAE State command. + */ + typedef enum WdCmdMsgs__SetVSAESelection + { + WD_CMD_MSGS__VSAE__ON = 0xFF, //!< Enable VSAE + WD_CMD_MSGS__VSAE__OFF = 0x00, //!< Disable VSAE + WD_CMD_MSGS__VSAE__FORCE_LOW = 0x66 //!< Force VSAE low + } WdCmdMsgs__SetVSAESelection; -/** - * @brief The magic number that is expected as the parameter of the "Prepare to Deploy" and "Deploy" commands. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER = 0x60u; + /** + * @brief The magic number that is expected as the parameter of all of the commands that change the mode. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_MODE_CHANGE_MAGIC_NUMBER = 0x77u; -/** - * @brief The first magic number expected as a parameter of the "Dangerous Force Battery State" command. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_ONE = 0xF0u; + /** + * @brief The magic number that is expected as the parameter of the "Prepare to Deploy" and "Deploy" commands. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_DEPLOYMENT_MAGIC_NUMBER = 0x60u; -/** - * @brief The second magic number expected as a parameter of the "Dangerous Force Battery State" command. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_TWO = 0x01u; + /** + * @brief The first magic number expected as a parameter of the "Dangerous Force Battery State" command. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_ONE = 0xF0u; -/** - * @brief The first magic number expected as a parameter of the "Clear Reset Memory" command. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_ONE = 0xC7u; + /** + * @brief The second magic number expected as a parameter of the "Dangerous Force Battery State" command. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_DANG_FORCE_BATT_STATE_MAGIC_NUMBER_TWO = 0x01u; -/** - * @brief The second magic number expected as a parameter of the "Clear Reset Memory" command. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_TWO = 0x19u; + /** + * @brief The first magic number expected as a parameter of the "Clear Reset Memory" command. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_ONE = 0xC7u; -/** - * @brief The magic number that is expected as the parameter of the "Request Detailed Report" command. - */ -static const uint8_t WD_CMD_MSGS__CONFIRM_REQ_DET_REPORT_MAGIC_NUMBER = 0x57u; + /** + * @brief The second magic number expected as a parameter of the "Clear Reset Memory" command. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_CLR_RST_MEM_MAGIC_NUMBER_TWO = 0x19u; -/** - * @brief The magic number that is expected as the parameter of the "Set Debug Comms State" command. - */ -static const uint8_t WD_CMD_MSGS__SET_DEBUG_COMMS_STATE_MAGIC_NUMBER = 0xCCu; + /** + * @brief The magic number that is expected as the parameter of the "Request Detailed Report" command. + */ + static const uint8_t WD_CMD_MSGS__CONFIRM_REQ_DET_REPORT_MAGIC_NUMBER = 0x57u; -/** - * @brief The magic number that is expected as the parameter of the "Set VSAE State" command. - */ -static const uint8_t WD_CMD_MSGS__SET_VSAE_STATE_MAGIC_NUMBER = 0xBBu; + /** + * @brief The magic number that is expected as the parameter of the "Set Debug Comms State" command. + */ + static const uint8_t WD_CMD_MSGS__SET_DEBUG_COMMS_STATE_MAGIC_NUMBER = 0xCCu; -/** - * @brief The magic number expected as the first byte of the response message. - */ -static const uint8_t WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER = 0x0Au; + /** + * @brief The magic number that is expected as the parameter of the "Set VSAE State" command. + */ + static const uint8_t WD_CMD_MSGS__SET_VSAE_STATE_MAGIC_NUMBER = 0xBBu; -//###################################################################################################################### -// Message Bodies -//###################################################################################################################### + /** + * @brief The magic number expected as the first byte of the response message. + */ + static const uint8_t WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER = 0x0Au; -/** - * @brief The body of a "Reset Specific" command. - */ -typedef struct WdCmdMsgs__MsgBody__ResetSpecific -{ - WdCmdMsgs__ResetSpecificId resetId; //!< The reset value. -} WdCmdMsgs__MsgBody__ResetSpecific; + // ###################################################################################################################### + // Message Bodies + // ###################################################################################################################### -/** - * @brief The body of a "Prepare for Deploy" command. - */ -typedef struct WdCmdMsgs__MsgBody__PrepForDeploy -{ - uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. -} WdCmdMsgs__MsgBody__PrepForDeploy; + /** + * @brief The body of a "Reset Specific" command. + */ + typedef struct WdCmdMsgs__MsgBody__ResetSpecific + { + WdCmdMsgs__ResetSpecificId resetId; //!< The reset value. + } WdCmdMsgs__MsgBody__ResetSpecific; -/** - * @brief The body of a "Deploy" command. - */ -typedef struct WdCmdMsgs__MsgBody__Deploy -{ - uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. -} WdCmdMsgs__MsgBody__Deploy; + /** + * @brief The body of a "Prepare for Deploy" command. + */ + typedef struct WdCmdMsgs__MsgBody__PrepForDeploy + { + uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. + } WdCmdMsgs__MsgBody__PrepForDeploy; -/** - * @brief The body of a "Switch Connection Mode" command. - */ -typedef struct WdCmdMsgs__MsgBody__SwitchConnMode -{ - WdCmdMsgs__SwitchConnModeSelection connMode; //!< The connection mode to switch to. -} WdCmdMsgs__MsgBody__SwitchConnMode; + /** + * @brief The body of a "Deploy" command. + */ + typedef struct WdCmdMsgs__MsgBody__Deploy + { + uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. + } WdCmdMsgs__MsgBody__Deploy; -/** - * @brief The body of a "Set Debug Comms State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetDebugCommsState -{ - uint8_t magic; //!< Must be the expected number to perform this command. - WdCmdMsgs__SetDebugCommsSelection selection; -} WdCmdMsgs__MsgBody__SetDebugCommsState; + /** + * @brief The body of a "Switch Connection Mode" command. + */ + typedef struct WdCmdMsgs__MsgBody__SwitchConnMode + { + WdCmdMsgs__SwitchConnModeSelection connMode; //!< The connection mode to switch to. + } WdCmdMsgs__MsgBody__SwitchConnMode; -/** - * @brief The body of a "Set Auto Heater On Value" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetAutoHeaterOnValue -{ - uint16_t heaterOnValue; //!< The value to use as the automatic heater "on" value. -} WdCmdMsgs__MsgBody__SetAutoHeaterOnValue; + /** + * @brief The body of a "Set Debug Comms State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetDebugCommsState + { + uint8_t magic; //!< Must be the expected number to perform this command. + WdCmdMsgs__SetDebugCommsSelection selection; + } WdCmdMsgs__MsgBody__SetDebugCommsState; -/** - * @brief The body of a "Set Auto Heater Off Value" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetAutoHeaterOffValue -{ - uint16_t heaterOffValue; //!< The value to use as the automatic heater "off" value. -} WdCmdMsgs__MsgBody__SetAutoHeaterOffValue; + /** + * @brief The body of a "Set Auto Heater On Value" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetAutoHeaterOnValue + { + uint16_t heaterOnValue; //!< The value to use as the automatic heater "on" value. + } WdCmdMsgs__MsgBody__SetAutoHeaterOnValue; -/** - * @brief The body of a "Set Heater Duty Cycle Maximum" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetHeaterDutyCycle -{ - uint16_t dutyCycle; //!< The duty cycle value. -} WdCmdMsgs__MsgBody__SetHeaterDutyCycle; + /** + * @brief The body of a "Set Auto Heater Off Value" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetAutoHeaterOffValue + { + uint16_t heaterOffValue; //!< The value to use as the automatic heater "off" value. + } WdCmdMsgs__MsgBody__SetAutoHeaterOffValue; -/** - * @brief The body of a "Set Heater Duty Cycle Period" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod -{ - uint16_t dutyCyclePeriod; //!< The duty cycle period value. -} WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod; + /** + * @brief The body of a "Set Heater Duty Cycle Maximum" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetHeaterDutyCycle + { + uint16_t dutyCycle; //!< The duty cycle value. + } WdCmdMsgs__MsgBody__SetHeaterDutyCycle; -/** - * @brief The body of a "Set Thermister V Setpoint" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetVSAEState -{ - uint8_t magic; //!< Must be the expected number to perform this command. - WdCmdMsgs__SetVSAESelection selection; -} WdCmdMsgs__MsgBody__SetVSAEState; + /** + * @brief The body of a "Set Heater Duty Cycle Period" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod + { + uint16_t dutyCyclePeriod; //!< The duty cycle period value. + } WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod; -/** - * @brief The body of an "Enter Sleep Mode" command. - */ -typedef struct WdCmdMsgs__MsgBody__EnterSleepMode -{ - uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. -} WdCmdMsgs__MsgBody__EnterSleepMode; + /** + * @brief The body of a "Set Thermister V Setpoint" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetVSAEState + { + uint8_t magic; //!< Must be the expected number to perform this command. + WdCmdMsgs__SetVSAESelection selection; + } WdCmdMsgs__MsgBody__SetVSAEState; -/** - * @brief The body of an "Enter Keep Alive Mode" command. - */ -typedef struct WdCmdMsgs__MsgBody__EnterKeepAliveMode -{ - uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. -} WdCmdMsgs__MsgBody__EnterKeepAliveMode; + /** + * @brief The body of an "Enter Sleep Mode" command. + */ + typedef struct WdCmdMsgs__MsgBody__EnterSleepMode + { + uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. + } WdCmdMsgs__MsgBody__EnterSleepMode; -/** - * @brief The body of an "Enter Service Mode" command. - */ -typedef struct WdCmdMsgs__MsgBody__EnterServiceMode -{ - uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. -} WdCmdMsgs__MsgBody__EnterServiceMode; + /** + * @brief The body of an "Enter Keep Alive Mode" command. + */ + typedef struct WdCmdMsgs__MsgBody__EnterKeepAliveMode + { + uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. + } WdCmdMsgs__MsgBody__EnterKeepAliveMode; -/** - * @brief The body of an "Dangerous Force Battery State" command. - */ -typedef struct WdCmdMsgs__MsgBody__DangForceBattState -{ - uint8_t confirmationMagicNumberOne; //!< Must be the first expected magic number for this command to be performed. - uint8_t confirmationMagicNumberTwo; //!< Must be the second expected magic number for this command to be performed. - WdCmdMsgs__DangForceBattStateSelection state; //!< The state to force. -} WdCmdMsgs__MsgBody__DangForceBattState; + /** + * @brief The body of an "Enter Service Mode" command. + */ + typedef struct WdCmdMsgs__MsgBody__EnterServiceMode + { + uint8_t confirmationMagicNumber; //!< Must be the expected magic number for this command to be performed. + } WdCmdMsgs__MsgBody__EnterServiceMode; -/** - * @brief The body of an "Set Charge En State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetChargeEnState -{ - WdCmdMsgs__SetChargeEnSelection selection; //!< The charge enable state to be set. -} WdCmdMsgs__MsgBody__SetChargeEnState; + /** + * @brief The body of an "Dangerous Force Battery State" command. + */ + typedef struct WdCmdMsgs__MsgBody__DangForceBattState + { + uint8_t confirmationMagicNumberOne; //!< Must be the first expected magic number for this command to be performed. + uint8_t confirmationMagicNumberTwo; //!< Must be the second expected magic number for this command to be performed. + WdCmdMsgs__DangForceBattStateSelection state; //!< The state to force. + } WdCmdMsgs__MsgBody__DangForceBattState; -/** - * @brief The body of an "Set Charge Reg En State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetChargeRegEnState -{ - WdCmdMsgs__SetChargeRegEnSelection selection; //!< The charge regulator enable state to be set. -} WdCmdMsgs__MsgBody__SetChargeRegEnState; + /** + * @brief The body of an "Set Charge En State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetChargeEnState + { + WdCmdMsgs__SetChargeEnSelection selection; //!< The charge enable state to be set. + } WdCmdMsgs__MsgBody__SetChargeEnState; -/** - * @brief The body of an "Set Batt En State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetBattEnState -{ - WdCmdMsgs__SetBattEnSelection selection; //!< The battery enable state to be set. -} WdCmdMsgs__MsgBody__SetBattEnState; + /** + * @brief The body of an "Set Charge Reg En State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetChargeRegEnState + { + WdCmdMsgs__SetChargeRegEnSelection selection; //!< The charge regulator enable state to be set. + } WdCmdMsgs__MsgBody__SetChargeRegEnState; -/** - * @brief The body of an "Set Batt Ctrl En State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetBattCtrlEnState -{ - WdCmdMsgs__SetBattCtrlEnSelection selection; //!< The battery control enable state to be set. -} WdCmdMsgs__MsgBody__SetBattCtrlEnState; + /** + * @brief The body of an "Set Batt En State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetBattEnState + { + WdCmdMsgs__SetBattEnSelection selection; //!< The battery enable state to be set. + } WdCmdMsgs__MsgBody__SetBattEnState; -/** - * @brief The body of an "Set Latch Batt State" command. - */ -typedef struct WdCmdMsgs__MsgBody__SetLatchBattState -{ - WdCmdMsgs__SetLatchBattSelection selection; //!< The latch battery state to be set. -} WdCmdMsgs__MsgBody__SetLatchBattState; + /** + * @brief The body of an "Set Batt Ctrl En State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetBattCtrlEnState + { + WdCmdMsgs__SetBattCtrlEnSelection selection; //!< The battery control enable state to be set. + } WdCmdMsgs__MsgBody__SetBattCtrlEnState; -/** - * @brief The body of an "Latch Set Pulse Low" command. - */ -typedef struct WdCmdMsgs__MsgBody__LatchSetPulseLow -{ + /** + * @brief The body of an "Set Latch Batt State" command. + */ + typedef struct WdCmdMsgs__MsgBody__SetLatchBattState + { + WdCmdMsgs__SetLatchBattSelection selection; //!< The latch battery state to be set. + } WdCmdMsgs__MsgBody__SetLatchBattState; + + /** + * @brief The body of an "Latch Set Pulse Low" command. + */ + typedef struct WdCmdMsgs__MsgBody__LatchSetPulseLow + { WdCmdMsgs__LatchSetResetSelection selection; //!< The latch set state to be set. -} WdCmdMsgs__MsgBody__LatchSetPulseLow; + } WdCmdMsgs__MsgBody__LatchSetPulseLow; -/** - * @brief The body of an "Latch Reset Pulse Low" command. - */ -typedef struct WdCmdMsgs__MsgBody__LatchResetPulseLow -{ + /** + * @brief The body of an "Latch Reset Pulse Low" command. + */ + typedef struct WdCmdMsgs__MsgBody__LatchResetPulseLow + { WdCmdMsgs__LatchSetResetSelection selection; //!< The latch reset state to be set. -} WdCmdMsgs__MsgBody__LatchResetPulseLow; + } WdCmdMsgs__MsgBody__LatchResetPulseLow; -/** - * @brief The body of an "Clear Reset Memory" command. - */ -typedef struct WdCmdMsgs__MsgBody__ClearResetMemory -{ - uint8_t magicOne; - uint8_t magicTwo; -} WdCmdMsgs__MsgBody__ClearResetMemory; + /** + * @brief The body of an "Clear Reset Memory" command. + */ + typedef struct WdCmdMsgs__MsgBody__ClearResetMemory + { + uint8_t magicOne; + uint8_t magicTwo; + } WdCmdMsgs__MsgBody__ClearResetMemory; /** * @brief The body of an "Echo" command. */ #define MAX_ECHO_LENGTH 10 -typedef struct WdCmdMsgs__MsgBody__Echo -{ + typedef struct WdCmdMsgs__MsgBody__Echo + { - uint8_t numBytesToEcho; - uint8_t bytesToEcho[MAX_ECHO_LENGTH]; // allocate max space so we don't have to malloc and free it -} WdCmdMsgs__MsgBody__Echo; - -/** - * @brief The body of an "Request Detailed Report" command. - */ -typedef struct WdCmdMsgs__MsgBody__RequestDetailedReport -{ - uint8_t magic; -} WdCmdMsgs__MsgBody__RequestDetailedReport; + uint8_t numBytesToEcho; + uint8_t bytesToEcho[MAX_ECHO_LENGTH]; // allocate max space so we don't have to malloc and free it + } WdCmdMsgs__MsgBody__Echo; -//###################################################################################################################### -// Overall Message Structure -//###################################################################################################################### + /** + * @brief The body of an "Request Detailed Report" command. + */ + typedef struct WdCmdMsgs__MsgBody__RequestDetailedReport + { + uint8_t magic; + } WdCmdMsgs__MsgBody__RequestDetailedReport; -/** - * @brief A union of all message bodies. - * - * Only the body that corresponds to the command ID of a given command should be accessed. - */ -typedef union -{ - WdCmdMsgs__MsgBody__ResetSpecific resetSpecific; - WdCmdMsgs__MsgBody__PrepForDeploy prepForDeploy; - WdCmdMsgs__MsgBody__Deploy deploy; - WdCmdMsgs__MsgBody__SwitchConnMode switchConnMode; - WdCmdMsgs__MsgBody__SetDebugCommsState setDebugCommsState; - WdCmdMsgs__MsgBody__SetAutoHeaterOnValue setAutoHeaterOnValue; - WdCmdMsgs__MsgBody__SetAutoHeaterOffValue setAutoHeaterOffValue; - WdCmdMsgs__MsgBody__SetHeaterDutyCycle setHeaterDutyCycle; - WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod setHeaterDutyCyclePeriod; - WdCmdMsgs__MsgBody__SetVSAEState setVSAEState; - WdCmdMsgs__MsgBody__EnterSleepMode enterSleepMode; - WdCmdMsgs__MsgBody__EnterKeepAliveMode enterKeepAliveMode; - WdCmdMsgs__MsgBody__EnterServiceMode enterServiceMode; - WdCmdMsgs__MsgBody__DangForceBattState dangForceBattState; - WdCmdMsgs__MsgBody__SetChargeEnState setChargeEnState; - WdCmdMsgs__MsgBody__SetChargeRegEnState setChargeRegEnState; - WdCmdMsgs__MsgBody__SetBattEnState setBattEnState; - WdCmdMsgs__MsgBody__SetBattCtrlEnState setBattCtrlEnState; - WdCmdMsgs__MsgBody__SetLatchBattState setLatchBattState; - WdCmdMsgs__MsgBody__LatchSetPulseLow latchSetPulseLow; - WdCmdMsgs__MsgBody__LatchResetPulseLow latchResetPulseLow; - WdCmdMsgs__MsgBody__ClearResetMemory clearResetMem; - WdCmdMsgs__MsgBody__Echo echo; - WdCmdMsgs__MsgBody__RequestDetailedReport reqDetReport; -} WdCmdMsgs__MessageBody; + // ###################################################################################################################### + // Overall Message Structure + // ###################################################################################################################### -/** - * @brief A watchdog command message. - */ -typedef struct WdCmdMsgs__Message -{ - CmdMsgs__CommonHeader commonHeader; //!< The FSW common header. - WdCmdMsgs__CommandId commandId; //!< The command ID. - WdCmdMsgs__MessageBody body; //!< The message body, if `commandId` is a message with a parameter. -} WdCmdMsgs__Message; + /** + * @brief A union of all message bodies. + * + * Only the body that corresponds to the command ID of a given command should be accessed. + */ + typedef union + { + WdCmdMsgs__MsgBody__ResetSpecific resetSpecific; + WdCmdMsgs__MsgBody__PrepForDeploy prepForDeploy; + WdCmdMsgs__MsgBody__Deploy deploy; + WdCmdMsgs__MsgBody__SwitchConnMode switchConnMode; + WdCmdMsgs__MsgBody__SetDebugCommsState setDebugCommsState; + WdCmdMsgs__MsgBody__SetAutoHeaterOnValue setAutoHeaterOnValue; + WdCmdMsgs__MsgBody__SetAutoHeaterOffValue setAutoHeaterOffValue; + WdCmdMsgs__MsgBody__SetHeaterDutyCycle setHeaterDutyCycle; + WdCmdMsgs__MsgBody__SetHeaterDutyCyclePeriod setHeaterDutyCyclePeriod; + WdCmdMsgs__MsgBody__SetVSAEState setVSAEState; + WdCmdMsgs__MsgBody__EnterSleepMode enterSleepMode; + WdCmdMsgs__MsgBody__EnterKeepAliveMode enterKeepAliveMode; + WdCmdMsgs__MsgBody__EnterServiceMode enterServiceMode; + WdCmdMsgs__MsgBody__DangForceBattState dangForceBattState; + WdCmdMsgs__MsgBody__SetChargeEnState setChargeEnState; + WdCmdMsgs__MsgBody__SetChargeRegEnState setChargeRegEnState; + WdCmdMsgs__MsgBody__SetBattEnState setBattEnState; + WdCmdMsgs__MsgBody__SetBattCtrlEnState setBattCtrlEnState; + WdCmdMsgs__MsgBody__SetLatchBattState setLatchBattState; + WdCmdMsgs__MsgBody__LatchSetPulseLow latchSetPulseLow; + WdCmdMsgs__MsgBody__LatchResetPulseLow latchResetPulseLow; + WdCmdMsgs__MsgBody__ClearResetMemory clearResetMem; + WdCmdMsgs__MsgBody__Echo echo; + WdCmdMsgs__MsgBody__RequestDetailedReport reqDetReport; + } WdCmdMsgs__MessageBody; -/** - * @brief A watchdog command response message. - */ -typedef struct WdCmdMsgs__Response -{ - uint8_t magicNumber; //!< Should always be set to `WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER`. - WdCmdMsgs__CommandId commandId; //!< The command ID of the message to which this is a response. - WdCmdMsgs__ResponseStatusCode statusCode; //!< The status of performing the message to which this is a reponse. -} WdCmdMsgs__Response; + /** + * @brief A watchdog command message. + */ + typedef struct WdCmdMsgs__Message + { + CmdMsgs__CommonHeader commonHeader; //!< The FSW common header. + WdCmdMsgs__CommandId commandId; //!< The command ID. + WdCmdMsgs__MessageBody body; //!< The message body, if `commandId` is a message with a parameter. + } WdCmdMsgs__Message; -//###################################################################################################################### -// Packed Sizes -//###################################################################################################################### + /** + * @brief A watchdog command response message. + */ + typedef struct WdCmdMsgs__Response + { + uint8_t magicNumber; //!< Should always be set to `WD_CMD_MSGS__RESPONSE_MAGIC_NUMBER`. + WdCmdMsgs__CommandId commandId; //!< The command ID of the message to which this is a response. + WdCmdMsgs__ResponseStatusCode statusCode; //!< The status of performing the message to which this is a reponse. + } WdCmdMsgs__Response; -/** - * @brief The packed sizes of the body and full message for the various command types as well as the command response. - */ -typedef enum WdCmdMsgs__PackedSize -{ - WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER = CMD_MSGS__PACKED_SIZE__COMMON_HEADER, - - // Bodies - - WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__DEPLOY_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_BODY = sizeof(uint16_t), - WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_BODY = 3 * sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_BODY = sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_BODY = 2 * sizeof(uint8_t), - WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_BODY = sizeof(uint8_t) + MAX_ECHO_LENGTH, // largest possible size - WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_BODY = sizeof(uint8_t), - - - // Full Messages - - WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG = (3 * sizeof(uint8_t)), - - WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_BODY, - WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_BODY, - WD_CMD_MSGS__PACKED_SIZE__DEPLOY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__DEPLOY_BODY, - WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_BODY, - WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_BODY, - WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_BODY, - WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_BODY, - WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_BODY, - WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_BODY, - WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_BODY, - WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_BODY, // maximum possible size - WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_BODY, - - WD_CMD_MSGS__PACKED_SIZE__SMALLEST_MSG = WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_MSG, - WD_CMD_MSGS__PACKED_SIZE__LARGEST_MSG = (WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG > WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG) ? WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG : WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG -} WdCmdMsgs__PackedSize; - -//###################################################################################################################### -// Message Serialization and Deserialization Functions -//###################################################################################################################### + // ###################################################################################################################### + // Packed Sizes + // ###################################################################################################################### + /** + * @brief The packed sizes of the body and full message for the various command types as well as the command response. + */ + typedef enum WdCmdMsgs__PackedSize + { + WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER = CMD_MSGS__PACKED_SIZE__COMMON_HEADER, + + // Bodies + + WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__DEPLOY_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_BODY = sizeof(uint16_t), + WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_BODY = 3 * sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_BODY = sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_BODY = 2 * sizeof(uint8_t), + WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_BODY = sizeof(uint8_t) + MAX_ECHO_LENGTH, // largest possible size + WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_BODY = sizeof(uint8_t), + + // Full Messages + + WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG = (3 * sizeof(uint8_t)), + + WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_BODY, + WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__PREP_FOR_DEPLOY_BODY, + WD_CMD_MSGS__PACKED_SIZE__DEPLOY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__DEPLOY_BODY, + WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SWITCH_CONN_MODE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_DEBUG_COMMS_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_ON_VALUE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_AUTO_HEATER_OFF_VALUE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_HEATER_DUTY_CYCLE_PERIOD_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_VSAE_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_SLEEP_MODE_BODY, + WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_KEEPALIVE_MODE_BODY, + WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ENTER_SERVICE_MODE_BODY, + WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_EN_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_CHARGE_REG_EN_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_EN_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_BATT_CTRL_EN_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__SET_LATCH_BATT_STATE_BODY, + WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__LATCH_SET_PULSE_LOW_BODY, + WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__LATCH_RESET_PULSE_LOW_BODY, + WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__CLEAR_RESET_MEMORY_BODY, + WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_BODY, // maximum possible size + WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_MSG = WD_CMD_MSGS__PACKED_SIZE__COMMON_HEADER + sizeof(uint16_t) + WD_CMD_MSGS__PACKED_SIZE__REQUEST_DETAILED_REPORT_BODY, + + WD_CMD_MSGS__PACKED_SIZE__SMALLEST_MSG = WD_CMD_MSGS__PACKED_SIZE__RESET_SPECIFIC_MSG, + WD_CMD_MSGS__PACKED_SIZE__LARGEST_MSG = (WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG > WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG) ? WD_CMD_MSGS__PACKED_SIZE__ECHO_MAX_MSG : WD_CMD_MSGS__PACKED_SIZE__DANG_FORCE_BATT_STATE_MSG + } WdCmdMsgs__PackedSize; + + // ###################################################################################################################### + // Message Serialization and Deserialization Functions + // ###################################################################################################################### -/** - * @brief Serializes the message in `src` with system endianness into the buffer `dst` with little endianness. - * - * @param src [IN] The response to be serialized. - * @param dst [OUT] The buffer into which the message will be serialized. Must have a large enough size, as determined - * by the value of `dstLen`, of at least WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG bytes. - * @param dstLen [IN] The length of the buffer pointed to by `dst`. - * - * @return One of the following: - * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. - * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. - * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `dst` was too small to hold the serialized message. - * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. - */ -WdCmdMsgs__Status WdCmdMsgs__serializeGroundResponse(const WdCmdMsgs__Response* src, - void* dst, - size_t dstLen); + /** + * @brief Serializes the message in `src` with system endianness into the buffer `dst` with little endianness. + * + * @param src [IN] The response to be serialized. + * @param dst [OUT] The buffer into which the message will be serialized. Must have a large enough size, as determined + * by the value of `dstLen`, of at least WD_CMD_MSGS__PACKED_SIZE__RESPONSE_MSG bytes. + * @param dstLen [IN] The length of the buffer pointed to by `dst`. + * + * @return One of the following: + * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. + * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. + * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `dst` was too small to hold the serialized message. + * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. + */ + WdCmdMsgs__Status WdCmdMsgs__serializeGroundResponse(const WdCmdMsgs__Response *src, + void *dst, + size_t dstLen); -/** - * @brief Deserializes the message body packed in `src` with little endianness into the struct `dst` with system - * endianness. - * - * The type of body in `src` is determined by `srcMsgId`. - * - * @param srcMsgId [IN] The message ID of the message body type packed in `src`. - * @param src [IN] The buffer containing the packed message body to be deserialized. Must have a size, as determined - * by the value of `srcLen`, that is large enough to fit the message body with the type specified by - * `srcMsgId`. The exact size required varies based on the type of the message body. - * @param srcLen [IN] The length of the buffer pointed to by `src`. - * @param dst [OUT] The struct into which the message body will be deserialized. - * - * @return One of the following: - * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. - * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. - * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `srcLen` was too small to hold the message body. - * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. - */ -WdCmdMsgs__Status -WdCmdMsgs__deserializeBody(WdCmdMsgs__CommandId srcMsgId, - const void* src, - size_t srcLen, - WdCmdMsgs__MessageBody* dst); + /** + * @brief Deserializes the message body packed in `src` with little endianness into the struct `dst` with system + * endianness. + * + * The type of body in `src` is determined by `srcMsgId`. + * + * @param srcMsgId [IN] The message ID of the message body type packed in `src`. + * @param src [IN] The buffer containing the packed message body to be deserialized. Must have a size, as determined + * by the value of `srcLen`, that is large enough to fit the message body with the type specified by + * `srcMsgId`. The exact size required varies based on the type of the message body. + * @param srcLen [IN] The length of the buffer pointed to by `src`. + * @param dst [OUT] The struct into which the message body will be deserialized. + * + * @return One of the following: + * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. + * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. + * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `srcLen` was too small to hold the message body. + * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. + */ + WdCmdMsgs__Status + WdCmdMsgs__deserializeBody(WdCmdMsgs__CommandId srcMsgId, + const void *src, + size_t srcLen, + WdCmdMsgs__MessageBody *dst); -/** - * @brief Deserializes the message packed in `src` with little endianness into the struct `dst` with system endianness. - * - * @param src [IN] The buffer containing the packed message to be deserialized. Must have a size, as determined by the - * value of `srcLen`, that is large enough to fit a message header and the message body whose type is - * specified in the message header. The exact size required varies based on the type of the message. At - * a minimum it must be WD_CMD_MSGS__PACKED_SIZE__SMALLEST_MSG, but it may need to be as large as - * WD_CMD_MSGS__PACKED_SIZE__LARGEST_MSG. - * @param srcLen [IN] The length of the buffer pointed to by `src`. - * @param dst [OUT] The struct into which the message will be deserialized. - * @param deserializeHeader [IN] Whether or not to deserialize the header into `dst->commonHeader`. This can be set to - * false if (for instance) the command header has already been deserialized prior to calling - * this function. - * - * @return One of the following: - * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. - * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. - * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `srcLen` was too small to hold the message. - * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. - */ -WdCmdMsgs__Status -WdCmdMsgs__deserializeMessage(const void* src, - size_t srcLen, - WdCmdMsgs__Message* dst, - BOOL deserializeHeader); + /** + * @brief Deserializes the message packed in `src` with little endianness into the struct `dst` with system endianness. + * + * @param src [IN] The buffer containing the packed message to be deserialized. Must have a size, as determined by the + * value of `srcLen`, that is large enough to fit a message header and the message body whose type is + * specified in the message header. The exact size required varies based on the type of the message. At + * a minimum it must be WD_CMD_MSGS__PACKED_SIZE__SMALLEST_MSG, but it may need to be as large as + * WD_CMD_MSGS__PACKED_SIZE__LARGEST_MSG. + * @param srcLen [IN] The length of the buffer pointed to by `src`. + * @param dst [OUT] The struct into which the message will be deserialized. + * @param deserializeHeader [IN] Whether or not to deserialize the header into `dst->commonHeader`. This can be set to + * false if (for instance) the command header has already been deserialized prior to calling + * this function. + * + * @return One of the following: + * - WD_CMD_MSGS__STATUS__SUCCESS: The function was successful. + * - WD_CMD_MSGS__STATUS__ERROR_NULL: `src` or `dst` was NULL. + * - WD_CMD_MSGS__STATUS__ERROR_BUFFER_TOO_SMALL: `srcLen` was too small to hold the message. + * - WD_CMD_MSGS__STATUS__ERROR_SERIALIZATION_ERROR: A Serialization function call returned an error. + */ + WdCmdMsgs__Status + WdCmdMsgs__deserializeMessage(const void *src, + size_t srcLen, + WdCmdMsgs__Message *dst, + BOOL deserializeHeader); -/** - * @} - */ + /** + * @} + */ #ifdef __cplusplus } /* close extern "C" */ diff --git a/Apps/FlightSoftware/Watchdog/include/flags.h b/Apps/FlightSoftware/Watchdog/include/flags.h index f4fd9d256..00d04c516 100644 --- a/Apps/FlightSoftware/Watchdog/include/flags.h +++ b/Apps/FlightSoftware/Watchdog/include/flags.h @@ -41,6 +41,25 @@ extern "C" #define ENTER_DEFAULT_LPM LPM1 #define EXIT_DEFAULT_LPM LPM1_EXIT + typedef enum Heater_ForceState + { + // force the heater to always be on or off (at whatever duty) + // - using specific enums to make it hard to be bitflipped + // into this state. + HEATER_FORCE_ALWAYS_ON = 0xAA, // heater always ON + HEATER_FORCE_ALWAYS_OFF = 0x55, // heater always OFF + HEATER_FORCE_NOTHING = 0xFF // let heater control do its thing + } Heater_ForceState; + + typedef enum HeaterControl_InputSource + { + // force the heater to always be on or off (at whatever duty) + // - using specific enums to make it hard to be bitflipped + // into this state. + HEATER_CONTROL_INPUT_BATT_RT = 0xAA, // Use Normal Battery RT Thermistor (Default) + HEATER_CONTROL_INPUT_CHARGER = 0x55, // Power up the Charging IC, Don't Charge, and use the Charging Thermistor (only as a last ditch effort) + } HeaterControl_InputSource; + typedef struct HeaterParams { uint16_t m_kpHeater; @@ -53,7 +72,9 @@ extern "C" BOOL m_heatingControlEnabled; uint16_t m_heaterDutyCyclePeriod; uint16_t m_heaterDutyCycle; - BOOL m_thresholdsChanged; // flag that the on or off thresholds have changed since they were last checked + BOOL m_thresholdsChanged; // flag that the on or off thresholds have changed since they were last checked + Heater_ForceState m_forceState; // force the heater to always be on or off (at whatever duty) - using specific enums to make it hard to be bitflipped into this state. + HeaterControl_InputSource m_inputSource; // what sensor should drive the heater controller (note, changing this should be accompanied by changing thresholds) } HeaterParams; #define DEFAULT_KP_HEATER 500 // deprecated diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 4f6ea132a..4c79f1505 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -253,9 +253,37 @@ namespace iris void RoverStateBase::heaterControl(RoverContext &theContext) { - unsigned short thermReading = theContext.m_adcValues.battRT; HeaterParams &hParams = theContext.m_details.m_hParams; + unsigned short thermReading; + if (m_hParams.m_inputSource == HEATER_CONTROL_INPUT_CHARGER) + { + thermReading = theContext.m_adcValues.battTherm; + } + else + { + // Default case (in case of bitflips, etc.), use normal thermistor: + thermReading = theContext.m_adcValues.battRT; + } + // Process force states and eject early (nothing more to do): + if (hParams.m_forceState == HEATER_FORCE_ALWAYS_ON) + { + if (!hParams.m_heating) + { + enableHeater(); + } + return; + } + else if (hParams.m_forceState == HEATER_FORCE_ALWAYS_OFF) + { + if (hParams.m_heating) + { + disableHeater(); + } + return; + } + + // Check for threshold changes that need to be handled first: if (hParams.m_thresholdsChanged) { // Ground operators changed the thresholds. Re-evaluate against @@ -280,11 +308,14 @@ namespace iris hParams.m_thresholdsChanged = false; } - // Check for failure cases, in which case, turn the heater on: + // Check for failure cases, in which case, turn the heater ON: if (thermReading < 5) { // if the sensor is giving an ADC reading of basically 0, we - // probably have an open circuit. For safety, enable the heater: + // probably have an open circuit (at max T for the thermistor + // (+155C), we only go as low as ~45). + // For safety, enable the heater (unless told explicitly not to do + // so via a force state): if (!hParams.m_heating) { // Let Earth know we're turning on the Heat (this might be during an LOS): @@ -300,7 +331,7 @@ namespace iris // In the HEATER_ON state... if (thermReading < hParams.m_heaterOffVal) { - // transition to HEATER_OFF + // if we should turn OFF and we're not being forced ON, transition to HEATER_OFF // Start heating when temperature rises high enough, which we detect via the ADC reading falling below a // configured (either via the default value or a value commanded from ground) ADC reading. disableHeater(); @@ -311,7 +342,7 @@ namespace iris // In the HEATER_OFF state... if (thermReading > hParams.m_heaterOnVal) { - // transition to HEATER_ON + // if we should turn ON and we're not being forced OFF, transition to HEATER_ON // Start heating when temperature drops low enough, which we detect via the ADC reading rising above a // configured (either via the default value or a value commanded from ground) ADC reading. enableHeater(); @@ -1803,6 +1834,53 @@ namespace iris SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__AUTO_HEATER_CONTROLLER_DISABLE); break; + case WD_CMD_MSGS__RESET_ID__HEATER_FORCE_OFF: + theContext.m_details.m_hParams.m_forceState = HEATER_FORCE_ALWAYS_OFF; + disableHeater(); + break; + case WD_CMD_MSGS__RESET_ID__HEATER_FORCE_ON: + theContext.m_details.m_hParams.m_forceState = HEATER_FORCE_ALWAYS_ON; + enableHeater(); + break; + case WD_CMD_MSGS__RESET_ID__HEATER_FORCE_NOTHING: + theContext.m_details.m_hParams.m_forceState = HEATER_FORCE_NOTHING; + break; + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_RT_INPUT: + theContext.m_details.m_hParams.m_inputSource = HEATER_CONTROL_INPUT_BATT_RT; + break; + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT_DEACTIVATE: + // Disable charger circuitry so we can return to normal: + blimp_regEnOff(); + blimp_chargerEnOff(); + blimp_battEnOff(); + break; + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT_ACTIVATE: + // Assert that charging should not happen: + blimp_chargerEnOff(); + // Turn on (but don't latch) the batteries (might be unsafe to turn + // on charger without the batteries connected, even with CE=OFF... + // need to test on SBC with BLiMP to determine). + // NOTE: So long as lander power is supplied, this shouldn't do + // anything since everything will be powered off lander power before + // battery power and since the batteries won't be latched, once + // lander power is removed, they should power back off. + blimp_battEnOn(); + // Then power up the charging regulator so the charging IC can + // create the VREF used by the charging TS: + // (unfortunately we can't just use an internal pullup with the ADC + // on the MSP430 so we have to do this this way) + blimp_regEnOn(); + // NOTE: Even if CE=OFF fails for some reason, if the batteries + // were to remain disconnected, charging wouldn't be able to + // happen (and this open circuit shouldn't cause an issue for the + // battery charging IC b/c it has over-voltage protection to handle + // a battery/load disconnect case). + break; + case WD_CMD_MSGS__RESET_ID__AUTO_HEATER_CONTROLLER_USE_CHARGER_INPUT: + // Just set the input source, don't change the circuitry (this might + // be desirable and lets us arm before actually messing with the circuitry): + theContext.m_details.m_hParams.m_inputSource = HEATER_CONTROL_INPUT_CHARGER; + break; case WD_CMD_MSGS__RESET_ID__HERCULES_WATCHDOG_ENABLE: theContext.m_watchdogOpts |= WDOPT_MONITOR_HERCULES; SET_RABI_IN_UINT(theContext.m_details.m_resetActionBits, RABI__HERCULES_WATCHDOG_ENABLE); diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp index 06d2c401d..5d753b62b 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateManager.cpp @@ -75,6 +75,8 @@ namespace iris m_context.m_details.m_hParams.m_heaterDutyCyclePeriod = DEFAULT_HEATER_DUTY_CYCLE_PERIOD; m_context.m_details.m_hParams.m_heaterDutyCycle = DEFAULT_HEATER_DUTY_CYCLE; m_context.m_details.m_hParams.m_thresholdsChanged = true; + m_context.m_details.m_hParams.m_forceState = HEATER_FORCE_NOTHING; + m_context.m_details.m_hParams.m_inputSource = HEATER_CONTROL_INPUT_BATT_RT; m_context.m_details.m_stateAsUint = static_cast(RoverState::ENTERING_KEEP_ALIVE); m_context.m_details.m_inputPinAndStateBits = 0; m_context.m_details.m_outputPinBits = 0; diff --git a/Apps/FlightSoftware/fprime/CubeRover/WatchDogInterface/WatchDogInterfaceComponentAi.xml b/Apps/FlightSoftware/fprime/CubeRover/WatchDogInterface/WatchDogInterfaceComponentAi.xml index 24178f921..a60956ff1 100644 --- a/Apps/FlightSoftware/fprime/CubeRover/WatchDogInterface/WatchDogInterfaceComponentAi.xml +++ b/Apps/FlightSoftware/fprime/CubeRover/WatchDogInterface/WatchDogInterfaceComponentAi.xml @@ -118,8 +118,15 @@ - - + + + + + + + + + From aed55753c20feab782b6eb98fddfc7a46aa1a51a Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Sun, 1 Jan 2023 06:09:45 -0500 Subject: [PATCH 34/39] WD: Fixed compilation issues with recent heater control changes. --- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 4c79f1505..5bce5c07d 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -255,9 +255,9 @@ namespace iris { HeaterParams &hParams = theContext.m_details.m_hParams; unsigned short thermReading; - if (m_hParams.m_inputSource == HEATER_CONTROL_INPUT_CHARGER) + if (hParams.m_inputSource == HEATER_CONTROL_INPUT_CHARGER) { - thermReading = theContext.m_adcValues.battTherm; + thermReading = theContext.m_adcValues.battTemp; } else { From f15090de14571f820fd0b20d308badddd03d9157 Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Sun, 1 Jan 2023 06:23:09 -0500 Subject: [PATCH 35/39] WD: Added extra catch to thermistor fault detection. --- .../Watchdog/src/stateMachine/RoverStateBase.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp index 5bce5c07d..5ccc131f9 100644 --- a/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp +++ b/Apps/FlightSoftware/Watchdog/src/stateMachine/RoverStateBase.cpp @@ -9,6 +9,7 @@ #include "drivers/uart.h" #include "event/event.h" #include "event/event_queue.h" +#include "utils/time.h" #include "comms/ground_msgs.h" #include "watchdog.h" @@ -309,11 +310,14 @@ namespace iris } // Check for failure cases, in which case, turn the heater ON: - if (thermReading < 5) + if (thermReading < 5 && Time__getTimeInCentiseconds() > 6000) { // if the sensor is giving an ADC reading of basically 0, we // probably have an open circuit (at max T for the thermistor // (+155C), we only go as low as ~45). + // NOTE: We provide a 60s grace period for everything to initialize. + // This is way longer than necessary but it's relatively short on + // thermal time-scales so this is fine. // For safety, enable the heater (unless told explicitly not to do // so via a force state): if (!hParams.m_heating) From 6bb52083a0b8ebbbb852484c40d3ad64f72e0965 Mon Sep 17 00:00:00 2001 From: zCoCo Date: Sun, 1 Jan 2023 06:58:39 -0500 Subject: [PATCH 36/39] WD: Tested (and verified) heater power level, ctrl on/off, heater force on/off, and on/off level commands. --- Apps/GroundSoftware/__command_aliases.py | 37 ++++++++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/Apps/GroundSoftware/__command_aliases.py b/Apps/GroundSoftware/__command_aliases.py index ea817bb2c..6faac99ff 100644 --- a/Apps/GroundSoftware/__command_aliases.py +++ b/Apps/GroundSoftware/__command_aliases.py @@ -525,6 +525,43 @@ class Parameter(Enum): DataPathway.WIRED ), + 'heater-force-off': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_ResetSpecific', + OrderedDict(reset_value='HEATER_FORCE_OFF'), + DataPathway.WIRED + ), + 'heater-force-on': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_ResetSpecific', + OrderedDict(reset_value='HEATER_FORCE_ON'), + DataPathway.WIRED + ), + 'heater-force-nothing': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_ResetSpecific', + OrderedDict(reset_value='HEATER_FORCE_NOTHING'), + DataPathway.WIRED + ), + + 'set-heater-on-level': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetAutoHeaterOnValue', + OrderedDict(on=4000), + DataPathway.WIRED + ), + 'set-heater-off-level': ( + DataPathway.WIRED, + Magic.WATCHDOG_COMMAND, + 'WatchDogInterface_SetAutoHeaterOffValue', + OrderedDict(off=1500), + DataPathway.WIRED + ), + From 3a1c8642afebb4a7b4957bf59afc7fb5c9007ae4 Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Mon, 2 Jan 2023 08:12:56 -0500 Subject: [PATCH 37/39] RC7+WD: Updated heater on/off threshold values. --- Apps/FlightSoftware/Watchdog/include/flags.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Apps/FlightSoftware/Watchdog/include/flags.h b/Apps/FlightSoftware/Watchdog/include/flags.h index 00d04c516..6669b76f0 100644 --- a/Apps/FlightSoftware/Watchdog/include/flags.h +++ b/Apps/FlightSoftware/Watchdog/include/flags.h @@ -82,9 +82,9 @@ extern "C" #define DEFAULT_HEATER_SETPOINT 3325 // deprecated #define DEFAULT_HEATER_WINDOW 60 // deprecated // 3670 is the -5 deg C thermistor voltage ADC reading - heater transitions to ON when T ADC < this value: -#define DEFAULT_HEATER_ON_VAL 3670 +#define DEFAULT_HEATER_ON_VAL 2781 // 3670 is the 0 deg C thermistor voltage ADC reading - heater transitions to OFF when T ADC > this value: -#define DEFAULT_HEATER_OFF_VAL 3352 +#define DEFAULT_HEATER_OFF_VAL 2291 #define DEFAULT_HEATING_CONTROL_ENABLED TRUE #define DEFAULT_HEATER_DUTY_CYCLE_PERIOD 10000 #define DEFAULT_HEATER_DUTY_CYCLE 8500 From ef092b1352f1790ef47653cc9a4bf745459e985f Mon Sep 17 00:00:00 2001 From: zCoCo Date: Mon, 2 Jan 2023 08:12:12 -0500 Subject: [PATCH 38/39] RC7+GDS: Corrected RT thermistor curve with 3V3ref. --- .../codec/packet_classes/watchdog_detailed_status.py | 2 +- Apps/GroundSoftware/__command_aliases.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py index d972dd419..7d471ed6a 100644 --- a/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py +++ b/Apps/GroundSoftware/IrisBackendv3/codec/packet_classes/watchdog_detailed_status.py @@ -56,7 +56,7 @@ class CustomPayload(): # TODO: 5k table taken from old Avionics conversion sheet. not yet checked/verified. (check it) BATT_5K_THERMISTOR_LOOKUP_TABLE = { # for 5k thermistor: https://www.tdk-electronics.tdk.com/inf/50/db/ntc/NTC_Mini_sensors_S863.pdf 'degC': np.asarray([-15, -10, -5, 0, 5, 10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60, 65, 70, 75, 80, 85, 90, 95, 100, 105, 110, 115, 120, 125, 130, 135, 140, 145, 150, 155]), - 'adc': np.asarray([4242, 3970, 3670, 3352, 3023, 2695, 2378, 2077, 1801, 1552, 1330, 1137, 969, 825, 702, 598, 510, 435, 372, 319, 274, 237, 204, 177, 154, 134, 117, 103, 90, 79, 70, 62, 55, 49, 44]) + 'adc': np.asarray([3214, 3008, 2781, 2540, 2291, 2042, 1801, 1574, 1365, 1176, 1008, 861, 734, 625, 532, 453, 386, 329, 282, 242, 208, 179, 155, 134, 116, 102, 89, 78, 68, 60, 53, 47, 42, 37, 33]) } BATT_CHRG_10K_THERMISTOR_LOOKUP_TABLE = { # for 10k thermistor (NTC10k_B57863S0103F040) 'degC': np.asarray([-55, -50, -45, -40, -35, -30, -25, -20, -15, -10, -5, 0, 5, 10, 15, 20, 25, 30, 35, 40, 45, 50, 55, 60, 65, 70, 75, 80, 85, 90, 95, 100, 105, 110, 115, 120, 125, 130, 135, 140, 145, 150, 155]), diff --git a/Apps/GroundSoftware/__command_aliases.py b/Apps/GroundSoftware/__command_aliases.py index 6faac99ff..5895599dd 100644 --- a/Apps/GroundSoftware/__command_aliases.py +++ b/Apps/GroundSoftware/__command_aliases.py @@ -551,14 +551,14 @@ class Parameter(Enum): DataPathway.WIRED, Magic.WATCHDOG_COMMAND, 'WatchDogInterface_SetAutoHeaterOnValue', - OrderedDict(on=4000), + OrderedDict(on=1000), DataPathway.WIRED ), 'set-heater-off-level': ( DataPathway.WIRED, Magic.WATCHDOG_COMMAND, 'WatchDogInterface_SetAutoHeaterOffValue', - OrderedDict(off=1500), + OrderedDict(off=500), DataPathway.WIRED ), From 0a2ecc30690a4bc0e85fb1d7f751028510aa37a8 Mon Sep 17 00:00:00 2001 From: iris-hermes-mobile Date: Mon, 2 Jan 2023 08:22:58 -0500 Subject: [PATCH 39/39] RC7: WD Bins uploaded. --- .../FSW/Watchdog/Debug_with_flag/Watchdog.map | 5138 ++ .../FSW/Watchdog/Debug_with_flag/Watchdog.out | Bin 0 -> 1337664 bytes .../Debug_with_flag/Watchdog_linkInfo.xml | 48315 ++++++++++++++++ .../FSW/Watchdog/Debug_with_flag/ccsObjs.opt | 1 + .../RC7/FSW/Watchdog/Debug_with_flag/makefile | 215 + .../FSW/Watchdog/Debug_with_flag/objects.mk | 8 + .../FSW/Watchdog/Debug_with_flag/sources.mk | 121 + .../FSW/Watchdog/Debug_with_flag/src/blimp.d | 6 + .../Debug_with_flag/src/comms/cmd_msgs.d | 35 + .../Debug_with_flag/src/comms/cmd_msgs.obj | Bin 0 -> 24224 bytes .../Debug_with_flag/src/comms/debug_comms.d | 61 + .../Debug_with_flag/src/comms/debug_comms.obj | Bin 0 -> 54396 bytes .../Debug_with_flag/src/comms/ground_msgs.d | 75 + .../Debug_with_flag/src/comms/ground_msgs.obj | Bin 0 -> 89128 bytes .../src/comms/hercules_comms.d | 63 + .../src/comms/hercules_comms.obj | Bin 0 -> 73160 bytes .../Debug_with_flag/src/comms/hercules_mpsm.d | 49 + .../src/comms/hercules_mpsm.obj | Bin 0 -> 56124 bytes .../Debug_with_flag/src/comms/hercules_msgs.d | 35 + .../src/comms/hercules_msgs.obj | Bin 0 -> 24536 bytes .../Debug_with_flag/src/comms/i2c_sensors.d | 63 + .../Debug_with_flag/src/comms/i2c_sensors.obj | Bin 0 -> 144164 bytes .../Debug_with_flag/src/comms/ip_udp.d | 39 + .../Debug_with_flag/src/comms/ip_udp.obj | Bin 0 -> 33708 bytes .../Debug_with_flag/src/comms/lander_comms.d | 65 + .../src/comms/lander_comms.obj | Bin 0 -> 67576 bytes .../Debug_with_flag/src/comms/slip_encode.d | 33 + .../Debug_with_flag/src/comms/slip_encode.obj | Bin 0 -> 20688 bytes .../Debug_with_flag/src/comms/slip_mpsm.d | 35 + .../Debug_with_flag/src/comms/slip_mpsm.obj | Bin 0 -> 31000 bytes .../Debug_with_flag/src/comms/subdir_rules.mk | 13 + .../Debug_with_flag/src/comms/subdir_vars.mk | 96 + .../src/comms/watchdog_cmd_msgs.d | 37 + .../src/comms/watchdog_cmd_msgs.obj | Bin 0 -> 111076 bytes .../Debug_with_flag/src/comms/wd_int_mpsm.d | 33 + .../Debug_with_flag/src/comms/wd_int_mpsm.obj | Bin 0 -> 22784 bytes .../Debug_with_flag/src/drivers/adc.d | 53 + .../Debug_with_flag/src/drivers/adc.obj | Bin 0 -> 41908 bytes .../Debug_with_flag/src/drivers/blimp.d | 61 + .../Debug_with_flag/src/drivers/blimp.obj | Bin 0 -> 104788 bytes .../Debug_with_flag/src/drivers/bsp.d | 63 + .../Debug_with_flag/src/drivers/bsp.obj | Bin 0 -> 133412 bytes .../Debug_with_flag/src/drivers/i2c.d | 61 + .../Debug_with_flag/src/drivers/i2c.obj | Bin 0 -> 59268 bytes .../src/drivers/subdir_rules.mk | 13 + .../src/drivers/subdir_vars.mk | 48 + .../Debug_with_flag/src/drivers/uart.d | 67 + .../Debug_with_flag/src/drivers/uart.obj | Bin 0 -> 87420 bytes .../Debug_with_flag/src/event/event_queue.d | 37 + .../Debug_with_flag/src/event/event_queue.obj | Bin 0 -> 32516 bytes .../Debug_with_flag/src/event/subdir_rules.mk | 13 + .../Debug_with_flag/src/event/subdir_vars.mk | 24 + .../Watchdog/Debug_with_flag/src/ground_cmd.d | 108 + .../Debug_with_flag/src/ground_cmd.obj | Bin 0 -> 62234 bytes .../FSW/Watchdog/Debug_with_flag/src/main.d | 195 + .../FSW/Watchdog/Debug_with_flag/src/main.obj | Bin 0 -> 289480 bytes .../src/stateMachine/RoverState.d | 7 + .../src/stateMachine/RoverState.obj | Bin 0 -> 11784 bytes .../src/stateMachine/RoverStateBase.d | 131 + .../src/stateMachine/RoverStateBase.obj | Bin 0 -> 309848 bytes .../RoverStateEnteringKeepAlive.d | 103 + .../RoverStateEnteringKeepAlive.obj | Bin 0 -> 170368 bytes .../stateMachine/RoverStateEnteringMission.d | 93 + .../RoverStateEnteringMission.obj | Bin 0 -> 176404 bytes .../stateMachine/RoverStateEnteringService.d | 83 + .../RoverStateEnteringService.obj | Bin 0 -> 150448 bytes .../stateMachine/RoverStateEnteringStasis.d | 85 + .../stateMachine/RoverStateEnteringStasis.obj | Bin 0 -> 166108 bytes .../src/stateMachine/RoverStateInit.d | 103 + .../src/stateMachine/RoverStateInit.obj | Bin 0 -> 149420 bytes .../src/stateMachine/RoverStateKeepAlive.d | 87 + .../src/stateMachine/RoverStateKeepAlive.obj | Bin 0 -> 148540 bytes .../src/stateMachine/RoverStateManager.d | 197 + .../src/stateMachine/RoverStateManager.obj | Bin 0 -> 315860 bytes .../src/stateMachine/RoverStateMission.d | 101 + .../src/stateMachine/RoverStateMission.obj | Bin 0 -> 162452 bytes .../src/stateMachine/RoverStateService.d | 93 + .../src/stateMachine/RoverStateService.obj | Bin 0 -> 166032 bytes .../src/stateMachine/RoverStateStasis.d | 89 + .../src/stateMachine/RoverStateStasis.obj | Bin 0 -> 145776 bytes .../src/stateMachine/subdir_rules.mk | 13 + .../src/stateMachine/subdir_vars.mk | 90 + .../Debug_with_flag/src/subdir_rules.mk | 20 + .../Debug_with_flag/src/subdir_vars.mk | 38 + .../Debug_with_flag/src/utils/ring_buffer.d | 33 + .../Debug_with_flag/src/utils/ring_buffer.obj | Bin 0 -> 38868 bytes .../Debug_with_flag/src/utils/serialization.d | 33 + .../src/utils/serialization.obj | Bin 0 -> 37640 bytes .../Debug_with_flag/src/utils/subdir_rules.mk | 13 + .../Debug_with_flag/src/utils/subdir_vars.mk | 36 + .../Watchdog/Debug_with_flag/src/utils/time.d | 23 + .../Debug_with_flag/src/utils/time.obj | Bin 0 -> 19644 bytes .../Watchdog/Debug_with_flag/src/watchdog.d | 75 + .../Watchdog/Debug_with_flag/src/watchdog.obj | Bin 0 -> 71964 bytes .../Watchdog/Debug_with_flag/subdir_rules.mk | 6 + .../Watchdog/Debug_with_flag/subdir_vars.mk | 9 + 96 files changed, 56840 insertions(+) create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.map create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.out create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog_linkInfo.xml create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/ccsObjs.opt create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/makefile create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/objects.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/sources.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/blimp.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/cmd_msgs.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/cmd_msgs.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/debug_comms.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/debug_comms.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/ground_msgs.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/ground_msgs.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_comms.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_comms.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_mpsm.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_mpsm.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_msgs.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/hercules_msgs.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/i2c_sensors.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/i2c_sensors.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/ip_udp.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/ip_udp.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/lander_comms.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/lander_comms.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/slip_encode.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/slip_encode.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/slip_mpsm.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/slip_mpsm.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/watchdog_cmd_msgs.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/watchdog_cmd_msgs.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/wd_int_mpsm.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/comms/wd_int_mpsm.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/adc.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/adc.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/blimp.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/blimp.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/bsp.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/bsp.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/i2c.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/i2c.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/uart.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/drivers/uart.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/event/event_queue.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/event/event_queue.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/event/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/event/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/ground_cmd.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/ground_cmd.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/main.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/main.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverState.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverState.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateBase.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateBase.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringKeepAlive.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringKeepAlive.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringMission.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringMission.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringService.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringService.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringStasis.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateEnteringStasis.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateInit.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateInit.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateKeepAlive.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateKeepAlive.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateManager.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateManager.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateMission.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateMission.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateService.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateService.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateStasis.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/RoverStateStasis.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/stateMachine/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/ring_buffer.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/ring_buffer.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/serialization.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/serialization.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/subdir_vars.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/time.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/utils/time.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/watchdog.d create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/src/watchdog.obj create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/subdir_rules.mk create mode 100644 Bins/RC7/FSW/Watchdog/Debug_with_flag/subdir_vars.mk diff --git a/Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.map b/Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.map new file mode 100644 index 000000000..e5148798c --- /dev/null +++ b/Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.map @@ -0,0 +1,5138 @@ +****************************************************************************** + MSP430 Linker Unix v18.12.2 +****************************************************************************** +>> Linked Mon Jan 2 07:44:13 2023 + +OUTPUT FILE NAME: +ENTRY POINT SYMBOL: "_c_int00_noargs_mpu" address: 000046c0 + + +MEMORY CONFIGURATION + + name origin length used unused attr fill +---------------------- -------- --------- -------- -------- ---- -------- + TINYRAM 0000000a 00000016 00000000 00000016 RWIX + BSL 00001000 00000800 00000000 00000800 RWIX + INFOD 00001800 00000080 00000000 00000080 RWIX + INFOC 00001880 00000080 00000000 00000080 RWIX + INFOB 00001900 00000080 00000000 00000080 RWIX + INFOA 00001980 00000080 00000000 00000080 RWIX + RAM 00001c00 00002000 00001f64 0000009c RWIX + FRAM 00004000 0000bf80 0000911d 00002e63 RWIX + JTAGSIGNATURE 0000ff80 00000004 00000004 00000000 RWIX ffff + BSLSIGNATURE 0000ff84 00000004 00000004 00000000 RWIX ffff + IPESIGNATURE 0000ff88 00000008 00000008 00000000 RWIX ffff + INT00 0000ff90 00000002 00000000 00000002 RWIX + INT01 0000ff92 00000002 00000000 00000002 RWIX + INT02 0000ff94 00000002 00000000 00000002 RWIX + INT03 0000ff96 00000002 00000000 00000002 RWIX + INT04 0000ff98 00000002 00000000 00000002 RWIX + INT05 0000ff9a 00000002 00000000 00000002 RWIX + INT06 0000ff9c 00000002 00000000 00000002 RWIX + INT07 0000ff9e 00000002 00000000 00000002 RWIX + INT08 0000ffa0 00000002 00000000 00000002 RWIX + INT09 0000ffa2 00000002 00000000 00000002 RWIX + INT10 0000ffa4 00000002 00000000 00000002 RWIX + INT11 0000ffa6 00000002 00000000 00000002 RWIX + INT12 0000ffa8 00000002 00000000 00000002 RWIX + INT13 0000ffaa 00000002 00000000 00000002 RWIX + INT14 0000ffac 00000002 00000000 00000002 RWIX + INT15 0000ffae 00000002 00000000 00000002 RWIX + INT16 0000ffb0 00000002 00000000 00000002 RWIX + INT17 0000ffb2 00000002 00000000 00000002 RWIX + INT18 0000ffb4 00000002 00000002 00000000 RWIX + INT19 0000ffb6 00000002 00000002 00000000 RWIX + INT20 0000ffb8 00000002 00000002 00000000 RWIX + INT21 0000ffba 00000002 00000002 00000000 RWIX + INT22 0000ffbc 00000002 00000002 00000000 RWIX + INT23 0000ffbe 00000002 00000002 00000000 RWIX + INT24 0000ffc0 00000002 00000002 00000000 RWIX + INT25 0000ffc2 00000002 00000002 00000000 RWIX + INT26 0000ffc4 00000002 00000002 00000000 RWIX + INT27 0000ffc6 00000002 00000002 00000000 RWIX + INT28 0000ffc8 00000002 00000002 00000000 RWIX + INT29 0000ffca 00000002 00000002 00000000 RWIX + INT30 0000ffcc 00000002 00000002 00000000 RWIX + INT31 0000ffce 00000002 00000002 00000000 RWIX + INT32 0000ffd0 00000002 00000002 00000000 RWIX + INT33 0000ffd2 00000002 00000002 00000000 RWIX + INT34 0000ffd4 00000002 00000002 00000000 RWIX + INT35 0000ffd6 00000002 00000002 00000000 RWIX + INT36 0000ffd8 00000002 00000002 00000000 RWIX + INT37 0000ffda 00000002 00000002 00000000 RWIX + INT38 0000ffdc 00000002 00000002 00000000 RWIX + INT39 0000ffde 00000002 00000002 00000000 RWIX + INT40 0000ffe0 00000002 00000002 00000000 RWIX + INT41 0000ffe2 00000002 00000002 00000000 RWIX + INT42 0000ffe4 00000002 00000002 00000000 RWIX + INT43 0000ffe6 00000002 00000002 00000000 RWIX + INT44 0000ffe8 00000002 00000002 00000000 RWIX + INT45 0000ffea 00000002 00000002 00000000 RWIX + INT46 0000ffec 00000002 00000002 00000000 RWIX + INT47 0000ffee 00000002 00000002 00000000 RWIX + INT48 0000fff0 00000002 00000002 00000000 RWIX + INT49 0000fff2 00000002 00000002 00000000 RWIX + INT50 0000fff4 00000002 00000002 00000000 RWIX + INT51 0000fff6 00000002 00000002 00000000 RWIX + INT52 0000fff8 00000002 00000002 00000000 RWIX + INT53 0000fffa 00000002 00000002 00000000 RWIX + INT54 0000fffc 00000002 00000002 00000000 RWIX + RESET 0000fffe 00000002 00000002 00000000 RWIX + FRAM2 00010000 00034000 0000b552 00028aae RWIX + + +SECTION ALLOCATION MAP + + output attributes/ +section page origin length input sections +-------- ---- ---------- ---------- ---------------- +.TI.persistent +* 0 00004000 00000002 + 00004000 00000002 RoverStateManager.obj (.TI.persistent) + +.binit 0 00004000 00000000 + +.cio 0 00004002 00000120 UNINITIALIZED + 00004002 00000120 rts430x_lc_rd_eabi.lib : trgmsg.c.obj (.cio) + +.sysmem 0 00004124 00000008 UNINITIALIZED + 00004124 00000008 rts430x_lc_rd_eabi.lib : memory.c.obj (.sysmem) + +.ipestruct +* 0 00004400 00000000 UNINITIALIZED + +.ipe 0 00004400 00000000 UNINITIALIZED + +.ipe_const +* 0 00004400 00000000 UNINITIALIZED + +.ipe:_isr +* 0 00004400 00000000 UNINITIALIZED + +.cinit 0 0000d08c 00000092 + 0000d08c 0000006f (.cinit..data.load) [load image, compression = lzss] + 0000d0fb 00000001 --HOLE-- [fill = 0] + 0000d0fc 0000000c (__TI_handler_table) + 0000d108 00000006 (.cinit..bss.load) [load image, compression = zero_init] + 0000d10e 00000010 (__TI_cinit_table) + +.init_array +* 0 00004000 00000000 UNINITIALIZED + +.text:_isr +* 0 00004400 000002f8 + 00004400 000000ca uart.obj (.text:_isr:USCI_A0_ISR) + 000044ca 000000ca uart.obj (.text:_isr:USCI_A1_ISR) + 00004594 00000098 adc.obj (.text:_isr:ADC12_ISR) + 0000462c 00000056 watchdog.obj (.text:_isr:port1_isr_handler) + 00004682 0000003e watchdog.obj (.text:_isr:Timer0_A1_ISR) + 000046c0 00000020 rts430x_lc_rd_eabi.lib : boot.c.obj (.text:_isr:_c_int00_noargs_mpu) + 000046e0 00000010 RoverStateManager.obj (.text:_isr:_Z7WDT_ISRv) + 000046f0 00000008 rts430x_lc_rd_eabi.lib : isr_trap.asm.obj (.text:_isr:__TI_ISR_TRAP) + +.bss 0 00001c00 00000d0e UNINITIALIZED + 00001c00 00000400 RoverStateManager.obj (.bss:_ZN43_INTERNAL_21_RoverStateManager_cpp_1f51f65b4iris13uart0RxBufferE) + 00002000 00000400 RoverStateManager.obj (.bss:_ZN43_INTERNAL_21_RoverStateManager_cpp_1f51f65b4iris13uart1TxBufferE) + 00002400 00000200 RoverStateManager.obj (.bss:_ZN43_INTERNAL_21_RoverStateManager_cpp_1f51f65b4iris13uart0TxBufferE) + 00002600 00000200 RoverStateManager.obj (.bss:_ZN43_INTERNAL_21_RoverStateManager_cpp_1f51f65b4iris13uart1RxBufferE) + 00002800 000000a0 (.common:__TI_tmpnams) + 000028a0 00000050 ring_buffer.obj (.bss:ALL_RING_BUFFERS) + 000028f0 00000010 RoverStateBase.obj (.bss:ECHO_BUFFER$9) + 00002900 00000008 (.common:parmbuf) + 00002908 00000004 rts430x_lc_rd_eabi.lib : memory.c.obj (.bss) + 0000290c 00000002 time.obj (.bss) + +.data 0 0000290e 00000c82 UNINITIALIZED + 0000290e 000002cc hercules_comms.obj (.data:theState) + 00002bda 000002cc lander_comms.obj (.data:theState) + 00002ea6 00000100 debug_comms.obj (.data:PRINT_BUFFER) + 00002fa6 00000100 lander_comms.obj (.data:uartRxData$1) + 000030a6 00000100 lander_comms.obj (.data:uartTxSlipData$5) + 000031a6 000000c8 rts430x_lc_rd_eabi.lib : defs.c.obj (.data:_ftable) + 0000326e 00000078 : host_device.c.obj (.data:_device) + 000032e6 00000040 hercules_comms.obj (.data:uartRxData$1) + 00003326 00000040 hercules_comms.obj (.data:uartRxData$3) + 00003366 0000003c rts430x_lc_rd_eabi.lib : host_device.c.obj (.data:_stream) + 000033a2 0000002f RoverStateBase.obj (.data:report$10) + 000033d1 00000001 ground_msgs.obj (.data) + 000033d2 0000002f RoverStateBase.obj (.data:reportBuffer$11) + 00003401 00000001 lander_comms.obj (.data) + 00003402 00000022 i2c_sensors.obj (.data:internals) + 00003424 0000001c lander_comms.obj (.data:uartHeaderData$4) + 00003440 0000001a hercules_mpsm.obj (.data:theStateMachine) + 0000345a 0000001a uart.obj (.data:uart0State) + 00003474 0000001a uart.obj (.data:uart1State) + 0000348e 00000018 RoverStateEnteringMission.obj (.data:hb$1) + 000034a6 00000018 RoverStateMission.obj (.data:hb$1) + 000034be 00000018 RoverStateService.obj (.data:hb$1) + 000034d6 00000018 RoverStateBase.obj (.data:wdMessage$1) + 000034ee 00000014 lander_comms.obj (.data:txDurations$6) + 00003502 00000010 RoverStateBase.obj (.data:telemetrySerializationBuffer$5) + 00003512 0000000c watchdog.obj (.data) + 0000351e 00000009 debug_comms.obj (.data) + 00003527 00000001 --HOLE-- + 00003528 00000008 adc.obj (.data) + 00003530 00000008 i2c_sensors.obj (.data:tStatus$1) + 00003538 00000008 i2c_sensors.obj (.data:tStatus$2) + 00003540 00000008 i2c.obj (.data:theStatus) + 00003548 00000006 RoverStateBase.obj (.data:deployNotificationResponse$3) + 0000354e 00000006 RoverStateBase.obj (.data:response$2) + 00003554 00000006 event_queue.obj (.data:theQueue) + 0000355a 00000004 rts430x_lc_rd_eabi.lib : exit_gvars.c.obj (.data:__TI_cleanup_ptr) + 0000355e 00000004 : exit_gvars.c.obj (.data:__TI_dtors_ptr) + 00003562 00000004 : _lock.c.obj (.data:_lock) + 00003566 00000004 : _lock.c.obj (.data:_unlock) + 0000356a 00000004 blimp.obj (.data) + 0000356e 00000004 bsp.obj (.data) + 00003572 00000004 RoverStateBase.obj (.data:hb$12) + 00003576 00000004 RoverStateEnteringKeepAlive.obj (.data:hb$1) + 0000357a 00000004 slip_mpsm.obj (.data:theStateMachine) + 0000357e 00000003 RoverStateBase.obj (.data:responseSerializationBuffer$6) + 00003581 00000001 --HOLE-- + 00003582 00000002 RoverStateBase.obj (.data) + 00003584 00000002 hercules_comms.obj (.data) + 00003586 00000002 i2c_sensors.obj (.data) + 00003588 00000002 ring_buffer.obj (.data) + 0000358a 00000002 rts430x_lc_rd_eabi.lib : defs.c.obj (.data) + 0000358c 00000002 : exit.c.obj (.data) + 0000358e 00000002 : memory.c.obj (.data) + +.stack 0 0000362c 000005d4 UNINITIALIZED + 0000362c 00000004 rts430x_lc_rd_eabi.lib : boot.c.obj (.stack) + 00003630 000005d0 --HOLE-- + +$fill000 0 0000ff80 00000004 + 0000ff80 00000004 --HOLE-- [fill = ffff] + +$fill001 0 0000ff84 00000004 + 0000ff84 00000004 --HOLE-- [fill = ffff] + +$fill002 0 0000ff88 00000008 + 0000ff88 00000008 --HOLE-- [fill = ffff] + +LEA 0 0000ffb4 00000002 + 0000ffb4 00000002 rts430x_lc_rd_eabi.lib : int18.asm.obj (.int18) + +PORT8 0 0000ffb6 00000002 + 0000ffb6 00000002 rts430x_lc_rd_eabi.lib : int19.asm.obj (.int19) + +PORT7 0 0000ffb8 00000002 + 0000ffb8 00000002 rts430x_lc_rd_eabi.lib : int20.asm.obj (.int20) + +EUSCI_B3 0 0000ffba 00000002 + 0000ffba 00000002 rts430x_lc_rd_eabi.lib : int21.asm.obj (.int21) + +EUSCI_B2 0 0000ffbc 00000002 + 0000ffbc 00000002 rts430x_lc_rd_eabi.lib : int22.asm.obj (.int22) + +EUSCI_B1 0 0000ffbe 00000002 + 0000ffbe 00000002 rts430x_lc_rd_eabi.lib : int23.asm.obj (.int23) + +EUSCI_A3 0 0000ffc0 00000002 + 0000ffc0 00000002 rts430x_lc_rd_eabi.lib : int24.asm.obj (.int24) + +EUSCI_A2 0 0000ffc2 00000002 + 0000ffc2 00000002 rts430x_lc_rd_eabi.lib : int25.asm.obj (.int25) + +PORT6 0 0000ffc4 00000002 + 0000ffc4 00000002 rts430x_lc_rd_eabi.lib : int26.asm.obj (.int26) + +PORT5 0 0000ffc6 00000002 + 0000ffc6 00000002 rts430x_lc_rd_eabi.lib : int27.asm.obj (.int27) + +TIMER4_A1 +* 0 0000ffc8 00000002 + 0000ffc8 00000002 rts430x_lc_rd_eabi.lib : int28.asm.obj (.int28) + +TIMER4_A0 +* 0 0000ffca 00000002 + 0000ffca 00000002 rts430x_lc_rd_eabi.lib : int29.asm.obj (.int29) + +AES256 0 0000ffcc 00000002 + 0000ffcc 00000002 rts430x_lc_rd_eabi.lib : int30.asm.obj (.int30) + +RTC_C 0 0000ffce 00000002 + 0000ffce 00000002 rts430x_lc_rd_eabi.lib : int31.asm.obj (.int31) + +PORT4 0 0000ffd0 00000002 + 0000ffd0 00000002 rts430x_lc_rd_eabi.lib : int32.asm.obj (.int32) + +PORT3 0 0000ffd2 00000002 + 0000ffd2 00000002 rts430x_lc_rd_eabi.lib : int33.asm.obj (.int33) + +TIMER3_A1 +* 0 0000ffd4 00000002 + 0000ffd4 00000002 rts430x_lc_rd_eabi.lib : int34.asm.obj (.int34) + +TIMER3_A0 +* 0 0000ffd6 00000002 + 0000ffd6 00000002 rts430x_lc_rd_eabi.lib : int35.asm.obj (.int35) + +PORT2 0 0000ffd8 00000002 + 0000ffd8 00000002 rts430x_lc_rd_eabi.lib : int36.asm.obj (.int36) + +TIMER2_A1 +* 0 0000ffda 00000002 + 0000ffda 00000002 rts430x_lc_rd_eabi.lib : int37.asm.obj (.int37) + +TIMER2_A0 +* 0 0000ffdc 00000002 + 0000ffdc 00000002 rts430x_lc_rd_eabi.lib : int38.asm.obj (.int38) + +PORT1 0 0000ffde 00000002 + 0000ffde 00000002 watchdog.obj (.int39) + +TIMER1_A1 +* 0 0000ffe0 00000002 + 0000ffe0 00000002 rts430x_lc_rd_eabi.lib : int40.asm.obj (.int40) + +TIMER1_A0 +* 0 0000ffe2 00000002 + 0000ffe2 00000002 rts430x_lc_rd_eabi.lib : int41.asm.obj (.int41) + +DMA 0 0000ffe4 00000002 + 0000ffe4 00000002 rts430x_lc_rd_eabi.lib : int42.asm.obj (.int42) + +EUSCI_A1 0 0000ffe6 00000002 + 0000ffe6 00000002 uart.obj (.int43) + +TIMER0_A1 +* 0 0000ffe8 00000002 + 0000ffe8 00000002 watchdog.obj (.int44) + +TIMER0_A0 +* 0 0000ffea 00000002 + 0000ffea 00000002 rts430x_lc_rd_eabi.lib : int45.asm.obj (.int45) + +ADC12_B 0 0000ffec 00000002 + 0000ffec 00000002 adc.obj (.int46) + +EUSCI_B0 0 0000ffee 00000002 + 0000ffee 00000002 rts430x_lc_rd_eabi.lib : int47.asm.obj (.int47) + +EUSCI_A0 0 0000fff0 00000002 + 0000fff0 00000002 uart.obj (.int48) + +WDT 0 0000fff2 00000002 + 0000fff2 00000002 RoverStateManager.obj (.int49) + +TIMER0_B1 +* 0 0000fff4 00000002 + 0000fff4 00000002 rts430x_lc_rd_eabi.lib : int50.asm.obj (.int50) + +TIMER0_B0 +* 0 0000fff6 00000002 + 0000fff6 00000002 rts430x_lc_rd_eabi.lib : int51.asm.obj (.int51) + +COMP_E 0 0000fff8 00000002 + 0000fff8 00000002 rts430x_lc_rd_eabi.lib : int52.asm.obj (.int52) + +UNMI 0 0000fffa 00000002 + 0000fffa 00000002 rts430x_lc_rd_eabi.lib : int53.asm.obj (.int53) + +SYSNMI 0 0000fffc 00000002 + 0000fffc 00000002 rts430x_lc_rd_eabi.lib : int54.asm.obj (.int54) + +.reset 0 0000fffe 00000002 + 0000fffe 00000002 rts430x_lc_rd_eabi.lib : boot.c.obj (.reset) + +.const 0 000046f8 00008993 + 000046f8 000026f2 RoverStateBase.obj (.const:.string) + 00006dea 00000c46 RoverStateEnteringMission.obj (.const:.string) + 00007a30 00000970 RoverStateEnteringKeepAlive.obj (.const:.string) + 000083a0 000008e0 RoverStateInit.obj (.const:.string) + 00008c80 000007f2 i2c_sensors.obj (.const:.string) + 00009472 00000640 RoverStateMission.obj (.const:.string) + 00009ab2 00000590 RoverStateService.obj (.const:.string) + 0000a042 00000478 watchdog_cmd_msgs.obj (.const:.string) + 0000a4ba 000003f4 hercules_comms.obj (.const:.string) + 0000a8ae 000003f2 bsp.obj (.const:.string) + 0000aca0 000003d0 RoverStateKeepAlive.obj (.const:.string) + 0000b070 00000364 RoverStateManager.obj (.const:.string) + 0000b3d4 0000034c RoverStateEnteringService.obj (.const:.string) + 0000b720 000002e8 blimp.obj (.const:.string) + 0000ba08 0000024e lander_comms.obj (.const:.string) + 0000bc56 00000222 hercules_mpsm.obj (.const:.string) + 0000be78 0000021c watchdog.obj (.const:.string) + 0000c094 0000021a uart.obj (.const:.string) + 0000c2ae 00000140 debug_comms.obj (.const:.string) + 0000c3ee 000000fa i2c.obj (.const:.string) + 0000c4e8 000000e8 RoverStateService.obj (.const:_ZTVN4iris17RoverStateServiceE) + 0000c5d0 000000e8 RoverStateKeepAlive.obj (.const:_ZTVN4iris19RoverStateKeepAliveE) + 0000c6b8 000000e8 RoverStateEnteringService.obj (.const:_ZTVN4iris25RoverStateEnteringServiceE) + 0000c7a0 000000e8 RoverStateEnteringKeepAlive.obj (.const:_ZTVN4iris27RoverStateEnteringKeepAliveE) + 0000c888 000000e4 RoverStateBase.obj (.const:_ZTVN4iris14RoverStateBaseE) + 0000c96c 000000e4 RoverStateInit.obj (.const:_ZTVN4iris14RoverStateInitE) + 0000ca50 000000e4 RoverStateMission.obj (.const:_ZTVN4iris17RoverStateMissionE) + 0000cb34 000000e4 RoverStateEnteringMission.obj (.const:_ZTVN4iris25RoverStateEnteringMissionE) + 0000cc18 000000a6 RoverState.obj (.const:.string) + 0000ccbe 00000076 ground_msgs.obj (.const:.string) + 0000cd34 0000006a ip_udp.obj (.const:.string) + 0000cd9e 0000004a event_queue.obj (.const:.string) + 0000cde8 0000003a adc.obj (.const:.string) + 0000ce22 00000028 RoverState.obj (.const) + 0000ce4a 00000025 rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.const:.typeinfo:_ZTSN10__cxxabiv120__si_class_type_infoE) + 0000ce6f 00000001 lander_comms.obj (.const) + 0000ce70 00000025 RoverStateEnteringKeepAlive.obj (.const:.typeinfo:_ZTSN4iris27RoverStateEnteringKeepAliveE) + 0000ce95 00000001 --HOLE-- [fill = 0] + 0000ce96 00000023 RoverStateEnteringMission.obj (.const:.typeinfo:_ZTSN4iris25RoverStateEnteringMissionE) + 0000ceb9 00000001 --HOLE-- [fill = 0] + 0000ceba 00000023 RoverStateEnteringService.obj (.const:.typeinfo:_ZTSN4iris25RoverStateEnteringServiceE) + 0000cedd 00000001 --HOLE-- [fill = 0] + 0000cede 00000022 rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.const:.typeinfo:_ZTSN10__cxxabiv117__class_type_infoE) + 0000cf00 0000001d RoverStateKeepAlive.obj (.const:.typeinfo:_ZTSN4iris19RoverStateKeepAliveE) + 0000cf1d 00000001 --HOLE-- [fill = 0] + 0000cf1e 0000001b RoverStateMission.obj (.const:.typeinfo:_ZTSN4iris17RoverStateMissionE) + 0000cf39 00000001 --HOLE-- [fill = 0] + 0000cf3a 0000001b RoverStateService.obj (.const:.typeinfo:_ZTSN4iris17RoverStateServiceE) + 0000cf55 00000001 --HOLE-- [fill = 0] + 0000cf56 00000018 wd_int_mpsm.obj (.const:.string) + 0000cf6e 00000018 RoverStateBase.obj (.const:.typeinfo:_ZTSN4iris14RoverStateBaseE) + 0000cf86 00000018 RoverStateInit.obj (.const:.typeinfo:_ZTSN4iris14RoverStateInitE) + 0000cf9e 00000014 rts430x_lc_rd_eabi.lib : _printfi_min.c.obj (.const:.string) + 0000cfb2 00000014 uart.obj (.const:uart0Registers) + 0000cfc6 00000014 uart.obj (.const:uart1Registers) + 0000cfda 00000010 rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.const:_ZTVN10__cxxabiv117__class_type_infoE) + 0000cfea 00000010 : typeinfo.c.obj (.const:_ZTVN10__cxxabiv120__si_class_type_infoE) + 0000cffa 0000000d : stdlib_typeinfo.cpp.obj (.const:.typeinfo:_ZTSSt9type_info) + 0000d007 00000001 --HOLE-- [fill = 0] + 0000d008 0000000c : typeinfo.c.obj (.const:.typeinfo:_ZTIN10__cxxabiv117__class_type_infoE) + 0000d014 0000000c : typeinfo.c.obj (.const:.typeinfo:_ZTIN10__cxxabiv120__si_class_type_infoE) + 0000d020 0000000c RoverStateInit.obj (.const:.typeinfo:_ZTIN4iris14RoverStateInitE) + 0000d02c 0000000c RoverStateMission.obj (.const:.typeinfo:_ZTIN4iris17RoverStateMissionE) + 0000d038 0000000c RoverStateService.obj (.const:.typeinfo:_ZTIN4iris17RoverStateServiceE) + 0000d044 0000000c RoverStateKeepAlive.obj (.const:.typeinfo:_ZTIN4iris19RoverStateKeepAliveE) + 0000d050 0000000c RoverStateEnteringMission.obj (.const:.typeinfo:_ZTIN4iris25RoverStateEnteringMissionE) + 0000d05c 0000000c RoverStateEnteringService.obj (.const:.typeinfo:_ZTIN4iris25RoverStateEnteringServiceE) + 0000d068 0000000c RoverStateEnteringKeepAlive.obj (.const:.typeinfo:_ZTIN4iris27RoverStateEnteringKeepAliveE) + 0000d074 00000008 RoverStateBase.obj (.const:.typeinfo:_ZTIN4iris14RoverStateBaseE) + 0000d07c 00000008 rts430x_lc_rd_eabi.lib : stdlib_typeinfo.cpp.obj (.const:.typeinfo:_ZTISt9type_info) + 0000d084 00000007 RoverStateBase.obj (.const:.string:ECHO_HEADER$7) + +.text 0 00010000 0000b552 + 00010000 00000908 ground_msgs.obj (.text:GroundMsgs__generateDetailedReport) + 00010908 00000604 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doConditionalResetSpecificERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__ResponsebbbbRb) + 00010f0c 00000494 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission8spinOnceERNS_12RoverContextE) + 000113a0 000003ee RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001178e 00000350 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase21initiateNextI2cActionERNS_12RoverContextE) + 00011ade 000002ee bsp.obj (.text:initializeGpios) + 00011dcc 000002e8 watchdog.obj (.text:watchdog_monitor) + 000120b4 00000288 hercules_mpsm.obj (.text:HerculesMpsm__checkForValidHeader) + 0001233c 0000027c RoverStateMission.obj (.text:_ZN4iris17RoverStateMission15handleTimerTickERNS_12RoverContextE) + 000125b8 00000204 i2c_sensors.obj (.text:I2C_Sensors__getActionStatus) + 000127bc 000001fa ip_udp.obj (.text:IpUdp__generateAndSerializeIpUdpHeadersForData) + 000129b6 000001f4 RoverStateService.obj (.text:_ZN4iris17RoverStateService15handleTimerTickERNS_12RoverContextE) + 00012baa 000001d8 i2c_sensors.obj (.text:I2C_Sensors__spinOnce) + 00012d82 000001ce watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeBody) + 00012f50 000001c2 RoverStateInit.obj (.text:_ZN4iris14RoverStateInit12transitionToERNS_12RoverContextE) + 00013112 0000019c RoverStateBase.obj (.text:_ZN4iris14RoverStateBase17landerMsgCallbackEPhjPv) + 000132ae 00000186 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission15handleTimerTickERNS_12RoverContextE) + 00013434 0000017a hercules_comms.obj (.text:HerculesComms__tryGetMessage) + 000135ae 00000162 lander_comms.obj (.text:LanderComms__txData) + 00013710 00000160 uart.obj (.text:UART__initState) + 00013870 0000015e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26handleDownlinkFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj) + 000139ce 00000144 watchdog.obj (.text:watchdog_build_hercules_telem) + 00013b12 00000140 RoverStateManager.obj (.text:_ZN4iris17RoverStateManager4initEv) + 00013c52 0000013e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase19enableHerculesCommsERNS_12RoverContextE) + 00013d90 0000013a RoverStateManager.obj (.text:_ZN4iris17RoverStateManager11handleEventE11Event__Type) + 00013eca 00000138 hercules_msgs.obj (.text:HercMsgs__serializeHeader) + 00014002 00000132 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26sendDetailedReportToLanderERNS_12RoverContextEb) + 00014134 00000132 rts430x_lc_rd_eabi.lib : _printfi_min.c.obj (.text:_setfield) + 00014266 00000120 lander_comms.obj (.text:LanderComms__tryGetMessage) + 00014386 00000120 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive15handleTimerTickERNS_12RoverContextE) + 000144a6 0000011c watchdog.obj (.text:watchdog_init) + 000145c2 0000010c bsp.obj (.text:getResetReasonString) + 000146ce 0000010a RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive8spinOnceERNS_12RoverContextE) + 000147d8 00000108 rts430x_lc_rd_eabi.lib : memory.c.obj (.text:aligned_alloc) + 000148e0 00000100 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase23handleDebugFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj) + 000149e0 000000fc i2c_sensors.obj (.text:I2C_Sensors__writeIoExpanderPortDirectionsBlocking) + 00014adc 000000fc lander_comms.obj (.text:LanderComms__txDataUntilSendOrTimeout) + 00014bd8 000000fa i2c_sensors.obj (.text:I2C_Sensors__readRegNonBlocking) + 00014cd2 000000f0 i2c_sensors.obj (.text:I2C_Sensors__writeIoExpanderBlocking) + 00014dc2 000000f0 rts430x_lc_rd_eabi.lib : fputs.c.obj (.text:fputs) + 00014eb2 000000e8 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission8spinOnceERNS_12RoverContextE) + 00014f9a 000000e8 RoverStateService.obj (.text:_ZN4iris17RoverStateService8spinOnceERNS_12RoverContextE) + 00015082 000000e8 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive37transitionToWaitingForIoExpanderWriteERNS_12RoverContextE) + 0001516a 000000e6 ground_msgs.obj (.text:GroundMsgs__generateFullEarthHeartbeat) + 00015250 000000e4 uart.obj (.text:UART__flushTx) + 00015334 000000de rts430x_lc_rd_eabi.lib : setvbuf.c.obj (.text:setvbuf) + 00015412 000000dc : _printfi_min.c.obj (.text:__TI_printfi_minimal) + 000154ee 000000da : _printfi_min.c.obj (.text:_pproc_diouxp) + 000155c8 000000da : memory.c.obj (.text:free) + 000156a2 000000d4 hercules_comms.obj (.text:HerculesComms__txHerculesMsg) + 00015776 000000ca RoverStateManager.obj (.text:_ZN4iris17RoverStateManager11spinForeverEv) + 00015840 000000c8 lander_comms.obj (.text:LanderComms__slipEncodeAndTransmitBuffer) + 00015908 000000c2 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase13heaterControlERNS_12RoverContextE) + 000159ca 000000bc bsp.obj (.text:readOnChipInputs) + 00015a86 000000ba RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive8spinOnceERNS_12RoverContextE) + 00015b40 000000b8 slip_encode.obj (.text:SlipEncode__encode) + 00015bf8 000000b6 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase12echoToLanderERNS_12RoverContextEhPKh) + 00015cae 000000b6 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase24handleStrokeFromHerculesERNS_12RoverContextEP16HercMsgs__Header) + 00015d64 000000b4 i2c.obj (.text:I2C__spinOnce) + 00015e18 000000b0 i2c_sensors.obj (.text:I2C_Sensors__writeRegNonBlocking) + 00015ec8 000000b0 ip_udp.obj (.text:udp_checksum) + 00015f78 000000a8 ground_msgs.obj (.text:GroundMsgs__generateFlightEarthHeartbeat) + 00016020 000000a4 uart.obj (.text:UART__transmit) + 000160c4 000000a0 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase19herculesMsgCallbackEP16HercMsgs__HeaderPhjPv) + 00016164 0000009a rts430x_lc_rd_eabi.lib : hostlseek.c.obj (.text:HOSTlseek) + 000161fe 0000009a RoverStateBase.obj (.text:_ZN4iris14RoverStateBase23handleResetFromHerculesERNS_12RoverContextEP16HercMsgs__Header) + 00016298 00000098 cmd_msgs.obj (.text:CmdMsgs__deserializeHeader) + 00016330 00000094 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response) + 000163c4 00000090 hercules_comms.obj (.text:HerculesComms__resetState) + 00016454 00000090 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite1ERNS_12RoverContextE) + 000164e4 0000008a RoverStateBase.obj (.text:_ZN4iris14RoverStateBase18pumpMsgsFromLanderERNS_12RoverContextE) + 0001656e 0000008a RoverStateBase.obj (.text:_ZN4iris14RoverStateBase18sendLanderResponseERNS_12RoverContextER19WdCmdMsgs__Response) + 000165f8 00000088 i2c_sensors.obj (.text:I2C_Sensors__currentMsb) + 00016680 00000088 RoverStateManager.obj (.text:_ZN4iris17RoverStateManager26getStateObjectForStateEnumENS_10RoverStateE) + 00016708 00000086 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__serializeGroundResponse) + 0001678e 00000084 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeDangForceBattStateBody) + 00016812 00000084 RoverStateManager.obj (.text:_ZN4iris17RoverStateManagerC1EPKc) + 00016896 00000084 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite2ERNS_12RoverContextE) + 0001691a 00000082 serialization.obj (.text:Serialization__deserializeAs32Bit) + 0001699c 00000082 serialization.obj (.text:Serialization__serializeAs64Bit) + 00016a1e 00000082 slip_mpsm.obj (.text:SlipMpsm__process) + 00016aa0 00000082 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeMessage) + 00016b22 00000082 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase15handleWdIntEdgeEbRNS_12RoverContextE) + 00016ba4 00000082 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite3ERNS_12RoverContextE) + 00016c26 00000080 RoverState.obj (.text:_ZN4iris13stateToStringENS_10RoverStateE) + 00016ca6 00000080 RoverStateManager.obj (.text:_ZN4iris17RoverStateManager22transitionUntilSettledENS_10RoverStateE) + 00016d26 0000007e rts430x_lc_rd_eabi.lib : _io_perm.c.obj (.text:__TI_wrt_ok) + 00016da4 0000007a i2c_sensors.obj (.text:I2C_Sensors__chargeMsb) + 00016e1e 0000007a slip_mpsm.obj (.text:SlipMpsm__appendData) + 00016e98 00000078 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission40transitionToWaitingForFuelGaugeOrTimeoutERNS_12RoverContextE) + 00016f10 00000076 debug_comms.obj (.text:DebugComms__tryPrintfToLanderNonblocking) + 00016f86 00000076 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response) + 00016ffc 00000076 RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response) + 00017072 00000076 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response) + 000170e8 00000076 rts430x_lc_rd_eabi.lib : copy_decompress_lzss.c.obj (.text:decompress:lzss:__TI_decompress_lzss) + 0001715e 00000074 : hostrename.c.obj (.text:HOSTrename) + 000171d2 00000074 lander_comms.obj (.text:LanderComms__determineSlipEncodedSize) + 00017246 00000074 rts430x_lc_rd_eabi.lib : fclose.c.obj (.text:__TI_closefile) + 000172ba 00000072 i2c_sensors.obj (.text:I2C_Sensors__ioExpanderWritePort0) + 0001732c 00000072 serialization.obj (.text:Serialization__serializeAs32Bit) + 0001739e 00000070 rts430x_lc_rd_eabi.lib : hostopen.c.obj (.text:HOSTopen) + 0001740e 00000070 i2c_sensors.obj (.text:I2C_Sensors__ioExpanderInitPort0) + 0001747e 00000070 rts430x_lc_rd_eabi.lib : memory.c.obj (.text:split) + 000174ee 0000006e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeEchoBody) + 0001755c 0000006c rts430x_lc_rd_eabi.lib : hostwrite.c.obj (.text:HOSTwrite) + 000175c8 0000006c hercules_mpsm.obj (.text:HerculesMpsm__process) + 00017634 0000006c ring_buffer.obj (.text:RingBuffer__init) + 000176a0 0000006c adc.obj (.text:adc_init) + 0001770c 0000006a rts430x_lc_rd_eabi.lib : hostread.c.obj (.text:HOSTread) + 00017776 0000006a i2c_sensors.obj (.text:I2C_Sensors__ioExpanderReadPort1) + 000177e0 0000006a i2c_sensors.obj (.text:I2C_Sensors__readControl) + 0001784a 0000006a blimp.obj (.text:blimp_latchResetHigh) + 000178b4 0000006a blimp.obj (.text:blimp_latchResetLow) + 0001791e 0000006a rts430x_lc_rd_eabi.lib : fseek.c.obj (.text:fseek) + 00017988 0000006a ip_udp.obj (.text:ip_checksum) + 000179f2 00000068 serialization.obj (.text:Serialization__serializeAs16Bit) + 00017a5a 00000066 hercules_comms.obj (.text:HerculesComms__uninitialize) + 00017ac0 00000066 hercules_mpsm.obj (.text:HerculesMpsm__initMsg) + 00017b26 00000066 i2c_sensors.obj (.text:I2C_Sensors__ioExpanderInitPort1) + 00017b8c 00000066 i2c_sensors.obj (.text:I2C_Sensors__ioExpanderWritePort1) + 00017bf2 00000066 uart.obj (.text:UART__receive) + 00017c58 00000066 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetDebugCommsStateBody) + 00017cbe 00000066 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetVSAEStateBody) + 00017d24 00000066 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdSetDebugCommsStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00017d8a 00000064 hercules_mpsm.obj (.text:HerculesMpsm__appendData) + 00017dee 00000064 serialization.obj (.text:Serialization__deserializeAs16Bit) + 00017e52 00000064 rts430x_lc_rd_eabi.lib : fflush.c.obj (.text:__TI_doflush) + 00017eb6 00000064 blimp.obj (.text:blimp_initialize) + 00017f1a 00000064 blimp.obj (.text:blimp_latchSetHigh) + 00017f7e 00000064 blimp.obj (.text:blimp_latchSetLow) + 00017fe2 00000062 i2c_sensors.obj (.text:I2C_Sensors__lowPower) + 00018044 00000062 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase24doGndCmdLatchSetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 000180a6 00000062 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdLatchResetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00018108 00000062 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001816a 00000060 serialization.obj (.text:Serialization__serializeAs8Bit) + 000181ca 0000005c hercules_comms.obj (.text:HerculesComms__init) + 00018226 0000005c i2c_sensors.obj (.text:I2C_Sensors__accumulatedChargeLsb) + 00018282 0000005c lander_comms.obj (.text:LanderComms__init) + 000182de 0000005c serialization.obj (.text:Serialization__deserializeAs8Bit) + 0001833a 0000005c watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeClearResetMemoryBody) + 00018396 0000005a blimp.obj (.text:blimp_latchResetOff) + 000183f0 0000005a rts430x_lc_rd_eabi.lib : close.c.obj (.text:close) + 0001844a 0000005a : getdevice.c.obj (.text:getdevice) + 000184a4 00000058 i2c_sensors.obj (.text:I2C_Sensors__accumulatedChargeMsb) + 000184fc 00000058 rts430x_lc_rd_eabi.lib : fflush.c.obj (.text:fflush) + 00018554 00000056 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase20pumpMsgsFromHerculesERNS_12RoverContextE) + 000185aa 00000056 blimp.obj (.text:blimp_latchSetOff) + 00018600 00000054 rts430x_lc_rd_eabi.lib : autoinit.c.obj (.text:__TI_auto_init_nobinit_nopinit_hold_wdt:__TI_auto_init_nobinit_nopinit_hold_wdt) + 00018654 00000052 i2c_sensors.obj (.text:I2C_Sensors__currentLsb) + 000186a6 00000052 i2c_sensors.obj (.text:I2C_Sensors__gaugeTempMsb) + 000186f8 00000052 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase20doGndCmdSetVSAEStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001874a 00000052 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase24doGndCmdSetChargeEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001879c 00000052 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase25doGndCmdSetLatchBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 000187ee 00000052 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdDangForceBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00018840 00000050 i2c_sensors.obj (.text:I2C_Sensors__chargeLsb) + 00018890 00000050 i2c_sensors.obj (.text:I2C_Sensors__gaugeTempLsb) + 000188e0 00000050 i2c_sensors.obj (.text:I2C_Sensors__voltageLsb) + 00018930 00000050 i2c_sensors.obj (.text:I2C_Sensors__voltageMsb) + 00018980 00000050 i2c.obj (.text:I2C__txRegAddress) + 000189d0 00000050 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSwitchConnModeBody) + 00018a20 00000050 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase14txDownlinkDataERNS_12RoverContextEPvjb) + 00018a70 0000004e rts430x_lc_rd_eabi.lib : hostclose.c.obj (.text:HOSTclose) + 00018abe 0000004e uart.obj (.text:UART__init1) + 00018b0c 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeLatchResetPulseLowBody) + 00018b5a 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeLatchSetPulseLowBody) + 00018ba8 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeResetSpecificBody) + 00018bf6 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetBattCtrlEnStateBody) + 00018c44 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetBattEnStateBody) + 00018c92 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetChargeEnStateBody) + 00018ce0 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetChargeRegEnStateBody) + 00018d2e 0000004e watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetLatchBattStateBody) + 00018d7c 0000004c hercules_mpsm.obj (.text:HerculesMpsm__reset) + 00018dc8 0000004c RoverStateMission.obj (.text:_ZN4iris17RoverStateMission22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00018e14 0000004c RoverStateService.obj (.text:_ZN4iris17RoverStateService22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00018e60 0000004a i2c_sensors.obj (.text:I2C_Sensors__writeControl) + 00018eaa 0000004a uart.obj (.text:UART__init0) + 00018ef4 0000004a rts430x_lc_rd_eabi.lib : exit.c.obj (.text:exit) + 00018f3e 00000048 uart.obj (.text:UART__checkIfSendable) + 00018f86 00000048 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive12transitionToERNS_12RoverContextE) + 00018fce 00000048 rts430x_lc_rd_eabi.lib : _printfi_min.c.obj (.text:_pproc_str) + 00019016 00000046 : hostunlink.c.obj (.text:HOSTunlink) + 0001905c 00000046 hercules_comms.obj (.text:HerculesComms__txDownlinkData) + 000190a2 00000046 hercules_comms.obj (.text:HerculesComms__txUplinkMsg) + 000190e8 00000044 debug_comms.obj (.text:DebugComms__tryStringBufferToLanderNonblocking) + 0001912c 00000044 ip_udp.obj (.text:IpUdp__identifyDataInUdpPacket) + 00019170 00000044 rts430x_lc_rd_eabi.lib : sprintf.c.obj (.text:sprintf) + 000191b4 00000042 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22doGndCmdSetBattEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 000191f6 00000042 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase27doGndCmdSetChargeRegEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019238 00000042 bsp.obj (.text:clockInit) + 0001927a 00000040 event_queue.obj (.text:EventQueue__get) + 000192ba 00000040 hercules_comms.obj (.text:HerculesComms__txResponseMsg) + 000192fa 00000040 i2c.obj (.text:I2C__write) + 0001933a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeDeployBody) + 0001937a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeEnterKeepAliveModeBody) + 000193ba 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeEnterServiceModeBody) + 000193fa 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeEnterSleepModeBody) + 0001943a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializePrepForDeployBody) + 0001947a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeRequestDetailedReportBody) + 000194ba 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetAutoHeaterOffValueBody) + 000194fa 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetAutoHeaterOnValueBody) + 0001953a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetHeaterDutyCycleBody) + 0001957a 00000040 watchdog_cmd_msgs.obj (.text:WdCmdMsgs__deserializeSetHeaterDutyCyclePeriodBody) + 000195ba 0000003e i2c.obj (.text:I2C__read) + 000195f8 0000003e uart.obj (.text:UART__checkRxRbErrors) + 00019636 0000003e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase33handleRadioPowerCycleRadioCommandERNS_12RoverContextE) + 00019674 0000003e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase36handleRadioPowerCycleHerculesCommandERNS_12RoverContextE) + 000196b2 0000003e bsp.obj (.text:enableHeater) + 000196f0 0000003e rts430x_lc_rd_eabi.lib : lsl32.asm.obj (.text:l_lsl_const) + 0001972e 0000003e : lseek.c.obj (.text:lseek) + 0001976c 0000003c event_queue.obj (.text:EventQueue__initialize) + 000197a8 0000003c ring_buffer.obj (.text:RingBuffer__get) + 000197e4 0000003c ring_buffer.obj (.text:RingBuffer__peekAt) + 00019820 0000003c ring_buffer.obj (.text:RingBuffer__put) + 0001985c 0000003c RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdSetHeaterDutyCycleERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019898 0000003c rts430x_lc_rd_eabi.lib : write.c.obj (.text:write) + 000198d4 0000003a ring_buffer.obj (.text:RingBuffer__putOverwrite) + 0001990e 0000003a RoverStateService.obj (.text:_ZN4iris17RoverStateService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019948 0000003a RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019982 0000003a rts430x_lc_rd_eabi.lib : lsr64.c.obj (.text:__mspabi_srlll) + 000199bc 0000003a : vsprintf.c.obj (.text:vsprintf) + 000199f6 00000038 hercules_comms.obj (.text:HerculesComms__transmitBuffer) + 00019a2e 00000038 hercules_mpsm.obj (.text:HerculesMpsm__checkRb) + 00019a66 00000038 lander_comms.obj (.text:LanderComms__transmitBuffer) + 00019a9e 00000038 uart.obj (.text:UART__uninit0) + 00019ad6 00000038 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive25transitionToFinishUpSetupERNS_12RoverContextE) + 00019b0e 00000036 uart.obj (.text:UART__checkRxZerosMaxCountSinceLastCheck) + 00019b44 00000036 uart.obj (.text:UART__uart1Init) + 00019b7a 00000036 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase12doGndCmdEchoERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019bb0 00000036 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission12transitionToERNS_12RoverContextE) + 00019be6 00000036 rts430x_lc_rd_eabi.lib : fopen.c.obj (.text:__TI_cleanup) + 00019c1c 00000036 : trgmsg.c.obj (.text:__TI_writemsg) + 00019c52 00000034 uart.obj (.text:UART__uart0Init) + 00019c86 00000034 adc.obj (.text:adcCheckVoltageLevels) + 00019cba 00000034 blimp.obj (.text:blimp_latchBattUpdate) + 00019cee 00000034 blimp.obj (.text:blimp_normalBoot) + 00019d22 00000032 i2c_sensors.obj (.text:I2C_Sensors__initiateWriteIoExpander) + 00019d54 00000032 i2c.obj (.text:I2C__getTransactionStatus) + 00019d86 00000032 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive15handleTimerTickERNS_12RoverContextE) + 00019db8 00000032 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive18handleHerculesDataERNS_12RoverContextE) + 00019dea 00000032 rts430x_lc_rd_eabi.lib : trgmsg.c.obj (.text:__TI_readmsg) + 00019e1c 00000032 blimp.obj (.text:blimp_bstat_dangerous_forceHigh) + 00019e4e 00000032 blimp.obj (.text:blimp_bstat_dangerous_forceLow) + 00019e80 00000032 blimp.obj (.text:blimp_bstat_safe_restoreInput) + 00019eb2 00000032 blimp.obj (.text:blimp_vSysAllEnOff) + 00019ee4 00000032 rts430x_lc_rd_eabi.lib : strncpy.c.obj (.text:strncpy) + 00019f16 00000030 debug_comms.obj (.text:DebugComms__flush) + 00019f46 00000030 i2c.obj (.text:I2C__rxStart) + 00019f76 00000030 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase25handleRadioGotWifiCommandERNS_12RoverContextE) + 00019fa6 00000030 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 00019fd6 00000030 RoverStateService.obj (.text:_ZN4iris17RoverStateService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a006 00000030 blimp.obj (.text:blimp_bstat) + 0001a036 00000030 rts430x_lc_rd_eabi.lib : unlink.c.obj (.text:unlink) + 0001a066 0000002e hercules_comms.obj (.text:HerculesComms__flushTx) + 0001a094 0000002e hercules_mpsm.obj (.text:HerculesMpsm__peekRb) + 0001a0c2 0000002e i2c_sensors.obj (.text:I2C_Sensors__initiateIoExpanderInitialization) + 0001a0f0 0000002e i2c.obj (.text:I2C__init) + 0001a11e 0000002e lander_comms.obj (.text:LanderComms__flushTx) + 0001a14c 0000002e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase24doGndCmdClearResetMemoryERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a17a 0000002e RoverStateInit.obj (.text:_ZN4iris14RoverStateInitC1ENS_10RoverStateEPKc) + 0001a1a8 0000002e blimp.obj (.text:blimp_chargerEnOff) + 0001a1d6 0000002e blimp.obj (.text:blimp_latchResetPulseLow) + 0001a204 0000002e blimp.obj (.text:blimp_latchSetPulseLow) + 0001a232 0000002e blimp.obj (.text:blimp_vSysAllEnForceLow) + 0001a260 0000002e blimp.obj (.text:blimp_vSysAllEnOn) + 0001a28e 0000002e rts430x_lc_rd_eabi.lib : getdevice.c.obj (.text:finddevice) + 0001a2bc 0000002e main.obj (.text:main) + 0001a2ea 0000002c i2c_sensors.obj (.text:I2C_Sensors__getIoExpanderPortDirections) + 0001a316 0000002c i2c.obj (.text:I2C__waitForStop) + 0001a342 0000002c RoverStateBase.obj (.text:_ZN4iris14RoverStateBase32doGndCmdSetHeaterDutyCyclePeriodERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a36e 0000002c RoverStateMission.obj (.text:_ZN4iris17RoverStateMissionC1Ev) + 0001a39a 0000002c RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission29transitionToWaitingForI2cDoneERNS_12RoverContextE) + 0001a3c6 0000002c MSPMPU_INIT_LIB_CCS_msp430_large_code_restricted_data.lib : mpu_init.o (.text:__mpu_init) + 0001a3f2 0000002c rts430x_lc_rd_eabi.lib : memory.c.obj (.text:free_list_insert) + 0001a41e 0000002a i2c.obj (.text:I2C__txData) + 0001a448 0000002a RoverStateBase.obj (.text:_ZN4iris14RoverStateBase28doGndCmdSetAutoHeaterOnValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a472 0000002a RoverStateBase.obj (.text:_ZN4iris14RoverStateBase29doGndCmdSetAutoHeaterOffValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a49c 0000002a RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive12transitionToERNS_12RoverContextE) + 0001a4c6 0000002a blimp.obj (.text:blimp_chargerEnForceHigh) + 0001a4f0 0000002a blimp.obj (.text:blimp_chargerEnOn) + 0001a51a 0000002a rts430x_lc_rd_eabi.lib : memory.c.obj (.text:free_list_remove) + 0001a544 00000028 slip_mpsm.obj (.text:SlipMpsm__initMsg) + 0001a56c 00000028 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase21doGndCmdResetSpecificERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a594 00000028 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22handleUplinkFromLanderERNS_12RoverContextEPhj) + 0001a5bc 00000026 event_queue.obj (.text:EventQueue__put) + 0001a5e2 00000026 i2c.obj (.text:I2C__checkAck) + 0001a608 00000026 i2c.obj (.text:I2C__confirmStart) + 0001a62e 00000026 i2c.obj (.text:I2C__rxDataAndStop) + 0001a654 00000026 i2c.obj (.text:I2C__txStart) + 0001a67a 00000026 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission13heaterControlERNS_12RoverContextE) + 0001a6a0 00000026 bsp.obj (.text:setHerculesReset) + 0001a6c6 00000024 i2c_sensors.obj (.text:I2C_Sensors__initiateGaugeReadings) + 0001a6ea 00000024 i2c_sensors.obj (.text:I2C_Sensors__initiateReadControl) + 0001a70e 00000024 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMissionC1Ev) + 0001a732 00000024 RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a756 00000024 RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringServiceC1ENS_10RoverStateE) + 0001a77a 00000024 RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringServiceC1Ev) + 0001a79e 00000024 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a7c2 00000024 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAliveC1ENS_10RoverStateE) + 0001a7e6 00000024 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAliveC1Ev) + 0001a80a 00000024 rts430x_lc_rd_eabi.lib : copy_zero_init.c.obj (.text:decompress:ZI:__TI_zero_init) + 0001a82e 00000024 bsp.obj (.text:disableHeater) + 0001a852 00000024 bsp.obj (.text:disableUart0Pins) + 0001a876 00000022 i2c_sensors.obj (.text:I2C_Sensors__initiateReadIoExpander) + 0001a898 00000022 i2c_sensors.obj (.text:I2C_Sensors__initiateWriteLowPower) + 0001a8ba 00000022 i2c.obj (.text:I2C__stop) + 0001a8dc 00000022 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase29doGndCmdRequestDetailedReportERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001a8fe 00000022 RoverStateService.obj (.text:_ZN4iris17RoverStateServiceC1Ev) + 0001a920 00000022 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAliveC1Ev) + 0001a942 00000022 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission41transitionToWatitingForWifiReadyOrTimeoutERNS_12RoverContextE) + 0001a964 00000020 i2c_sensors.obj (.text:I2C_Sensors__initiateFuelGaugeInitialization) + 0001a984 00000020 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase21handleWdIntRisingEdgeERNS_12RoverContextE) + 0001a9a4 00000020 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22handleWdIntFallingEdgeERNS_12RoverContextE) + 0001a9c4 00000020 RoverStateBase.obj (.text:_ZN4iris14RoverStateBaseC1ENS_10RoverStateE) + 0001a9e4 00000020 rts430x_lc_rd_eabi.lib : sprintf.c.obj (.text:_outs) + 0001aa04 00000020 : vsprintf.c.obj (.text:_outs) + 0001aa24 0000001e i2c_sensors.obj (.text:I2C_Sensors__clearLastAction) + 0001aa42 0000001e i2c_sensors.obj (.text:I2C_Sensors__writeIoExpanderCurrentValuesBlocking) + 0001aa60 0000001e ring_buffer.obj (.text:RingBuffer__full) + 0001aa7e 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001aa9c 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase16handleLanderDataERNS_12RoverContextE) + 0001aaba 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase18handleHerculesDataERNS_12RoverContextE) + 0001aad8 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001aaf6 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22doGndCmdEnterSleepModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001ab14 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001ab32 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001ab50 0000001e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase26doGndCmdSetBattCtrlEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001ab6e 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit14handleHighTempERNS_12RoverContextE) + 0001ab8c 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit15handleTimerTickERNS_12RoverContextE) + 0001abaa 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit16handleLanderDataERNS_12RoverContextE) + 0001abc8 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit16handlePowerIssueERNS_12RoverContextE) + 0001abe6 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit18handleHerculesDataERNS_12RoverContextE) + 0001ac04 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response) + 0001ac22 0000001e RoverStateInit.obj (.text:_ZN4iris14RoverStateInit8spinOnceERNS_12RoverContextE) + 0001ac40 0000001e RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive18handleHerculesDataERNS_12RoverContextE) + 0001ac5e 0000001e RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission12transitionToERNS_12RoverContextE) + 0001ac7c 0000001e RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService12transitionToERNS_12RoverContextE) + 0001ac9a 0000001e blimp.obj (.text:blimp_battEnOff) + 0001acb8 0000001e blimp.obj (.text:blimp_latchBattOff) + 0001acd6 0000001e blimp.obj (.text:blimp_regEnOff) + 0001acf4 0000001e bsp.obj (.text:enableUart1Pins) + 0001ad12 0000001e rts430x_lc_rd_eabi.lib : memccpy.c.obj (.text:memccpy) + 0001ad30 0000001e bsp.obj (.text:releaseHerculesReset) + 0001ad4e 0000001c RoverStateBase.obj (.text:_ZN4iris14RoverStateBase22doGndCmdSwitchConnModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001ad6a 0000001c rts430x_lc_rd_eabi.lib : strchr.c.obj (.text:strchr) + 0001ad86 0000001c : strcmp.c.obj (.text:strcmp) + 0001ada2 0000001a hercules_comms.obj (.text:HerculesComms__isInitialized) + 0001adbc 0000001a uart.obj (.text:UART__isInitialized) + 0001add6 0000001a wd_int_mpsm.obj (.text:WdIntMpsm__processEdge) + 0001adf0 0000001a RoverStateMission.obj (.text:_ZN4iris17RoverStateMission20canEnterLowPowerModeERNS_12RoverContextE) + 0001ae0a 0000001a RoverStateService.obj (.text:_ZN4iris17RoverStateService12transitionToERNS_12RoverContextE) + 0001ae24 0000001a RoverStateService.obj (.text:_ZN4iris17RoverStateService20canEnterLowPowerModeERNS_12RoverContextE) + 0001ae3e 0000001a RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive20canEnterLowPowerModeERNS_12RoverContextE) + 0001ae58 0000001a RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService18handleHerculesDataERNS_12RoverContextE) + 0001ae72 0000001a rts430x_lc_rd_eabi.lib : assert.c.obj (.text:_abort_msg) + 0001ae8c 0000001a blimp.obj (.text:blimp_battEnOn) + 0001aea6 0000001a blimp.obj (.text:blimp_latchBattOn) + 0001aec0 0000001a bsp.obj (.text:enableUart0Pins) + 0001aeda 00000018 ring_buffer.obj (.text:RingBuffer__empty) + 0001aef2 00000018 ring_buffer.obj (.text:RingBuffer__freeCount) + 0001af0a 00000018 RoverStateService.obj (.text:_ZN4iris17RoverStateService21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001af22 00000018 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001af3a 00000018 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb) + 0001af52 00000018 blimp.obj (.text:blimp_regEnOn) + 0001af6a 00000018 bsp.obj (.text:powerOffRadio) + 0001af82 00000018 rts430x_lc_rd_eabi.lib : mult16_f5hw.asm.obj (.text) + 0001af9a 00000018 bsp.obj (.text:setFPGAReset) + 0001afb2 00000016 i2c_sensors.obj (.text:I2C_Sensors__initiateWriteIoExpanderCurrentValues) + 0001afc8 00000016 rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.text:_ZN10__cxxabiv120__si_class_type_infoD0Ev) + 0001afde 00000016 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase14handleHighTempERNS_12RoverContextE) + 0001aff4 00000016 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase28handleRadioExitStasisCommandERNS_12RoverContextE) + 0001b00a 00000016 RoverStateMission.obj (.text:_ZN4iris17RoverStateMission16handlePowerIssueERNS_12RoverContextE) + 0001b020 00000016 RoverStateService.obj (.text:_ZN4iris17RoverStateService16handlePowerIssueERNS_12RoverContextE) + 0001b036 00000016 RoverStateKeepAlive.obj (.text:_ZN4iris19RoverStateKeepAlive16handlePowerIssueERNS_12RoverContextE) + 0001b04c 00000016 RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission16handlePowerIssueERNS_12RoverContextE) + 0001b062 00000016 RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService16handlePowerIssueERNS_12RoverContextE) + 0001b078 00000016 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive16handlePowerIssueERNS_12RoverContextE) + 0001b08e 00000016 RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive22handleUplinkFromLanderERNS_12RoverContextEPhj) + 0001b0a4 00000016 bsp.obj (.text:disable3V3PowerRail) + 0001b0ba 00000016 bsp.obj (.text:enableWdIntFallingEdgeInterrupt) + 0001b0d0 00000016 bsp.obj (.text:enableWdIntRisingEdgeInterrupt) + 0001b0e6 00000016 bsp.obj (.text:fpgaCameraSelectLo) + 0001b0fc 00000016 rts430x_lc_rd_eabi.lib : memory.c.obj (.text:heap_start) + 0001b112 00000016 : memchr.c.obj (.text:memchr) + 0001b128 00000016 : memset.c.obj (.text:memset) + 0001b13e 00000016 bsp.obj (.text:powerOnRadio) + 0001b154 00000016 bsp.obj (.text:releaseFPGAReset) + 0001b16a 00000016 rts430x_lc_rd_eabi.lib : div16u.asm.obj (.text) + 0001b180 00000016 bsp.obj (.text:setRadioReset) + 0001b196 00000016 bsp.obj (.text:startChargingBatteries) + 0001b1ac 00000016 bsp.obj (.text:unsetDeploy) + 0001b1c2 00000014 debug_comms.obj (.text:DebugComms__registerHerculesComms) + 0001b1d6 00000014 debug_comms.obj (.text:DebugComms__registerLanderComms) + 0001b1ea 00000014 debug_comms.obj (.text:DebugComms__setEnabled) + 0001b1fe 00000014 ring_buffer.obj (.text:RingBuffer__clear) + 0001b212 00000014 ring_buffer.obj (.text:RingBuffer__usedCount) + 0001b226 00000014 rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.text:_ZN10__cxxabiv117__class_type_infoD0Ev) + 0001b23a 00000014 RoverStateBase.obj (.text:_ZN4iris14RoverStateBase8getStateEv) + 0001b24e 00000014 rts430x_lc_rd_eabi.lib : sprintf.c.obj (.text:_outc) + 0001b262 00000014 : vsprintf.c.obj (.text:_outc) + 0001b276 00000014 : memcpy.c.obj (.text:memcpy) + 0001b28a 00000014 bsp.obj (.text:powerOffFpga) + 0001b29e 00000014 bsp.obj (.text:powerOffHercules) + 0001b2b2 00000014 bsp.obj (.text:powerOffMotors) + 0001b2c6 00000014 bsp.obj (.text:releaseRadioReset) + 0001b2da 00000012 i2c_sensors.obj (.text:I2C_Sensors__stop) + 0001b2ec 00000012 rts430x_lc_rd_eabi.lib : copy_decompress_none.c.obj (.text:decompress:none:__TI_decompress_none) + 0001b2fe 00000012 bsp.obj (.text:enable3V3PowerRail) + 0001b310 00000012 adc.obj (.text:isAdcSampleDone) + 0001b322 00000012 rts430x_lc_rd_eabi.lib : strcpy.c.obj (.text:strcpy) + 0001b334 00000010 bsp.obj (.text:fpgaCameraSelectHi) + 0001b344 00000010 bsp.obj (.text:getWdIntState) + 0001b354 00000010 main.obj (.text:hook_sp_check) + 0001b364 00000010 rts430x_lc_rd_eabi.lib : lsr32.asm.obj (.text:l_lsr) + 0001b374 00000010 bsp.obj (.text:powerOnFpga) + 0001b384 00000010 bsp.obj (.text:powerOnHercules) + 0001b394 00000010 bsp.obj (.text:powerOnMotors) + 0001b3a4 00000010 bsp.obj (.text:setDeploy) + 0001b3b4 0000000e i2c_sensors.obj (.text:I2C_Sensors__init) + 0001b3c2 0000000e rts430x_lc_rd_eabi.lib : typeinfo.c.obj (.text:_ZN10__cxxabiv117__class_type_infoD1Ev) + 0001b3d0 0000000e : typeinfo.c.obj (.text:_ZN10__cxxabiv120__si_class_type_infoD1Ev) + 0001b3de 0000000e RoverStateBase.obj (.text:_ZN4iris14RoverStateBase29handleRadioEnterStasisCommandERNS_12RoverContextE) + 0001b3ec 0000000e blimp.obj (.text:blimp_batteryState) + 0001b3fa 0000000e rts430x_lc_rd_eabi.lib : strlen.c.obj (.text:strlen) + 0001b408 0000000e watchdog.obj (.text:watchdog_get_wd_int_flat_duration) + 0001b416 0000000c RoverStateBase.obj (.text:_ZN4iris14RoverStateBase20canEnterLowPowerModeERNS_12RoverContextE) + 0001b422 0000000c RoverStateInit.obj (.text:_ZN4iris14RoverStateInit20canEnterLowPowerModeERNS_12RoverContextE) + 0001b42e 0000000c RoverStateEnteringMission.obj (.text:_ZN4iris25RoverStateEnteringMission20canEnterLowPowerModeERNS_12RoverContextE) + 0001b43a 0000000c RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService28nextStateAfterSetupCompletesEv) + 0001b446 0000000c RoverStateEnteringService.obj (.text:_ZN4iris25RoverStateEnteringService8spinOnceERNS_12RoverContextE) + 0001b452 0000000c RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive20canEnterLowPowerModeERNS_12RoverContextE) + 0001b45e 0000000c RoverStateEnteringKeepAlive.obj (.text:_ZN4iris27RoverStateEnteringKeepAlive28nextStateAfterSetupCompletesEv) + 0001b46a 0000000a rts430x_lc_rd_eabi.lib : new.cpp.obj (.text:_ZdlPv) + 0001b474 0000000a bsp.obj (.text:disableBatteries) + 0001b47e 0000000a bsp.obj (.text:enableBatteries) + 0001b488 0000000a bsp.obj (.text:releaseMotorsReset) + 0001b492 0000000a rts430x_lc_rd_eabi.lib : lsl16.asm.obj (.text) + 0001b49c 0000000a : lsr16.asm.obj (.text) + 0001b4a6 0000000a bsp.obj (.text:setMotorsReset) + 0001b4b0 0000000a bsp.obj (.text:stopChargingBatteries) + 0001b4ba 00000008 rts430x_lc_rd_eabi.lib : pure_virt.c.obj (.text:__cxa_pure_virtual) + 0001b4c2 00000008 : memory.c.obj (.text:malloc) + 0001b4ca 00000008 bsp.obj (.text:releaseMotor1Reset) + 0001b4d2 00000008 bsp.obj (.text:releaseMotor2Reset) + 0001b4da 00000008 bsp.obj (.text:releaseMotor3Reset) + 0001b4e2 00000008 bsp.obj (.text:releaseMotor4Reset) + 0001b4ea 00000008 bsp.obj (.text:setMotor1Reset) + 0001b4f2 00000008 bsp.obj (.text:setMotor2Reset) + 0001b4fa 00000008 bsp.obj (.text:setMotor3Reset) + 0001b502 00000008 bsp.obj (.text:setMotor4Reset) + 0001b50a 00000006 i2c_sensors.obj (.text:I2C_Sensors__clearIoExpanderPort0OutputBits) + 0001b510 00000006 i2c_sensors.obj (.text:I2C_Sensors__clearIoExpanderPort1OutputBits) + 0001b516 00000006 i2c_sensors.obj (.text:I2C_Sensors__setIoExpanderPort0OutputBits) + 0001b51c 00000006 i2c_sensors.obj (.text:I2C_Sensors__setIoExpanderPort1OutputBits) + 0001b522 00000006 time.obj (.text:Time__getPointerToCentisecondCount) + 0001b528 00000006 time.obj (.text:Time__getTimeInCentiseconds) + 0001b52e 00000006 rts430x_lc_rd_eabi.lib : exit.c.obj (.text:abort) + 0001b534 00000006 bsp.obj (.text:disableVSysAllPowerRail) + 0001b53a 00000006 bsp.obj (.text:enableVSysAllPowerRail) + 0001b540 00000004 rts430x_lc_rd_eabi.lib : new.cpp.obj (.text:_ZdlPvj) + 0001b544 00000004 : error.c.obj (.text:__abort_execution) + 0001b548 00000004 : pre_init.c.obj (.text:_system_pre_init) + 0001b54c 00000002 : stdlib_typeinfo.cpp.obj (.text:_ZNSt9type_infoD1Ev) + 0001b54e 00000002 : _lock.c.obj (.text:_nop) + 0001b550 00000002 : startup.c.obj (.text:_system_post_cinit) + +MODULE SUMMARY + + Module code ro data rw data + ------ ---- ------- ------- + ./src/ + watchdog.obj 1514 544 12 + main.obj 62 0 0 + +--+---------------------------------+-------+---------+---------+ + Total: 1576 544 12 + + ./src/comms/ + i2c_sensors.obj 4092 2034 52 + watchdog_cmd_msgs.obj 2608 1144 0 + lander_comms.obj 1404 591 1277 + hercules_comms.obj 1260 1012 846 + ground_msgs.obj 2710 118 1 + hercules_mpsm.obj 1136 546 26 + ip_udp.obj 856 106 0 + debug_comms.obj 294 320 265 + hercules_msgs.obj 312 0 0 + slip_mpsm.obj 292 0 4 + slip_encode.obj 184 0 0 + cmd_msgs.obj 152 0 0 + wd_int_mpsm.obj 26 24 0 + +--+---------------------------------+-------+---------+---------+ + Total: 15326 5895 2471 + + ./src/drivers/ + bsp.obj 2096 1010 4 + uart.obj 1778 582 52 + blimp.obj 1534 744 4 + i2c.obj 802 250 8 + adc.obj 330 60 8 + +--+---------------------------------+-------+---------+---------+ + Total: 6540 2646 76 + + ./src/event/ + event_queue.obj 162 74 6 + +--+---------------------------------+-------+---------+---------+ + Total: 162 74 6 + + ./src/stateMachine/ + RoverStateBase.obj 8266 10237 171 + RoverStateEnteringMission.obj 2384 3417 24 + RoverStateManager.obj 1248 870 3074 + RoverStateEnteringKeepAlive.obj 1148 2697 4 + RoverStateMission.obj 1422 1867 24 + RoverStateInit.obj 718 2536 0 + RoverStateService.obj 1046 1695 24 + RoverStateKeepAlive.obj 548 1249 0 + RoverStateEnteringService.obj 386 1123 0 + RoverState.obj 128 206 0 + +--+---------------------------------+-------+---------+---------+ + Total: 17294 25897 3321 + + ./src/utils/ + serialization.obj 766 0 0 + ring_buffer.obj 464 0 82 + time.obj 12 0 2 + +--+---------------------------------+-------+---------+---------+ + Total: 1242 0 84 + + /home/iris/ti/ccs910/ccs/ccs_base/msp430/lib/FR59xx/MSPMPU_INIT_LIB_CCS_msp430_large_code_restricted_data.lib + mpu_init.o 44 0 0 + +--+---------------------------------+-------+---------+---------+ + Total: 44 0 0 + + /home/iris/ti/ccs910/ccs/tools/compiler/ti-cgt-msp430_18.12.2.LTS/lib/rts430x_lc_rd_eabi.lib + _printfi_min.c.obj 816 20 0 + memory.c.obj 710 0 6 + trgmsg.c.obj 104 0 288 + defs.c.obj 0 0 362 + fputs.c.obj 240 0 0 + setvbuf.c.obj 222 0 0 + typeinfo.c.obj 70 127 0 + fflush.c.obj 188 0 0 + host_device.c.obj 0 0 180 + hostlseek.c.obj 154 0 0 + getdevice.c.obj 136 0 0 + _io_perm.c.obj 126 0 0 + hostopen.c.obj 112 0 8 + sprintf.c.obj 120 0 0 + copy_decompress_lzss.c.obj 118 0 0 + fclose.c.obj 116 0 0 + hostrename.c.obj 116 0 0 + vsprintf.c.obj 110 0 0 + hostwrite.c.obj 108 0 0 + fseek.c.obj 106 0 0 + hostread.c.obj 106 0 0 + close.c.obj 90 0 0 + autoinit.c.obj 84 0 0 + exit.c.obj 80 0 2 + hostclose.c.obj 78 0 0 + hostunlink.c.obj 70 0 0 + lseek.c.obj 62 0 0 + lsl32.asm.obj 62 0 0 + write.c.obj 60 0 0 + lsr64.c.obj 58 0 0 + fopen.c.obj 54 0 0 + strncpy.c.obj 50 0 0 + unlink.c.obj 48 0 0 + copy_zero_init.c.obj 36 0 0 + boot.c.obj 32 2 0 + memccpy.c.obj 30 0 0 + strchr.c.obj 28 0 0 + strcmp.c.obj 28 0 0 + assert.c.obj 26 0 0 + mult16_f5hw.asm.obj 24 0 0 + stdlib_typeinfo.cpp.obj 2 21 0 + div16u.asm.obj 22 0 0 + memchr.c.obj 22 0 0 + memset.c.obj 22 0 0 + memcpy.c.obj 20 0 0 + copy_decompress_none.c.obj 18 0 0 + strcpy.c.obj 18 0 0 + lsr32.asm.obj 16 0 0 + new.cpp.obj 14 0 0 + strlen.c.obj 14 0 0 + _lock.c.obj 2 0 8 + lsl16.asm.obj 10 0 0 + lsr16.asm.obj 10 0 0 + exit_gvars.c.obj 0 0 8 + isr_trap.asm.obj 8 0 0 + pure_virt.c.obj 8 0 0 + error.c.obj 4 0 0 + pre_init.c.obj 4 0 0 + int18.asm.obj 0 2 0 + int19.asm.obj 0 2 0 + int20.asm.obj 0 2 0 + int21.asm.obj 0 2 0 + int22.asm.obj 0 2 0 + int23.asm.obj 0 2 0 + int24.asm.obj 0 2 0 + int25.asm.obj 0 2 0 + int26.asm.obj 0 2 0 + int27.asm.obj 0 2 0 + int28.asm.obj 0 2 0 + int29.asm.obj 0 2 0 + int30.asm.obj 0 2 0 + int31.asm.obj 0 2 0 + int32.asm.obj 0 2 0 + int33.asm.obj 0 2 0 + int34.asm.obj 0 2 0 + int35.asm.obj 0 2 0 + int36.asm.obj 0 2 0 + int37.asm.obj 0 2 0 + int38.asm.obj 0 2 0 + int40.asm.obj 0 2 0 + int41.asm.obj 0 2 0 + int42.asm.obj 0 2 0 + int45.asm.obj 0 2 0 + int47.asm.obj 0 2 0 + int50.asm.obj 0 2 0 + int51.asm.obj 0 2 0 + int52.asm.obj 0 2 0 + int53.asm.obj 0 2 0 + int54.asm.obj 0 2 0 + startup.c.obj 2 0 0 + +--+---------------------------------+-------+---------+---------+ + Total: 4994 232 862 + + Heap: 0 0 8 + Stack: 0 0 1492 + Linker Generated: 0 145 0 + +--+---------------------------------+-------+---------+---------+ + Grand Total: 47178 35433 8332 + + +LINKER GENERATED COPY TABLES + +__TI_cinit_table @ 0000d10e records: 2, size/record: 8, table size: 16 + .data: load addr=0000d08c, load size=0000006f bytes, run addr=0000290e, run size=00000c82 bytes, compression=lzss + .bss: load addr=0000d108, load size=00000006 bytes, run addr=00001c00, run size=00000d0e bytes, compression=zero_init + + +LINKER GENERATED HANDLER TABLE + +__TI_handler_table @ 0000d0fc records: 3, size/record: 4, table size: 12 + index: 0, handler: __TI_zero_init + index: 1, handler: __TI_decompress_lzss + index: 2, handler: __TI_decompress_none + + +GLOBAL SYMBOLS: SORTED ALPHABETICALLY BY Name + +address name +------- ---- +00000800 ADC12CTL0 +00000801 ADC12CTL0_H +00000800 ADC12CTL0_L +00000802 ADC12CTL1 +00000803 ADC12CTL1_H +00000802 ADC12CTL1_L +00000804 ADC12CTL2 +00000805 ADC12CTL2_H +00000804 ADC12CTL2_L +00000806 ADC12CTL3 +00000807 ADC12CTL3_H +00000806 ADC12CTL3_L +0000080a ADC12HI +0000080b ADC12HI_H +0000080a ADC12HI_L +00000812 ADC12IER0 +00000813 ADC12IER0_H +00000812 ADC12IER0_L +00000814 ADC12IER1 +00000815 ADC12IER1_H +00000814 ADC12IER1_L +00000816 ADC12IER2 +00000817 ADC12IER2_H +00000816 ADC12IER2_L +0000080c ADC12IFGR0 +0000080d ADC12IFGR0_H +0000080c ADC12IFGR0_L +0000080e ADC12IFGR1 +0000080f ADC12IFGR1_H +0000080e ADC12IFGR1_L +00000810 ADC12IFGR2 +00000811 ADC12IFGR2_H +00000810 ADC12IFGR2_L +00000818 ADC12IV +00000819 ADC12IV_H +00000818 ADC12IV_L +00000808 ADC12LO +00000809 ADC12LO_H +00000808 ADC12LO_L +00000820 ADC12MCTL0 +00000821 ADC12MCTL0_H +00000820 ADC12MCTL0_L +00000822 ADC12MCTL1 +00000834 ADC12MCTL10 +00000835 ADC12MCTL10_H +00000834 ADC12MCTL10_L +00000836 ADC12MCTL11 +00000837 ADC12MCTL11_H +00000836 ADC12MCTL11_L +00000838 ADC12MCTL12 +00000839 ADC12MCTL12_H +00000838 ADC12MCTL12_L +0000083a ADC12MCTL13 +0000083b ADC12MCTL13_H +0000083a ADC12MCTL13_L +0000083c ADC12MCTL14 +0000083d ADC12MCTL14_H +0000083c ADC12MCTL14_L +0000083e ADC12MCTL15 +0000083f ADC12MCTL15_H +0000083e ADC12MCTL15_L +00000840 ADC12MCTL16 +00000841 ADC12MCTL16_H +00000840 ADC12MCTL16_L +00000842 ADC12MCTL17 +00000843 ADC12MCTL17_H +00000842 ADC12MCTL17_L +00000844 ADC12MCTL18 +00000845 ADC12MCTL18_H +00000844 ADC12MCTL18_L +00000846 ADC12MCTL19 +00000847 ADC12MCTL19_H +00000846 ADC12MCTL19_L +00000823 ADC12MCTL1_H +00000822 ADC12MCTL1_L +00000824 ADC12MCTL2 +00000848 ADC12MCTL20 +00000849 ADC12MCTL20_H +00000848 ADC12MCTL20_L +0000084a ADC12MCTL21 +0000084b ADC12MCTL21_H +0000084a ADC12MCTL21_L +0000084c ADC12MCTL22 +0000084d ADC12MCTL22_H +0000084c ADC12MCTL22_L +0000084e ADC12MCTL23 +0000084f ADC12MCTL23_H +0000084e ADC12MCTL23_L +00000850 ADC12MCTL24 +00000851 ADC12MCTL24_H +00000850 ADC12MCTL24_L +00000852 ADC12MCTL25 +00000853 ADC12MCTL25_H +00000852 ADC12MCTL25_L +00000854 ADC12MCTL26 +00000855 ADC12MCTL26_H +00000854 ADC12MCTL26_L +00000856 ADC12MCTL27 +00000857 ADC12MCTL27_H +00000856 ADC12MCTL27_L +00000858 ADC12MCTL28 +00000859 ADC12MCTL28_H +00000858 ADC12MCTL28_L +0000085a ADC12MCTL29 +0000085b ADC12MCTL29_H +0000085a ADC12MCTL29_L +00000825 ADC12MCTL2_H +00000824 ADC12MCTL2_L +00000826 ADC12MCTL3 +0000085c ADC12MCTL30 +0000085d ADC12MCTL30_H +0000085c ADC12MCTL30_L +0000085e ADC12MCTL31 +0000085f ADC12MCTL31_H +0000085e ADC12MCTL31_L +00000827 ADC12MCTL3_H +00000826 ADC12MCTL3_L +00000828 ADC12MCTL4 +00000829 ADC12MCTL4_H +00000828 ADC12MCTL4_L +0000082a ADC12MCTL5 +0000082b ADC12MCTL5_H +0000082a ADC12MCTL5_L +0000082c ADC12MCTL6 +0000082d ADC12MCTL6_H +0000082c ADC12MCTL6_L +0000082e ADC12MCTL7 +0000082f ADC12MCTL7_H +0000082e ADC12MCTL7_L +00000830 ADC12MCTL8 +00000831 ADC12MCTL8_H +00000830 ADC12MCTL8_L +00000832 ADC12MCTL9 +00000833 ADC12MCTL9_H +00000832 ADC12MCTL9_L +00000860 ADC12MEM0 +00000861 ADC12MEM0_H +00000860 ADC12MEM0_L +00000862 ADC12MEM1 +00000874 ADC12MEM10 +00000875 ADC12MEM10_H +00000874 ADC12MEM10_L +00000876 ADC12MEM11 +00000877 ADC12MEM11_H +00000876 ADC12MEM11_L +00000878 ADC12MEM12 +00000879 ADC12MEM12_H +00000878 ADC12MEM12_L +0000087a ADC12MEM13 +0000087b ADC12MEM13_H +0000087a ADC12MEM13_L +0000087c ADC12MEM14 +0000087d ADC12MEM14_H +0000087c ADC12MEM14_L +0000087e ADC12MEM15 +0000087f ADC12MEM15_H +0000087e ADC12MEM15_L +00000880 ADC12MEM16 +00000881 ADC12MEM16_H +00000880 ADC12MEM16_L +00000882 ADC12MEM17 +00000883 ADC12MEM17_H +00000882 ADC12MEM17_L +00000884 ADC12MEM18 +00000885 ADC12MEM18_H +00000884 ADC12MEM18_L +00000886 ADC12MEM19 +00000887 ADC12MEM19_H +00000886 ADC12MEM19_L +00000863 ADC12MEM1_H +00000862 ADC12MEM1_L +00000864 ADC12MEM2 +00000888 ADC12MEM20 +00000889 ADC12MEM20_H +00000888 ADC12MEM20_L +0000088a ADC12MEM21 +0000088b ADC12MEM21_H +0000088a ADC12MEM21_L +0000088c ADC12MEM22 +0000088d ADC12MEM22_H +0000088c ADC12MEM22_L +0000088e ADC12MEM23 +0000088f ADC12MEM23_H +0000088e ADC12MEM23_L +00000890 ADC12MEM24 +00000891 ADC12MEM24_H +00000890 ADC12MEM24_L +00000892 ADC12MEM25 +00000893 ADC12MEM25_H +00000892 ADC12MEM25_L +00000894 ADC12MEM26 +00000895 ADC12MEM26_H +00000894 ADC12MEM26_L +00000896 ADC12MEM27 +00000897 ADC12MEM27_H +00000896 ADC12MEM27_L +00000898 ADC12MEM28 +00000899 ADC12MEM28_H +00000898 ADC12MEM28_L +0000089a ADC12MEM29 +0000089b ADC12MEM29_H +0000089a ADC12MEM29_L +00000865 ADC12MEM2_H +00000864 ADC12MEM2_L +00000866 ADC12MEM3 +0000089c ADC12MEM30 +0000089d ADC12MEM30_H +0000089c ADC12MEM30_L +0000089e ADC12MEM31 +0000089f ADC12MEM31_H +0000089e ADC12MEM31_L +00000867 ADC12MEM3_H +00000866 ADC12MEM3_L +00000868 ADC12MEM4 +00000869 ADC12MEM4_H +00000868 ADC12MEM4_L +0000086a ADC12MEM5 +0000086b ADC12MEM5_H +0000086a ADC12MEM5_L +0000086c ADC12MEM6 +0000086d ADC12MEM6_H +0000086c ADC12MEM6_L +0000086e ADC12MEM7 +0000086f ADC12MEM7_H +0000086e ADC12MEM7_L +00000870 ADC12MEM8 +00000871 ADC12MEM8_H +00000870 ADC12MEM8_L +00000872 ADC12MEM9 +00000873 ADC12MEM9_H +00000872 ADC12MEM9_L +00004594 ADC12_ISR +000009c0 AESACTL0 +000009c1 AESACTL0_H +000009c0 AESACTL0_L +000009c2 AESACTL1 +000009c3 AESACTL1_H +000009c2 AESACTL1_L +000009c8 AESADIN +000009c9 AESADIN_H +000009c8 AESADIN_L +000009ca AESADOUT +000009cb AESADOUT_H +000009ca AESADOUT_L +000009c6 AESAKEY +000009c7 AESAKEY_H +000009c6 AESAKEY_L +000009c4 AESASTAT +000009c5 AESASTAT_H +000009c4 AESASTAT_L +000009cc AESAXDIN +000009cd AESAXDIN_H +000009cc AESAXDIN_L +000009ce AESAXIN +000009cf AESAXIN_H +000009ce AESAXIN_L +000004be BCD2BIN +000004bf BCD2BIN_H +000004be BCD2BIN_L +000004bc BIN2BCD +000004bd BIN2BCD_H +000004bc BIN2BCD_L +0001b52e C$$EXIT +00019c4e C$$IO$$ +0000043e CAPTIO0CTL +0000043f CAPTIO0CTL_H +0000043e CAPTIO0CTL_L +0000047e CAPTIO1CTL +0000047f CAPTIO1CTL_H +0000047e CAPTIO1CTL_L +000008c0 CECTL0 +000008c1 CECTL0_H +000008c0 CECTL0_L +000008c2 CECTL1 +000008c3 CECTL1_H +000008c2 CECTL1_L +000008c4 CECTL2 +000008c5 CECTL2_H +000008c4 CECTL2_L +000008c6 CECTL3 +000008c7 CECTL3_H +000008c6 CECTL3_L +000008cc CEINT +000008cd CEINT_H +000008cc CEINT_L +000008ce CEIV +000008cf CEIV_H +000008ce CEIV_L +00000996 CRC16DIRBW0 +00000997 CRC16DIRBW0_H +00000996 CRC16DIRBW0_L +00000990 CRC16DIW0 +00000991 CRC16DIW0_H +00000990 CRC16DIW0_L +00000998 CRC16INIRESW0 +00000999 CRC16INIRESW0_H +00000998 CRC16INIRESW0_L +0000099e CRC16RESRW0 +0000099f CRC16RESRW0_H +0000099e CRC16RESRW0_L +00000986 CRC32DIRBW0 +00000987 CRC32DIRBW0_H +00000986 CRC32DIRBW0_L +00000984 CRC32DIRBW1 +00000985 CRC32DIRBW1_H +00000984 CRC32DIRBW1_L +00000980 CRC32DIW0 +00000981 CRC32DIW0_H +00000980 CRC32DIW0_L +00000982 CRC32DIW1 +00000983 CRC32DIW1_H +00000982 CRC32DIW1_L +00000988 CRC32INIRESW0 +00000989 CRC32INIRESW0_H +00000988 CRC32INIRESW0_L +0000098a CRC32INIRESW1 +0000098b CRC32INIRESW1_H +0000098a CRC32INIRESW1_L +0000098e CRC32RESRW0 +0000098f CRC32RESRW0_H +0000098e CRC32RESRW0_L +0000098c CRC32RESRW1 +0000098d CRC32RESRW1_H +0000098c CRC32RESRW1_L +00000150 CRCDI +00000152 CRCDIRB +00000153 CRCDIRB_H +00000152 CRCDIRB_L +00000151 CRCDI_H +00000150 CRCDI_L +00000154 CRCINIRES +00000155 CRCINIRES_H +00000154 CRCINIRES_L +00000156 CRCRESR +00000157 CRCRESR_H +00000156 CRCRESR_L +00000160 CSCTL0 +00000161 CSCTL0_H +00000160 CSCTL0_L +00000162 CSCTL1 +00000163 CSCTL1_H +00000162 CSCTL1_L +00000164 CSCTL2 +00000165 CSCTL2_H +00000164 CSCTL2_L +00000166 CSCTL3 +00000167 CSCTL3_H +00000166 CSCTL3_L +00000168 CSCTL4 +00000169 CSCTL4_H +00000168 CSCTL4_L +0000016a CSCTL5 +0000016b CSCTL5_H +0000016a CSCTL5_L +0000016c CSCTL6 +0000016d CSCTL6_H +0000016c CSCTL6_L +00016298 CmdMsgs__deserializeHeader +00000510 DMA0CTL +00000511 DMA0CTL_H +00000510 DMA0CTL_L +00000516 DMA0DA +00000518 DMA0DAH +00000516 DMA0DAL +00000512 DMA0SA +00000514 DMA0SAH +00000512 DMA0SAL +0000051a DMA0SZ +0000051b DMA0SZ_H +0000051a DMA0SZ_L +00000520 DMA1CTL +00000521 DMA1CTL_H +00000520 DMA1CTL_L +00000526 DMA1DA +00000528 DMA1DAH +00000526 DMA1DAL +00000522 DMA1SA +00000524 DMA1SAH +00000522 DMA1SAL +0000052a DMA1SZ +0000052b DMA1SZ_H +0000052a DMA1SZ_L +00000530 DMA2CTL +00000531 DMA2CTL_H +00000530 DMA2CTL_L +00000536 DMA2DA +00000538 DMA2DAH +00000536 DMA2DAL +00000532 DMA2SA +00000534 DMA2SAH +00000532 DMA2SAL +0000053a DMA2SZ +0000053b DMA2SZ_H +0000053a DMA2SZ_L +00000540 DMA3CTL +00000541 DMA3CTL_H +00000540 DMA3CTL_L +00000546 DMA3DA +00000548 DMA3DAH +00000546 DMA3DAL +00000542 DMA3SA +00000544 DMA3SAH +00000542 DMA3SAL +0000054a DMA3SZ +0000054b DMA3SZ_H +0000054a DMA3SZ_L +00000550 DMA4CTL +00000551 DMA4CTL_H +00000550 DMA4CTL_L +00000556 DMA4DA +00000558 DMA4DAH +00000556 DMA4DAL +00000552 DMA4SA +00000554 DMA4SAH +00000552 DMA4SAL +0000055a DMA4SZ +0000055b DMA4SZ_H +0000055a DMA4SZ_L +00000560 DMA5CTL +00000561 DMA5CTL_H +00000560 DMA5CTL_L +00000566 DMA5DA +00000568 DMA5DAH +00000566 DMA5DAL +00000562 DMA5SA +00000564 DMA5SAH +00000562 DMA5SAL +0000056a DMA5SZ +0000056b DMA5SZ_H +0000056a DMA5SZ_L +00000500 DMACTL0 +00000501 DMACTL0_H +00000500 DMACTL0_L +00000502 DMACTL1 +00000503 DMACTL1_H +00000502 DMACTL1_L +00000504 DMACTL2 +00000505 DMACTL2_H +00000504 DMACTL2_L +00000508 DMACTL4 +00000509 DMACTL4_H +00000508 DMACTL4_L +0000050e DMAIV +0000050f DMAIV_H +0000050e DMAIV_L +00019f16 DebugComms__flush +0001b1c2 DebugComms__registerHerculesComms +0001b1d6 DebugComms__registerLanderComms +0001b1ea DebugComms__setEnabled +00016f10 DebugComms__tryPrintfToLanderNonblocking +000190e8 DebugComms__tryStringBufferToLanderNonblocking +0001927a EventQueue__get +0001976c EventQueue__initialize +0001a5bc EventQueue__put +00000140 FRCTL0 +00000141 FRCTL0_H +00000140 FRCTL0_L +00000144 GCCTL0 +00000145 GCCTL0_H +00000144 GCCTL0_L +00000146 GCCTL1 +00000147 GCCTL1_H +00000146 GCCTL1_L +00010000 GroundMsgs__generateDetailedReport +00015f78 GroundMsgs__generateFlightEarthHeartbeat +0001516a GroundMsgs__generateFullEarthHeartbeat +00018a70 HOSTclose +00016164 HOSTlseek +0001739e HOSTopen +0001770c HOSTread +0001715e HOSTrename +00019016 HOSTunlink +0001755c HOSTwrite +00013eca HercMsgs__serializeHeader +0001a066 HerculesComms__flushTx +000181ca HerculesComms__init +0001ada2 HerculesComms__isInitialized +000163c4 HerculesComms__resetState +00013434 HerculesComms__tryGetMessage +0001905c HerculesComms__txDownlinkData +000192ba HerculesComms__txResponseMsg +000190a2 HerculesComms__txUplinkMsg +00017a5a HerculesComms__uninitialize +00017ac0 HerculesMpsm__initMsg +000175c8 HerculesMpsm__process +00018d7c HerculesMpsm__reset +0001b50a I2C_Sensors__clearIoExpanderPort0OutputBits +0001b510 I2C_Sensors__clearIoExpanderPort1OutputBits +0001aa24 I2C_Sensors__clearLastAction +000125b8 I2C_Sensors__getActionStatus +0001a2ea I2C_Sensors__getIoExpanderPortDirections +0001b3b4 I2C_Sensors__init +0001a964 I2C_Sensors__initiateFuelGaugeInitialization +0001a6c6 I2C_Sensors__initiateGaugeReadings +0001a0c2 I2C_Sensors__initiateIoExpanderInitialization +0001a6ea I2C_Sensors__initiateReadControl +0001a876 I2C_Sensors__initiateReadIoExpander +00019d22 I2C_Sensors__initiateWriteIoExpander +0001afb2 I2C_Sensors__initiateWriteIoExpanderCurrentValues +0001a898 I2C_Sensors__initiateWriteLowPower +0001b516 I2C_Sensors__setIoExpanderPort0OutputBits +0001b51c I2C_Sensors__setIoExpanderPort1OutputBits +00012baa I2C_Sensors__spinOnce +0001b2da I2C_Sensors__stop +00014cd2 I2C_Sensors__writeIoExpanderBlocking +0001aa42 I2C_Sensors__writeIoExpanderCurrentValuesBlocking +000149e0 I2C_Sensors__writeIoExpanderPortDirectionsBlocking +00019d54 I2C__getTransactionStatus +0001a0f0 I2C__init +000195ba I2C__read +00015d64 I2C__spinOnce +0001a8ba I2C__stop +000192fa I2C__write +000127bc IpUdp__generateAndSerializeIpUdpHeadersForData +0001912c IpUdp__identifyDataInUdpPacket +00000a80 LEACAP +00000a82 LEACAPH +00000a80 LEACAPL +00000a98 LEACMA +00000a9a LEACMAH +00000a98 LEACMAL +00000a9c LEACMCTL +00000a9e LEACMCTLH +00000a9c LEACMCTLL +00000aa8 LEACMDSTAT +00000aaa LEACMDSTATH +00000aa8 LEACMDSTATL +00000a84 LEACNF0 +00000a86 LEACNF0H +00000a84 LEACNF0L +00000a88 LEACNF1 +00000a8a LEACNF1H +00000a88 LEACNF1L +00000a8c LEACNF2 +00000a8e LEACNF2H +00000a8c LEACNF2L +00000ab4 LEADSTSTAT +00000ab6 LEADSTSTATH +00000ab4 LEADSTSTATL +00000af4 LEAIE +00000af6 LEAIEH +00000af4 LEAIEL +00000af8 LEAIFG +00000afa LEAIFGH +00000af8 LEAIFGL +00000af0 LEAIFGSET +00000af2 LEAIFGSETH +00000af0 LEAIFGSETL +00000afc LEAIV +00000afe LEAIVH +00000afc LEAIVL +00000a90 LEAMB +00000a92 LEAMBH +00000a90 LEAMBL +00000a94 LEAMT +00000a96 LEAMTH +00000a94 LEAMTL +00000ad0 LEAPMCB +00000ad2 LEAPMCBH +00000ad0 LEAPMCBL +00000ac0 LEAPMCTL +00000ac2 LEAPMCTLH +00000ac0 LEAPMCTLL +00000ac4 LEAPMDST +00000ac6 LEAPMDSTH +00000ac4 LEAPMDSTL +00000acc LEAPMS0 +00000ace LEAPMS0H +00000acc LEAPMS0L +00000ac8 LEAPMS1 +00000aca LEAPMS1H +00000ac8 LEAPMS1L +00000ab0 LEAS0STAT +00000ab2 LEAS0STATH +00000ab0 LEAS0STATL +00000aac LEAS1STAT +00000aae LEAS1STATH +00000aac LEAS1STATL +0001a11e LanderComms__flushTx +00018282 LanderComms__init +00014266 LanderComms__tryGetMessage +000135ae LanderComms__txData +00014adc LanderComms__txDataUntilSendOrTimeout +000004c4 MAC +000004da MAC32H +000004db MAC32H_H +000004da MAC32H_L +000004d8 MAC32L +000004d9 MAC32L_H +000004d8 MAC32L_L +000004c6 MACS +000004de MACS32H +000004df MACS32H_H +000004de MACS32H_L +000004dc MACS32L +000004dd MACS32L_H +000004dc MACS32L_L +000004c7 MACS_H +000004c6 MACS_L +000004c5 MAC_H +000004c4 MAC_L +000005a0 MPUCTL0 +000005a1 MPUCTL0_H +000005a0 MPUCTL0_L +000005a2 MPUCTL1 +000005a3 MPUCTL1_H +000005a2 MPUCTL1_L +000005aa MPUIPC0 +000005ab MPUIPC0_H +000005aa MPUIPC0_L +000005ae MPUIPSEGB1 +000005af MPUIPSEGB1_H +000005ae MPUIPSEGB1_L +000005ac MPUIPSEGB2 +000005ad MPUIPSEGB2_H +000005ac MPUIPSEGB2_L +000005a8 MPUSAM +000005a9 MPUSAM_H +000005a8 MPUSAM_L +000005a6 MPUSEGB1 +000005a7 MPUSEGB1_H +000005a6 MPUSEGB1_L +000005a4 MPUSEGB2 +000005a5 MPUSEGB2_H +000005a4 MPUSEGB2_L +000004c0 MPY +000004ec MPY32CTL0 +000004ed MPY32CTL0_H +000004ec MPY32CTL0_L +000004d2 MPY32H +000004d3 MPY32H_H +000004d2 MPY32H_L +000004d0 MPY32L +000004d1 MPY32L_H +000004d0 MPY32L_L +000004c2 MPYS +000004d6 MPYS32H +000004d7 MPYS32H_H +000004d6 MPYS32H_L +000004d4 MPYS32L +000004d5 MPYS32L_H +000004d4 MPYS32L_L +000004c3 MPYS_H +000004c2 MPYS_L +000004c1 MPY_H +000004c0 MPY_L +000004c8 OP2 +000004e2 OP2H +000004e3 OP2H_H +000004e2 OP2H_L +000004e0 OP2L +000004e1 OP2L_H +000004e0 OP2L_L +000004c9 OP2_H +000004c8 OP2_L +00000204 P1DIR +0000021a P1IE +00000218 P1IES +0000021c P1IFG +00000200 P1IN +0000020e P1IV +0000020f P1IV_H +0000020e P1IV_L +00000202 P1OUT +00000206 P1REN +0000020a P1SEL0 +0000020c P1SEL1 +00000216 P1SELC +00000205 P2DIR +0000021b P2IE +00000219 P2IES +0000021d P2IFG +00000201 P2IN +0000021e P2IV +0000021f P2IV_H +0000021e P2IV_L +00000203 P2OUT +00000207 P2REN +0000020b P2SEL0 +0000020d P2SEL1 +00000217 P2SELC +00000224 P3DIR +0000023a P3IE +00000238 P3IES +0000023c P3IFG +00000220 P3IN +0000022e P3IV +0000022f P3IV_H +0000022e P3IV_L +00000222 P3OUT +00000226 P3REN +0000022a P3SEL0 +0000022c P3SEL1 +00000236 P3SELC +00000225 P4DIR +0000023b P4IE +00000239 P4IES +0000023d P4IFG +00000221 P4IN +0000023e P4IV +0000023f P4IV_H +0000023e P4IV_L +00000223 P4OUT +00000227 P4REN +0000022b P4SEL0 +0000022d P4SEL1 +00000237 P4SELC +00000244 P5DIR +0000025a P5IE +00000258 P5IES +0000025c P5IFG +00000240 P5IN +0000024e P5IV +0000024f P5IV_H +0000024e P5IV_L +00000242 P5OUT +00000246 P5REN +0000024a P5SEL0 +0000024c P5SEL1 +00000256 P5SELC +00000245 P6DIR +0000025b P6IE +00000259 P6IES +0000025d P6IFG +00000241 P6IN +0000025e P6IV +0000025f P6IV_H +0000025e P6IV_L +00000243 P6OUT +00000247 P6REN +0000024b P6SEL0 +0000024d P6SEL1 +00000257 P6SELC +00000264 P7DIR +0000027a P7IE +00000278 P7IES +0000027c P7IFG +00000260 P7IN +0000026e P7IV +0000026f P7IV_H +0000026e P7IV_L +00000262 P7OUT +00000266 P7REN +0000026a P7SEL0 +0000026c P7SEL1 +00000276 P7SELC +00000265 P8DIR +0000027b P8IE +00000279 P8IES +0000027d P8IFG +00000261 P8IN +0000027e P8IV +0000027f P8IV_H +0000027e P8IV_L +00000263 P8OUT +00000267 P8REN +0000026b P8SEL0 +0000026d P8SEL1 +00000277 P8SELC +00000204 PADIR +00000205 PADIR_H +00000204 PADIR_L +0000021a PAIE +00000218 PAIES +00000219 PAIES_H +00000218 PAIES_L +0000021b PAIE_H +0000021a PAIE_L +0000021c PAIFG +0000021d PAIFG_H +0000021c PAIFG_L +00000200 PAIN +00000201 PAIN_H +00000200 PAIN_L +00000202 PAOUT +00000203 PAOUT_H +00000202 PAOUT_L +00000206 PAREN +00000207 PAREN_H +00000206 PAREN_L +0000020a PASEL0 +0000020b PASEL0_H +0000020a PASEL0_L +0000020c PASEL1 +0000020d PASEL1_H +0000020c PASEL1_L +00000216 PASELC +00000217 PASELC_H +00000216 PASELC_L +00000224 PBDIR +00000225 PBDIR_H +00000224 PBDIR_L +0000023a PBIE +00000238 PBIES +00000239 PBIES_H +00000238 PBIES_L +0000023b PBIE_H +0000023a PBIE_L +0000023c PBIFG +0000023d PBIFG_H +0000023c PBIFG_L +00000220 PBIN +00000221 PBIN_H +00000220 PBIN_L +00000222 PBOUT +00000223 PBOUT_H +00000222 PBOUT_L +00000226 PBREN +00000227 PBREN_H +00000226 PBREN_L +0000022a PBSEL0 +0000022b PBSEL0_H +0000022a PBSEL0_L +0000022c PBSEL1 +0000022d PBSEL1_H +0000022c PBSEL1_L +00000236 PBSELC +00000237 PBSELC_H +00000236 PBSELC_L +00000244 PCDIR +00000245 PCDIR_H +00000244 PCDIR_L +0000025a PCIE +00000258 PCIES +00000259 PCIES_H +00000258 PCIES_L +0000025b PCIE_H +0000025a PCIE_L +0000025c PCIFG +0000025d PCIFG_H +0000025c PCIFG_L +00000240 PCIN +00000241 PCIN_H +00000240 PCIN_L +00000242 PCOUT +00000243 PCOUT_H +00000242 PCOUT_L +00000246 PCREN +00000247 PCREN_H +00000246 PCREN_L +0000024a PCSEL0 +0000024b PCSEL0_H +0000024a PCSEL0_L +0000024c PCSEL1 +0000024d PCSEL1_H +0000024c PCSEL1_L +00000256 PCSELC +00000257 PCSELC_H +00000256 PCSELC_L +00000264 PDDIR +00000265 PDDIR_H +00000264 PDDIR_L +0000027a PDIE +00000278 PDIES +00000279 PDIES_H +00000278 PDIES_L +0000027b PDIE_H +0000027a PDIE_L +0000027c PDIFG +0000027d PDIFG_H +0000027c PDIFG_L +00000260 PDIN +00000261 PDIN_H +00000260 PDIN_L +00000262 PDOUT +00000263 PDOUT_H +00000262 PDOUT_L +00000266 PDREN +00000267 PDREN_H +00000266 PDREN_L +0000026a PDSEL0 +0000026b PDSEL0_H +0000026a PDSEL0_L +0000026c PDSEL1 +0000026d PDSEL1_H +0000026c PDSEL1_L +00000276 PDSELC +00000277 PDSELC_H +00000276 PDSELC_L +00000324 PJDIR +00000325 PJDIR_H +00000324 PJDIR_L +00000320 PJIN +00000321 PJIN_H +00000320 PJIN_L +00000322 PJOUT +00000323 PJOUT_H +00000322 PJOUT_L +00000326 PJREN +00000327 PJREN_H +00000326 PJREN_L +0000032a PJSEL0 +0000032b PJSEL0_H +0000032a PJSEL0_L +0000032c PJSEL1 +0000032d PJSEL1_H +0000032c PJSEL1_L +00000336 PJSELC +00000337 PJSELC_H +00000336 PJSELC_L +00000130 PM5CTL0 +00000131 PM5CTL0_H +00000130 PM5CTL0_L +00000120 PMMCTL0 +00000121 PMMCTL0_H +00000120 PMMCTL0_L +0000012a PMMIFG +0000012b PMMIFG_H +0000012a PMMIFG_L +00000158 RCCTL0 +00000159 RCCTL0_H +00000158 RCCTL0_L +000001b0 REFCTL0 +000001b1 REFCTL0_H +000001b0 REFCTL0_L +000004e4 RES0 +000004e5 RES0_H +000004e4 RES0_L +000004e6 RES1 +000004e7 RES1_H +000004e6 RES1_L +000004e8 RES2 +000004e9 RES2_H +000004e8 RES2_L +000004ea RES3 +000004eb RES3_H +000004ea RES3_L +000004cc RESHI +000004cd RESHI_H +000004cc RESHI_L +000004ca RESLO +000004cb RESLO_H +000004ca RESLO_L +000004ac RT0PS +000004ad RT1PS +000004ba RTCADOWDAY +000004bb RTCADOWDAY_H +000004ba RTCADOWDAY_L +000004b8 RTCAMINHR +000004b9 RTCAMINHR_H +000004b8 RTCAMINHR_L +000004b0 RTCCNT1 +000004b0 RTCCNT12 +000004b1 RTCCNT12_H +000004b0 RTCCNT12_L +000004b1 RTCCNT2 +000004b2 RTCCNT3 +000004b2 RTCCNT34 +000004b3 RTCCNT34_H +000004b2 RTCCNT34_L +000004b3 RTCCNT4 +000004a0 RTCCTL0 +000004a1 RTCCTL0_H +000004a0 RTCCTL0_L +000004a2 RTCCTL13 +000004a3 RTCCTL13_H +000004a2 RTCCTL13_L +000004b4 RTCDATE +000004b5 RTCDATE_H +000004b4 RTCDATE_L +000004ae RTCIV +000004af RTCIV_H +000004ae RTCIV_L +000004a4 RTCOCAL +000004a5 RTCOCAL_H +000004a4 RTCOCAL_L +000004ac RTCPS +000004a8 RTCPS0CTL +000004a9 RTCPS0CTL_H +000004a8 RTCPS0CTL_L +000004aa RTCPS1CTL +000004ab RTCPS1CTL_H +000004aa RTCPS1CTL_L +000004ad RTCPS_H +000004ac RTCPS_L +000004a6 RTCTCMP +000004a7 RTCTCMP_H +000004a6 RTCTCMP_L +000004b0 RTCTIM0 +000004b1 RTCTIM0_H +000004b0 RTCTIM0_L +000004b2 RTCTIM1 +000004b3 RTCTIM1_H +000004b2 RTCTIM1_L +000004b6 RTCYEAR +000004b7 RTCYEAR_H +000004b6 RTCYEAR_L +0001b1fe RingBuffer__clear +0001aeda RingBuffer__empty +0001aef2 RingBuffer__freeCount +0001aa60 RingBuffer__full +000197a8 RingBuffer__get +000197a8 RingBuffer__getOverwrite +00017634 RingBuffer__init +000197e4 RingBuffer__peekAt +00019820 RingBuffer__put +000198d4 RingBuffer__putOverwrite +0001b212 RingBuffer__usedCount +00000100 SFRIE1 +00000101 SFRIE1_H +00000100 SFRIE1_L +00000102 SFRIFG1 +00000103 SFRIFG1_H +00000102 SFRIFG1_L +00000104 SFRRPCR +00000105 SFRRPCR_H +00000104 SFRRPCR_L +000004ce SUMEXT +000004cf SUMEXT_H +000004ce SUMEXT_L +00000180 SYSCTL +00000181 SYSCTL_H +00000180 SYSCTL_L +00000186 SYSJMBC +00000187 SYSJMBC_H +00000186 SYSJMBC_L +00000188 SYSJMBI0 +00000189 SYSJMBI0_H +00000188 SYSJMBI0_L +0000018a SYSJMBI1 +0000018b SYSJMBI1_H +0000018a SYSJMBI1_L +0000018c SYSJMBO0 +0000018d SYSJMBO0_H +0000018c SYSJMBO0_L +0000018e SYSJMBO1 +0000018f SYSJMBO1_H +0000018e SYSJMBO1_L +0000019e SYSRSTIV +0000019f SYSRSTIV_H +0000019e SYSRSTIV_L +0000019c SYSSNIV +0000019d SYSSNIV_H +0000019c SYSSNIV_L +0000019a SYSUNIV +0000019b SYSUNIV_H +0000019a SYSUNIV_L +00017dee Serialization__deserializeAs16Bit +0001691a Serialization__deserializeAs32Bit +000182de Serialization__deserializeAs8Bit +000179f2 Serialization__serializeAs16Bit +0001732c Serialization__serializeAs32Bit +0001699c Serialization__serializeAs64Bit +0001816a Serialization__serializeAs8Bit +00015b40 SlipEncode__encode +0001a544 SlipMpsm__initMsg +00016a1e SlipMpsm__process +00000352 TA0CCR0 +00000353 TA0CCR0_H +00000352 TA0CCR0_L +00000354 TA0CCR1 +00000355 TA0CCR1_H +00000354 TA0CCR1_L +00000356 TA0CCR2 +00000357 TA0CCR2_H +00000356 TA0CCR2_L +00000342 TA0CCTL0 +00000343 TA0CCTL0_H +00000342 TA0CCTL0_L +00000344 TA0CCTL1 +00000345 TA0CCTL1_H +00000344 TA0CCTL1_L +00000346 TA0CCTL2 +00000347 TA0CCTL2_H +00000346 TA0CCTL2_L +00000340 TA0CTL +00000341 TA0CTL_H +00000340 TA0CTL_L +00000360 TA0EX0 +00000361 TA0EX0_H +00000360 TA0EX0_L +0000036e TA0IV +0000036f TA0IV_H +0000036e TA0IV_L +00000350 TA0R +00000351 TA0R_H +00000350 TA0R_L +00000392 TA1CCR0 +00000393 TA1CCR0_H +00000392 TA1CCR0_L +00000394 TA1CCR1 +00000395 TA1CCR1_H +00000394 TA1CCR1_L +00000396 TA1CCR2 +00000397 TA1CCR2_H +00000396 TA1CCR2_L +00000382 TA1CCTL0 +00000383 TA1CCTL0_H +00000382 TA1CCTL0_L +00000384 TA1CCTL1 +00000385 TA1CCTL1_H +00000384 TA1CCTL1_L +00000386 TA1CCTL2 +00000387 TA1CCTL2_H +00000386 TA1CCTL2_L +00000380 TA1CTL +00000381 TA1CTL_H +00000380 TA1CTL_L +000003a0 TA1EX0 +000003a1 TA1EX0_H +000003a0 TA1EX0_L +000003ae TA1IV +000003af TA1IV_H +000003ae TA1IV_L +00000390 TA1R +00000391 TA1R_H +00000390 TA1R_L +00000412 TA2CCR0 +00000413 TA2CCR0_H +00000412 TA2CCR0_L +00000414 TA2CCR1 +00000415 TA2CCR1_H +00000414 TA2CCR1_L +00000402 TA2CCTL0 +00000403 TA2CCTL0_H +00000402 TA2CCTL0_L +00000404 TA2CCTL1 +00000405 TA2CCTL1_H +00000404 TA2CCTL1_L +00000400 TA2CTL +00000401 TA2CTL_H +00000400 TA2CTL_L +00000420 TA2EX0 +00000421 TA2EX0_H +00000420 TA2EX0_L +0000042e TA2IV +0000042f TA2IV_H +0000042e TA2IV_L +00000410 TA2R +00000411 TA2R_H +00000410 TA2R_L +00000452 TA3CCR0 +00000453 TA3CCR0_H +00000452 TA3CCR0_L +00000454 TA3CCR1 +00000455 TA3CCR1_H +00000454 TA3CCR1_L +00000442 TA3CCTL0 +00000443 TA3CCTL0_H +00000442 TA3CCTL0_L +00000444 TA3CCTL1 +00000445 TA3CCTL1_H +00000444 TA3CCTL1_L +00000440 TA3CTL +00000441 TA3CTL_H +00000440 TA3CTL_L +00000460 TA3EX0 +00000461 TA3EX0_H +00000460 TA3EX0_L +0000046e TA3IV +0000046f TA3IV_H +0000046e TA3IV_L +00000450 TA3R +00000451 TA3R_H +00000450 TA3R_L +000007d2 TA4CCR0 +000007d3 TA4CCR0_H +000007d2 TA4CCR0_L +000007d4 TA4CCR1 +000007d5 TA4CCR1_H +000007d4 TA4CCR1_L +000007d6 TA4CCR2 +000007d7 TA4CCR2_H +000007d6 TA4CCR2_L +000007c2 TA4CCTL0 +000007c3 TA4CCTL0_H +000007c2 TA4CCTL0_L +000007c4 TA4CCTL1 +000007c5 TA4CCTL1_H +000007c4 TA4CCTL1_L +000007c6 TA4CCTL2 +000007c7 TA4CCTL2_H +000007c6 TA4CCTL2_L +000007c0 TA4CTL +000007c1 TA4CTL_H +000007c0 TA4CTL_L +000007e0 TA4EX0 +000007e1 TA4EX0_H +000007e0 TA4EX0_L +000007ee TA4IV +000007ef TA4IV_H +000007ee TA4IV_L +000007d0 TA4R +000007d1 TA4R_H +000007d0 TA4R_L +000003d2 TB0CCR0 +000003d3 TB0CCR0_H +000003d2 TB0CCR0_L +000003d4 TB0CCR1 +000003d5 TB0CCR1_H +000003d4 TB0CCR1_L +000003d6 TB0CCR2 +000003d7 TB0CCR2_H +000003d6 TB0CCR2_L +000003d8 TB0CCR3 +000003d9 TB0CCR3_H +000003d8 TB0CCR3_L +000003da TB0CCR4 +000003db TB0CCR4_H +000003da TB0CCR4_L +000003dc TB0CCR5 +000003dd TB0CCR5_H +000003dc TB0CCR5_L +000003de TB0CCR6 +000003df TB0CCR6_H +000003de TB0CCR6_L +000003c2 TB0CCTL0 +000003c3 TB0CCTL0_H +000003c2 TB0CCTL0_L +000003c4 TB0CCTL1 +000003c5 TB0CCTL1_H +000003c4 TB0CCTL1_L +000003c6 TB0CCTL2 +000003c7 TB0CCTL2_H +000003c6 TB0CCTL2_L +000003c8 TB0CCTL3 +000003c9 TB0CCTL3_H +000003c8 TB0CCTL3_L +000003ca TB0CCTL4 +000003cb TB0CCTL4_H +000003ca TB0CCTL4_L +000003cc TB0CCTL5 +000003cd TB0CCTL5_H +000003cc TB0CCTL5_L +000003ce TB0CCTL6 +000003cf TB0CCTL6_H +000003ce TB0CCTL6_L +000003c0 TB0CTL +000003c1 TB0CTL_H +000003c0 TB0CTL_L +000003e0 TB0EX0 +000003e1 TB0EX0_H +000003e0 TB0EX0_L +000003ee TB0IV +000003ef TB0IV_H +000003ee TB0IV_L +000003d0 TB0R +000003d1 TB0R_H +000003d0 TB0R_L +0001b522 Time__getPointerToCentisecondCount +0001b528 Time__getTimeInCentiseconds +00004682 Timer0_A1_ISR +00018f3e UART__checkIfSendable +000195f8 UART__checkRxRbErrors +00019b0e UART__checkRxZerosMaxCountSinceLastCheck +00015250 UART__flushTx +00018eaa UART__init0 +00018abe UART__init1 +0001adbc UART__isInitialized +00017bf2 UART__receive +00016020 UART__transmit +00019a9e UART__uninit0 +000005d0 UCA0ABCTL +000005d1 UCA0ABCTL_H +000005d0 UCA0ABCTL_L +000005c6 UCA0BRW +000005c7 UCA0BRW_H +000005c6 UCA0BRW_L +000005c0 UCA0CTLW0 +000005c1 UCA0CTLW0_H +000005c0 UCA0CTLW0_L +000005c2 UCA0CTLW1 +000005c3 UCA0CTLW1_H +000005c2 UCA0CTLW1_L +000005da UCA0IE +000005db UCA0IE_H +000005da UCA0IE_L +000005dc UCA0IFG +000005dd UCA0IFG_H +000005dc UCA0IFG_L +000005d2 UCA0IRCTL +000005d3 UCA0IRCTL_H +000005d2 UCA0IRCTL_L +000005de UCA0IV +000005df UCA0IV_H +000005de UCA0IV_L +000005c8 UCA0MCTLW +000005c9 UCA0MCTLW_H +000005c8 UCA0MCTLW_L +000005cc UCA0RXBUF +000005cd UCA0RXBUF_H +000005cc UCA0RXBUF_L +000005ca UCA0STATW +000005cb UCA0STATW_H +000005ca UCA0STATW_L +000005ce UCA0TXBUF +000005cf UCA0TXBUF_H +000005ce UCA0TXBUF_L +000005f0 UCA1ABCTL +000005f1 UCA1ABCTL_H +000005f0 UCA1ABCTL_L +000005e6 UCA1BRW +000005e7 UCA1BRW_H +000005e6 UCA1BRW_L +000005e0 UCA1CTLW0 +000005e1 UCA1CTLW0_H +000005e0 UCA1CTLW0_L +000005e2 UCA1CTLW1 +000005e3 UCA1CTLW1_H +000005e2 UCA1CTLW1_L +000005fa UCA1IE +000005fb UCA1IE_H +000005fa UCA1IE_L +000005fc UCA1IFG +000005fd UCA1IFG_H +000005fc UCA1IFG_L +000005f2 UCA1IRCTL +000005f3 UCA1IRCTL_H +000005f2 UCA1IRCTL_L +000005fe UCA1IV +000005ff UCA1IV_H +000005fe UCA1IV_L +000005e8 UCA1MCTLW +000005e9 UCA1MCTLW_H +000005e8 UCA1MCTLW_L +000005ec UCA1RXBUF +000005ed UCA1RXBUF_H +000005ec UCA1RXBUF_L +000005ea UCA1STATW +000005eb UCA1STATW_H +000005ea UCA1STATW_L +000005ee UCA1TXBUF +000005ef UCA1TXBUF_H +000005ee UCA1TXBUF_L +00000610 UCA2ABCTL +00000611 UCA2ABCTL_H +00000610 UCA2ABCTL_L +00000606 UCA2BRW +00000607 UCA2BRW_H +00000606 UCA2BRW_L +00000600 UCA2CTLW0 +00000601 UCA2CTLW0_H +00000600 UCA2CTLW0_L +00000602 UCA2CTLW1 +00000603 UCA2CTLW1_H +00000602 UCA2CTLW1_L +0000061a UCA2IE +0000061b UCA2IE_H +0000061a UCA2IE_L +0000061c UCA2IFG +0000061d UCA2IFG_H +0000061c UCA2IFG_L +00000612 UCA2IRCTL +00000613 UCA2IRCTL_H +00000612 UCA2IRCTL_L +0000061e UCA2IV +0000061f UCA2IV_H +0000061e UCA2IV_L +00000608 UCA2MCTLW +00000609 UCA2MCTLW_H +00000608 UCA2MCTLW_L +0000060c UCA2RXBUF +0000060d UCA2RXBUF_H +0000060c UCA2RXBUF_L +0000060a UCA2STATW +0000060b UCA2STATW_H +0000060a UCA2STATW_L +0000060e UCA2TXBUF +0000060f UCA2TXBUF_H +0000060e UCA2TXBUF_L +00000630 UCA3ABCTL +00000631 UCA3ABCTL_H +00000630 UCA3ABCTL_L +00000626 UCA3BRW +00000627 UCA3BRW_H +00000626 UCA3BRW_L +00000620 UCA3CTLW0 +00000621 UCA3CTLW0_H +00000620 UCA3CTLW0_L +00000622 UCA3CTLW1 +00000623 UCA3CTLW1_H +00000622 UCA3CTLW1_L +0000063a UCA3IE +0000063b UCA3IE_H +0000063a UCA3IE_L +0000063c UCA3IFG +0000063d UCA3IFG_H +0000063c UCA3IFG_L +00000632 UCA3IRCTL +00000633 UCA3IRCTL_H +00000632 UCA3IRCTL_L +0000063e UCA3IV +0000063f UCA3IV_H +0000063e UCA3IV_L +00000628 UCA3MCTLW +00000629 UCA3MCTLW_H +00000628 UCA3MCTLW_L +0000062c UCA3RXBUF +0000062d UCA3RXBUF_H +0000062c UCA3RXBUF_L +0000062a UCA3STATW +0000062b UCA3STATW_H +0000062a UCA3STATW_L +0000062e UCA3TXBUF +0000062f UCA3TXBUF_H +0000062e UCA3TXBUF_L +0000065e UCB0ADDMASK +0000065f UCB0ADDMASK_H +0000065e UCB0ADDMASK_L +0000065c UCB0ADDRX +0000065d UCB0ADDRX_H +0000065c UCB0ADDRX_L +00000646 UCB0BRW +00000647 UCB0BRW_H +00000646 UCB0BRW_L +00000640 UCB0CTLW0 +00000641 UCB0CTLW0_H +00000640 UCB0CTLW0_L +00000642 UCB0CTLW1 +00000643 UCB0CTLW1_H +00000642 UCB0CTLW1_L +00000654 UCB0I2COA0 +00000655 UCB0I2COA0_H +00000654 UCB0I2COA0_L +00000656 UCB0I2COA1 +00000657 UCB0I2COA1_H +00000656 UCB0I2COA1_L +00000658 UCB0I2COA2 +00000659 UCB0I2COA2_H +00000658 UCB0I2COA2_L +0000065a UCB0I2COA3 +0000065b UCB0I2COA3_H +0000065a UCB0I2COA3_L +00000660 UCB0I2CSA +00000661 UCB0I2CSA_H +00000660 UCB0I2CSA_L +0000066a UCB0IE +0000066b UCB0IE_H +0000066a UCB0IE_L +0000066c UCB0IFG +0000066d UCB0IFG_H +0000066c UCB0IFG_L +0000066e UCB0IV +0000066f UCB0IV_H +0000066e UCB0IV_L +0000064c UCB0RXBUF +0000064d UCB0RXBUF_H +0000064c UCB0RXBUF_L +00000648 UCB0STATW +00000649 UCB0STATW_H +00000648 UCB0STATW_L +0000064a UCB0TBCNT +0000064b UCB0TBCNT_H +0000064a UCB0TBCNT_L +0000064e UCB0TXBUF +0000064f UCB0TXBUF_H +0000064e UCB0TXBUF_L +0000069e UCB1ADDMASK +0000069f UCB1ADDMASK_H +0000069e UCB1ADDMASK_L +0000069c UCB1ADDRX +0000069d UCB1ADDRX_H +0000069c UCB1ADDRX_L +00000686 UCB1BRW +00000687 UCB1BRW_H +00000686 UCB1BRW_L +00000680 UCB1CTLW0 +00000681 UCB1CTLW0_H +00000680 UCB1CTLW0_L +00000682 UCB1CTLW1 +00000683 UCB1CTLW1_H +00000682 UCB1CTLW1_L +00000694 UCB1I2COA0 +00000695 UCB1I2COA0_H +00000694 UCB1I2COA0_L +00000696 UCB1I2COA1 +00000697 UCB1I2COA1_H +00000696 UCB1I2COA1_L +00000698 UCB1I2COA2 +00000699 UCB1I2COA2_H +00000698 UCB1I2COA2_L +0000069a UCB1I2COA3 +0000069b UCB1I2COA3_H +0000069a UCB1I2COA3_L +000006a0 UCB1I2CSA +000006a1 UCB1I2CSA_H +000006a0 UCB1I2CSA_L +000006aa UCB1IE +000006ab UCB1IE_H +000006aa UCB1IE_L +000006ac UCB1IFG +000006ad UCB1IFG_H +000006ac UCB1IFG_L +000006ae UCB1IV +000006af UCB1IV_H +000006ae UCB1IV_L +0000068c UCB1RXBUF +0000068d UCB1RXBUF_H +0000068c UCB1RXBUF_L +00000688 UCB1STATW +00000689 UCB1STATW_H +00000688 UCB1STATW_L +0000068a UCB1TBCNT +0000068b UCB1TBCNT_H +0000068a UCB1TBCNT_L +0000068e UCB1TXBUF +0000068f UCB1TXBUF_H +0000068e UCB1TXBUF_L +000006de UCB2ADDMASK +000006df UCB2ADDMASK_H +000006de UCB2ADDMASK_L +000006dc UCB2ADDRX +000006dd UCB2ADDRX_H +000006dc UCB2ADDRX_L +000006c6 UCB2BRW +000006c7 UCB2BRW_H +000006c6 UCB2BRW_L +000006c0 UCB2CTLW0 +000006c1 UCB2CTLW0_H +000006c0 UCB2CTLW0_L +000006c2 UCB2CTLW1 +000006c3 UCB2CTLW1_H +000006c2 UCB2CTLW1_L +000006d4 UCB2I2COA0 +000006d5 UCB2I2COA0_H +000006d4 UCB2I2COA0_L +000006d6 UCB2I2COA1 +000006d7 UCB2I2COA1_H +000006d6 UCB2I2COA1_L +000006d8 UCB2I2COA2 +000006d9 UCB2I2COA2_H +000006d8 UCB2I2COA2_L +000006da UCB2I2COA3 +000006db UCB2I2COA3_H +000006da UCB2I2COA3_L +000006e0 UCB2I2CSA +000006e1 UCB2I2CSA_H +000006e0 UCB2I2CSA_L +000006ea UCB2IE +000006eb UCB2IE_H +000006ea UCB2IE_L +000006ec UCB2IFG +000006ed UCB2IFG_H +000006ec UCB2IFG_L +000006ee UCB2IV +000006ef UCB2IV_H +000006ee UCB2IV_L +000006cc UCB2RXBUF +000006cd UCB2RXBUF_H +000006cc UCB2RXBUF_L +000006c8 UCB2STATW +000006c9 UCB2STATW_H +000006c8 UCB2STATW_L +000006ca UCB2TBCNT +000006cb UCB2TBCNT_H +000006ca UCB2TBCNT_L +000006ce UCB2TXBUF +000006cf UCB2TXBUF_H +000006ce UCB2TXBUF_L +0000071e UCB3ADDMASK +0000071f UCB3ADDMASK_H +0000071e UCB3ADDMASK_L +0000071c UCB3ADDRX +0000071d UCB3ADDRX_H +0000071c UCB3ADDRX_L +00000706 UCB3BRW +00000707 UCB3BRW_H +00000706 UCB3BRW_L +00000700 UCB3CTLW0 +00000701 UCB3CTLW0_H +00000700 UCB3CTLW0_L +00000702 UCB3CTLW1 +00000703 UCB3CTLW1_H +00000702 UCB3CTLW1_L +00000714 UCB3I2COA0 +00000715 UCB3I2COA0_H +00000714 UCB3I2COA0_L +00000716 UCB3I2COA1 +00000717 UCB3I2COA1_H +00000716 UCB3I2COA1_L +00000718 UCB3I2COA2 +00000719 UCB3I2COA2_H +00000718 UCB3I2COA2_L +0000071a UCB3I2COA3 +0000071b UCB3I2COA3_H +0000071a UCB3I2COA3_L +00000720 UCB3I2CSA +00000721 UCB3I2CSA_H +00000720 UCB3I2CSA_L +0000072a UCB3IE +0000072b UCB3IE_H +0000072a UCB3IE_L +0000072c UCB3IFG +0000072d UCB3IFG_H +0000072c UCB3IFG_L +0000072e UCB3IV +0000072f UCB3IV_H +0000072e UCB3IV_L +0000070c UCB3RXBUF +0000070d UCB3RXBUF_H +0000070c UCB3RXBUF_L +00000708 UCB3STATW +00000709 UCB3STATW_H +00000708 UCB3STATW_L +0000070a UCB3TBCNT +0000070b UCB3TBCNT_H +0000070a UCB3TBCNT_L +0000070e UCB3TXBUF +0000070f UCB3TXBUF_H +0000070e UCB3TXBUF_L +00004400 USCI_A0_ISR +000044ca USCI_A1_ISR +0000015c WDTCTL +0000015d WDTCTL_H +0000015c WDTCTL_L +00012d82 WdCmdMsgs__deserializeBody +00016aa0 WdCmdMsgs__deserializeMessage +00016708 WdCmdMsgs__serializeGroundResponse +0001add6 WdIntMpsm__processEdge +00004002 _CIOBUF_ +000046e0 _Z7WDT_ISRv +0001b226 _ZN10__cxxabiv117__class_type_infoD0Ev +0001b3c2 _ZN10__cxxabiv117__class_type_infoD1Ev +0001b3c2 _ZN10__cxxabiv117__class_type_infoD2Ev +0001afc8 _ZN10__cxxabiv120__si_class_type_infoD0Ev +0001b3d0 _ZN10__cxxabiv120__si_class_type_infoD1Ev +0001b3d0 _ZN10__cxxabiv120__si_class_type_infoD2Ev +00016c26 _ZN4iris13stateToStringENS_10RoverStateE +00019b7a _ZN4iris14RoverStateBase12doGndCmdEchoERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00015bf8 _ZN4iris14RoverStateBase12echoToLanderERNS_12RoverContextEhPKh +00015908 _ZN4iris14RoverStateBase13heaterControlERNS_12RoverContextE +0001aa7e _ZN4iris14RoverStateBase14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001afde _ZN4iris14RoverStateBase14handleHighTempERNS_12RoverContextE +00018a20 _ZN4iris14RoverStateBase14txDownlinkDataERNS_12RoverContextEPvjb +00016b22 _ZN4iris14RoverStateBase15handleWdIntEdgeEbRNS_12RoverContextE +0001aa9c _ZN4iris14RoverStateBase16handleLanderDataERNS_12RoverContextE +00013112 _ZN4iris14RoverStateBase17landerMsgCallbackEPhjPv +0001aaba _ZN4iris14RoverStateBase18handleHerculesDataERNS_12RoverContextE +000164e4 _ZN4iris14RoverStateBase18pumpMsgsFromLanderERNS_12RoverContextE +0001656e _ZN4iris14RoverStateBase18sendLanderResponseERNS_12RoverContextER19WdCmdMsgs__Response +00013c52 _ZN4iris14RoverStateBase19enableHerculesCommsERNS_12RoverContextE +000160c4 _ZN4iris14RoverStateBase19herculesMsgCallbackEP16HercMsgs__HeaderPhjPv +0001b416 _ZN4iris14RoverStateBase20canEnterLowPowerModeERNS_12RoverContextE +000186f8 _ZN4iris14RoverStateBase20doGndCmdSetVSAEStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018554 _ZN4iris14RoverStateBase20pumpMsgsFromHerculesERNS_12RoverContextE +0001aad8 _ZN4iris14RoverStateBase21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a56c _ZN4iris14RoverStateBase21doGndCmdResetSpecificERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a984 _ZN4iris14RoverStateBase21handleWdIntRisingEdgeERNS_12RoverContextE +0001178e _ZN4iris14RoverStateBase21initiateNextI2cActionERNS_12RoverContextE +0001aaf6 _ZN4iris14RoverStateBase22doGndCmdEnterSleepModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000191b4 _ZN4iris14RoverStateBase22doGndCmdSetBattEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ad4e _ZN4iris14RoverStateBase22doGndCmdSwitchConnModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a594 _ZN4iris14RoverStateBase22handleUplinkFromLanderERNS_12RoverContextEPhj +0001a9a4 _ZN4iris14RoverStateBase22handleWdIntFallingEdgeERNS_12RoverContextE +000113a0 _ZN4iris14RoverStateBase22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000148e0 _ZN4iris14RoverStateBase23handleDebugFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj +000161fe _ZN4iris14RoverStateBase23handleResetFromHerculesERNS_12RoverContextEP16HercMsgs__Header +0001a14c _ZN4iris14RoverStateBase24doGndCmdClearResetMemoryERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab14 _ZN4iris14RoverStateBase24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018044 _ZN4iris14RoverStateBase24doGndCmdLatchSetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001874a _ZN4iris14RoverStateBase24doGndCmdSetChargeEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00015cae _ZN4iris14RoverStateBase24handleStrokeFromHerculesERNS_12RoverContextEP16HercMsgs__Header +0001879c _ZN4iris14RoverStateBase25doGndCmdSetLatchBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019f76 _ZN4iris14RoverStateBase25handleRadioGotWifiCommandERNS_12RoverContextE +00010908 _ZN4iris14RoverStateBase26doConditionalResetSpecificERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__ResponsebbbbRb +000187ee _ZN4iris14RoverStateBase26doGndCmdDangForceBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab32 _ZN4iris14RoverStateBase26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000180a6 _ZN4iris14RoverStateBase26doGndCmdLatchResetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab50 _ZN4iris14RoverStateBase26doGndCmdSetBattCtrlEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00017d24 _ZN4iris14RoverStateBase26doGndCmdSetDebugCommsStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001985c _ZN4iris14RoverStateBase26doGndCmdSetHeaterDutyCycleERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00013870 _ZN4iris14RoverStateBase26handleDownlinkFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj +00014002 _ZN4iris14RoverStateBase26sendDetailedReportToLanderERNS_12RoverContextEb +000191f6 _ZN4iris14RoverStateBase27doGndCmdSetChargeRegEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a448 _ZN4iris14RoverStateBase28doGndCmdSetAutoHeaterOnValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001aff4 _ZN4iris14RoverStateBase28handleRadioExitStasisCommandERNS_12RoverContextE +0001a8dc _ZN4iris14RoverStateBase29doGndCmdRequestDetailedReportERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a472 _ZN4iris14RoverStateBase29doGndCmdSetAutoHeaterOffValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001b3de _ZN4iris14RoverStateBase29handleRadioEnterStasisCommandERNS_12RoverContextE +0001a342 _ZN4iris14RoverStateBase32doGndCmdSetHeaterDutyCyclePeriodERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019636 _ZN4iris14RoverStateBase33handleRadioPowerCycleRadioCommandERNS_12RoverContextE +00019674 _ZN4iris14RoverStateBase36handleRadioPowerCycleHerculesCommandERNS_12RoverContextE +0001b23a _ZN4iris14RoverStateBase8getStateEv +0001a9c4 _ZN4iris14RoverStateBaseC1ENS_10RoverStateE +0001a9c4 _ZN4iris14RoverStateBaseC2ENS_10RoverStateE +00012f50 _ZN4iris14RoverStateInit12transitionToERNS_12RoverContextE +0001ab6e _ZN4iris14RoverStateInit14handleHighTempERNS_12RoverContextE +0001ab8c _ZN4iris14RoverStateInit15handleTimerTickERNS_12RoverContextE +0001abaa _ZN4iris14RoverStateInit16handleLanderDataERNS_12RoverContextE +0001abc8 _ZN4iris14RoverStateInit16handlePowerIssueERNS_12RoverContextE +0001abe6 _ZN4iris14RoverStateInit18handleHerculesDataERNS_12RoverContextE +0001ac04 _ZN4iris14RoverStateInit19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001b422 _ZN4iris14RoverStateInit20canEnterLowPowerModeERNS_12RoverContextE +0001ac22 _ZN4iris14RoverStateInit8spinOnceERNS_12RoverContextE +0001a17a _ZN4iris14RoverStateInitC1ENS_10RoverStateEPKc +0001a17a _ZN4iris14RoverStateInitC2ENS_10RoverStateEPKc +00013d90 _ZN4iris17RoverStateManager11handleEventE11Event__Type +00015776 _ZN4iris17RoverStateManager11spinForeverEv +00016ca6 _ZN4iris17RoverStateManager22transitionUntilSettledENS_10RoverStateE +00016680 _ZN4iris17RoverStateManager26getStateObjectForStateEnumENS_10RoverStateE +00013b12 _ZN4iris17RoverStateManager4initEv +00016812 _ZN4iris17RoverStateManagerC1EPKc +00016812 _ZN4iris17RoverStateManagerC2EPKc +00019bb0 _ZN4iris17RoverStateMission12transitionToERNS_12RoverContextE +0001a67a _ZN4iris17RoverStateMission13heaterControlERNS_12RoverContextE +00018108 _ZN4iris17RoverStateMission14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001233c _ZN4iris17RoverStateMission15handleTimerTickERNS_12RoverContextE +0001b00a _ZN4iris17RoverStateMission16handlePowerIssueERNS_12RoverContextE +00016330 _ZN4iris17RoverStateMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001adf0 _ZN4iris17RoverStateMission20canEnterLowPowerModeERNS_12RoverContextE +00018dc8 _ZN4iris17RoverStateMission22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019fa6 _ZN4iris17RoverStateMission24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00014eb2 _ZN4iris17RoverStateMission8spinOnceERNS_12RoverContextE +0001a36e _ZN4iris17RoverStateMissionC1Ev +0001a36e _ZN4iris17RoverStateMissionC2Ev +0001ae0a _ZN4iris17RoverStateService12transitionToERNS_12RoverContextE +000129b6 _ZN4iris17RoverStateService15handleTimerTickERNS_12RoverContextE +0001b020 _ZN4iris17RoverStateService16handlePowerIssueERNS_12RoverContextE +0001ae24 _ZN4iris17RoverStateService20canEnterLowPowerModeERNS_12RoverContextE +0001af0a _ZN4iris17RoverStateService21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018e14 _ZN4iris17RoverStateService22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001990e _ZN4iris17RoverStateService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019fd6 _ZN4iris17RoverStateService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00014f9a _ZN4iris17RoverStateService8spinOnceERNS_12RoverContextE +0001a8fe _ZN4iris17RoverStateServiceC1Ev +0001a8fe _ZN4iris17RoverStateServiceC2Ev +00018f86 _ZN4iris19RoverStateKeepAlive12transitionToERNS_12RoverContextE +00019d86 _ZN4iris19RoverStateKeepAlive15handleTimerTickERNS_12RoverContextE +0001b036 _ZN4iris19RoverStateKeepAlive16handlePowerIssueERNS_12RoverContextE +0001ac40 _ZN4iris19RoverStateKeepAlive18handleHerculesDataERNS_12RoverContextE +0001ae3e _ZN4iris19RoverStateKeepAlive20canEnterLowPowerModeERNS_12RoverContextE +0001af22 _ZN4iris19RoverStateKeepAlive24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001af3a _ZN4iris19RoverStateKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000146ce _ZN4iris19RoverStateKeepAlive8spinOnceERNS_12RoverContextE +0001a920 _ZN4iris19RoverStateKeepAliveC1Ev +0001a920 _ZN4iris19RoverStateKeepAliveC2Ev +0001ac5e _ZN4iris25RoverStateEnteringMission12transitionToERNS_12RoverContextE +000132ae _ZN4iris25RoverStateEnteringMission15handleTimerTickERNS_12RoverContextE +0001b04c _ZN4iris25RoverStateEnteringMission16handlePowerIssueERNS_12RoverContextE +00016f86 _ZN4iris25RoverStateEnteringMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001b42e _ZN4iris25RoverStateEnteringMission20canEnterLowPowerModeERNS_12RoverContextE +0001a39a _ZN4iris25RoverStateEnteringMission29transitionToWaitingForI2cDoneERNS_12RoverContextE +00016454 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite1ERNS_12RoverContextE +00016896 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite2ERNS_12RoverContextE +00016ba4 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite3ERNS_12RoverContextE +00016e98 _ZN4iris25RoverStateEnteringMission40transitionToWaitingForFuelGaugeOrTimeoutERNS_12RoverContextE +0001a942 _ZN4iris25RoverStateEnteringMission41transitionToWatitingForWifiReadyOrTimeoutERNS_12RoverContextE +00010f0c _ZN4iris25RoverStateEnteringMission8spinOnceERNS_12RoverContextE +0001a70e _ZN4iris25RoverStateEnteringMissionC1Ev +0001a70e _ZN4iris25RoverStateEnteringMissionC2Ev +0001ac7c _ZN4iris25RoverStateEnteringService12transitionToERNS_12RoverContextE +0001b062 _ZN4iris25RoverStateEnteringService16handlePowerIssueERNS_12RoverContextE +0001ae58 _ZN4iris25RoverStateEnteringService18handleHerculesDataERNS_12RoverContextE +00016ffc _ZN4iris25RoverStateEnteringService19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001a732 _ZN4iris25RoverStateEnteringService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019948 _ZN4iris25RoverStateEnteringService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001b43a _ZN4iris25RoverStateEnteringService28nextStateAfterSetupCompletesEv +0001b446 _ZN4iris25RoverStateEnteringService8spinOnceERNS_12RoverContextE +0001a756 _ZN4iris25RoverStateEnteringServiceC1ENS_10RoverStateE +0001a77a _ZN4iris25RoverStateEnteringServiceC1Ev +0001a756 _ZN4iris25RoverStateEnteringServiceC2ENS_10RoverStateE +0001a77a _ZN4iris25RoverStateEnteringServiceC2Ev +0001a49c _ZN4iris27RoverStateEnteringKeepAlive12transitionToERNS_12RoverContextE +00014386 _ZN4iris27RoverStateEnteringKeepAlive15handleTimerTickERNS_12RoverContextE +0001b078 _ZN4iris27RoverStateEnteringKeepAlive16handlePowerIssueERNS_12RoverContextE +00019db8 _ZN4iris27RoverStateEnteringKeepAlive18handleHerculesDataERNS_12RoverContextE +00017072 _ZN4iris27RoverStateEnteringKeepAlive19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001b452 _ZN4iris27RoverStateEnteringKeepAlive20canEnterLowPowerModeERNS_12RoverContextE +0001b08e _ZN4iris27RoverStateEnteringKeepAlive22handleUplinkFromLanderERNS_12RoverContextEPhj +00019ad6 _ZN4iris27RoverStateEnteringKeepAlive25transitionToFinishUpSetupERNS_12RoverContextE +0001a79e _ZN4iris27RoverStateEnteringKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001b45e _ZN4iris27RoverStateEnteringKeepAlive28nextStateAfterSetupCompletesEv +00015082 _ZN4iris27RoverStateEnteringKeepAlive37transitionToWaitingForIoExpanderWriteERNS_12RoverContextE +00015a86 _ZN4iris27RoverStateEnteringKeepAlive8spinOnceERNS_12RoverContextE +0001a7c2 _ZN4iris27RoverStateEnteringKeepAliveC1ENS_10RoverStateE +0001a7e6 _ZN4iris27RoverStateEnteringKeepAliveC1Ev +0001a7c2 _ZN4iris27RoverStateEnteringKeepAliveC2ENS_10RoverStateE +0001a7e6 _ZN4iris27RoverStateEnteringKeepAliveC2Ev +0001b54c _ZNSt9type_infoD1Ev +0001b54c _ZNSt9type_infoD2Ev +0001b52e _ZSt17__throw_bad_allocv +0000d008 _ZTIN10__cxxabiv117__class_type_infoE +0000d014 _ZTIN10__cxxabiv120__si_class_type_infoE +0000d074 _ZTIN4iris14RoverStateBaseE +0000d020 _ZTIN4iris14RoverStateInitE +0000d02c _ZTIN4iris17RoverStateMissionE +0000d038 _ZTIN4iris17RoverStateServiceE +0000d044 _ZTIN4iris19RoverStateKeepAliveE +0000d050 _ZTIN4iris25RoverStateEnteringMissionE +0000d05c _ZTIN4iris25RoverStateEnteringServiceE +0000d068 _ZTIN4iris27RoverStateEnteringKeepAliveE +0000d07c _ZTISt9type_info +0000cede _ZTSN10__cxxabiv117__class_type_infoE +0000ce4a _ZTSN10__cxxabiv120__si_class_type_infoE +0000cf6e _ZTSN4iris14RoverStateBaseE +0000cf86 _ZTSN4iris14RoverStateInitE +0000cf1e _ZTSN4iris17RoverStateMissionE +0000cf3a _ZTSN4iris17RoverStateServiceE +0000cf00 _ZTSN4iris19RoverStateKeepAliveE +0000ce96 _ZTSN4iris25RoverStateEnteringMissionE +0000ceba _ZTSN4iris25RoverStateEnteringServiceE +0000ce70 _ZTSN4iris27RoverStateEnteringKeepAliveE +0000cffa _ZTSSt9type_info +0000cfda _ZTVN10__cxxabiv117__class_type_infoE +0000cfea _ZTVN10__cxxabiv120__si_class_type_infoE +0000c888 _ZTVN4iris14RoverStateBaseE +0000c96c _ZTVN4iris14RoverStateInitE +0000ca50 _ZTVN4iris17RoverStateMissionE +0000c4e8 _ZTVN4iris17RoverStateServiceE +0000c5d0 _ZTVN4iris19RoverStateKeepAliveE +0000cb34 _ZTVN4iris25RoverStateEnteringMissionE +0000c6b8 _ZTVN4iris25RoverStateEnteringServiceE +0000c7a0 _ZTVN4iris27RoverStateEnteringKeepAliveE +0001b46a _ZdlPv +0001b540 _ZdlPvj +00003c00 __STACK_END +000005d4 __STACK_SIZE +00000008 __SYSMEM_SIZE +0000d10e __TI_CINIT_Base +0000d11e __TI_CINIT_Limit +0000d0fc __TI_Handler_Table_Base +0000d108 __TI_Handler_Table_Limit +000046f0 __TI_ISR_TRAP +00018600 __TI_auto_init_nobinit_nopinit_hold_wdt +00019be6 __TI_cleanup +0000355a __TI_cleanup_ptr +00017246 __TI_closefile +000170e8 __TI_decompress_lzss +0001b2ec __TI_decompress_none +00017e52 __TI_doflush +0000355e __TI_dtors_ptr +0000358c __TI_enable_exit_profile_output +0000358a __TI_ft_end +0000ffb4 __TI_int18 +0000ffb6 __TI_int19 +0000ffb8 __TI_int20 +0000ffba __TI_int21 +0000ffbc __TI_int22 +0000ffbe __TI_int23 +0000ffc0 __TI_int24 +0000ffc2 __TI_int25 +0000ffc4 __TI_int26 +0000ffc6 __TI_int27 +0000ffc8 __TI_int28 +0000ffca __TI_int29 +0000ffcc __TI_int30 +0000ffce __TI_int31 +0000ffd0 __TI_int32 +0000ffd2 __TI_int33 +0000ffd4 __TI_int34 +0000ffd6 __TI_int35 +0000ffd8 __TI_int36 +0000ffda __TI_int37 +0000ffdc __TI_int38 +0000ffde __TI_int39 +0000ffe0 __TI_int40 +0000ffe2 __TI_int41 +0000ffe4 __TI_int42 +0000ffe6 __TI_int43 +0000ffe8 __TI_int44 +0000ffea __TI_int45 +0000ffec __TI_int46 +0000ffee __TI_int47 +0000fff0 __TI_int48 +0000fff2 __TI_int49 +0000fff4 __TI_int50 +0000fff6 __TI_int51 +0000fff8 __TI_int52 +0000fffa __TI_int53 +0000fffc __TI_int54 +ffffffff __TI_pprof_out_hndl +00015412 __TI_printfi_minimal +ffffffff __TI_prof_data_size +ffffffff __TI_prof_data_start +00019dea __TI_readmsg +00002800 __TI_tmpnams +00019c1c __TI_writemsg +00016d26 __TI_wrt_ok +0001a80a __TI_zero_init +0001b544 __abort_execution +ffffffff __c_args__ +0001b4ba __cxa_pure_virtual +00000001 __mpu_enable +0001a3c6 __mpu_init +0001b16a __mspabi_divu +0001af82 __mspabi_mpyi_f5hw +0001b16a __mspabi_remu +0001b492 __mspabi_slli +00019728 __mspabi_slll_1 +00019704 __mspabi_slll_10 +00019700 __mspabi_slll_11 +000196fc __mspabi_slll_12 +000196f8 __mspabi_slll_13 +000196f4 __mspabi_slll_14 +000196f0 __mspabi_slll_15 +00019724 __mspabi_slll_2 +00019720 __mspabi_slll_3 +0001971c __mspabi_slll_4 +00019718 __mspabi_slll_5 +00019714 __mspabi_slll_6 +00019710 __mspabi_slll_7 +0001970c __mspabi_slll_8 +00019708 __mspabi_slll_9 +0001b49c __mspabi_srli +0001b364 __mspabi_srll +00019982 __mspabi_srlll +0001ae72 _abort_msg +000046c0 _c_int00_noargs_mpu +0000326e _device +000031a6 _ftable +00003562 _lock +0001b54e _nop +0000fffe _reset_vector +0000362c _stack +00003366 _stream +00004124 _sys_memory +0001b550 _system_post_cinit +0001b548 _system_pre_init +00003566 _unlock +0001b52e abort +00019c86 adcCheckVoltageLevels +000176a0 adc_init +000147d8 aligned_alloc +0001ac9a blimp_battEnOff +0001ae8c blimp_battEnOn +0001b3ec blimp_batteryState +0001a006 blimp_bstat +00019e1c blimp_bstat_dangerous_forceHigh +00019e4e blimp_bstat_dangerous_forceLow +00019e80 blimp_bstat_safe_restoreInput +0001a4c6 blimp_chargerEnForceHigh +0001a1a8 blimp_chargerEnOff +0001a4f0 blimp_chargerEnOn +00017eb6 blimp_initialize +0001acb8 blimp_latchBattOff +0001aea6 blimp_latchBattOn +00019cba blimp_latchBattUpdate +0001784a blimp_latchResetHigh +000178b4 blimp_latchResetLow +00018396 blimp_latchResetOff +0001a1d6 blimp_latchResetPulseLow +00017f1a blimp_latchSetHigh +00017f7e blimp_latchSetLow +000185aa blimp_latchSetOff +0001a204 blimp_latchSetPulseLow +00019cee blimp_normalBoot +0001acd6 blimp_regEnOff +0001af52 blimp_regEnOn +0001a232 blimp_vSysAllEnForceLow +00019eb2 blimp_vSysAllEnOff +0001a260 blimp_vSysAllEnOn +00019238 clockInit +000183f0 close +0001b0a4 disable3V3PowerRail +0001b474 disableBatteries +0001a82e disableHeater +0001a852 disableUart0Pins +0001b534 disableVSysAllPowerRail +0001b2fe enable3V3PowerRail +0001b47e enableBatteries +000196b2 enableHeater +0001aec0 enableUart0Pins +0001acf4 enableUart1Pins +0001b53a enableVSysAllPowerRail +0001b0ba enableWdIntFallingEdgeInterrupt +0001b0d0 enableWdIntRisingEdgeInterrupt +00018ef4 exit +000184fc fflush +0001a28e finddevice +0001b334 fpgaCameraSelectHi +0001b0e6 fpgaCameraSelectLo +00014dc2 fputs +00004400 fram_ipe_end +00004400 fram_ipe_start +00004000 fram_rw_start +00004400 fram_rx_start +000155c8 free +0001791e fseek +000145c2 getResetReasonString +0001b344 getWdIntState +0001844a getdevice +0001b354 hook_sp_check +00011ade initializeGpios +0001b310 isAdcSampleDone +0001972e lseek +0001a2bc main +0001b4c2 malloc +000147d8 memalign +0001ad12 memccpy +0001b112 memchr +0001b276 memcpy +0001b128 memset +0000a501 mpu_ctl0_value +00001513 mpu_sam_value +00000440 mpu_segment_border1 +00000440 mpu_segment_border2 +00002900 parmbuf +0000462c port1_isr_handler +0001b28a powerOffFpga +0001b29e powerOffHercules +0001b2b2 powerOffMotors +0001af6a powerOffRadio +0001b374 powerOnFpga +0001b384 powerOnHercules +0001b394 powerOnMotors +0001b13e powerOnRadio +000159ca readOnChipInputs +0001b154 releaseFPGAReset +0001ad30 releaseHerculesReset +0001b4ca releaseMotor1Reset +0001b4d2 releaseMotor2Reset +0001b4da releaseMotor3Reset +0001b4e2 releaseMotor4Reset +0001b488 releaseMotorsReset +0001b2c6 releaseRadioReset +0001a036 remove +0001b3a4 setDeploy +0001af9a setFPGAReset +0001a6a0 setHerculesReset +0001b4ea setMotor1Reset +0001b4f2 setMotor2Reset +0001b4fa setMotor3Reset +0001b502 setMotor4Reset +0001b4a6 setMotorsReset +0001b180 setRadioReset +00015334 setvbuf +00019170 sprintf +0001b196 startChargingBatteries +0001b4b0 stopChargingBatteries +0001ad6a strchr +0001ad86 strcmp +0001b322 strcpy +0001b3fa strlen +00019ee4 strncpy +00003554 theQueue +0001a036 unlink +0001b1ac unsetDeploy +000199bc vsprintf +000139ce watchdog_build_hercules_telem +0001b408 watchdog_get_wd_int_flat_duration +000144a6 watchdog_init +00011dcc watchdog_monitor +00019898 write + + +GLOBAL SYMBOLS: SORTED BY Symbol Address + +address name +------- ---- +00000001 __mpu_enable +00000008 __SYSMEM_SIZE +00000100 SFRIE1 +00000100 SFRIE1_L +00000101 SFRIE1_H +00000102 SFRIFG1 +00000102 SFRIFG1_L +00000103 SFRIFG1_H +00000104 SFRRPCR +00000104 SFRRPCR_L +00000105 SFRRPCR_H +00000120 PMMCTL0 +00000120 PMMCTL0_L +00000121 PMMCTL0_H +0000012a PMMIFG +0000012a PMMIFG_L +0000012b PMMIFG_H +00000130 PM5CTL0 +00000130 PM5CTL0_L +00000131 PM5CTL0_H +00000140 FRCTL0 +00000140 FRCTL0_L +00000141 FRCTL0_H +00000144 GCCTL0 +00000144 GCCTL0_L +00000145 GCCTL0_H +00000146 GCCTL1 +00000146 GCCTL1_L +00000147 GCCTL1_H +00000150 CRCDI +00000150 CRCDI_L +00000151 CRCDI_H +00000152 CRCDIRB +00000152 CRCDIRB_L +00000153 CRCDIRB_H +00000154 CRCINIRES +00000154 CRCINIRES_L +00000155 CRCINIRES_H +00000156 CRCRESR +00000156 CRCRESR_L +00000157 CRCRESR_H +00000158 RCCTL0 +00000158 RCCTL0_L +00000159 RCCTL0_H +0000015c WDTCTL +0000015c WDTCTL_L +0000015d WDTCTL_H +00000160 CSCTL0 +00000160 CSCTL0_L +00000161 CSCTL0_H +00000162 CSCTL1 +00000162 CSCTL1_L +00000163 CSCTL1_H +00000164 CSCTL2 +00000164 CSCTL2_L +00000165 CSCTL2_H +00000166 CSCTL3 +00000166 CSCTL3_L +00000167 CSCTL3_H +00000168 CSCTL4 +00000168 CSCTL4_L +00000169 CSCTL4_H +0000016a CSCTL5 +0000016a CSCTL5_L +0000016b CSCTL5_H +0000016c CSCTL6 +0000016c CSCTL6_L +0000016d CSCTL6_H +00000180 SYSCTL +00000180 SYSCTL_L +00000181 SYSCTL_H +00000186 SYSJMBC +00000186 SYSJMBC_L +00000187 SYSJMBC_H +00000188 SYSJMBI0 +00000188 SYSJMBI0_L +00000189 SYSJMBI0_H +0000018a SYSJMBI1 +0000018a SYSJMBI1_L +0000018b SYSJMBI1_H +0000018c SYSJMBO0 +0000018c SYSJMBO0_L +0000018d SYSJMBO0_H +0000018e SYSJMBO1 +0000018e SYSJMBO1_L +0000018f SYSJMBO1_H +0000019a SYSUNIV +0000019a SYSUNIV_L +0000019b SYSUNIV_H +0000019c SYSSNIV +0000019c SYSSNIV_L +0000019d SYSSNIV_H +0000019e SYSRSTIV +0000019e SYSRSTIV_L +0000019f SYSRSTIV_H +000001b0 REFCTL0 +000001b0 REFCTL0_L +000001b1 REFCTL0_H +00000200 P1IN +00000200 PAIN +00000200 PAIN_L +00000201 P2IN +00000201 PAIN_H +00000202 P1OUT +00000202 PAOUT +00000202 PAOUT_L +00000203 P2OUT +00000203 PAOUT_H +00000204 P1DIR +00000204 PADIR +00000204 PADIR_L +00000205 P2DIR +00000205 PADIR_H +00000206 P1REN +00000206 PAREN +00000206 PAREN_L +00000207 P2REN +00000207 PAREN_H +0000020a P1SEL0 +0000020a PASEL0 +0000020a PASEL0_L +0000020b P2SEL0 +0000020b PASEL0_H +0000020c P1SEL1 +0000020c PASEL1 +0000020c PASEL1_L +0000020d P2SEL1 +0000020d PASEL1_H +0000020e P1IV +0000020e P1IV_L +0000020f P1IV_H +00000216 P1SELC +00000216 PASELC +00000216 PASELC_L +00000217 P2SELC +00000217 PASELC_H +00000218 P1IES +00000218 PAIES +00000218 PAIES_L +00000219 P2IES +00000219 PAIES_H +0000021a P1IE +0000021a PAIE +0000021a PAIE_L +0000021b P2IE +0000021b PAIE_H +0000021c P1IFG +0000021c PAIFG +0000021c PAIFG_L +0000021d P2IFG +0000021d PAIFG_H +0000021e P2IV +0000021e P2IV_L +0000021f P2IV_H +00000220 P3IN +00000220 PBIN +00000220 PBIN_L +00000221 P4IN +00000221 PBIN_H +00000222 P3OUT +00000222 PBOUT +00000222 PBOUT_L +00000223 P4OUT +00000223 PBOUT_H +00000224 P3DIR +00000224 PBDIR +00000224 PBDIR_L +00000225 P4DIR +00000225 PBDIR_H +00000226 P3REN +00000226 PBREN +00000226 PBREN_L +00000227 P4REN +00000227 PBREN_H +0000022a P3SEL0 +0000022a PBSEL0 +0000022a PBSEL0_L +0000022b P4SEL0 +0000022b PBSEL0_H +0000022c P3SEL1 +0000022c PBSEL1 +0000022c PBSEL1_L +0000022d P4SEL1 +0000022d PBSEL1_H +0000022e P3IV +0000022e P3IV_L +0000022f P3IV_H +00000236 P3SELC +00000236 PBSELC +00000236 PBSELC_L +00000237 P4SELC +00000237 PBSELC_H +00000238 P3IES +00000238 PBIES +00000238 PBIES_L +00000239 P4IES +00000239 PBIES_H +0000023a P3IE +0000023a PBIE +0000023a PBIE_L +0000023b P4IE +0000023b PBIE_H +0000023c P3IFG +0000023c PBIFG +0000023c PBIFG_L +0000023d P4IFG +0000023d PBIFG_H +0000023e P4IV +0000023e P4IV_L +0000023f P4IV_H +00000240 P5IN +00000240 PCIN +00000240 PCIN_L +00000241 P6IN +00000241 PCIN_H +00000242 P5OUT +00000242 PCOUT +00000242 PCOUT_L +00000243 P6OUT +00000243 PCOUT_H +00000244 P5DIR +00000244 PCDIR +00000244 PCDIR_L +00000245 P6DIR +00000245 PCDIR_H +00000246 P5REN +00000246 PCREN +00000246 PCREN_L +00000247 P6REN +00000247 PCREN_H +0000024a P5SEL0 +0000024a PCSEL0 +0000024a PCSEL0_L +0000024b P6SEL0 +0000024b PCSEL0_H +0000024c P5SEL1 +0000024c PCSEL1 +0000024c PCSEL1_L +0000024d P6SEL1 +0000024d PCSEL1_H +0000024e P5IV +0000024e P5IV_L +0000024f P5IV_H +00000256 P5SELC +00000256 PCSELC +00000256 PCSELC_L +00000257 P6SELC +00000257 PCSELC_H +00000258 P5IES +00000258 PCIES +00000258 PCIES_L +00000259 P6IES +00000259 PCIES_H +0000025a P5IE +0000025a PCIE +0000025a PCIE_L +0000025b P6IE +0000025b PCIE_H +0000025c P5IFG +0000025c PCIFG +0000025c PCIFG_L +0000025d P6IFG +0000025d PCIFG_H +0000025e P6IV +0000025e P6IV_L +0000025f P6IV_H +00000260 P7IN +00000260 PDIN +00000260 PDIN_L +00000261 P8IN +00000261 PDIN_H +00000262 P7OUT +00000262 PDOUT +00000262 PDOUT_L +00000263 P8OUT +00000263 PDOUT_H +00000264 P7DIR +00000264 PDDIR +00000264 PDDIR_L +00000265 P8DIR +00000265 PDDIR_H +00000266 P7REN +00000266 PDREN +00000266 PDREN_L +00000267 P8REN +00000267 PDREN_H +0000026a P7SEL0 +0000026a PDSEL0 +0000026a PDSEL0_L +0000026b P8SEL0 +0000026b PDSEL0_H +0000026c P7SEL1 +0000026c PDSEL1 +0000026c PDSEL1_L +0000026d P8SEL1 +0000026d PDSEL1_H +0000026e P7IV +0000026e P7IV_L +0000026f P7IV_H +00000276 P7SELC +00000276 PDSELC +00000276 PDSELC_L +00000277 P8SELC +00000277 PDSELC_H +00000278 P7IES +00000278 PDIES +00000278 PDIES_L +00000279 P8IES +00000279 PDIES_H +0000027a P7IE +0000027a PDIE +0000027a PDIE_L +0000027b P8IE +0000027b PDIE_H +0000027c P7IFG +0000027c PDIFG +0000027c PDIFG_L +0000027d P8IFG +0000027d PDIFG_H +0000027e P8IV +0000027e P8IV_L +0000027f P8IV_H +00000320 PJIN +00000320 PJIN_L +00000321 PJIN_H +00000322 PJOUT +00000322 PJOUT_L +00000323 PJOUT_H +00000324 PJDIR +00000324 PJDIR_L +00000325 PJDIR_H +00000326 PJREN +00000326 PJREN_L +00000327 PJREN_H +0000032a PJSEL0 +0000032a PJSEL0_L +0000032b PJSEL0_H +0000032c PJSEL1 +0000032c PJSEL1_L +0000032d PJSEL1_H +00000336 PJSELC +00000336 PJSELC_L +00000337 PJSELC_H +00000340 TA0CTL +00000340 TA0CTL_L +00000341 TA0CTL_H +00000342 TA0CCTL0 +00000342 TA0CCTL0_L +00000343 TA0CCTL0_H +00000344 TA0CCTL1 +00000344 TA0CCTL1_L +00000345 TA0CCTL1_H +00000346 TA0CCTL2 +00000346 TA0CCTL2_L +00000347 TA0CCTL2_H +00000350 TA0R +00000350 TA0R_L +00000351 TA0R_H +00000352 TA0CCR0 +00000352 TA0CCR0_L +00000353 TA0CCR0_H +00000354 TA0CCR1 +00000354 TA0CCR1_L +00000355 TA0CCR1_H +00000356 TA0CCR2 +00000356 TA0CCR2_L +00000357 TA0CCR2_H +00000360 TA0EX0 +00000360 TA0EX0_L +00000361 TA0EX0_H +0000036e TA0IV +0000036e TA0IV_L +0000036f TA0IV_H +00000380 TA1CTL +00000380 TA1CTL_L +00000381 TA1CTL_H +00000382 TA1CCTL0 +00000382 TA1CCTL0_L +00000383 TA1CCTL0_H +00000384 TA1CCTL1 +00000384 TA1CCTL1_L +00000385 TA1CCTL1_H +00000386 TA1CCTL2 +00000386 TA1CCTL2_L +00000387 TA1CCTL2_H +00000390 TA1R +00000390 TA1R_L +00000391 TA1R_H +00000392 TA1CCR0 +00000392 TA1CCR0_L +00000393 TA1CCR0_H +00000394 TA1CCR1 +00000394 TA1CCR1_L +00000395 TA1CCR1_H +00000396 TA1CCR2 +00000396 TA1CCR2_L +00000397 TA1CCR2_H +000003a0 TA1EX0 +000003a0 TA1EX0_L +000003a1 TA1EX0_H +000003ae TA1IV +000003ae TA1IV_L +000003af TA1IV_H +000003c0 TB0CTL +000003c0 TB0CTL_L +000003c1 TB0CTL_H +000003c2 TB0CCTL0 +000003c2 TB0CCTL0_L +000003c3 TB0CCTL0_H +000003c4 TB0CCTL1 +000003c4 TB0CCTL1_L +000003c5 TB0CCTL1_H +000003c6 TB0CCTL2 +000003c6 TB0CCTL2_L +000003c7 TB0CCTL2_H +000003c8 TB0CCTL3 +000003c8 TB0CCTL3_L +000003c9 TB0CCTL3_H +000003ca TB0CCTL4 +000003ca TB0CCTL4_L +000003cb TB0CCTL4_H +000003cc TB0CCTL5 +000003cc TB0CCTL5_L +000003cd TB0CCTL5_H +000003ce TB0CCTL6 +000003ce TB0CCTL6_L +000003cf TB0CCTL6_H +000003d0 TB0R +000003d0 TB0R_L +000003d1 TB0R_H +000003d2 TB0CCR0 +000003d2 TB0CCR0_L +000003d3 TB0CCR0_H +000003d4 TB0CCR1 +000003d4 TB0CCR1_L +000003d5 TB0CCR1_H +000003d6 TB0CCR2 +000003d6 TB0CCR2_L +000003d7 TB0CCR2_H +000003d8 TB0CCR3 +000003d8 TB0CCR3_L +000003d9 TB0CCR3_H +000003da TB0CCR4 +000003da TB0CCR4_L +000003db TB0CCR4_H +000003dc TB0CCR5 +000003dc TB0CCR5_L +000003dd TB0CCR5_H +000003de TB0CCR6 +000003de TB0CCR6_L +000003df TB0CCR6_H +000003e0 TB0EX0 +000003e0 TB0EX0_L +000003e1 TB0EX0_H +000003ee TB0IV +000003ee TB0IV_L +000003ef TB0IV_H +00000400 TA2CTL +00000400 TA2CTL_L +00000401 TA2CTL_H +00000402 TA2CCTL0 +00000402 TA2CCTL0_L +00000403 TA2CCTL0_H +00000404 TA2CCTL1 +00000404 TA2CCTL1_L +00000405 TA2CCTL1_H +00000410 TA2R +00000410 TA2R_L +00000411 TA2R_H +00000412 TA2CCR0 +00000412 TA2CCR0_L +00000413 TA2CCR0_H +00000414 TA2CCR1 +00000414 TA2CCR1_L +00000415 TA2CCR1_H +00000420 TA2EX0 +00000420 TA2EX0_L +00000421 TA2EX0_H +0000042e TA2IV +0000042e TA2IV_L +0000042f TA2IV_H +0000043e CAPTIO0CTL +0000043e CAPTIO0CTL_L +0000043f CAPTIO0CTL_H +00000440 TA3CTL +00000440 TA3CTL_L +00000440 mpu_segment_border1 +00000440 mpu_segment_border2 +00000441 TA3CTL_H +00000442 TA3CCTL0 +00000442 TA3CCTL0_L +00000443 TA3CCTL0_H +00000444 TA3CCTL1 +00000444 TA3CCTL1_L +00000445 TA3CCTL1_H +00000450 TA3R +00000450 TA3R_L +00000451 TA3R_H +00000452 TA3CCR0 +00000452 TA3CCR0_L +00000453 TA3CCR0_H +00000454 TA3CCR1 +00000454 TA3CCR1_L +00000455 TA3CCR1_H +00000460 TA3EX0 +00000460 TA3EX0_L +00000461 TA3EX0_H +0000046e TA3IV +0000046e TA3IV_L +0000046f TA3IV_H +0000047e CAPTIO1CTL +0000047e CAPTIO1CTL_L +0000047f CAPTIO1CTL_H +000004a0 RTCCTL0 +000004a0 RTCCTL0_L +000004a1 RTCCTL0_H +000004a2 RTCCTL13 +000004a2 RTCCTL13_L +000004a3 RTCCTL13_H +000004a4 RTCOCAL +000004a4 RTCOCAL_L +000004a5 RTCOCAL_H +000004a6 RTCTCMP +000004a6 RTCTCMP_L +000004a7 RTCTCMP_H +000004a8 RTCPS0CTL +000004a8 RTCPS0CTL_L +000004a9 RTCPS0CTL_H +000004aa RTCPS1CTL +000004aa RTCPS1CTL_L +000004ab RTCPS1CTL_H +000004ac RT0PS +000004ac RTCPS +000004ac RTCPS_L +000004ad RT1PS +000004ad RTCPS_H +000004ae RTCIV +000004ae RTCIV_L +000004af RTCIV_H +000004b0 RTCCNT1 +000004b0 RTCCNT12 +000004b0 RTCCNT12_L +000004b0 RTCTIM0 +000004b0 RTCTIM0_L +000004b1 RTCCNT12_H +000004b1 RTCCNT2 +000004b1 RTCTIM0_H +000004b2 RTCCNT3 +000004b2 RTCCNT34 +000004b2 RTCCNT34_L +000004b2 RTCTIM1 +000004b2 RTCTIM1_L +000004b3 RTCCNT34_H +000004b3 RTCCNT4 +000004b3 RTCTIM1_H +000004b4 RTCDATE +000004b4 RTCDATE_L +000004b5 RTCDATE_H +000004b6 RTCYEAR +000004b6 RTCYEAR_L +000004b7 RTCYEAR_H +000004b8 RTCAMINHR +000004b8 RTCAMINHR_L +000004b9 RTCAMINHR_H +000004ba RTCADOWDAY +000004ba RTCADOWDAY_L +000004bb RTCADOWDAY_H +000004bc BIN2BCD +000004bc BIN2BCD_L +000004bd BIN2BCD_H +000004be BCD2BIN +000004be BCD2BIN_L +000004bf BCD2BIN_H +000004c0 MPY +000004c0 MPY_L +000004c1 MPY_H +000004c2 MPYS +000004c2 MPYS_L +000004c3 MPYS_H +000004c4 MAC +000004c4 MAC_L +000004c5 MAC_H +000004c6 MACS +000004c6 MACS_L +000004c7 MACS_H +000004c8 OP2 +000004c8 OP2_L +000004c9 OP2_H +000004ca RESLO +000004ca RESLO_L +000004cb RESLO_H +000004cc RESHI +000004cc RESHI_L +000004cd RESHI_H +000004ce SUMEXT +000004ce SUMEXT_L +000004cf SUMEXT_H +000004d0 MPY32L +000004d0 MPY32L_L +000004d1 MPY32L_H +000004d2 MPY32H +000004d2 MPY32H_L +000004d3 MPY32H_H +000004d4 MPYS32L +000004d4 MPYS32L_L +000004d5 MPYS32L_H +000004d6 MPYS32H +000004d6 MPYS32H_L +000004d7 MPYS32H_H +000004d8 MAC32L +000004d8 MAC32L_L +000004d9 MAC32L_H +000004da MAC32H +000004da MAC32H_L +000004db MAC32H_H +000004dc MACS32L +000004dc MACS32L_L +000004dd MACS32L_H +000004de MACS32H +000004de MACS32H_L +000004df MACS32H_H +000004e0 OP2L +000004e0 OP2L_L +000004e1 OP2L_H +000004e2 OP2H +000004e2 OP2H_L +000004e3 OP2H_H +000004e4 RES0 +000004e4 RES0_L +000004e5 RES0_H +000004e6 RES1 +000004e6 RES1_L +000004e7 RES1_H +000004e8 RES2 +000004e8 RES2_L +000004e9 RES2_H +000004ea RES3 +000004ea RES3_L +000004eb RES3_H +000004ec MPY32CTL0 +000004ec MPY32CTL0_L +000004ed MPY32CTL0_H +00000500 DMACTL0 +00000500 DMACTL0_L +00000501 DMACTL0_H +00000502 DMACTL1 +00000502 DMACTL1_L +00000503 DMACTL1_H +00000504 DMACTL2 +00000504 DMACTL2_L +00000505 DMACTL2_H +00000508 DMACTL4 +00000508 DMACTL4_L +00000509 DMACTL4_H +0000050e DMAIV +0000050e DMAIV_L +0000050f DMAIV_H +00000510 DMA0CTL +00000510 DMA0CTL_L +00000511 DMA0CTL_H +00000512 DMA0SA +00000512 DMA0SAL +00000514 DMA0SAH +00000516 DMA0DA +00000516 DMA0DAL +00000518 DMA0DAH +0000051a DMA0SZ +0000051a DMA0SZ_L +0000051b DMA0SZ_H +00000520 DMA1CTL +00000520 DMA1CTL_L +00000521 DMA1CTL_H +00000522 DMA1SA +00000522 DMA1SAL +00000524 DMA1SAH +00000526 DMA1DA +00000526 DMA1DAL +00000528 DMA1DAH +0000052a DMA1SZ +0000052a DMA1SZ_L +0000052b DMA1SZ_H +00000530 DMA2CTL +00000530 DMA2CTL_L +00000531 DMA2CTL_H +00000532 DMA2SA +00000532 DMA2SAL +00000534 DMA2SAH +00000536 DMA2DA +00000536 DMA2DAL +00000538 DMA2DAH +0000053a DMA2SZ +0000053a DMA2SZ_L +0000053b DMA2SZ_H +00000540 DMA3CTL +00000540 DMA3CTL_L +00000541 DMA3CTL_H +00000542 DMA3SA +00000542 DMA3SAL +00000544 DMA3SAH +00000546 DMA3DA +00000546 DMA3DAL +00000548 DMA3DAH +0000054a DMA3SZ +0000054a DMA3SZ_L +0000054b DMA3SZ_H +00000550 DMA4CTL +00000550 DMA4CTL_L +00000551 DMA4CTL_H +00000552 DMA4SA +00000552 DMA4SAL +00000554 DMA4SAH +00000556 DMA4DA +00000556 DMA4DAL +00000558 DMA4DAH +0000055a DMA4SZ +0000055a DMA4SZ_L +0000055b DMA4SZ_H +00000560 DMA5CTL +00000560 DMA5CTL_L +00000561 DMA5CTL_H +00000562 DMA5SA +00000562 DMA5SAL +00000564 DMA5SAH +00000566 DMA5DA +00000566 DMA5DAL +00000568 DMA5DAH +0000056a DMA5SZ +0000056a DMA5SZ_L +0000056b DMA5SZ_H +000005a0 MPUCTL0 +000005a0 MPUCTL0_L +000005a1 MPUCTL0_H +000005a2 MPUCTL1 +000005a2 MPUCTL1_L +000005a3 MPUCTL1_H +000005a4 MPUSEGB2 +000005a4 MPUSEGB2_L +000005a5 MPUSEGB2_H +000005a6 MPUSEGB1 +000005a6 MPUSEGB1_L +000005a7 MPUSEGB1_H +000005a8 MPUSAM +000005a8 MPUSAM_L +000005a9 MPUSAM_H +000005aa MPUIPC0 +000005aa MPUIPC0_L +000005ab MPUIPC0_H +000005ac MPUIPSEGB2 +000005ac MPUIPSEGB2_L +000005ad MPUIPSEGB2_H +000005ae MPUIPSEGB1 +000005ae MPUIPSEGB1_L +000005af MPUIPSEGB1_H +000005c0 UCA0CTLW0 +000005c0 UCA0CTLW0_L +000005c1 UCA0CTLW0_H +000005c2 UCA0CTLW1 +000005c2 UCA0CTLW1_L +000005c3 UCA0CTLW1_H +000005c6 UCA0BRW +000005c6 UCA0BRW_L +000005c7 UCA0BRW_H +000005c8 UCA0MCTLW +000005c8 UCA0MCTLW_L +000005c9 UCA0MCTLW_H +000005ca UCA0STATW +000005ca UCA0STATW_L +000005cb UCA0STATW_H +000005cc UCA0RXBUF +000005cc UCA0RXBUF_L +000005cd UCA0RXBUF_H +000005ce UCA0TXBUF +000005ce UCA0TXBUF_L +000005cf UCA0TXBUF_H +000005d0 UCA0ABCTL +000005d0 UCA0ABCTL_L +000005d1 UCA0ABCTL_H +000005d2 UCA0IRCTL +000005d2 UCA0IRCTL_L +000005d3 UCA0IRCTL_H +000005d4 __STACK_SIZE +000005da UCA0IE +000005da UCA0IE_L +000005db UCA0IE_H +000005dc UCA0IFG +000005dc UCA0IFG_L +000005dd UCA0IFG_H +000005de UCA0IV +000005de UCA0IV_L +000005df UCA0IV_H +000005e0 UCA1CTLW0 +000005e0 UCA1CTLW0_L +000005e1 UCA1CTLW0_H +000005e2 UCA1CTLW1 +000005e2 UCA1CTLW1_L +000005e3 UCA1CTLW1_H +000005e6 UCA1BRW +000005e6 UCA1BRW_L +000005e7 UCA1BRW_H +000005e8 UCA1MCTLW +000005e8 UCA1MCTLW_L +000005e9 UCA1MCTLW_H +000005ea UCA1STATW +000005ea UCA1STATW_L +000005eb UCA1STATW_H +000005ec UCA1RXBUF +000005ec UCA1RXBUF_L +000005ed UCA1RXBUF_H +000005ee UCA1TXBUF +000005ee UCA1TXBUF_L +000005ef UCA1TXBUF_H +000005f0 UCA1ABCTL +000005f0 UCA1ABCTL_L +000005f1 UCA1ABCTL_H +000005f2 UCA1IRCTL +000005f2 UCA1IRCTL_L +000005f3 UCA1IRCTL_H +000005fa UCA1IE +000005fa UCA1IE_L +000005fb UCA1IE_H +000005fc UCA1IFG +000005fc UCA1IFG_L +000005fd UCA1IFG_H +000005fe UCA1IV +000005fe UCA1IV_L +000005ff UCA1IV_H +00000600 UCA2CTLW0 +00000600 UCA2CTLW0_L +00000601 UCA2CTLW0_H +00000602 UCA2CTLW1 +00000602 UCA2CTLW1_L +00000603 UCA2CTLW1_H +00000606 UCA2BRW +00000606 UCA2BRW_L +00000607 UCA2BRW_H +00000608 UCA2MCTLW +00000608 UCA2MCTLW_L +00000609 UCA2MCTLW_H +0000060a UCA2STATW +0000060a UCA2STATW_L +0000060b UCA2STATW_H +0000060c UCA2RXBUF +0000060c UCA2RXBUF_L +0000060d UCA2RXBUF_H +0000060e UCA2TXBUF +0000060e UCA2TXBUF_L +0000060f UCA2TXBUF_H +00000610 UCA2ABCTL +00000610 UCA2ABCTL_L +00000611 UCA2ABCTL_H +00000612 UCA2IRCTL +00000612 UCA2IRCTL_L +00000613 UCA2IRCTL_H +0000061a UCA2IE +0000061a UCA2IE_L +0000061b UCA2IE_H +0000061c UCA2IFG +0000061c UCA2IFG_L +0000061d UCA2IFG_H +0000061e UCA2IV +0000061e UCA2IV_L +0000061f UCA2IV_H +00000620 UCA3CTLW0 +00000620 UCA3CTLW0_L +00000621 UCA3CTLW0_H +00000622 UCA3CTLW1 +00000622 UCA3CTLW1_L +00000623 UCA3CTLW1_H +00000626 UCA3BRW +00000626 UCA3BRW_L +00000627 UCA3BRW_H +00000628 UCA3MCTLW +00000628 UCA3MCTLW_L +00000629 UCA3MCTLW_H +0000062a UCA3STATW +0000062a UCA3STATW_L +0000062b UCA3STATW_H +0000062c UCA3RXBUF +0000062c UCA3RXBUF_L +0000062d UCA3RXBUF_H +0000062e UCA3TXBUF +0000062e UCA3TXBUF_L +0000062f UCA3TXBUF_H +00000630 UCA3ABCTL +00000630 UCA3ABCTL_L +00000631 UCA3ABCTL_H +00000632 UCA3IRCTL +00000632 UCA3IRCTL_L +00000633 UCA3IRCTL_H +0000063a UCA3IE +0000063a UCA3IE_L +0000063b UCA3IE_H +0000063c UCA3IFG +0000063c UCA3IFG_L +0000063d UCA3IFG_H +0000063e UCA3IV +0000063e UCA3IV_L +0000063f UCA3IV_H +00000640 UCB0CTLW0 +00000640 UCB0CTLW0_L +00000641 UCB0CTLW0_H +00000642 UCB0CTLW1 +00000642 UCB0CTLW1_L +00000643 UCB0CTLW1_H +00000646 UCB0BRW +00000646 UCB0BRW_L +00000647 UCB0BRW_H +00000648 UCB0STATW +00000648 UCB0STATW_L +00000649 UCB0STATW_H +0000064a UCB0TBCNT +0000064a UCB0TBCNT_L +0000064b UCB0TBCNT_H +0000064c UCB0RXBUF +0000064c UCB0RXBUF_L +0000064d UCB0RXBUF_H +0000064e UCB0TXBUF +0000064e UCB0TXBUF_L +0000064f UCB0TXBUF_H +00000654 UCB0I2COA0 +00000654 UCB0I2COA0_L +00000655 UCB0I2COA0_H +00000656 UCB0I2COA1 +00000656 UCB0I2COA1_L +00000657 UCB0I2COA1_H +00000658 UCB0I2COA2 +00000658 UCB0I2COA2_L +00000659 UCB0I2COA2_H +0000065a UCB0I2COA3 +0000065a UCB0I2COA3_L +0000065b UCB0I2COA3_H +0000065c UCB0ADDRX +0000065c UCB0ADDRX_L +0000065d UCB0ADDRX_H +0000065e UCB0ADDMASK +0000065e UCB0ADDMASK_L +0000065f UCB0ADDMASK_H +00000660 UCB0I2CSA +00000660 UCB0I2CSA_L +00000661 UCB0I2CSA_H +0000066a UCB0IE +0000066a UCB0IE_L +0000066b UCB0IE_H +0000066c UCB0IFG +0000066c UCB0IFG_L +0000066d UCB0IFG_H +0000066e UCB0IV +0000066e UCB0IV_L +0000066f UCB0IV_H +00000680 UCB1CTLW0 +00000680 UCB1CTLW0_L +00000681 UCB1CTLW0_H +00000682 UCB1CTLW1 +00000682 UCB1CTLW1_L +00000683 UCB1CTLW1_H +00000686 UCB1BRW +00000686 UCB1BRW_L +00000687 UCB1BRW_H +00000688 UCB1STATW +00000688 UCB1STATW_L +00000689 UCB1STATW_H +0000068a UCB1TBCNT +0000068a UCB1TBCNT_L +0000068b UCB1TBCNT_H +0000068c UCB1RXBUF +0000068c UCB1RXBUF_L +0000068d UCB1RXBUF_H +0000068e UCB1TXBUF +0000068e UCB1TXBUF_L +0000068f UCB1TXBUF_H +00000694 UCB1I2COA0 +00000694 UCB1I2COA0_L +00000695 UCB1I2COA0_H +00000696 UCB1I2COA1 +00000696 UCB1I2COA1_L +00000697 UCB1I2COA1_H +00000698 UCB1I2COA2 +00000698 UCB1I2COA2_L +00000699 UCB1I2COA2_H +0000069a UCB1I2COA3 +0000069a UCB1I2COA3_L +0000069b UCB1I2COA3_H +0000069c UCB1ADDRX +0000069c UCB1ADDRX_L +0000069d UCB1ADDRX_H +0000069e UCB1ADDMASK +0000069e UCB1ADDMASK_L +0000069f UCB1ADDMASK_H +000006a0 UCB1I2CSA +000006a0 UCB1I2CSA_L +000006a1 UCB1I2CSA_H +000006aa UCB1IE +000006aa UCB1IE_L +000006ab UCB1IE_H +000006ac UCB1IFG +000006ac UCB1IFG_L +000006ad UCB1IFG_H +000006ae UCB1IV +000006ae UCB1IV_L +000006af UCB1IV_H +000006c0 UCB2CTLW0 +000006c0 UCB2CTLW0_L +000006c1 UCB2CTLW0_H +000006c2 UCB2CTLW1 +000006c2 UCB2CTLW1_L +000006c3 UCB2CTLW1_H +000006c6 UCB2BRW +000006c6 UCB2BRW_L +000006c7 UCB2BRW_H +000006c8 UCB2STATW +000006c8 UCB2STATW_L +000006c9 UCB2STATW_H +000006ca UCB2TBCNT +000006ca UCB2TBCNT_L +000006cb UCB2TBCNT_H +000006cc UCB2RXBUF +000006cc UCB2RXBUF_L +000006cd UCB2RXBUF_H +000006ce UCB2TXBUF +000006ce UCB2TXBUF_L +000006cf UCB2TXBUF_H +000006d4 UCB2I2COA0 +000006d4 UCB2I2COA0_L +000006d5 UCB2I2COA0_H +000006d6 UCB2I2COA1 +000006d6 UCB2I2COA1_L +000006d7 UCB2I2COA1_H +000006d8 UCB2I2COA2 +000006d8 UCB2I2COA2_L +000006d9 UCB2I2COA2_H +000006da UCB2I2COA3 +000006da UCB2I2COA3_L +000006db UCB2I2COA3_H +000006dc UCB2ADDRX +000006dc UCB2ADDRX_L +000006dd UCB2ADDRX_H +000006de UCB2ADDMASK +000006de UCB2ADDMASK_L +000006df UCB2ADDMASK_H +000006e0 UCB2I2CSA +000006e0 UCB2I2CSA_L +000006e1 UCB2I2CSA_H +000006ea UCB2IE +000006ea UCB2IE_L +000006eb UCB2IE_H +000006ec UCB2IFG +000006ec UCB2IFG_L +000006ed UCB2IFG_H +000006ee UCB2IV +000006ee UCB2IV_L +000006ef UCB2IV_H +00000700 UCB3CTLW0 +00000700 UCB3CTLW0_L +00000701 UCB3CTLW0_H +00000702 UCB3CTLW1 +00000702 UCB3CTLW1_L +00000703 UCB3CTLW1_H +00000706 UCB3BRW +00000706 UCB3BRW_L +00000707 UCB3BRW_H +00000708 UCB3STATW +00000708 UCB3STATW_L +00000709 UCB3STATW_H +0000070a UCB3TBCNT +0000070a UCB3TBCNT_L +0000070b UCB3TBCNT_H +0000070c UCB3RXBUF +0000070c UCB3RXBUF_L +0000070d UCB3RXBUF_H +0000070e UCB3TXBUF +0000070e UCB3TXBUF_L +0000070f UCB3TXBUF_H +00000714 UCB3I2COA0 +00000714 UCB3I2COA0_L +00000715 UCB3I2COA0_H +00000716 UCB3I2COA1 +00000716 UCB3I2COA1_L +00000717 UCB3I2COA1_H +00000718 UCB3I2COA2 +00000718 UCB3I2COA2_L +00000719 UCB3I2COA2_H +0000071a UCB3I2COA3 +0000071a UCB3I2COA3_L +0000071b UCB3I2COA3_H +0000071c UCB3ADDRX +0000071c UCB3ADDRX_L +0000071d UCB3ADDRX_H +0000071e UCB3ADDMASK +0000071e UCB3ADDMASK_L +0000071f UCB3ADDMASK_H +00000720 UCB3I2CSA +00000720 UCB3I2CSA_L +00000721 UCB3I2CSA_H +0000072a UCB3IE +0000072a UCB3IE_L +0000072b UCB3IE_H +0000072c UCB3IFG +0000072c UCB3IFG_L +0000072d UCB3IFG_H +0000072e UCB3IV +0000072e UCB3IV_L +0000072f UCB3IV_H +000007c0 TA4CTL +000007c0 TA4CTL_L +000007c1 TA4CTL_H +000007c2 TA4CCTL0 +000007c2 TA4CCTL0_L +000007c3 TA4CCTL0_H +000007c4 TA4CCTL1 +000007c4 TA4CCTL1_L +000007c5 TA4CCTL1_H +000007c6 TA4CCTL2 +000007c6 TA4CCTL2_L +000007c7 TA4CCTL2_H +000007d0 TA4R +000007d0 TA4R_L +000007d1 TA4R_H +000007d2 TA4CCR0 +000007d2 TA4CCR0_L +000007d3 TA4CCR0_H +000007d4 TA4CCR1 +000007d4 TA4CCR1_L +000007d5 TA4CCR1_H +000007d6 TA4CCR2 +000007d6 TA4CCR2_L +000007d7 TA4CCR2_H +000007e0 TA4EX0 +000007e0 TA4EX0_L +000007e1 TA4EX0_H +000007ee TA4IV +000007ee TA4IV_L +000007ef TA4IV_H +00000800 ADC12CTL0 +00000800 ADC12CTL0_L +00000801 ADC12CTL0_H +00000802 ADC12CTL1 +00000802 ADC12CTL1_L +00000803 ADC12CTL1_H +00000804 ADC12CTL2 +00000804 ADC12CTL2_L +00000805 ADC12CTL2_H +00000806 ADC12CTL3 +00000806 ADC12CTL3_L +00000807 ADC12CTL3_H +00000808 ADC12LO +00000808 ADC12LO_L +00000809 ADC12LO_H +0000080a ADC12HI +0000080a ADC12HI_L +0000080b ADC12HI_H +0000080c ADC12IFGR0 +0000080c ADC12IFGR0_L +0000080d ADC12IFGR0_H +0000080e ADC12IFGR1 +0000080e ADC12IFGR1_L +0000080f ADC12IFGR1_H +00000810 ADC12IFGR2 +00000810 ADC12IFGR2_L +00000811 ADC12IFGR2_H +00000812 ADC12IER0 +00000812 ADC12IER0_L +00000813 ADC12IER0_H +00000814 ADC12IER1 +00000814 ADC12IER1_L +00000815 ADC12IER1_H +00000816 ADC12IER2 +00000816 ADC12IER2_L +00000817 ADC12IER2_H +00000818 ADC12IV +00000818 ADC12IV_L +00000819 ADC12IV_H +00000820 ADC12MCTL0 +00000820 ADC12MCTL0_L +00000821 ADC12MCTL0_H +00000822 ADC12MCTL1 +00000822 ADC12MCTL1_L +00000823 ADC12MCTL1_H +00000824 ADC12MCTL2 +00000824 ADC12MCTL2_L +00000825 ADC12MCTL2_H +00000826 ADC12MCTL3 +00000826 ADC12MCTL3_L +00000827 ADC12MCTL3_H +00000828 ADC12MCTL4 +00000828 ADC12MCTL4_L +00000829 ADC12MCTL4_H +0000082a ADC12MCTL5 +0000082a ADC12MCTL5_L +0000082b ADC12MCTL5_H +0000082c ADC12MCTL6 +0000082c ADC12MCTL6_L +0000082d ADC12MCTL6_H +0000082e ADC12MCTL7 +0000082e ADC12MCTL7_L +0000082f ADC12MCTL7_H +00000830 ADC12MCTL8 +00000830 ADC12MCTL8_L +00000831 ADC12MCTL8_H +00000832 ADC12MCTL9 +00000832 ADC12MCTL9_L +00000833 ADC12MCTL9_H +00000834 ADC12MCTL10 +00000834 ADC12MCTL10_L +00000835 ADC12MCTL10_H +00000836 ADC12MCTL11 +00000836 ADC12MCTL11_L +00000837 ADC12MCTL11_H +00000838 ADC12MCTL12 +00000838 ADC12MCTL12_L +00000839 ADC12MCTL12_H +0000083a ADC12MCTL13 +0000083a ADC12MCTL13_L +0000083b ADC12MCTL13_H +0000083c ADC12MCTL14 +0000083c ADC12MCTL14_L +0000083d ADC12MCTL14_H +0000083e ADC12MCTL15 +0000083e ADC12MCTL15_L +0000083f ADC12MCTL15_H +00000840 ADC12MCTL16 +00000840 ADC12MCTL16_L +00000841 ADC12MCTL16_H +00000842 ADC12MCTL17 +00000842 ADC12MCTL17_L +00000843 ADC12MCTL17_H +00000844 ADC12MCTL18 +00000844 ADC12MCTL18_L +00000845 ADC12MCTL18_H +00000846 ADC12MCTL19 +00000846 ADC12MCTL19_L +00000847 ADC12MCTL19_H +00000848 ADC12MCTL20 +00000848 ADC12MCTL20_L +00000849 ADC12MCTL20_H +0000084a ADC12MCTL21 +0000084a ADC12MCTL21_L +0000084b ADC12MCTL21_H +0000084c ADC12MCTL22 +0000084c ADC12MCTL22_L +0000084d ADC12MCTL22_H +0000084e ADC12MCTL23 +0000084e ADC12MCTL23_L +0000084f ADC12MCTL23_H +00000850 ADC12MCTL24 +00000850 ADC12MCTL24_L +00000851 ADC12MCTL24_H +00000852 ADC12MCTL25 +00000852 ADC12MCTL25_L +00000853 ADC12MCTL25_H +00000854 ADC12MCTL26 +00000854 ADC12MCTL26_L +00000855 ADC12MCTL26_H +00000856 ADC12MCTL27 +00000856 ADC12MCTL27_L +00000857 ADC12MCTL27_H +00000858 ADC12MCTL28 +00000858 ADC12MCTL28_L +00000859 ADC12MCTL28_H +0000085a ADC12MCTL29 +0000085a ADC12MCTL29_L +0000085b ADC12MCTL29_H +0000085c ADC12MCTL30 +0000085c ADC12MCTL30_L +0000085d ADC12MCTL30_H +0000085e ADC12MCTL31 +0000085e ADC12MCTL31_L +0000085f ADC12MCTL31_H +00000860 ADC12MEM0 +00000860 ADC12MEM0_L +00000861 ADC12MEM0_H +00000862 ADC12MEM1 +00000862 ADC12MEM1_L +00000863 ADC12MEM1_H +00000864 ADC12MEM2 +00000864 ADC12MEM2_L +00000865 ADC12MEM2_H +00000866 ADC12MEM3 +00000866 ADC12MEM3_L +00000867 ADC12MEM3_H +00000868 ADC12MEM4 +00000868 ADC12MEM4_L +00000869 ADC12MEM4_H +0000086a ADC12MEM5 +0000086a ADC12MEM5_L +0000086b ADC12MEM5_H +0000086c ADC12MEM6 +0000086c ADC12MEM6_L +0000086d ADC12MEM6_H +0000086e ADC12MEM7 +0000086e ADC12MEM7_L +0000086f ADC12MEM7_H +00000870 ADC12MEM8 +00000870 ADC12MEM8_L +00000871 ADC12MEM8_H +00000872 ADC12MEM9 +00000872 ADC12MEM9_L +00000873 ADC12MEM9_H +00000874 ADC12MEM10 +00000874 ADC12MEM10_L +00000875 ADC12MEM10_H +00000876 ADC12MEM11 +00000876 ADC12MEM11_L +00000877 ADC12MEM11_H +00000878 ADC12MEM12 +00000878 ADC12MEM12_L +00000879 ADC12MEM12_H +0000087a ADC12MEM13 +0000087a ADC12MEM13_L +0000087b ADC12MEM13_H +0000087c ADC12MEM14 +0000087c ADC12MEM14_L +0000087d ADC12MEM14_H +0000087e ADC12MEM15 +0000087e ADC12MEM15_L +0000087f ADC12MEM15_H +00000880 ADC12MEM16 +00000880 ADC12MEM16_L +00000881 ADC12MEM16_H +00000882 ADC12MEM17 +00000882 ADC12MEM17_L +00000883 ADC12MEM17_H +00000884 ADC12MEM18 +00000884 ADC12MEM18_L +00000885 ADC12MEM18_H +00000886 ADC12MEM19 +00000886 ADC12MEM19_L +00000887 ADC12MEM19_H +00000888 ADC12MEM20 +00000888 ADC12MEM20_L +00000889 ADC12MEM20_H +0000088a ADC12MEM21 +0000088a ADC12MEM21_L +0000088b ADC12MEM21_H +0000088c ADC12MEM22 +0000088c ADC12MEM22_L +0000088d ADC12MEM22_H +0000088e ADC12MEM23 +0000088e ADC12MEM23_L +0000088f ADC12MEM23_H +00000890 ADC12MEM24 +00000890 ADC12MEM24_L +00000891 ADC12MEM24_H +00000892 ADC12MEM25 +00000892 ADC12MEM25_L +00000893 ADC12MEM25_H +00000894 ADC12MEM26 +00000894 ADC12MEM26_L +00000895 ADC12MEM26_H +00000896 ADC12MEM27 +00000896 ADC12MEM27_L +00000897 ADC12MEM27_H +00000898 ADC12MEM28 +00000898 ADC12MEM28_L +00000899 ADC12MEM28_H +0000089a ADC12MEM29 +0000089a ADC12MEM29_L +0000089b ADC12MEM29_H +0000089c ADC12MEM30 +0000089c ADC12MEM30_L +0000089d ADC12MEM30_H +0000089e ADC12MEM31 +0000089e ADC12MEM31_L +0000089f ADC12MEM31_H +000008c0 CECTL0 +000008c0 CECTL0_L +000008c1 CECTL0_H +000008c2 CECTL1 +000008c2 CECTL1_L +000008c3 CECTL1_H +000008c4 CECTL2 +000008c4 CECTL2_L +000008c5 CECTL2_H +000008c6 CECTL3 +000008c6 CECTL3_L +000008c7 CECTL3_H +000008cc CEINT +000008cc CEINT_L +000008cd CEINT_H +000008ce CEIV +000008ce CEIV_L +000008cf CEIV_H +00000980 CRC32DIW0 +00000980 CRC32DIW0_L +00000981 CRC32DIW0_H +00000982 CRC32DIW1 +00000982 CRC32DIW1_L +00000983 CRC32DIW1_H +00000984 CRC32DIRBW1 +00000984 CRC32DIRBW1_L +00000985 CRC32DIRBW1_H +00000986 CRC32DIRBW0 +00000986 CRC32DIRBW0_L +00000987 CRC32DIRBW0_H +00000988 CRC32INIRESW0 +00000988 CRC32INIRESW0_L +00000989 CRC32INIRESW0_H +0000098a CRC32INIRESW1 +0000098a CRC32INIRESW1_L +0000098b CRC32INIRESW1_H +0000098c CRC32RESRW1 +0000098c CRC32RESRW1_L +0000098d CRC32RESRW1_H +0000098e CRC32RESRW0 +0000098e CRC32RESRW0_L +0000098f CRC32RESRW0_H +00000990 CRC16DIW0 +00000990 CRC16DIW0_L +00000991 CRC16DIW0_H +00000996 CRC16DIRBW0 +00000996 CRC16DIRBW0_L +00000997 CRC16DIRBW0_H +00000998 CRC16INIRESW0 +00000998 CRC16INIRESW0_L +00000999 CRC16INIRESW0_H +0000099e CRC16RESRW0 +0000099e CRC16RESRW0_L +0000099f CRC16RESRW0_H +000009c0 AESACTL0 +000009c0 AESACTL0_L +000009c1 AESACTL0_H +000009c2 AESACTL1 +000009c2 AESACTL1_L +000009c3 AESACTL1_H +000009c4 AESASTAT +000009c4 AESASTAT_L +000009c5 AESASTAT_H +000009c6 AESAKEY +000009c6 AESAKEY_L +000009c7 AESAKEY_H +000009c8 AESADIN +000009c8 AESADIN_L +000009c9 AESADIN_H +000009ca AESADOUT +000009ca AESADOUT_L +000009cb AESADOUT_H +000009cc AESAXDIN +000009cc AESAXDIN_L +000009cd AESAXDIN_H +000009ce AESAXIN +000009ce AESAXIN_L +000009cf AESAXIN_H +00000a80 LEACAP +00000a80 LEACAPL +00000a82 LEACAPH +00000a84 LEACNF0 +00000a84 LEACNF0L +00000a86 LEACNF0H +00000a88 LEACNF1 +00000a88 LEACNF1L +00000a8a LEACNF1H +00000a8c LEACNF2 +00000a8c LEACNF2L +00000a8e LEACNF2H +00000a90 LEAMB +00000a90 LEAMBL +00000a92 LEAMBH +00000a94 LEAMT +00000a94 LEAMTL +00000a96 LEAMTH +00000a98 LEACMA +00000a98 LEACMAL +00000a9a LEACMAH +00000a9c LEACMCTL +00000a9c LEACMCTLL +00000a9e LEACMCTLH +00000aa8 LEACMDSTAT +00000aa8 LEACMDSTATL +00000aaa LEACMDSTATH +00000aac LEAS1STAT +00000aac LEAS1STATL +00000aae LEAS1STATH +00000ab0 LEAS0STAT +00000ab0 LEAS0STATL +00000ab2 LEAS0STATH +00000ab4 LEADSTSTAT +00000ab4 LEADSTSTATL +00000ab6 LEADSTSTATH +00000ac0 LEAPMCTL +00000ac0 LEAPMCTLL +00000ac2 LEAPMCTLH +00000ac4 LEAPMDST +00000ac4 LEAPMDSTL +00000ac6 LEAPMDSTH +00000ac8 LEAPMS1 +00000ac8 LEAPMS1L +00000aca LEAPMS1H +00000acc LEAPMS0 +00000acc LEAPMS0L +00000ace LEAPMS0H +00000ad0 LEAPMCB +00000ad0 LEAPMCBL +00000ad2 LEAPMCBH +00000af0 LEAIFGSET +00000af0 LEAIFGSETL +00000af2 LEAIFGSETH +00000af4 LEAIE +00000af4 LEAIEL +00000af6 LEAIEH +00000af8 LEAIFG +00000af8 LEAIFGL +00000afa LEAIFGH +00000afc LEAIV +00000afc LEAIVL +00000afe LEAIVH +00001513 mpu_sam_value +00002800 __TI_tmpnams +00002900 parmbuf +000031a6 _ftable +0000326e _device +00003366 _stream +00003554 theQueue +0000355a __TI_cleanup_ptr +0000355e __TI_dtors_ptr +00003562 _lock +00003566 _unlock +0000358a __TI_ft_end +0000358c __TI_enable_exit_profile_output +0000362c _stack +00003c00 __STACK_END +00004000 fram_rw_start +00004002 _CIOBUF_ +00004124 _sys_memory +00004400 USCI_A0_ISR +00004400 fram_ipe_end +00004400 fram_ipe_start +00004400 fram_rx_start +000044ca USCI_A1_ISR +00004594 ADC12_ISR +0000462c port1_isr_handler +00004682 Timer0_A1_ISR +000046c0 _c_int00_noargs_mpu +000046e0 _Z7WDT_ISRv +000046f0 __TI_ISR_TRAP +0000a501 mpu_ctl0_value +0000c4e8 _ZTVN4iris17RoverStateServiceE +0000c5d0 _ZTVN4iris19RoverStateKeepAliveE +0000c6b8 _ZTVN4iris25RoverStateEnteringServiceE +0000c7a0 _ZTVN4iris27RoverStateEnteringKeepAliveE +0000c888 _ZTVN4iris14RoverStateBaseE +0000c96c _ZTVN4iris14RoverStateInitE +0000ca50 _ZTVN4iris17RoverStateMissionE +0000cb34 _ZTVN4iris25RoverStateEnteringMissionE +0000ce4a _ZTSN10__cxxabiv120__si_class_type_infoE +0000ce70 _ZTSN4iris27RoverStateEnteringKeepAliveE +0000ce96 _ZTSN4iris25RoverStateEnteringMissionE +0000ceba _ZTSN4iris25RoverStateEnteringServiceE +0000cede _ZTSN10__cxxabiv117__class_type_infoE +0000cf00 _ZTSN4iris19RoverStateKeepAliveE +0000cf1e _ZTSN4iris17RoverStateMissionE +0000cf3a _ZTSN4iris17RoverStateServiceE +0000cf6e _ZTSN4iris14RoverStateBaseE +0000cf86 _ZTSN4iris14RoverStateInitE +0000cfda _ZTVN10__cxxabiv117__class_type_infoE +0000cfea _ZTVN10__cxxabiv120__si_class_type_infoE +0000cffa _ZTSSt9type_info +0000d008 _ZTIN10__cxxabiv117__class_type_infoE +0000d014 _ZTIN10__cxxabiv120__si_class_type_infoE +0000d020 _ZTIN4iris14RoverStateInitE +0000d02c _ZTIN4iris17RoverStateMissionE +0000d038 _ZTIN4iris17RoverStateServiceE +0000d044 _ZTIN4iris19RoverStateKeepAliveE +0000d050 _ZTIN4iris25RoverStateEnteringMissionE +0000d05c _ZTIN4iris25RoverStateEnteringServiceE +0000d068 _ZTIN4iris27RoverStateEnteringKeepAliveE +0000d074 _ZTIN4iris14RoverStateBaseE +0000d07c _ZTISt9type_info +0000d0fc __TI_Handler_Table_Base +0000d108 __TI_Handler_Table_Limit +0000d10e __TI_CINIT_Base +0000d11e __TI_CINIT_Limit +0000ffb4 __TI_int18 +0000ffb6 __TI_int19 +0000ffb8 __TI_int20 +0000ffba __TI_int21 +0000ffbc __TI_int22 +0000ffbe __TI_int23 +0000ffc0 __TI_int24 +0000ffc2 __TI_int25 +0000ffc4 __TI_int26 +0000ffc6 __TI_int27 +0000ffc8 __TI_int28 +0000ffca __TI_int29 +0000ffcc __TI_int30 +0000ffce __TI_int31 +0000ffd0 __TI_int32 +0000ffd2 __TI_int33 +0000ffd4 __TI_int34 +0000ffd6 __TI_int35 +0000ffd8 __TI_int36 +0000ffda __TI_int37 +0000ffdc __TI_int38 +0000ffde __TI_int39 +0000ffe0 __TI_int40 +0000ffe2 __TI_int41 +0000ffe4 __TI_int42 +0000ffe6 __TI_int43 +0000ffe8 __TI_int44 +0000ffea __TI_int45 +0000ffec __TI_int46 +0000ffee __TI_int47 +0000fff0 __TI_int48 +0000fff2 __TI_int49 +0000fff4 __TI_int50 +0000fff6 __TI_int51 +0000fff8 __TI_int52 +0000fffa __TI_int53 +0000fffc __TI_int54 +0000fffe _reset_vector +00010000 GroundMsgs__generateDetailedReport +00010908 _ZN4iris14RoverStateBase26doConditionalResetSpecificERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__ResponsebbbbRb +00010f0c _ZN4iris25RoverStateEnteringMission8spinOnceERNS_12RoverContextE +000113a0 _ZN4iris14RoverStateBase22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001178e _ZN4iris14RoverStateBase21initiateNextI2cActionERNS_12RoverContextE +00011ade initializeGpios +00011dcc watchdog_monitor +0001233c _ZN4iris17RoverStateMission15handleTimerTickERNS_12RoverContextE +000125b8 I2C_Sensors__getActionStatus +000127bc IpUdp__generateAndSerializeIpUdpHeadersForData +000129b6 _ZN4iris17RoverStateService15handleTimerTickERNS_12RoverContextE +00012baa I2C_Sensors__spinOnce +00012d82 WdCmdMsgs__deserializeBody +00012f50 _ZN4iris14RoverStateInit12transitionToERNS_12RoverContextE +00013112 _ZN4iris14RoverStateBase17landerMsgCallbackEPhjPv +000132ae _ZN4iris25RoverStateEnteringMission15handleTimerTickERNS_12RoverContextE +00013434 HerculesComms__tryGetMessage +000135ae LanderComms__txData +00013870 _ZN4iris14RoverStateBase26handleDownlinkFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj +000139ce watchdog_build_hercules_telem +00013b12 _ZN4iris17RoverStateManager4initEv +00013c52 _ZN4iris14RoverStateBase19enableHerculesCommsERNS_12RoverContextE +00013d90 _ZN4iris17RoverStateManager11handleEventE11Event__Type +00013eca HercMsgs__serializeHeader +00014002 _ZN4iris14RoverStateBase26sendDetailedReportToLanderERNS_12RoverContextEb +00014266 LanderComms__tryGetMessage +00014386 _ZN4iris27RoverStateEnteringKeepAlive15handleTimerTickERNS_12RoverContextE +000144a6 watchdog_init +000145c2 getResetReasonString +000146ce _ZN4iris19RoverStateKeepAlive8spinOnceERNS_12RoverContextE +000147d8 aligned_alloc +000147d8 memalign +000148e0 _ZN4iris14RoverStateBase23handleDebugFromHerculesERNS_12RoverContextEP16HercMsgs__HeaderPhj +000149e0 I2C_Sensors__writeIoExpanderPortDirectionsBlocking +00014adc LanderComms__txDataUntilSendOrTimeout +00014cd2 I2C_Sensors__writeIoExpanderBlocking +00014dc2 fputs +00014eb2 _ZN4iris17RoverStateMission8spinOnceERNS_12RoverContextE +00014f9a _ZN4iris17RoverStateService8spinOnceERNS_12RoverContextE +00015082 _ZN4iris27RoverStateEnteringKeepAlive37transitionToWaitingForIoExpanderWriteERNS_12RoverContextE +0001516a GroundMsgs__generateFullEarthHeartbeat +00015250 UART__flushTx +00015334 setvbuf +00015412 __TI_printfi_minimal +000155c8 free +00015776 _ZN4iris17RoverStateManager11spinForeverEv +00015908 _ZN4iris14RoverStateBase13heaterControlERNS_12RoverContextE +000159ca readOnChipInputs +00015a86 _ZN4iris27RoverStateEnteringKeepAlive8spinOnceERNS_12RoverContextE +00015b40 SlipEncode__encode +00015bf8 _ZN4iris14RoverStateBase12echoToLanderERNS_12RoverContextEhPKh +00015cae _ZN4iris14RoverStateBase24handleStrokeFromHerculesERNS_12RoverContextEP16HercMsgs__Header +00015d64 I2C__spinOnce +00015f78 GroundMsgs__generateFlightEarthHeartbeat +00016020 UART__transmit +000160c4 _ZN4iris14RoverStateBase19herculesMsgCallbackEP16HercMsgs__HeaderPhjPv +00016164 HOSTlseek +000161fe _ZN4iris14RoverStateBase23handleResetFromHerculesERNS_12RoverContextEP16HercMsgs__Header +00016298 CmdMsgs__deserializeHeader +00016330 _ZN4iris17RoverStateMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +000163c4 HerculesComms__resetState +00016454 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite1ERNS_12RoverContextE +000164e4 _ZN4iris14RoverStateBase18pumpMsgsFromLanderERNS_12RoverContextE +0001656e _ZN4iris14RoverStateBase18sendLanderResponseERNS_12RoverContextER19WdCmdMsgs__Response +00016680 _ZN4iris17RoverStateManager26getStateObjectForStateEnumENS_10RoverStateE +00016708 WdCmdMsgs__serializeGroundResponse +00016812 _ZN4iris17RoverStateManagerC1EPKc +00016812 _ZN4iris17RoverStateManagerC2EPKc +00016896 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite2ERNS_12RoverContextE +0001691a Serialization__deserializeAs32Bit +0001699c Serialization__serializeAs64Bit +00016a1e SlipMpsm__process +00016aa0 WdCmdMsgs__deserializeMessage +00016b22 _ZN4iris14RoverStateBase15handleWdIntEdgeEbRNS_12RoverContextE +00016ba4 _ZN4iris25RoverStateEnteringMission38transitionToWaitingForIoExpanderWrite3ERNS_12RoverContextE +00016c26 _ZN4iris13stateToStringENS_10RoverStateE +00016ca6 _ZN4iris17RoverStateManager22transitionUntilSettledENS_10RoverStateE +00016d26 __TI_wrt_ok +00016e98 _ZN4iris25RoverStateEnteringMission40transitionToWaitingForFuelGaugeOrTimeoutERNS_12RoverContextE +00016f10 DebugComms__tryPrintfToLanderNonblocking +00016f86 _ZN4iris25RoverStateEnteringMission19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +00016ffc _ZN4iris25RoverStateEnteringService19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +00017072 _ZN4iris27RoverStateEnteringKeepAlive19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +000170e8 __TI_decompress_lzss +0001715e HOSTrename +00017246 __TI_closefile +0001732c Serialization__serializeAs32Bit +0001739e HOSTopen +0001755c HOSTwrite +000175c8 HerculesMpsm__process +00017634 RingBuffer__init +000176a0 adc_init +0001770c HOSTread +0001784a blimp_latchResetHigh +000178b4 blimp_latchResetLow +0001791e fseek +000179f2 Serialization__serializeAs16Bit +00017a5a HerculesComms__uninitialize +00017ac0 HerculesMpsm__initMsg +00017bf2 UART__receive +00017d24 _ZN4iris14RoverStateBase26doGndCmdSetDebugCommsStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00017dee Serialization__deserializeAs16Bit +00017e52 __TI_doflush +00017eb6 blimp_initialize +00017f1a blimp_latchSetHigh +00017f7e blimp_latchSetLow +00018044 _ZN4iris14RoverStateBase24doGndCmdLatchSetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000180a6 _ZN4iris14RoverStateBase26doGndCmdLatchResetPulseLowERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018108 _ZN4iris17RoverStateMission14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001816a Serialization__serializeAs8Bit +000181ca HerculesComms__init +00018282 LanderComms__init +000182de Serialization__deserializeAs8Bit +00018396 blimp_latchResetOff +000183f0 close +0001844a getdevice +000184fc fflush +00018554 _ZN4iris14RoverStateBase20pumpMsgsFromHerculesERNS_12RoverContextE +000185aa blimp_latchSetOff +00018600 __TI_auto_init_nobinit_nopinit_hold_wdt +000186f8 _ZN4iris14RoverStateBase20doGndCmdSetVSAEStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001874a _ZN4iris14RoverStateBase24doGndCmdSetChargeEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001879c _ZN4iris14RoverStateBase25doGndCmdSetLatchBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000187ee _ZN4iris14RoverStateBase26doGndCmdDangForceBattStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018a20 _ZN4iris14RoverStateBase14txDownlinkDataERNS_12RoverContextEPvjb +00018a70 HOSTclose +00018abe UART__init1 +00018d7c HerculesMpsm__reset +00018dc8 _ZN4iris17RoverStateMission22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018e14 _ZN4iris17RoverStateService22performWatchdogCommandERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00018eaa UART__init0 +00018ef4 exit +00018f3e UART__checkIfSendable +00018f86 _ZN4iris19RoverStateKeepAlive12transitionToERNS_12RoverContextE +00019016 HOSTunlink +0001905c HerculesComms__txDownlinkData +000190a2 HerculesComms__txUplinkMsg +000190e8 DebugComms__tryStringBufferToLanderNonblocking +0001912c IpUdp__identifyDataInUdpPacket +00019170 sprintf +000191b4 _ZN4iris14RoverStateBase22doGndCmdSetBattEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +000191f6 _ZN4iris14RoverStateBase27doGndCmdSetChargeRegEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019238 clockInit +0001927a EventQueue__get +000192ba HerculesComms__txResponseMsg +000192fa I2C__write +000195ba I2C__read +000195f8 UART__checkRxRbErrors +00019636 _ZN4iris14RoverStateBase33handleRadioPowerCycleRadioCommandERNS_12RoverContextE +00019674 _ZN4iris14RoverStateBase36handleRadioPowerCycleHerculesCommandERNS_12RoverContextE +000196b2 enableHeater +000196f0 __mspabi_slll_15 +000196f4 __mspabi_slll_14 +000196f8 __mspabi_slll_13 +000196fc __mspabi_slll_12 +00019700 __mspabi_slll_11 +00019704 __mspabi_slll_10 +00019708 __mspabi_slll_9 +0001970c __mspabi_slll_8 +00019710 __mspabi_slll_7 +00019714 __mspabi_slll_6 +00019718 __mspabi_slll_5 +0001971c __mspabi_slll_4 +00019720 __mspabi_slll_3 +00019724 __mspabi_slll_2 +00019728 __mspabi_slll_1 +0001972e lseek +0001976c EventQueue__initialize +000197a8 RingBuffer__get +000197a8 RingBuffer__getOverwrite +000197e4 RingBuffer__peekAt +00019820 RingBuffer__put +0001985c _ZN4iris14RoverStateBase26doGndCmdSetHeaterDutyCycleERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019898 write +000198d4 RingBuffer__putOverwrite +0001990e _ZN4iris17RoverStateService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019948 _ZN4iris25RoverStateEnteringService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019982 __mspabi_srlll +000199bc vsprintf +00019a9e UART__uninit0 +00019ad6 _ZN4iris27RoverStateEnteringKeepAlive25transitionToFinishUpSetupERNS_12RoverContextE +00019b0e UART__checkRxZerosMaxCountSinceLastCheck +00019b7a _ZN4iris14RoverStateBase12doGndCmdEchoERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019bb0 _ZN4iris17RoverStateMission12transitionToERNS_12RoverContextE +00019be6 __TI_cleanup +00019c1c __TI_writemsg +00019c4e C$$IO$$ +00019c86 adcCheckVoltageLevels +00019cba blimp_latchBattUpdate +00019cee blimp_normalBoot +00019d22 I2C_Sensors__initiateWriteIoExpander +00019d54 I2C__getTransactionStatus +00019d86 _ZN4iris19RoverStateKeepAlive15handleTimerTickERNS_12RoverContextE +00019db8 _ZN4iris27RoverStateEnteringKeepAlive18handleHerculesDataERNS_12RoverContextE +00019dea __TI_readmsg +00019e1c blimp_bstat_dangerous_forceHigh +00019e4e blimp_bstat_dangerous_forceLow +00019e80 blimp_bstat_safe_restoreInput +00019eb2 blimp_vSysAllEnOff +00019ee4 strncpy +00019f16 DebugComms__flush +00019f76 _ZN4iris14RoverStateBase25handleRadioGotWifiCommandERNS_12RoverContextE +00019fa6 _ZN4iris17RoverStateMission24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +00019fd6 _ZN4iris17RoverStateService26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a006 blimp_bstat +0001a036 remove +0001a036 unlink +0001a066 HerculesComms__flushTx +0001a0c2 I2C_Sensors__initiateIoExpanderInitialization +0001a0f0 I2C__init +0001a11e LanderComms__flushTx +0001a14c _ZN4iris14RoverStateBase24doGndCmdClearResetMemoryERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a17a _ZN4iris14RoverStateInitC1ENS_10RoverStateEPKc +0001a17a _ZN4iris14RoverStateInitC2ENS_10RoverStateEPKc +0001a1a8 blimp_chargerEnOff +0001a1d6 blimp_latchResetPulseLow +0001a204 blimp_latchSetPulseLow +0001a232 blimp_vSysAllEnForceLow +0001a260 blimp_vSysAllEnOn +0001a28e finddevice +0001a2bc main +0001a2ea I2C_Sensors__getIoExpanderPortDirections +0001a342 _ZN4iris14RoverStateBase32doGndCmdSetHeaterDutyCyclePeriodERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a36e _ZN4iris17RoverStateMissionC1Ev +0001a36e _ZN4iris17RoverStateMissionC2Ev +0001a39a _ZN4iris25RoverStateEnteringMission29transitionToWaitingForI2cDoneERNS_12RoverContextE +0001a3c6 __mpu_init +0001a448 _ZN4iris14RoverStateBase28doGndCmdSetAutoHeaterOnValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a472 _ZN4iris14RoverStateBase29doGndCmdSetAutoHeaterOffValueERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a49c _ZN4iris27RoverStateEnteringKeepAlive12transitionToERNS_12RoverContextE +0001a4c6 blimp_chargerEnForceHigh +0001a4f0 blimp_chargerEnOn +0001a544 SlipMpsm__initMsg +0001a56c _ZN4iris14RoverStateBase21doGndCmdResetSpecificERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a594 _ZN4iris14RoverStateBase22handleUplinkFromLanderERNS_12RoverContextEPhj +0001a5bc EventQueue__put +0001a67a _ZN4iris17RoverStateMission13heaterControlERNS_12RoverContextE +0001a6a0 setHerculesReset +0001a6c6 I2C_Sensors__initiateGaugeReadings +0001a6ea I2C_Sensors__initiateReadControl +0001a70e _ZN4iris25RoverStateEnteringMissionC1Ev +0001a70e _ZN4iris25RoverStateEnteringMissionC2Ev +0001a732 _ZN4iris25RoverStateEnteringService24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a756 _ZN4iris25RoverStateEnteringServiceC1ENS_10RoverStateE +0001a756 _ZN4iris25RoverStateEnteringServiceC2ENS_10RoverStateE +0001a77a _ZN4iris25RoverStateEnteringServiceC1Ev +0001a77a _ZN4iris25RoverStateEnteringServiceC2Ev +0001a79e _ZN4iris27RoverStateEnteringKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a7c2 _ZN4iris27RoverStateEnteringKeepAliveC1ENS_10RoverStateE +0001a7c2 _ZN4iris27RoverStateEnteringKeepAliveC2ENS_10RoverStateE +0001a7e6 _ZN4iris27RoverStateEnteringKeepAliveC1Ev +0001a7e6 _ZN4iris27RoverStateEnteringKeepAliveC2Ev +0001a80a __TI_zero_init +0001a82e disableHeater +0001a852 disableUart0Pins +0001a876 I2C_Sensors__initiateReadIoExpander +0001a898 I2C_Sensors__initiateWriteLowPower +0001a8ba I2C__stop +0001a8dc _ZN4iris14RoverStateBase29doGndCmdRequestDetailedReportERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001a8fe _ZN4iris17RoverStateServiceC1Ev +0001a8fe _ZN4iris17RoverStateServiceC2Ev +0001a920 _ZN4iris19RoverStateKeepAliveC1Ev +0001a920 _ZN4iris19RoverStateKeepAliveC2Ev +0001a942 _ZN4iris25RoverStateEnteringMission41transitionToWatitingForWifiReadyOrTimeoutERNS_12RoverContextE +0001a964 I2C_Sensors__initiateFuelGaugeInitialization +0001a984 _ZN4iris14RoverStateBase21handleWdIntRisingEdgeERNS_12RoverContextE +0001a9a4 _ZN4iris14RoverStateBase22handleWdIntFallingEdgeERNS_12RoverContextE +0001a9c4 _ZN4iris14RoverStateBaseC1ENS_10RoverStateE +0001a9c4 _ZN4iris14RoverStateBaseC2ENS_10RoverStateE +0001aa24 I2C_Sensors__clearLastAction +0001aa42 I2C_Sensors__writeIoExpanderCurrentValuesBlocking +0001aa60 RingBuffer__full +0001aa7e _ZN4iris14RoverStateBase14doGndCmdDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001aa9c _ZN4iris14RoverStateBase16handleLanderDataERNS_12RoverContextE +0001aaba _ZN4iris14RoverStateBase18handleHerculesDataERNS_12RoverContextE +0001aad8 _ZN4iris14RoverStateBase21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001aaf6 _ZN4iris14RoverStateBase22doGndCmdEnterSleepModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab14 _ZN4iris14RoverStateBase24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab32 _ZN4iris14RoverStateBase26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab50 _ZN4iris14RoverStateBase26doGndCmdSetBattCtrlEnStateERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ab6e _ZN4iris14RoverStateInit14handleHighTempERNS_12RoverContextE +0001ab8c _ZN4iris14RoverStateInit15handleTimerTickERNS_12RoverContextE +0001abaa _ZN4iris14RoverStateInit16handleLanderDataERNS_12RoverContextE +0001abc8 _ZN4iris14RoverStateInit16handlePowerIssueERNS_12RoverContextE +0001abe6 _ZN4iris14RoverStateInit18handleHerculesDataERNS_12RoverContextE +0001ac04 _ZN4iris14RoverStateInit19performResetCommandERNS_12RoverContextE26WdCmdMsgs__ResetSpecificIdP19WdCmdMsgs__Response +0001ac22 _ZN4iris14RoverStateInit8spinOnceERNS_12RoverContextE +0001ac40 _ZN4iris19RoverStateKeepAlive18handleHerculesDataERNS_12RoverContextE +0001ac5e _ZN4iris25RoverStateEnteringMission12transitionToERNS_12RoverContextE +0001ac7c _ZN4iris25RoverStateEnteringService12transitionToERNS_12RoverContextE +0001ac9a blimp_battEnOff +0001acb8 blimp_latchBattOff +0001acd6 blimp_regEnOff +0001acf4 enableUart1Pins +0001ad12 memccpy +0001ad30 releaseHerculesReset +0001ad4e _ZN4iris14RoverStateBase22doGndCmdSwitchConnModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001ad6a strchr +0001ad86 strcmp +0001ada2 HerculesComms__isInitialized +0001adbc UART__isInitialized +0001add6 WdIntMpsm__processEdge +0001adf0 _ZN4iris17RoverStateMission20canEnterLowPowerModeERNS_12RoverContextE +0001ae0a _ZN4iris17RoverStateService12transitionToERNS_12RoverContextE +0001ae24 _ZN4iris17RoverStateService20canEnterLowPowerModeERNS_12RoverContextE +0001ae3e _ZN4iris19RoverStateKeepAlive20canEnterLowPowerModeERNS_12RoverContextE +0001ae58 _ZN4iris25RoverStateEnteringService18handleHerculesDataERNS_12RoverContextE +0001ae72 _abort_msg +0001ae8c blimp_battEnOn +0001aea6 blimp_latchBattOn +0001aec0 enableUart0Pins +0001aeda RingBuffer__empty +0001aef2 RingBuffer__freeCount +0001af0a _ZN4iris17RoverStateService21doGndCmdPrepForDeployERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001af22 _ZN4iris19RoverStateKeepAlive24doGndCmdEnterServiceModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001af3a _ZN4iris19RoverStateKeepAlive26doGndCmdEnterKeepAliveModeERNS_12RoverContextERK18WdCmdMsgs__MessageR19WdCmdMsgs__ResponseS7_Rb +0001af52 blimp_regEnOn +0001af6a powerOffRadio +0001af82 __mspabi_mpyi_f5hw +0001af9a setFPGAReset +0001afb2 I2C_Sensors__initiateWriteIoExpanderCurrentValues +0001afc8 _ZN10__cxxabiv120__si_class_type_infoD0Ev +0001afde _ZN4iris14RoverStateBase14handleHighTempERNS_12RoverContextE +0001aff4 _ZN4iris14RoverStateBase28handleRadioExitStasisCommandERNS_12RoverContextE +0001b00a _ZN4iris17RoverStateMission16handlePowerIssueERNS_12RoverContextE +0001b020 _ZN4iris17RoverStateService16handlePowerIssueERNS_12RoverContextE +0001b036 _ZN4iris19RoverStateKeepAlive16handlePowerIssueERNS_12RoverContextE +0001b04c _ZN4iris25RoverStateEnteringMission16handlePowerIssueERNS_12RoverContextE +0001b062 _ZN4iris25RoverStateEnteringService16handlePowerIssueERNS_12RoverContextE +0001b078 _ZN4iris27RoverStateEnteringKeepAlive16handlePowerIssueERNS_12RoverContextE +0001b08e _ZN4iris27RoverStateEnteringKeepAlive22handleUplinkFromLanderERNS_12RoverContextEPhj +0001b0a4 disable3V3PowerRail +0001b0ba enableWdIntFallingEdgeInterrupt +0001b0d0 enableWdIntRisingEdgeInterrupt +0001b0e6 fpgaCameraSelectLo +0001b112 memchr +0001b128 memset +0001b13e powerOnRadio +0001b154 releaseFPGAReset +0001b16a __mspabi_divu +0001b16a __mspabi_remu +0001b180 setRadioReset +0001b196 startChargingBatteries +0001b1ac unsetDeploy +0001b1c2 DebugComms__registerHerculesComms +0001b1d6 DebugComms__registerLanderComms +0001b1ea DebugComms__setEnabled +0001b1fe RingBuffer__clear +0001b212 RingBuffer__usedCount +0001b226 _ZN10__cxxabiv117__class_type_infoD0Ev +0001b23a _ZN4iris14RoverStateBase8getStateEv +0001b276 memcpy +0001b28a powerOffFpga +0001b29e powerOffHercules +0001b2b2 powerOffMotors +0001b2c6 releaseRadioReset +0001b2da I2C_Sensors__stop +0001b2ec __TI_decompress_none +0001b2fe enable3V3PowerRail +0001b310 isAdcSampleDone +0001b322 strcpy +0001b334 fpgaCameraSelectHi +0001b344 getWdIntState +0001b354 hook_sp_check +0001b364 __mspabi_srll +0001b374 powerOnFpga +0001b384 powerOnHercules +0001b394 powerOnMotors +0001b3a4 setDeploy +0001b3b4 I2C_Sensors__init +0001b3c2 _ZN10__cxxabiv117__class_type_infoD1Ev +0001b3c2 _ZN10__cxxabiv117__class_type_infoD2Ev +0001b3d0 _ZN10__cxxabiv120__si_class_type_infoD1Ev +0001b3d0 _ZN10__cxxabiv120__si_class_type_infoD2Ev +0001b3de _ZN4iris14RoverStateBase29handleRadioEnterStasisCommandERNS_12RoverContextE +0001b3ec blimp_batteryState +0001b3fa strlen +0001b408 watchdog_get_wd_int_flat_duration +0001b416 _ZN4iris14RoverStateBase20canEnterLowPowerModeERNS_12RoverContextE +0001b422 _ZN4iris14RoverStateInit20canEnterLowPowerModeERNS_12RoverContextE +0001b42e _ZN4iris25RoverStateEnteringMission20canEnterLowPowerModeERNS_12RoverContextE +0001b43a _ZN4iris25RoverStateEnteringService28nextStateAfterSetupCompletesEv +0001b446 _ZN4iris25RoverStateEnteringService8spinOnceERNS_12RoverContextE +0001b452 _ZN4iris27RoverStateEnteringKeepAlive20canEnterLowPowerModeERNS_12RoverContextE +0001b45e _ZN4iris27RoverStateEnteringKeepAlive28nextStateAfterSetupCompletesEv +0001b46a _ZdlPv +0001b474 disableBatteries +0001b47e enableBatteries +0001b488 releaseMotorsReset +0001b492 __mspabi_slli +0001b49c __mspabi_srli +0001b4a6 setMotorsReset +0001b4b0 stopChargingBatteries +0001b4ba __cxa_pure_virtual +0001b4c2 malloc +0001b4ca releaseMotor1Reset +0001b4d2 releaseMotor2Reset +0001b4da releaseMotor3Reset +0001b4e2 releaseMotor4Reset +0001b4ea setMotor1Reset +0001b4f2 setMotor2Reset +0001b4fa setMotor3Reset +0001b502 setMotor4Reset +0001b50a I2C_Sensors__clearIoExpanderPort0OutputBits +0001b510 I2C_Sensors__clearIoExpanderPort1OutputBits +0001b516 I2C_Sensors__setIoExpanderPort0OutputBits +0001b51c I2C_Sensors__setIoExpanderPort1OutputBits +0001b522 Time__getPointerToCentisecondCount +0001b528 Time__getTimeInCentiseconds +0001b52e C$$EXIT +0001b52e _ZSt17__throw_bad_allocv +0001b52e abort +0001b534 disableVSysAllPowerRail +0001b53a enableVSysAllPowerRail +0001b540 _ZdlPvj +0001b544 __abort_execution +0001b548 _system_pre_init +0001b54c _ZNSt9type_infoD1Ev +0001b54c _ZNSt9type_infoD2Ev +0001b54e _nop +0001b550 _system_post_cinit +ffffffff __TI_pprof_out_hndl +ffffffff __TI_prof_data_size +ffffffff __TI_prof_data_start +ffffffff __c_args__ + +[2033 symbols] diff --git a/Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.out b/Bins/RC7/FSW/Watchdog/Debug_with_flag/Watchdog.out new file mode 100644 index 0000000000000000000000000000000000000000..d99db7505e6af7cad714eab9f3bb145ed0617cf1 GIT binary patch literal 1337664 zcmdSC34B!5`8R%MCd*_pnTaIE5F@$ZfB_;|NLbPvvfS*1Bu#=KMTRT`35FzO0pw>T zfJLPdkg=%Ly_Nzhl8C;RT3Osk48dZ5R?&(-+mC-=+bU9D+uCa0?{n_Gv*peZDAM;2 zpL6HlbDpz5=Q+=IPSzKc73y?4rvB5jCPrUJ3K>gW7|jxIjOIz{OkhTq$d(&9go1UjBPjVyr~k!WN}xoAfN(YGlb3$(saQ@}>eoG=;Dey56Wg_nDoM zHgWqm!`~BRC^LKJWya+9NcPNIj7<|;bLXH0i)CvCW7mmtS`bP*if_?mVk>idqlEiW zl5o_?m`T`G9m96*iea%VJZV=c{f3HLq!<JGb!Pa}^ zEE~uE$IukRqU4@DrP-6t|6lc_BD#mg4$+LT*kjJbj9gpa_HiuMm?b2$#EeJsmKqt8 z-|CEd<*mVpapkGYj3LTfqY*R5<5n0=%3HJ1th}`tEy`P)F;aPJH;&UdP3@SC2Ekdc(+s(YxguE6*@}_WGcDI>bA&5B!o?os%Or$!; zNz?4x${FjcT*7J$)TRwUq~564e%2dR{G8dTxAjJ`&1MN0@_0O+Uv8z+k3UOeX^;p$ z?afH`O}0U@FDg%OYH#XDO|NQQ?P#y=tnGB<)pj_f)PnMAduob1wt)GAoweN2$ukzL z_6sw8Mq_PDL$jl*wxOxDvUQE4UAm>d*-`9hukUJhbV#i$S0cTjiYiUxl}fEGosPAg z12TFRRk)~Uq7a&HMADBG)OBOsvVuh4va*5eplx$yrGqj_NG?N_EpVIowa~6 z&Ffg+VYkn7bad1%cT}a$_K2)?dzy}prhtRvuPl=B!m0ispjZ=&!s|FHgO$an7%8Szg%MUXRWDl1{PTad!1s-l!bytDEW_ z^I97&(bnR(URRHKy>lIow%q2X)t94Y7iP&lZbsFYp}#2}Yxsuh+=5F;{Leqez-Avl z=sTvAuGvM+`Hs4-<+SH?T*5x{LWO!NRdBS_)`2I%UX|a}f!C&%JVDMFLkzeIZSNYwB(NV`s5Ch zyyn%`H#W66lD*qFt-h^|v9jFq{DLaGR55Q}wcTD_lUp;Ne&u?|jo* znL2~!RTic|d@#P1jVqY%XpZ+Ynk`+;&263StdZx`9t{O%vVcMoWx$K;^{iPlOsuW; zmgd&lhPwl^)csimp22~94C3a2EkKDVAIl4iR-R<;*itd+C0bgdNTWCbno&x93-s7ig{^SALnkpSO^UqYY`()6iC}J?ApjpGLIsKUjY%HopI4{VB8m z!}b4X`=2`dKimJ*+0=hG`GCbJAf?jA6?cAl%MM(|#jVuTSu|39cbN3fwfU`UT4?nSx_&o1?zd(I9}IYe*s@-c{SoKTNDpX5l+q z!L~Pb3iETTYEl@ZpOO4;S8Y4jZ29AWHFL?7(Vg|;26p-ka2P&qRR=-fvI)aZEX^+~ zsP@ObH>#vwlaib#x7-W0h>PsQ%<2BQm{f(sD{fleSmRjPra7s8F)J;lzP5#{OrU7x zmLGqTasb>?tVc5UL>a<*V32CV^C%2%Xq@}Z}sRO!#f`;Xq$}aySp>Tt| zjKbPxQaJc6#BV97ie{dd!n4$qkUOx`^p8R25)HPDi%Msw+lBY_@ggr z$_%PB<|5<-Vvsf0$EA}M(m^7%cnPl>E`Y39zGO06Mk;Dh@m;AD3P#Z z)z#MDTmV8`xteuB&6wN1{QUG%0lc`zrE^)>{{Ys*S;PP6`OPN}oh$Q2wk-oplV<-f z!>pyx1jX_@YqJ{_#~QDB(^RcuD*cv|HiK~A+j%3hb%mM(>WX3C zgATI+y1~|#+UE0acWE=cov7evrfiNS4V9YowhsT`V#TTostamhe-W;qLv|l-21;2w zajkpJq-D6REL=PRH$JbaqXR92^PAg~EdX4q!qjr9rlg}o+po&Cx&oAR0YZ|x<^z7LD;@1MO(5Bt5`tUv8dwewYzguiJ8rCUOT%yt6y&{=%kM(fTA`{=C?JCztgKxv zovhrkMgxM(cU|p{jwGS8wG$cv4oiB0E|Z7;Ah2c4?*e1$>e8kOe)C-vEz%et#b}lR z)lt9&dD*Rc{@XeO0?Q~cZ~Cmx_S%*XzP@W(7u4c~`=yk$7OZXKjKqTWrcOtyCPKRL zQSh<^j8E)rbSUni(^lG{Sk8rQV6|hi7De|9JUV*je+1G~pynCP7^KbiGX`n(`K>M5 zDudCKo0{fXuI31iVun&@E8;&Vz9bm>k^L{6_Ks?FMu{QQHT$Q*A%A!CO~&2P%u9Nz z=e$6xq9Q%{Ojf}TeM<$1@JdH(m!{+E=;}!Eu0yS&u*=b0RNJ-O5x9!WI&Pd}9|b0k z5);z?^O(SGOrz-0td6#(mWq~oKWkiDtG}SCq^7`LQeiJxSjk;H6l;R^-ZaWG&aas(|0)jE^88?QY22Rz5}a<2tSYDDV;$61_9`g6xmOB zS(Ayu!;3Ztp{q?;1}qkq6B-Miu-bhs%AH??@hUHYCAYq-z1`8$N!vkdi`H(Cc)l_e zLC~|De|x;rQi%ti-{P`uD9ntorjZ(fumM_|h(o$1t>{;X-* zceeR}u|$eWTFP*xJ?H&~ja;Q0EZZ zTEW`G-EYFb%Lh!KPO_wn8q6FiMYx<&z2%7WK#n+WGrBs`W&zJ+r|#TkbY#TQ+0}+^ zy{*~N>FDs3V*=Hmc7cv6qifrR%141(m^xY$4pA6Y`yn*IlqopqNCF{=O5$7-6cAG| z%bK`%$tt)&RCKkPL@Y&wNFOyWUW|kpa6S|>)Oln~jS=)KUR}7}W5k4d49yHE=QL^$ zC~(OdkPFd&1Z)9_savMG6f(9K3V7I@zY8gQR1|LdOl`i@N8Zz9;XKABupECL`!`cf z-m{~LC! zw1Dl%@WjVL_>FWl&Tr#;qBaf|JDQtYlY|1ek2H=S?Y@2#o2hT7p0>M5VtIoBt2bkz~}dP%u07v6Z# z@ze}|eoH0r3eq^ITsgPi&7XOmYbN->Q>QU=zGH)NA=!g-?w6$R)GCke2JGzxY~n5s z&36R8O9hbT_~Ga@xtoxz2Zb*5!S%AziBRl29m>=h{%jF6=A&jPwYZ4!6N;fWBL^Ot z#ass0Za3HIVmQCk?oH3|pjRVid32_U^YpEa4(dZ03(JO^i~deKMJ831^YGUv*`DCv zhf5O+HRemUY+t61r3Ip5qchk9?iXoJ+Mz$Gzxgut$V>JZF;}DV84TQ`M)(^Fop3n3 zTpfa;)-UdzU-|CA&;C2SzPcYU5B|Oh^orZhQZ;#8P3KnPB|KbPN5xO5bt|l_KW)$@ zmZ5xVokg~5)j5%G64ZOnYnT}H=^b>m4a&ym+Kx_nN5RoP(mHBjlQ!Q)6wH&Oxlp#t zr@^UQKRlAtBGH)ZJ*g9JH4){`%=F|_(RSWYM@vU*dxzcL1PD4jhoe zpy~92Zik5h_d=Anw&XRp*58ah$veHtWqTuIL?!Ou02X5-jw)1n%7%IiA41 z<5e{(^TJlIp;AG(dp^)lanJWI2Pz0z4KHg?d}_f}Keg>;Sg?w!-a9X!r4kpK5^Cf( zwc}g>D(i3|wFi9-tS?af6^PC3NQSl84kspBSkoXE@Q!JmBl9K*>WL0bn&L+@?@Lqy zDdshrrjp#5be?3iTBDK*IzYkg>Yy=XbKyrOyhoQ3h??+~>mFsF8Sh1b7$JA@CjppWaEby@%i7<3=!Vr0;BP^DaXjN1~!0!|0WZ z=#x9mHHg|{SXGdl@3{?K2)6m=y|^KqnM%4U&oQJ9s6*)0Gqv{|i`0`GJ~-qB;~oaD z(e^*4Dw)=X;8t!LdhBmF<*wN_mo>b^d%GM7?HvQ!Eq_QZ&|TV8t};S3Y`ttv)C_ftTNbXI)DAe`Nnq z>%M%JBCVdgj#_;Oml_3_k^jIRri}Lm*cdg&>)+Ue)cOAR_8_$vmvawN>eSeSF6j;d zPxcGnA-s1it^Ll|w_Xb-(4MHFMf1Dekm5}Br5~MNmB-k+B;L#6r!lf#+N%Pr*bAn| z9w${ga9J=Z>l{VxIN|{1oP7H)w3_aFf*W88Q=qsfwtBE7ueIS8KX6_oD*&8)Q5y&F zQI+(e&RpRI0G=g7@8pxp zEg~zMI+dIBd{ft|5jfK7sUZz4DS7FF8)N0ZE%&^WQ}+JH8G&_<_SOzJ z3JHl#9sGLE$)?fa+q|}pm3Dhuduu%|`}BirUblf>P`QNt7|YR>>t!|Zof^;1kHq(; z4wstJ(J*3MsTIDXxvaUXqp@Z!W2B|6XptJ5+DclWeS|*Ly=05pnp!*j&a1K>8rpGw zuDv6hBQdT){ z?X(PGP3_GNIu)XnQ|*9htf})BVRch0%yndcQd6YrVydG0hU#L)MLnUPER*jo^SRjx*F0g$ zy4pIKXS&C&O>O`=|9rTRrdBq!bSUujox;Bx`0dgTUV%H866?;!JYwXGtey<|L?zsk z%51kIfs3j1*7s;ZTt1DDX6=_z=c85sD0CnswoDV`86c%?9j?)z20~MiGPNwP3ma45 z8MshAiDoNDr{i$RteRzv_LPhUM>BpxfRimQTnl()W|SvdT!ne~y{38jYHIcE0-Rq1 zj?sA}`%7cT@ap0ywYT$XTj1%@j@3*q%&tCo+Tdh}v>Dil`Hoysw*vb~VXORyn+kAQ z?#MseL_SmXjqpTL&&YL{<#>+1ZJk^fl_Paa{*MtBOkvU^8J7 z;T~H7`j}1}4UVsQa5AIf^m*q--lMLJE!XK4e1GKqk&aa~p8jr+)W{(-`D!*_7XSRM zP}uzpIPnG;g;eF*LH<{D3Q}<|3HD&Sz2=rSa9kzc#~yK?ylQWf?<$meB6Yzw;o6mY zOnip`#(6pTJ#rW2T#2V1Qps7{BFrxbPmr(hRh_7CGzA6j3po-2SK%Jr?me@C{UyD1 zp0aZ_$0Yn|DTtyC2xMcUJ4I0cOfY!%lIp6!H@GM&7O$OC>qZqfT!8bL8aK%(`OZUY z)R_-Z^XSia`ftVMJe}je6{FaNM=>53xYGt0*-;+=7)`4#ht)7ZU%qqx4%X|HZT8jG zw{+w-<1aZ?v@qY8W%xsyK5rtXjJ4^w=&}pp?~4e?rZp1s%1^ppk6_pD(vSPFMTK&p0V5 zN?Ti0$QBZInmzM26W#Y|Gu@i2=HR_UKYYdnF{-xE3zGM5M1CIYQv#3EEQ61?+M9Z6 zAH09%p7O6W^$UMzkX%Q(L@%eibqb!lFgaVRY690^FLCJ;2u%WO6qLHTn<~wWt8How z#~ROG^Et57JdxV66B`KEdZ@EPeX=*;?_WWy)YV~MrXpRSbY8sN5}H*<`z_Td1$(M& z;ZyW(B(2lIB}a90Q(FP#`UXb>|7#mwP(FG~ue1(V#@v<$&I`E}oZkA`(Pjf@<^_st zyGbqQ=2}O^CCMttX6`xa(uS5)+UMt2j^vG++Gue6@kV}f$^4O;)t5igs$b!V($dKT zR-=y>slAl{u#Kv{^e)#^LB|5jhmSJRyLGfoyklH?I#nSkD=Z0+l(gQlKxv0t(JZ>knupxri}+aHLHj)6BjUn$Mqfrjqb{4Lxh#`A5W4GUYQ`M06m94-IFt8qTr%7qm449yiT3a=-u(=javg%hw8)=AT7w8K0 z9yXVTceIq_Jm=`Y%TxGjN2b-QsKIZURHONM8Aj*dB)U;h0w2)S;i$(wlO3#)50ZN< z?2viwYZ{QH)4mMbvAvQ5-vLA9h*lYUdQFJ;k1zN&*a% zk9DD?vLce7V8r5P^Q)y27Yu(-@qm|&Y^h3a`71^FQnxDguP8uG?SLUbt;x$Eq1Mj- zd@i;|H=YER)_g1sbOa5!>Xza7Q4pbKp-`2_R@cG>0&4ORXWiuF5xJ^(E_Yc(Q3W|t z?JsFzONb)7+wU3+(#ZOxsUxG3><+#v9sKEK+mVY?z#uWVw%*LIyYfIbl0rEECDh#l zQ5$xrT>5JjGCg0ri0oeTYS(f!t!~0aVRR%$B4V%3hyqzvS3u%yhiCqhWn{YJ!{z?d zi2Tpq$%Yu2x~bRm!YEUx9tUGS@RhLJbS~3|EXbQ* zPeX1)1Ge-IITb``SyTH;IfDY@nVW7ct*!=->YL!AUr==$AkkqwyQ$N zOh~H|@x4XICfuxJTd&eF}~6FSz8u=su*%lny*{e82JeTDS5AJH+(13LEE9XeKu@YOv! zb`YWRNwg8)`Q19U8=>qm9b5NP9eaNd^8P@_^f@{%UgF5sQ z*n)n}QTmzlly^TjKZLw!|4^ZhZQiEc&qt%s-nR4i^BweIH2us(8z&%Ks(vm}`neeW ztirq2d~TL>tPcGwMEb251FiX_evW27N88V0%w^gyE?qy>`E2y)=L?uWPrRjmu0=mL zFTywg$Ncs4QqJeY=wmc+^it1fC;Azq%;zECmS;Z?A>K3i>nFk7i!~T%eU5fM)6mCD z*-u)V0{S=sZQO^lKSpRlP-##P-j5?p0KQfx`=84or2oI%$0YReENCCCOW%1EuLXSs zzV?;t*a6Tq-+5fO8)I;{j-}L(u8+nI=cltYkGnx1FBQJhJXWHQ)BND-{xr~R^wDh9 zu_Xa$&*s+A^>H*b_EO_2o$6(*pd5c1ldeLVTToDG&n?5BoMaxa?)2({svAnA0>;!A zS5EvT&T9P8O2*U|R|@{3V|7V2Q+}8@zkF_a#e(uVZd=Oq4iYSDT4g>@!^$T68AG=K z&%Wi37PymiItuZZaQU@X&HS{#V=|*$1u}3d+vWKzjcj2yh;4^BdZ5TR{Wy zz{_qSUaX`AQI+^3Ay8?srZ$gZa@x&X;}Tl!FQs!b*SN_B?jh01D-4sb@YG|tUl z-zRGi+`hUxnddh#JhHbn=84Q>3LMxUuWv4Qu%?dOhWhGSx*n4*<0i>W79Z)2bK*D1 z2ky&YXKKdHtoc%E8keqO2N@fOkcKb^p%P&s!U}|TgpCMW5Xw_i!0@kKTU*z(IyDXN z9ZmLn+*Q$GCnFjvTh>~@j+Cc2wKsJHyvqz&q(EudRFrc~0bvvy6v245DRm~==i4B; zrc^DvyQ>b*^C7az#;s&>t*Q`{j9O4E-(c0;Rv6@g%Mlu$0ua>FF6W zX3m;jTUQS=He(anP%vYI2p=GvMtC3LGlV}Qe2efk!oLvcpAl5*7`VepeKKbljqf+{ zeH`3ab?0o?#4vX5BuX4&>{dX~dnw*2H@$C0puL&i$9cSG;+=Rfif0JKr_lROsr#-eC#W6>)E7VJaSCecQWDX=YIE^Zr8Zs z+d9T%gk?=mm{R^67&QH>hb@MzF~et>3Hj4&-md+r0&63t9e$9=VScmPYroNY-yXZh1Z8HFKsek@c|16TMM2&%SL4 zvHi{vWP8V;x4mmH2%-crAgniP;KqOC{5M+l1)df*sCx>}6Q*fWZ`6tnW@k{kn4=pe z$a3k01CcC<>1<0Rdx?(OUtaRp@-zL|b1RS{@D#hW1Su^q+y7c&ulS(9LQc!^Ogm=( zYi_J(YPUz~ZAi`YN@Y5#(Jsx&`J65J2WtJR?4f$f>lJAoejG=85LZ%0|xCyTul!XM;wXO&M||48`y13u0FYFW?z0{NwDun1Ric zt`M_x{>AM7FfjXD{S^jwlVo(owDOphQi5dvdk~}6E-5jvmScno21f6<9ZM(vUk88b`fU!}^IRVh6|qBI&2vx33rZt=w6C3(M@e$ryEK34IY z>HX!wY%uI87R)|1Xkq)b;%kcajM^H)PL?yaHS#1d{p377yF2paJcBy=MjF+m4$oTl z0iVYehp=mkjXb|eGyl8ACcfGtq&a!LQHi}YQz7hxj>>zm$+NsUIl;{0G|xJrJ87w~ zR789p@o5F)^^eWYgrQU0gZ!|4bH>3M{J86#JF#e%qZk2~X)RH7V|s#1<<#$u03MvNMbhBY!9BS5%nkv4o_WE;+y zTq9u*QDfrK$Hn0ydJ+K)Fy6P}eL()+gfiqFP&@5En#I*ZHI6WyR)>+(3&L6hr|yodaYbgIdArgzZ&$KwiY!Qti2Nb?L3nf}YjNR` z<;%3}mx8IiL{#h+*r`W^>9xJ4B3vYu(m_ zznPheZ5Ggv?6XHgW!#fX$VM*uru8NF!_50ZYh3P!E-RrplF##1Y=~pe5O6u6cnpsl z>lGKxxCF1baXfCkSDe7(uJwqc6&>lKF78(D7b#_oM#^J6C0Zlp zUY-)Gk#Yx5iPK0~$5X~>q^#sAf=0?xk=EWsb|Qr6(CR+=x(;7|F}S}cxOa@do3bem%?t$O=b&or?CaO*Rw^rNvwyJuOz+IWb|=R)jkzW_O#|hKY;C?Cv4f zikK$ESXeEdSFlC4O3@xdRJuF1vSMr4D;8*i5n{|b)`Q<>giphviNWtQgkyM*!EXq{ zR}s+OAiRz68p1B5?ZV^KVA7 zI=nR~d9>kgJE+3%KIMj9pjkRWKK~{YmZDTQ?2S&NPfLcgdZV7|m7%+t8~U$Vi<}{V z{e0qcIn?4m0WR}78BXwkJEOq8r@;LVaOuyXW}|?b(S}p*GW!+SR~6W!fL;1{Z`8Ma z1i2gIptkj(0(n4zd|?hv32<*e)f=_vvEHa%Pl@=Vx1RmIQB}`m0A@a5Qt>;?Ze`c=Jh!smsJ@-o@icm$ zwr4zYb-Hlkc?Bn8vfh4q0v~(Atli4&hiAS0mOFN*63en)le&0W^31Ys_Z*xP-{xt3 zJC(E?ciJCCB`(q(cUtU?I>1{)BkGPHLi|nz!&s0z{utuZ`3eBM-W~ru;y*s1l&^Eg z?<05x19O-={$a#F!Qpp%;F=S$eSIi7$9pF3K>Y55@?3tX6WDru>z|Xq8NS!x`)eh= zn+dEH-{+L?9DFaw_ovFYfNwj#w@^Ki-t|-?e%CWfxq6PZdT)q4K&((9blz#{NbBYp zxBC?36@0MHhV+L~Yot$nEaD&CE!P@}*6mj4i@H*b;!dBK($Yoxq9W7Z7U_$NO@Cjc zFDWtogT;Q4^Cq-k_kdytv3m-Fz&&p$H3Cl}TOR}EZ@?aqi9Nu^1|s^+J#4~iqV)+S z;F_FgLA84j5)po3OW4$gptp7FwnS}^#<8Q)wb)snX4i5_0(-q~Ki+$zUYK~?+`B!5 zjbjsSRQpq{41C@fIq|JQtT!i3XXIZEt4;U{0dG%fJ*y+p!f`B`x2rcQ<`KDsAX^W+ z7cFYvAM5;lqS1LJFY(J3&k|=SB~Dm_{YJ8|4d894cX9~^;n3OPGXi34`v#;+W(~`> zrbD7RVXBCt_eAAg%!y<~!xEp1zstg2Hy2C&&PWz6Q0vmyFtqiRFti`#zAHttncH6t z3r(c7a!Nz<SLcg@y9=HM-)8o%c@cjXK@8MXF*{JJkyezqv=L$;`yBG*(5^=y;$$|yBPc;p>=u-^(BzW{GhWClq&kGado!8sUnrm>KZ~bM;8q`>I zRA-p0&QP(3?c%*7yvyu+43ualXwo9kBqMvx`nu&+&?VB(&C=Pxi=L_@`ZORh_EioX z5!g=1gL+6$#E^GS<*NO54ai~z zG8d48F32_w$mt4X5+IklAR9Fx$0?9kc|kU4K!z!hdU1CitqFOx8`*q?1Bqe%5j||i zjkLb+a#pbiCR(NJ9Xqd&%iEY?vS;ovBxY{R-0@9vyhMBGj)TX|cfC*rAtIqVd&gg< zZp=Dq%H9!^250RkVa|08C7Wy zQQH<%+wMnc_w&(oYLqrOs?t_d+jwcKP+G%YYFo2LX|Io}vy6boqdl$Ur z#?p-$kFglOdz!F&j$s4f=a1~6^>o@$GjXY@CF7hFq(3I<5ljeX{i(N12xk39`2C1} zj|J(^QGhgJ;!m^w+}SfsuRnD5+hN8I{Z-G-y_v%h3+dU6GJ+8d2;m43`efFU@yN?T z?4!3L^dFrHMtKH=a0EH+@Y!!r%3+j3kSD>_o&(gma|T{lIDg8J&!7~lDFXGcXMn*o zRDVvgp`Hl{QxKBS_9+NSX!{fd{GP(^sU-b5{GOxVv!AmGyj6$K{!^)$`lH7E%@udp z75BL-ZoMn+j2b6RM7`G{OhvdJbx%dO9(7Me!0##ip1K}&Pes5l>YvD;*Wr1Fzn@|B zewe=>=I`tI`+B_hK}TRSY?LM-OhHI8?09*CfyV0a*~3a39(Tp8S7VN;FvH)x zpB(30IfliwV+L3flMm@_yZ*pfc3$!!s|~cM@6bn#y#rqOmslww?5?+r2qpwr{s3dN zWkb!8d?-jbbPAR*z-B|rO+FN*#9M{lsFbGuiG|y-}~!512vC`L6J_7p_fFwG)SBDVgv$ z?=Yx&seAtiHOH<{c9^I+&4WQi8&SMLN;_qcNLL@@($x#l)4T?{{?v*}+O|Jl;c;_i=a+FHz+!Uqs~|s##h!cz~7S_g9T3G<*p%qlr_v!YWT`;4HNG7 ztl`js5Vnwwv5BT))cE+*Wll5SO=g`ZtT$P!UC1n-Iv@Ztdw&X)HTwdIlr3 z$_lE3F(Pd+?7Qgg1a?yQ3>%9+4_| z7{?Mh?hROub4_*nHp0AjVWktLFU5^ceR{BP7e++P`Fi-z;sbel%t8X537fLFhq5t{ z49V8`^~AdCbSw$sUz1?-L+C+Rgb0!( z>5zCjPe2`J={dxGJKV=po*`PFGu=5%qq0*?xxiXMzI&!7*T+?{2sUrO6Ff-R7cMx)iQ0^VZ#O#em z+ts2xPu~p3B4-TeZU&8avoYy&_ztnUPu}^CIpfm}*onR!4npaAUM}GP@p~cg-6KqR z&3qMhgC5qR`0nX#^6Y&q&fXr+3`vyxL$Tkq7kbsNa|*EN25@TQq%pfP9$qsQ73IZS zBj;4Ic9Ruy@mp#8;+-5GfjC#B?Xw?~TggKfyOA29A*=m%mv`}l_GNwk0QTpcVA zy;0`-h9X+$n$Oth>Y3$?`7Qfg14fbFPMY_j7mG_(xSLDO@BN@u&m!J4zx9Js1N(6# zy=^FGY(trzZI}n&lrZveXr8xZp6uOZc^|Y4ywvd}J&}89etBQ}(O2St;30&WkMr1h zZhy$%&NBv-F$NS#-WTB2f}Mx6PcV9?_PCXj!aqoois2Q;ndbekW(w;pd+N17-Z}avz zdtSnN*WP>JD+eyq^oZ8}@shHC$S}8Yn2~$HQR%AlQ2eXVf1>zTT_TDzaOH{5W#%+6)8gZ#3^+I`ae#6Ckb992zMehBjh8*BQOM+wi6Z8 z+e)M-P{!&t{pLr-63}Ovf?GI+lhf}-de49Lo44clP&@3TfZGB%qT8Nu-AJDVxLfgS z>FhVJ1>9=D5tUZ!YC+nEsA~n%8j(h{SWR1sw2#*Jn-?Q(5z>h6Mxz~`b(8~U>DGQT zX`?1>>^B$U_lev4&3VX^gFHd7frK&AgwlTZX;RhoIN^wphmeVohA;(T0zw?Z7=#k( zT9mSTbH6zOzuWKZH(!n4zdQQPSK+q?@lp6qxvSr7#qWnm56ABlEBno%_|3t$0k!K8 zXkKoFpN#3j^kmb6VM)Z}=(iEKs|UABtAo}u&1+_KKP2|!5u~N+euCy!_PC~9<83jM zTXQmD&1tk{!kY6vTim8>1j#mKQxRfzvr>GOBUIUbEoQ=+vk0+C>?S-T*;2$eARzC? zOh`aaB`u=SDE<5OuT0aiHxb@P_yplg1eOdMgAj{gLr6g=Mi3DOjVD5fpsU{V;~sc} z$?uu>Zg#&ryIt>Z-bKD-GR(qTJ6-Qz-`nDPKXh-S>pk-)b*}eyKUwU0f9cj6T<>2y zD_!sFoTaY!L(Y8Hd*-G&uJ^6WXSv?j-J9lm-_eugdjGIzlIuOcM{vD=_2W3#`?R~G zUGIy2Y;nDte{6KUf7VHR^1p`3UPnFzq`^Oq*)(pU*(9I1g_!XV;?%e2Z`<*5imo?m z)()cmuxMjkU)n;F^Oc-_=5LXya`P6V%H;|bymyO2l}lxtqAV@%Lmln=spK-26&8-mN$Rg+{oq}#M$Z2lPlQ!O$rLC_XIfkY39UD3-_#8f?L5(ZXOq1m1Hy7M;1I^$jTT<^YbRQjIRqx4<%X@EVoAG+QJe4Q2Xb#@HvEQGJKnjX2Iy-}Y% zSPF=I$YeU(BB{T03(F4M$WA&LxO$nl5_7DKW-pYfI%Ar_Sf+Bqs9zp3k_q<>6JO+=rXo z<-S1W7P+OMP`-;D1rTZO*u?8pb{OYr;I@cZeD1ht+D^#9Qn{pK*un%+@rTGZ&S zX>B8FDsk5o#%s!4K|Kg_W(vepSWQ;z_pBn9+=??`-NmU3U{xi_q-IkVY`xUSZLBsmdf-$5f;=wyj@t6#3dJ;F~RH?1()&qw89eyh|*DWA1! zjqu-LUBh}cm9e|oR!9J`;AW3w#k^nYuWV82$=Wve?CosRD*MqkDqG=Xuy!HM8p-o# zw6d!_29H78L2}0mtPuFhT3+K+uJ{+~o<;tkqO?~$j`fA}LOI_I|4a;(7V$MY8$3$b z;;ry<_&5z`7@#u+-RRu_$w4&Yj09pSj-+KHQqKJse6($1&Yy=jiY6)U9wVEWG~oO= zE#B4#J=N_QS0-+dOgty)R7kI8`6-R;vR}{+dwT}-N$~TM^+_A0+cWgyj_TVp;;N~n z_om7v<|O4yOX`g}vd-)b7UY^vPPK3?*M}Zug@RVignn``^hy!5X*(3M zOee@=M1Hkl54I$SDRgWWwEx5@42F7osKqjsTX^b_Oq=v{MhheV5d2uwk-two2N_kD zZb%e!-WlF5o~qWtYHLfUv8P=kvA2iqPN6S`ohY&QT+R`E-%~mO?K17%TLGKRAz!@C zjekcD$+-Q=A=;U~RPZn8S8n`^|CJX0P5Kq#AJw0QGKY*OLwlo6tvX?*)hn9xF3Duh zwlZgkV31C2(&41RKZn!BUDX5nUbGSOD&c&R>28!kJ=liUg5z39ctX(N*ErM$4t2sf z6zU6sy&Jh(hsFUPm+eyX8AQrWl9fzhNU|D({hPS4F-PU`HR1f55m?cW(GB9iA&kcR zCz#y;518Qmkw_;UFByd5Uq4q6M;j_+x-!=Q)4AFE{Nh%){*lyz zvQZV+%M@h1K&|uMW4~{Z+w8f=zBwN_=AjXMhwrg_Pzvp_TBTHJl#+RaH>SSJOEEQ2 zDcTn4YNeFE8{GJQkV^5kVPL=SAG| zJrRN(&onnm)e1M;WgL<{F&dS+XF0rgtwF3L@)naVBQ&}gdFyKy;y|y;or2NTACX6Q z9k93#TA@8K?-s zlfFU`kCS`WfeIrVz$uJRaYpSlG%VqGf)Btm82&=1aW2k+rvYci=5cx`906U+p;M9@ zaN>z5TrQ9Iwoc|Lc&1t>Z#W{anyDJFxjwK<6j<4c>RoP*4{W0XOBkx^R${o%!0KKa zIa;6RSQg*0n(uSd!d<=c{2c40H9k|Jg@5jK;|A;V#xR+aGW8LLvDmM3m~9z51RLK9 ztV(>vH`7;8oBSoT^DkV&O=*+Xa>!fp{8BfBr}erw@%+Yo3Qv*!7SG?C-p2E<#&_6h z={>wfUiUtp>El1Z_lI~JW*_0XkNpw4x==QVb$JYB4@fWJ?G=RA5RM}Z$TjAC!hdx+ zf5u9F9^qq_ZK`8dYqr$}nq9}W+{;)+6r=`N-gY+=4yt+z*@tP0oyJcLBWuTtuo~nF zB=5v>d1v2Nx4h$x=_{4_x!0~>x=Y^C;+0zz=zR(_t*|5Z5o;0}pFy;SyUa0h?tiCzW+at6iEJT=tU_&q=oXx_fiP{hLsnSr) zBa6grltyzH&8S?O51PZ{=6SA^NS~A(R|;&MUU{awQsBSsl`_ed0)3xX%2-zlI6tox zvnwUYCnfa$2rf4fmKpi#|JI{Vk72w>Hi(PLEepSafu&i@n7^DX4Onr8`bPEDs> ziCgbNpN2JaD0Dyc7~9z6(|e;BbJIa@+4XR+yk8gJ?52ZtH*3+s=9>xsttOWR&qQ43 zPsLY_Hkeg;rv(Huk{SnR@k7>h{6g>>vi#9NA| zZ5UTgy``QW2ZW`>a_68?jUjpQ>u1f2RC|TD#P|uM0a?o_ON_UANQ|p}B*t1ujJuQF za*A7G+?`Ca%SefFz9KP-ihOqj^4;#_-l%aa;xU&=&^6UaaTvv;m@iq1Jf^><__&^| z5wH_M0wwM@=^l8J2qN?v*W|*UB{|u%vHet39xIA@Ys1h_Cj*;br^;+llf_sS1|u4OyyDqPBY1RJ8z2-X@cAqqlLE-HhhuOeH(E-3l*;C;BCs@ z=+dP`D;A><0q?dLjkKkl&)O~X6jNlrmUFc|?BHP;f3!T*RPBz+HM)J;mW$f{W~$Xo z&2j9o>IGL0`?6LYlhs};esk}*a%6~0!=f|#fR{Oj9eFv19QZCSH9USQ$Iu6UHy_WN zSdHQFxA6U@z$ljKj{xRFz#K6oz{@pZ)5eNZi2sniX4nDF=WRenvLgmhJ?62}*bG^s zB5h0$o3xk4BO&i$UH0~?Spw`HaqI?L_V#dQ!8`t*pv~$`u_bRxMMy)Kj*xC!h7-va zHUso01kdD6GZALlejsLVzm8dvZxSm+T0BcfdzGyt(-**L`-|n;EnfYWmo^4MW@qF;fU_6gMsmJrnCuO^+x{ijPp-~|} ziupDbv)$+PJT=ns@GerNE)y{W!0)sJgx{o{p|2$eyz!e(RgHm;OF2_VeibZM7$+_H zA{sZ3*zsHfT5||KrHjdn4RgJi*?G)*C8irO>bWpaZxYbc=T4dvwxr-3&)IQdiCfB2 zd{*gzvm0w`K6!{o&7khW$dG2`U- z4O47GVWHBTKg|5Y8|Ej8YKB^IvkQx@_#mR>FX1e9-tc=7;d~DX02^WTT-1+utV z=2?C`ZDVp-!pqjJ$s2oMJ0JIQSo!}p??s6TZ{3BqflK-sQL)~r+d8QP;(3C&G)Mfj ztZyJ~1Ifer^JVHWUZ9!v);6rx&=Y8D8{R=F{#Mc1SsD;}3_dSGdyY`>w? zZ;;b;PhspLB-Kv;!o=5bqBR(C@`=_bw#jQ{a2u_a5T(7JY{UKu|47+mKN7kI@>O%& z6XX(ztBT!Dy^nETZ3|H>Ut70(mKdp&_&jJBKUrDmK20|mViuX}ztW=z9!(Z={xM8? zYV}SB(uTaQ>>Jw^zC)(z&;LrUOV(wo=W&Oi%Ot!w{VR1BxWTn=c;}d|NP23Hk6byj zfW3*&nHKl3&$zyo`kvSu0-i4MxmV24u7(YPm)oE5s+nSDpm!lj=G#w(*!A1WK1+|O zj)>06Db-!G>Dy}~V)}Bz7A@Avwkm?IkW3HilI&8(_J0oRg$n0?UsnOTVvxw&OD7Hn zlNN(~6N%#r!MVX#Ew4mufCovYE``n3C9!N>BDgv|yDE1Q*24ZCS_?fa1$;!!Llsi7 zByRs^I1AKJ6w0M}QgZIGM^Z9Eg=6=oW&{ZvooN|5VTshYBRwMun)oo5o*@Y3&T!kY z|Bg>Dbn0yzi-OYM1vg0N5*JE0;by3E_ywpb*|pQGdhXU6%YUJi_yS7wJU>jk!=O*lAU9OAro=& z!~u`#ecxcRd48M9On1grM@wP|$lO~cXSnO+d+L8C3GEuwS(u>DHG&coMUDF!>EY$hqG@PuieWnRQzj6=b&i^7LHIQ@Cti!p}H zga@!`ad6LP*K(>JO7rWq%FYL zCl1hE8f5c#`=uqps~fvqFUd}%_gl2i?HSy;UZ(%DBonMq^9R?g&6>W$|t0mPOfP zbFug}Xj(!cWPbQr;+AyqH}Ft|#^_VrmUkNWB?jTCXTf+HK=V#R2Oo-OFy{AkNeH|! zPnU#3hD|P}{NWz?>7G4`i|~qrmm}h=UU9I<`J(9Hh^&;AGDS*3(;2dnoP-q8(Eo;cv$b z<2xowuvIwU#C~bvb{LCCoz#YCd{h0@PWn#4w|O(!fHxG#R*J{aGx?ORd|&1Or@Glv z@~&)K;tstn3|2SMqz5+}YfC5{!?OEAY@{uLZFxR@leS&YpCSB7oW=ldrpP{~7b)Ec zZBDF|efICe)_1m4z+Q&$P-*sdolc)P8#3kZ4AH{aYQm~x2j4e@3hT^z@*)SF%#;$u zr%)4*IW>j_i=^|Czt@>9h!0`blF!YDDb8wQL``YO=#D*?^YKp?Wtb#RUrod@(hR1t zFxC1&5hY>(|ek%03O=Af>SXHq|6;kZj-*r!b>Pnxb2*47Yj}N8MAM z0u9(i$R;h1%n?}ZyVcNDg$-E=lWze_*jjP4VhUuN4mQ?CyDt1+q2ID`3vd!fDm{0| zti*>DMTy`FHY`qISBSl+HBO|P1Sr*px`-=H;`*8trCM~hyGod$EiU$Dc@XC z=Ip&TJ~suvJ-C<^eVY>fhGh}FQHD%&x?2G~r#p<141_yj#MzM0b>i&2%S=?exLh+DLm;7 zOY&UEO%1GgKZG?Lr$Z&2zq34xxY6+$NBQKQi_vPva5ncH72=gApFNz(PU3L_cOvs(oYjU#<16c zkFP>QJvMg+Zoo(b{oL_$qMz`u!n)(P)WRZP;o$*MB5o;pLBFNokbXQdne(=uENt*dc*$=+@xqCktvm5)t2p_C**n`^l%cTyQ z@r&yiO$}N;Fj`u42`Ge1T@8?&EvYpOq^|aEJflHUAh_p9x*9ma%8u)R; z$2Duf`8?BuI`5lG@MLM~HxHByx~zSIkF_uCp*`2h7QZL54HC&2(U3FxAz`jEn^_#@ z=bqej>_5=vaQ_s@`ys2Wk&rk{EObjgmx3~|3j{Athfg?eVUln=WfA$15pDdU622AW zff7dR+X#7uWWJmq#6u@7`viS7JW;HXfHk>B_K9`u1|u7n3qE|2sKYI;;5W&)BU&&? zt3u>DiJs?U_XvLQcyh4fSk znuC+5CF1r~S6Si9WCoR>TmoYIc3vY=-Z;EZ+jA9g82c<}=NCE07OHzv-_CFzZ^TSZ z+Y`*+^#bK3`xmVfNOOCr2?jOwutzEk&+OcR z?qQuP@9?+oymSNcxdV}GygT(9k5t@6eC~kYnfgzU)F8QJkGy~LNHqpA*{_dm#$JkSchUVkpYl5BTlTn+xw@IUI2MDGn(u>?`vBDF3@nhp;}*!d;#TYd zcOaOgFe&VzIZ5Fqe=;}Dy;@qk{RmpUcKdsbsA~A4@SP!vTT1|23c4vJicHO_}-|td)7f$p-)_g{j$8Yhkcbu z()8*+_bI%J(rm0>>{qblolTq@MSI_PPP@FVgirdj;(2@0U|u()UG4i-%bOxADEgcU z3#iT7zPTxi?r4PHkVg%&Z|X82aRt{Fi5aob7KPc0!PWJl z{~<12(M?h~G(|?FK!;Qy$CG~OrV+ZKFz6I;vLFb2&koZ45R|I#GGiYa0GIHJIW~71 z8=ISgJtqlmUdqqJ9W7*RbL7!N9XpEKsqct9T4Z2HArajfc@%z1M0vu4-^03_T+TyB|jddF@+Z!Jhaqvd%0W+oRfpQIlrcJZMe<(??&8&OgD88 zl+!)=uVa^xZ@R~Q(tuI#lO|bA&IdV)=L>V?(<9$6xA%sbm@bj-$fumRsav^;TK4^t zJ-Tp`S|Vv6Gn)P~0MX?Sk5DTiqbk%b&x6+zMWd5EesKl@+=nc`J@Yd7U+x!qZom0{ zArTbt{wtFx29ikV%8K470h*pLn+yIez{4{(Mg+aO|4&mr~u8<7&mQ?jkaF8GS5|1rp8IAFzDUCZlSUd)L- zR>UUX5qZZI^roAPXR&_rosslwps$jk$#>CLNicnthD_cPxrJa$Lnq$~pWC|`n=Jbj z#y^OI4wLCT;-?Sg#4gU$@ptomIkEOU!{lu!ls(Y$en( zZ+cqnkVkGj=RLeFBb!G}Paj7q?fb`->Tycsd)6Gz%ULBllP%LuUw_D;WuA1CD7`Gt zaDL44KJZOG+dN0i+97-M%oYdCC%A9S2RQ2@`|%{p_dH|AmT!;#?1yT~1oDAFyn2tc zI}dpW9tHj2H$L$OoU z&8;H6w0sL0!4lv1Jjy4p2lsjW2Rt-y7MDljIHf(2HPjwiGj|sx_EljqxSJ3+dYEwT zLN_Lrqz*bGyDZNi@3LE22_rm^JU9#aY}NqkYTqA^o#ioj01=O_t~dGQzP^#S1zzd5 zWzb#sz<}lcYJEegb;L=X5w+fqQhoeDaN_7T@GA!RRjKQX{_0B)Tg=ar9)%9-H@Oz* z0DE&nG4M3PETJr3mJ@3pt>a?&}+fk>L zU1__U#iY|oX8i4j_13K|^XTt2Shr?xXZgWN^tTO;Ra~8}7tcvor_;^rvLvkfJMMr6 zx8_+BPGMwr8?X-IHbwEbXuL(^EfnR)ZMw>a(|N$ZDWpNc?>Kf1|E*zT@p~12&ty^j z*UYT^w~&Qnt;1XIfGSVLJR+B&uInlA9z2eFlZY42dz9MY-iuSkSvX4})1Ij)&;9p5 zWJ)n!{0;Q6{(K0>aLV)>XlcRC=}0T*n_u?DBdSNOAW51i%K%o4yx+>}ImM$DQy{~|AI6pq%X1Xw{dt| z$KR%qbr{->b&nB5CgO#?^j3(smY>mE4c@-pLudP^K=W9~y_l9E*PNUlq~PzE0OlP3 z&QZQ;op@4^$}SoQy44)gE-1zvP>ur!&rda;3_vvwpiFP7v3CU3Fh$eeBm0uh65lYN zgq4f@`KCGJY~#Se(v1p9V!70^BQYtd;u?$~-3w4!{%QD%QuCsS`faefZo}VySyJ7y z9()q*xS@JA?uNWl43TE+7?b1;IT#|t zS{2xs>KQven=0lJR}GI0(Bna;p3!-iSt9g+4^q$nIh+Q`WnG5VNn8}P-J2*@2M^UB zLUIj-j$&L3onzT3t;>K%4|cUNwjFqX3gZ_qMSDRRIFw0z9O+3?2v5@s1f3)i|M`W1 z>?Sf!KFIes;z8vTPt$O_MYysu6U8Drhef+7_R{<7%+3U1_Qnl-e>c)D%YA#@d_knR z2O6nQ4U;#;S7(RdI(@2KPLr;|2?+2V03 zJsy-Q9^(+d=^7jHj@j0C_`Y5dmB7D#t9-@suQ!#iEBM!-@@3**$CWPwRygSyR9;Bk zPYXNbHr$TYaOXjOZyDzn=tdcT`{&02R>E$S=e-hsNs_6{b|vqiCTN%8k;UbdOxXP+ z(ld8Vu$gcspC~oa=PUW!m9|MZgKmZHA`YWLZ?SkAi-PXRhO#Od8dJGPi!y`!oaY=~A?y<_CtZC25Ujfcj5% z9%!%0t^-XNBoSC%$Vy|Dt{1ZpbOY-na3^^(=(gbM4e)_)cxLZNoh?OTeYJ^83Ur_7eOZCj7N4y~Td4JWko2;T0+!bKd%YxqB1% zDvPTRc;>mwbGIxvxd|bJ5FrXeWC;l(Mhv+u5)wcX77+2(1e$ zATCwvidvQ0ifFA1n`qTqw_4x6)~yIyH)_8Bf95{Py*J4XeSP2W`+mSLbI&=mJ~L;| z%$zwhlkd*D47w^C^dJZ0x)vM`uFg+IKYdrkXJ5AQ9qf`k4NH2w@&`I?>az;g7Vd$* zbS*Shq|FSDhkZ|GFmr}WG;MXl+U04;POkQT#EHtx6580!oPj+@=>Bgj<80d+0d%il z-M|*-EV#Ydp>+!Twy@bD!*X``9%4ebgSqU65+CmM!~N@Fv*_KB$l!F<&+b62bL8Qw z1M&7U$Gw|R%O3#ww|8?U^cno^nco{YXX(9=`aS(y?UKoPuIH#JyQe=jWm;C7U2jUFOE!y|{NB5&QG2F)+Isc%PvsM*)2J%83^S4$N&*G+@XR&kmY%pTofO$yd zx}kMU?C5SOJ@2*F4biz~{O13QTyJi)a^)Q5|LR-&23C}~G4goF9f=8L*A4xv4{*S(=zy}`O$fxSeH6xxibiWXN9!VauU45&`JUJpX ziM(qy_js^^@xa>Q2HX|Xx|hT|@vT*i7ps`nII(b9p-0RtIwg-cBc#oI7W)h?NJKAI zx&vrmP_%ABd|pYAbi1O<>={_u;=XjuN?T`y12H3f8S}B$xnS>tm5?VBg0-7Y$vNO2 ze|^rl?zkOlCfa)5qvI!h;W>bLSVdXwrZ4+p+z$@e6rZC*97xb%;zMD2lnvN)v|mn< zUN63cHHo(Ff(B@;IQ^je`o!z04Vs`dN5uxTL%@n{r)yiU9>Ihes|$~4&cPg|bI$Q> zmU%DXtP%ND*XfG?yiSYO6kd;S@2Ez79oFb8SaJ0qoB3S)&xdcy>60+-pYE3v_+nfC zbsMnDo%vk^`X5WCGIg*cCtvJ|PqD7~tT5+tQ+Lf(pgO2Z5sPzs)8g$-%`#hGU!Chf$ z<(L_|^Otk?m%+!JyPv|j`xY-Kc*o`ULflcT_5Ga7Cu1&Ogd3J@n8!PDmz|z5J(gvL zpbeMlJLg*UJFlpfa_b7YZ-H0oe}BN<>_IP1HT{(+vY|max0l1)YHG30ZK>gr0DH3E6Pt5>A5~pU?+xLPB4-u7n)8?u7nuJqZKh z{yZTUt}v2ZdX}kgePMeIQ&u;SXcDc0es@jcHSBd`qkG-z!lSCS!Zoto6{AMBeL1cB z8MQA5)Lu%f_T>iLSp{}N3uVQe(Pd#@gflZs_u^JFI?68t@2=X!x(SKsZ(6^i=Z;%K zJ=)UqwC23rXB);SFeVC@ObeXFHcuk0?HdD~qg_MPLhhhsP6J=(P3%Cfw?(FV1UF_f)Ppy&xDDe9@EssKn|C z`@>sOawr+~O#OftqxASM+%@BI-{8!+x#->4cPdyPSKqJ9yXDhyF z(!bzu~l+pChEbG7dtA05__9hSJv`%H?ay%q!wLF46hCJfBnD;Pg{d8J^ z5BWSl*SaGi4YoMe?JF=>gWd(Z2_9-+Xfa3GKv|@7;mUN%)8sqa0<}uKUIlwM7v?2o zp-%Iz6(ezL2={AwzXoN~zaaGv2MhByKzHfO-hwnY;61B-p3iKU(-%=QrEl6i-mF(( zoNG+^&&S0=w^&n%Tbf%&M)p-`EO06ZXN1*kgJYwfU+B>{>3@)m7c-ikVKbVxxo}RS zb17E$&FQ;)j_hH*ap&=kmVK72u+y07>V{J6Al>B8DR6m2T=D0yu(|gpo{hYvj5Z0L zn~wFf6>t~W$kH|Tbu;Zi!!?=49lCX_ot#q&`fS!CX+}F^?SG=H4A150|6wlbOg?R# zz-u+<^J{oVMgpwY&xKgSNiXP3?4nD-47Bqn%4*`{^R=dV1NL3C?)k?Mr9_1x-Lev} zx9oUXBly35r}9we0efso6mE5|St7>m8*nC2kK8=~iL?s5r*aT`lv~OY#TMMJjho!n zo!jez)ADwLt1}>Ha#U~OXxch|?N@LueEV}!ClHfQEc823+K&4dBa+~Wn} zifb{Ky0B~!dbPixThO~Xe&|6jE&jv8yw5P*)_XS}J(C(cj@Sc=&&7F%Or-@G4lPJR z_Bq%Ue%I#BJ{uDAFL7pe{J8jQ_ra?1=9^Wh&Ca~x)TfM35(U9{wTHYa0d}hiPBC2R zPlg{k*i2tvi)_Kk9<)aMQ<}FDvS)cN&fkD}9@f6F5N;hcM4}<|Js??6>CtuQQ>ekh zK*%C!;!|p8qj1hs`os@U(6G;Qlqu(uUevOn zkFBtBC{_@2c;gN$ha1;N<}e+rW?Goi-Z=}Wr7|Gz zey?WzTX4n(_Sc28&>!DKZJz76QoN5}o;Y{|mb_0E@{L)oaiPs;__*6UH14Lh^uEl3 zV%)1desk9>j=R-u#@(-a`!MQOw=?2?-8)0|30MHD8N|AKS?bogc@K<(@uzdl`?0xe z!7NWAPIewG44nRSzg>k}jXnLE#IAn&-ZDKdniv=35$3x>xcC~%4b4LzMe)!h7{g+7 z(Pap+rtmF6?PJ=^j#kyW-2I8B2uU5&r+L`;If4s2l>)wg5kM?ekYn60r z7qjO5{UJGb?92?vIcs&-B)0Bg$+;_`*OHkn;~RD)+w9Zn7pZBFfc-#qD@W^I9CrfA z@02||pJ1w%POP1|bk>)L8d3j|@+VU6wa%oi87-x=XR~eSFk12r9fozG(y~Ca!!r)+ z9@4s&`GfI3ga?+4n5V`UWMHkxySZy&kB{5%J=>n6#N<4T^J1K~^-x|?M-R&gpAYB9 zxD$Bs1H6r;TefFx->bQ2Acqbsio>a~eb8rpwDq7=dtV7mg_P@dykm1@^Ja<_Zm!rd z&gN22saH#!eL1hw^kj zatEpHcWDijn#sG~;g{0(w`*BpTGve*^1nFS8LB(Z^r@pkO}JRz@ZHNLWh}Lp0@py( zy%hJWE%o5;Lc9}jt$cnK^~9|CygX~}`xxd`*4#H^tP8dSS~E?axVdAV;CPhv<>Bb@ zD2yLMqhjRf&^J(+mR>XitK40MjW}s~y*Peon{d6FoPCXmfAwmS`KqtL=U!Wa<9%rr z6OJF^nd>-M#q#&huA{wH?HzW=H63Tii)Ww}CqAy*i>up)Pc>+zM@Okn}ad5|@)y{Ni&Of}nWOHivy3Iw{ciV;6$qJo2UMqC&LjM_= z?=Gk)8lAsx!g%M7=c++-fX3THKfK$L!mx#e1qpQtZ*6C~tuujCSddt|<%zIk;n<>g z#al-pT7zuBIA~de6hi~@09HIC;K( z#zyX?mhhw&um^D`1J{Kf$Xv?XXf5dK!Y|wC(Jafx_Vs8SbF4Yf;b$YiG!1i}hR~ZC zNd+8hIf69gVL$jxp3K3#;nu^!hCJS_2RAfZ;A+yUyIiHSXsx@H7X9#v)?9dM&i~ca z=0~;bPb=H~cShFTPfKmx|7vP|{#R2g|6fh*?Vp?)`$Chbewy_ksk=&5x+|?4ON12! z-!S8?uAJ!}Yc>n`suoxH)H3c_#hx%7voF3A{gOH*H&pf!XG*>k-Kf?uTd)h@%zA3$ zXNj2gWpBV<+fo?%(MkgIQwMaD(CTc5ZJ<8i+EH2~Z(~WfU_HdNJ`JViiQIlLUT za-jT;HFx9c^WK)Zo3;C<*9l)l^>x&}fD18Ts;%)Og&w{!heQ!KW+{Bdu_)*Sn(QkBrhE{HO8jeq#LepBVqTpZNXX z{>1!e-NE(?uYYTQ!P}yLX|?;bbS$mGme|M&l+_}1Kaw^}{4;oh;}-r^DY zm?>!P4YqPGWm#XG>(UZ&-QLLBOHk*!JlVHEdyki9alU}}IRzlU$ov0RywC9gx9^Q% zOnoEE#ScY}P{SVyzmtP!Jvf#O+r^%%W1km_%{yGS?uv|k#iNn22R_gmo2QvGCuEAu z_3OsB+>|&WtL3J|miM*~>-Vq8*-{#bz1<;=* z<28dwt(n*N7rYdZfjdKBg^U;DGQ^@})LQTyrA2KSgTf@9UrRj9>uzo4y@rr>$_82O zQ)V3wmP6*Sy$<+zwpgScP&11HSh78m%=bt+Bm8%BTtScVka6pK{OA%16GU3=%+Ilg z+ZwW^w5+)G&TC3R51f1H(c}_w+i02bZ%Eqiu*~d%QukON*PKv__%psxYrsVL3ciT> zz7m%2teraFADJ(#HjwWRIMv5|FFaT(#I0pca0?~0ew$F;!=oz$m>&miWsJA<&st_F3B25+s=_f%xf;+f0>+%Csa z_y@c=Sy1??I^Ct`sTi}>{HO70ewQAh@%A!qYk*c4W3-W7g1Z@@>BlWB5;I?Y$8@W# z?XN5nPc%O*DGu*pUYmk@9MH7ht4DaBn)RF6d)4e-+XQI&q$P~nv4xDUR^@|odH}=gYvG-YB!Ves~ z4mFAo9Gik4J9ZW3iN6C+6o3zju^*%KU){gyIrzTzy+h9?t<(2!&u4s|qu(QD7UP{v zoR^8i+yOzltP&2pkukWEDtZCfb^+*+_~u2_#hwQ@JqN$n z-bP*Mb~X<1o7lc3*mb}f?$HwP;w(>}e2zbyOA6Nv>}Qv#Ufv|uDQ)=CBhQGQM)>$~ z^iW|mMTKG6`m5bm?l3-*eB=5@lAYTj%d$8_=4~BK4^n4}b4FXKjm19R{j599@dq}t zbbNJ@GWQ2qu2Umtq&DTvLbv5nYb^BYqU6_Wq zAq#&l?1jU1JC18^rgV81xBRg!uM@tAwq$L+u6EaVp+2*54>4-h*1DtA{C@b3b|Lmc z8RN0=7)PFIZZC%3fp`Y{(~NPWj)Abq1MX=m4{h-!vUDDiF>+PA?>e$p#aJ7PL2EJC zj2#Qbz+e2c8PzNdV$KfzRL07RN2js=cYjEp&RoQPko(vvKz`w6tcFmNp%0 z7i+!$ty+Px{R&~LingzP8~54imS)@O{)>?m(rnW&*w)nM@Qr7@lYsqIvtSFPfEqp3 z3@beR_*->&UrTsXh4)2;$6H6LU$ov20}DK~g}$c+FxuWOGK#WntB=6Q8{f_6058(>>xwwKJ`I1aGt9D|{RYux~Ueyf;`Y!y6;V7*F^Z zBMYiW=yf1;TuuDS)}HA@&vdAs>B~C`yX5Y0F<(UQWXnFU+KDp4XB>sJ_8FUkXrn`o z32dqDVzhJ9bA`@z!Hb<%PcBsD=)Bw*PYjyBRKvCi{sG` zLvpToMYv?dD~?fk@d~D07Yd!eHZt^@C_H^FLyy)aLEW*(uC@AjWdFm-bQCfP2^;C>*KI+aAvNwnubG04vl@DN6k+sj`#QD}fVhdi1JJ!pxO2`H0 zVdbuNE^#Z~D4fd!C265@&!)S4st?vrxzIOQGWN)3#%a~;n+1O^>Yj(2M2a%u>XcC< zic3m@J0RravMP!SvF9?&x$DR~&DeE0lq9ex1D(K(s9El3YE82VBluz4&2X3NHizC} z*e*S*WiPJ#g>LV23Tct3TYTEfoL6}8#}?-t#v1ASsIx%o4gjUO)l%Iavdu1^$NmnT z%iY^?$7`W|-GqBWzjxs`Ic431d+{spUN>R8V{h;djJ3Q+`#Rj>Z7(>ZNTe;Ec_1z> zp7*+)QQG~vxNTp+J#c5rliecIu=Awk8g7kIv`{Trni!!Z+LrTt zVhQeNSrt_W!_Z5tkWZe+nqbJfc0yV$HnEYR&h_BsPRw)o76RWc&|~7diTwU1v09HJ z>>Y>O?H#Z#(_eJ44!M{8NRKto9Kzsb@nTCK!hNZzqyDI)nu>$*@d@ui&-b41n_jR+ z1&4A?^gdQhOw(Fl=~J>;#o_@rGz{%PtW-9`bi<)TVtE= z$BJT{(!Pe*(C}&ecD1Xf?vdLOy5GB%o3^UeB=u&_?9yWD%XqU2=N7jq+tnsvS8X^W zxC@qe)lRn_lW;dZI2rb-BlAnpejLFjsc?D(GqZGS+p>3{m8Seey9EZ7v}+{~W0H<%HU{1>+gvjeX& zZwk5)riTin$Ei;ivqbw~6N4KOLjAMg6`m`+FK0@z@|wP?H7_kw?)_tAUIRlR z&cS@d`Ys)YdG#p4jHrZX)N#`)=G~kj?Z=D=uWr|WhuQu&y%Obzd$msG!@V|xEpjlV zTY2UP&wpBNafQ|lA2}}KjH7V9%5|t1+n(cjN6b(+v9zu2<;0k6sxdn;)LMb4)?x^o z3gHQb_+HJ?wC2kd(%ae%IB|nN7ydkX79StJfgxrTU73GT(N+1p8~kty zzx^H9{7wjFLgSPPjZ@}rxCJANyIx$ysWCZ$yD3eR7<)I?Qz$d~%CKGG-+kq5`m$c8 zv5!U7$_p*NGa`IpF^ZJG?;vIE>rq;%w)tw`G~7|uUa7S2#+bfCO52O8xoPM%^lK8! z@oTNpSXbJ2{?*#|F8sFjZMsVP?!#|e-zTrszTe`vt?%1d^D^Izc6|?Dp?yaqRNJ_R z)EpI7cnHiv~Z(60yOy#Rr|9T$z&oCMEQONgwVL;=J+M~f`azFJsd_v*Bnmliz*uxhG;$_@8H?h&RK;~l z*0gYQZAodVS&#tf%5<21ZOQo3gsuOATs;Vj`$eTC<9$CLk2NDDFV~~K&0qDlxMJSD ztR<}*!P=*|m0y0`6Y|NfF1BC+|-e6D<`t&cT#JEU4y&((JC)UCcj92i7>#@0ei)ipa+x>+p4E-Pw3UOPl;;F!>`2|AL5U#u}!t(JJ1hL2;O#^OW^Ij zFquQT(segM3l6Y)bble)Cdn@RL59s=0c-*=U zI_6uUvSx*NZ`*4uDbF5bb+0++7d{tX zPqk&{qr(3f(wGcYqlqPJ`JRR5l1GwD9_Oru+P^|&pP>1`t|X*hH?+3&V`EwJXzB{Z z8PU|^iYub2JyoxdrY6<2m+qCC576G>dq4w~?kYNkw?p$3E9_C68Dy(-&i8&;FV4`t zcyESr^l%#f(hb)B@n19lqonS&s7H^y-;%;NEh$ikLA^`%2;4;>xx3E(9}g?G($dAZ zIkMSDsUahG9Q0|r(i1@gO1jmi8LCaGv3lq*TU584mJy_GdyQ0_5G}!renxyv{Oz(& z{I$O7@A_ds3Tyswp1?UOgncCWGw42fzb`eClhD78+?6Pg9{Fd>SNzcO6}pWVs=3fC zPtW|;7CtXT%M7CpRJ6UtrzslmtZl-XTfI)<{s~8HC;ErpAqwjoz7Tg|1{BU)*=og0 z3vuQfA9oP5u?mcOg%Xd-#6XGn$94${iR_m#Z zBEvP~Z!?ZD)*7ujgpNCY^LJ?Vqm)mY9}nv|Y4z^V+;Ox zZlWB1qzBfE7ujZjn~o#?j@Lq8irg80Qwv_G@EvLet40-YCG$%R<@Zo1zxR{`09R}e z@A+2C>y{!0>$3Ay$qIWQ9lVC4*1ptwC(3h!J<8UU#BV;{YhMEWK2WdfWfWy#=8QYg zl+55dtw~&`W(Fk+o}qfThL=Cav~!9WCNB(rdNt`f%r8`5E^IZNX;TdCvU-mSonB zMA;}WeymaUe>?-VqyPU7x&-W0;Gf;mzyE;xy14`9)-GOLKVa_Sc@>N67u5Hkt9*?C z3u_lw4ydZDsvj`2vVKuR?UDggYwH$O)hwtOU0Xe`vaWu>;`+G@YnIgwm^!;*?!tMs z3o1&>Cgu$uIAFw*CG`VFS63}q*icqGzu}VEb(Jk)kl37M3o0(DYFJn?zk2opQ9d?H zN6Q*BI4d|H*sot!uy$VMg36k#$u(6gvX&1T+J8`P|J?p17mMyNVX&^kewr)vn-Ry?Sc|zI(Y1kdL1&+aW(Qz8! zU3;NGs2h}vpNr}S4aU#RxX}}u39y_p{ll~qGDcUeTYywqJC&mRf8~PgOmXjw$qS?59t}l z(VlV(zFC+v(fF}q4H}{|xT5n6bkH_A?CB(j!MQqzUv{2@4jP? z-<#)1F>tOFCmAE}!{-MV&nrbwjbM)RDrcilwtTgeehI6ASV23gJiqM7XCP#VoB@#` z$XNW9@*@0{RMv>!p$~;XDQC{BZxH`NBkuU$X@-sm zPfBNhx1EZW}w0e$H1!!Vh{eLBb#Wl?Ee^gyJMh61{@%AwnhdjpD{!Na?rE% znWT~2zYwX=$Y6z3Ya~wvYao&=p$kEL3`1bOB_`uto68>;g8r4Dx1ujsRt zNW2`@lgLhuoUM?@bg%-I+V6=Z%X3sdFKA@ALJn!(dv%*M~<1#^Y^dS%#ff=AR5*9RHEeSACrp@v6(6uhRqBfx zX;fc>Nxd-QM z=S%q6<7F>*Dh?j~>9J284tc6;2;eW8*EgfE56TMKg_M@88RoGN$n@m^L zcqJkvLVzQB4|`t#h<=J=1OT*0PX{yuY>!^TrUKby_C*LH8u4cnWNEv60PY$DleQ1x z8vjkuFh1jt)4*;0cmv#UVp?E0jd=bzi~xU3qnE~dYb*~xc875me@tTxeq0XYeEyim zJQD53#l#@y)sI+;d~E_3CZY^$K-v$;_%nbJ;B0B&#UgggAO45>Qw@Bh$PE~evDJ6eU_;>>ou}m#rcIsE>Usr*2oGK>@kh3RKfOYWR*e= zYUENP#$Sk}%gYo~{GCXGyf%%U@d@TEZct43B|OGKs2O9?;UB@DG*aS$Cd*SB+2k2S z0!#|td_s{qb|nnD`4!vz!QUhyj;U1g!F zfCq`B%VLH6hDeH>#^FOuaWKh0Gf6XIGB-~xzSM#b>%0O=*OO|Um)H}`u&}mvQAPcd zin$9b=PrUIj>PSclV2QxCwtQM_o9nyQ{lb`*F6!whW%%7ZJg5D^BCG07=|DBQsu`i z+6I^cD&%S468t&>U#bK-;3U)Wa~kCgY=onMYPMkq~zgGCea04t}(r@ADR04k> z{t6uV5gafCBY2yIaTKUaVw{D$RA6zx ztbSqn3em;5OUj#3%^mpL`|z{kec<}25DhCv)?QLmT~)JaDli_ zqN)K!{PmrsJh`T!s=BPQX5NIl@~Xv^waXfi*Q+OxS341-a<_3FBI5sqB9zRo!2&H* zIVdwfDMc=q@7_MN{Nu?WAt` zs>DS6{fJ$^qz;R{`J$`+dnw~iZ6(+__qXqXgG;;KMabo?LF1$j+d^s$Y^y^WxRaVm zH`G;Q)fuo&mQpP}HLg2%!Woc%2vIY4$x4xAyFf~IB8w1~9%G7x3lMs7<>LCv29auO zl#*ROgsbjvW6?D;2`(mVVjtSm9=S}8l&s$&$&*X68V=h%{e_q~Y3%s&ilWJ*M~|9> zxwm^ahMfqS;40H5j&)W;XF^<^bTyQT$Ky+a6=mfk%14O|=}AWIwBV@0p71}<^3Rms zIQX~V@IMXyBS#fY9)ox0OH0ctMvWg)R5EHLDmtzNJlLL>m<`cu6Y1y^QTnh*j$DTN z{ul#L&J8D>N{mZ$rB$|sYu(DS21uR-Ma$;TudFMt)zWo*ZOxqO+PTzVx737F4wwI7 z)EM)r;m#PI<cA;4 zj%KfpBgNpIi(@g?YUz^3QrG;&4Ppz}iodofPDn$0NJnT)8>tX$z%5r;%V2x4_SBh{Y3Kz!P#tWhf(#9Tp6kVu9i0D26$ThLFzVbcJ|LHR9UN8gVrm z@eRb_XPsn?_(oJC)>SU3s&A;Q3zMxapYD`hBU-b)urZpoYpiC?P|aFBx2yr%nu4IF5`mt`-H&wH8rW&(v?nkrkMGQ9WN!F}ychIa617pj_J7s3O4I3Fc zM$=}-YT8p&(=H4(EhmN+jHb1~aB@`BzO0(|b=|aD?ABv6j=4(7gc3M)n-rt*cXBnY z5iNGr>a^u!o${uLrqsSMn(n4pO?Q{H+ahOP>8Ma?3zH75>X3oTD}rZQJqzh+A4yl+ zeA&dSY((30;D^;{E#oZM72bhAy8b)9it;g2z(nE?__K+3RIRLm$3v`@V*oBpW34;`H&LcYI{~AYOlhf= z!z9GZbjRNTpjI-R_O7Z{x;sw=fLh6PP6mKl>EXN_0BR-6`5*w)%Bjvb0H9V*bAAs1 zwbIAgCtcM+UuQW0)ImRIBY-)m73aeMra9yQVOP1@4l!KiKNJi$A8Z z3qRQEdYV6`agap2@h4(-;~o8@lg7C})@h9@%0J+(8ORbt$Axx3T-vp8zfp6d@22KTT z;8PPR-4c9+I2TVyB}DbUhqeojz^QQUYA?aA)cba&-uEl@zF(>L{Yt$LQy zYnCi)sE7I72r1i8pzU5mRhX4)akHQUI} z64wFSr2bXR)I(Nlw(`zW*8$t4j(4e z;w8qIgK_hM@Z6$vx63K5`9YgbfAku~e2@GC5<1RGK`ttBvz-ZC779i3)sRTJ42HPQ=Jh+fVFO!5qA%OHEwxI++hHhx#ekbvIjIqZrM9-0D#Nkmm^#% z0aKpA=*A0h%Hf9;hxqCMAjP4+n*m6-Jj-{0UT!(e*9^esmS_70Wua_toSvQsz~PqX z__hK-@rV1~1Tf1j3x!LiXvz^w1fsu+?>Y`IWHH*~KLw;jw>;024@d$U>zNM7095Q* z4#*B@oaZ(`I{}q={s`#TfJ!}I1G*p3cu#gun6?9&;F$pEK|m8dmjikm(D|Ob0eu2! zlIImbp8_iLd=2O`K;@q9y@dD*&}7djKwkrz;#mghUx221b^!VY&@|60fW8HEf#+L5 z-vOHL>46pY_kb?+j05xopc$TJfQ|#Y$g>sDzX8qkyacEjP=#=*FE{0^*H{&o+l2TV z{7@B@z8?Xgwio#_A%s!ei+v*jptfs#ivggvYkfBXKy5Ge?FN9_uJe5W0JUB3GcjtK zZn?~N1^~>MmiwjvaJ%ItzD58Zw_NGF8-Uj>SNUEB;B(7Meg6ay=a#E|0gM{)Zn?%+ z03g9F*ZLL!K$#nTn*sRUa-Hu<07-7S-uD53WVgJ+=Y~=);FeeVh5$%$%d33T0i?R+ z)xNa=(%f=`?@<6<-LlE|4uEvGyw>M99p?LPdA)BCfDE_X=$iqcyIXGZ{R}{+TWbs=00-RiHeWXw zN$+>d+kNu@>~qVlzPkXN;+ETeuLJ1mmUs9ZIYRVu%R7B%0LXUByL?jsyz7?t_Zuwi`Qh`kQ^lur9CPu&4v7Yt4rvpFd`wjr2KkrL{b=WO# z`3K=rflT?rmy9(Av4+A61$)JJApm5t-?s_?VjU1Ju+dma9708sIJ;7K#9O$Sz)|WotK$XQYUw;5#t*?BO0Q}Z1 zzxG`U03Y}-;ZmVZ`OW8yUV`X%!V8%m_x(YK`O)_w02H-Zn97f1OAZ3ctKf)1Dzrm- zGXNn;Q+jg&A-qd^#{!z~MiUED1vI5cPDd=~Q*h=pYCw*X_NxJL4<=iVk?hdKg{k~a zd7k_wV|)r{Bf|w`skH41#qdi!;2tLgabeQmFy%z~N5<&x#4Tq!#^mrAQ^R7=A2Fs$ zZZA70AjW@@5|9^3yDL|hDo0jGvMq68Dt|~HYy%+1jd1*++XJ#v+J=T=_@NPIsfgQ$ zYogIlE|jca;=*JkWLzaLVlpqnIggZptdX{*ItDg|mPpR6i3?Ntn{uhVi!r{3vsTAg zE^YU<#8{zX5ErKMH?i({gE4YU^gJD7jkLYr5~ESYATCVhZ_3N13xS<8;rv6#xKi3u zv8-VuCCRH*4C2C6{-(S}4r7eF;hY9Ks^hxw>e$$}I!={0CrA+rneq5f+2~h_OTd7h{}_7&qt`zY33WUsw$K zBgRhbS0ctuaDD>{KJFoDdzW!h9e(+Uib34=ttR43>n=qkZcoOZ5JDOQ<)e}kjkqwG z64HK5;%z$NdGHRd(oENp@`sRR#t_aNf`{{@NO&pZuGoEYmTRzln1N+Zf|( zI6vqZ{|JxqX;=*951}YuWsCxkz#X%ycE6OiF@SW-9aD`&+%{1Y(Q;oYB5`4=NT&Q+ z+K_^CJ)8?b_Xgw-(uPy@p=5qkF^JnP*F+@KEGPEH1QEC}83}DIjAAD9IGk%4E+8F7 zn9MNM<_u+qFzJsNF5?CScE8}mT*Dy)hW!b~1K0JFDF$UIar+-yh^Yp}Bysy|A!4@d zVo(wix4#`C=EyXI!j8E8A0gsE+0~#tBW^z)BIe3;gVKq(-9JRwZ!8x$kN?PVciUzur8QV_S#3K4T;4}<-lxV<(+94NC4c5UMJbs=JZ zd5Xc_OWeM>C1g*79hA8Jo|cfk4E8MI_9sHbK{DH5=OJ!?B}B}TryA@Z#O-f~hy&$m z2D<=p`{yCz0NL9hmlL-)hlu@UAA^ic+@5%*uBCzUbc4J~+}@WKoWJlumK_OyK z+0P(z5w{Ns5eLg0gRDYam_fK;h%=1mKyvoPs4yLrw1CVtY>PuNddNJ3*GCYyuhK+M zCTtwIULbD2LKA&ia)?2uA}&m(gtX5zUI)p!25DadiZdV!4BPEG2E^QO#h%2iw2e%8 zZfn~2>5%r`vQVvohzpY`A?*>yKqM>gOc3HRQj%n`;e8nprr9Ni_b4FD5+)kntf2}z z-|$Y*&?LjVOhaXc_ijL#Czc!Dw>31`@Ftz5Xj2UDI1NoTyp0-~W_X|0&;^F~6F|sg zy5UV9rl1QA?|2Q(Kny@wA6#U3AJ?>*hWBF)RT$nLXR8>q4DUn@%{IJOYG{t(-L0Xy zhWB#~%`?0`3sk8p4R1LhtQh7S-qnCmf(3^6Q9#IT5xztFE;hX8IVxO@;my}jt>K-n zp(Td*8bDZXEH%8p(@>q^{YpdihBs%p@@+7@voy5K@ZPGS<%ah~Kq$c_hW8r{tuVZO z&sDUQhWA21Sih_?yw_{mrH1!e4Xs8D4P9n(p)?u9pqB~m~p%M<{Vhuvh#4ZV>Y(Vm)Sbd#y1DYT!a*}KUuq$xC4)12L8 z8fgkWSJPbGWLMG@TB2#5ZZe%Tg-+EpUpLu}G=q?#k~*!^cZRG%>XWS%dYM{09LtWy89yl zE8Vi2J8`sDada1^O52o~EQ_-%njjZ`_8ggI9|J%Sr#(66C2EwBW`c@=uotN$7?p5P zR7K4ul>}q46&6RGPbHNE<1#BOsHc%if_)Ri8og|O*_$+?!emKMO?`gOqLmnUI0b~X z9N9OlXgLhdqFG7EBzXqs)=a|wARL`+|02{rQTwx+=J3k_q!G3MNz+Wf97q~b`#&_z z?U#c{BWnM*rg@WOF7qI2caBkc#3jkWq!G2JXj(#&%p;Acy{D%6lVm<=MD6`FE!i)J z@H>dwS$8ONz_0HMAZkBThfDFxp$tdVUaD!SN!o6Ws4!VWsIpW{Kh*S~`@=aIPbs$O3B$Wi! zdtnHms1>BD-n)d!unY)0nPf+raDU# zJP@vHl3YLU&?U&0)BWf38RryZ$%S%WjYERO%etx-qCYJkp37J2WjmU5;g3qQ-7b zOT?`Mq!BgtX<8Dl+F@LxwhuHd&`XxET8Y{|*R<4rvXqrZR5-KX8eTd6av<_)w9*eG zq{;>}r354}f|&yVGp-bqHov^W><0h>vP0EUYu^Em*ietE6=I)E;I zdA)fQK$>4}H2vct4*c>4b1;B(zuaVw2hhzgH=7FqWccMT%qswN_sd^GFQF^y#_eDs z8MMIy8(yfWt>#kzP*Hc7uK_?s?Jz&5mtWp#{s;gSb(fhqK~>bR%u@lNqV6?^0YF9F zXO;j!MeQ^z0HC6NZB_$7Mcr?%1b~Wqz`POwD(XSuRJnTPL%fAeK4!iR{Cjp=syUqRd^2^_v9|1ryo;HsIKzsepOqr;P@q4p302JdH^K1Yp#vXGb02Jd{ zb3OnRW3PEB02Jdna}xj*<9Tx@0JPU1%;x~0ya7T>s9k80JPU( z(=$o6*K6jf0MK5qo96;Rd;Q6r3IOf(hPeblreD5k{sKS`zkJJl3P6@${@HvBz$t$D zw)ri9o__fkGocJJ%rDj6HZmXUitn+G`V9iB-jFY^+}WeZL9{M z<;OobY!Ee?G!3%i6ZTJ{#+{l5S@G#a(1;q3Yg&9)`5A>JQQLExmY69&r<@`xoXidV z^NVNE)Z!*Ix=jp21iS43JW~AdEP`a)i9dbgQT$|(aPyP1Hvrh8XFEreLJRQu0PM5? zzY+lMQ|c`oDzr`Zp(M3`1Lr}sA--!c@D!76%LjPM-PTy1Vqk7 z-JHds@iOQvRsM3MvzqZ7a+Gr;y&Q71^AP|T!N)k?1%U59&zUe4Y2loLa|i&ZLl!${ z0x%tNobzV@P$eb8p^~=AQtZSF`DZwHzzcazay||KS(G{d1OU^ka`PJiIF>NkOq-_W z1=G!u0APSW!(0Xc2KX15_W*za{!H^-05HI>FcU7oGQ=TgnS%lFK*((2P?^}|oF&Y) z0L?rNe#mv6a|Hn8TIt+EibKwKJ`Dihv%vWt02F$mQ%px!bI2-Z9{^bnd9kw$K%qk} za$W+U(IKmaL#1ewi~r6ncr)4-cp-~g=WYPVVu|y8QXF!r({Z87qRx3b0Ax|`ECGO& z8=N%&kn%F&Q1NYY`BUYzQR7oh!*P|>H^5fzU4sLC`zzHI27La}h* z=B(&gDDBx+EaOz25=y2xoM>3d&Shy;$@=PWD4Cj`5ETv{tI7rB%9bOIVLAkI9K*5` zHAZV1>P$@k1foW{rlHQ%N`NTD0UGflKxx@fS=H(gNL|hLiQ4$Fs2O`# zS*iWLaRnJuy8g^0Blu~7O- zb0edJmxXf&NjABNiOMZ-cIhxn%sl`E7}oU`0QAIq*D(O-QVp*3nW`r)!!>>k4L)6n zn6RHf=3-<#_%!lnriG!~b1JOMnT97J+DUZ+BycL)C-R_No6DI-u#yrhD)brU3S1vk zSy#7gNdtzLc8Fbg>?3YGl63~k;99pjjlGPNd5TieNcu07%i|#K+d($$GvV6*3y$q? zmjhZ22vOGIhqpN0iC_1#aE!KLcvq8r6V6tB2*i6kURGjCKBdX^d66A^k?|d9g_?G* z=t5E|NzTBJa1|cMD=eJ>@_iSc3Q6q>$Pr+P3|=@8FbMkGq6<%j#F69-P&`{VOnm@$ z(w9D^sZ$|o>QqRYIu(+pPKBhYQz2>UR7jdS6_Tb-g`}xdA!+JVNSZzslBQ3Er0G*3 zY5G)1nm!ehrcZ^Wg`EmX?vE)+_|f);x|JQ@Zs2rwkr8JuV}`bq4?H3vJb8Uc(+Ry| zL^_)6zZr$GPF0pJsb5?H-l=MU&A&)BDsh+7+K#;K9P@<#-8S);)YZmF>m1 zyj6S~TUYqIVwMzHh&o)~jBACAtJ_OLdxi?IC=^#8Q>eF&&4ljtO)_UnY453%Z$F5A z8a_lZvSMlB{}oc4JYrILMMXp1?3((;utAM?+$7}_;HfCOeL3SMqtbQUWV}%k3Zv>5 z_joyRP{7IOVYLB|gxs_GRE0N8^;n`SZol9${>xKM;|FV|o>cX~3E2dZ0 z)z+8JUJ=BBxQ4PSnERH@u5Spc+uY(EPlTs@0x@)^Dyw*2?^RK;pt6C$*qR^=Ppj%H z=hoKDs}~+ys#F{Bu>z$`9a$bMFM%}Lc&fy98&uSqkYq$K(WrQ5!RPT zu{%=<#6e(H0;)Xn5~((WKv4=L!AUg;;FhEK({T!RVI@s|D@AvC3Z-=mF1XOKi91+1 zk@tJIsT>}(eIC>CatQj9tCDPGVbUmctC12Gy3VYR?jpg2hfsT#%xN1m!sfnB4W25y z#12p}LEfv`!p*DPB+Ny~(Jg1jG& z!=SvKNVo*N0XeY~Ms!ckFx&URz2S40)zzUdw;QP=KbWrL%D;A_v`3G!JU;}!la5%T z;xiQ@QZ9PHsj*|FsSx4AUd(YaR|U74UyplwR4Jg3a}r%4&Zb}&-4i?SQ|?skfUlBb z5B^TFJ~bSbVAWKpqb#f8Btbp5P}%a?UF5cQdsRf>*xhDZXZ`9iDdSr^%|F6A4bI5v zo)kf3r{MVrcJ>e$#gOySU~R7S3X>Tdl>Z4c)>a00{+=$>%Zhz&IRW-r2KM>aEmHK~ za?-KS)VAznO{+o&eyk7Al)KxL%2ASS3S`h%6X-gH@Kua!p-`mJ0O>uF}HM z(A+2_y;Z*h9MxH#26Joi-Tvb4xbi81DUs6d4F+-k zoi6s36eGEz3GHlvxDkxBdy^F3(#=cVw_ zvAHR^vzcp8DbqXRr~2Aub#p5zL~z%6NOAQh=C^@Q`?)WOm8pE zj`BKDIUdEW`@l<`aO)Qg;{2Ab5aSiM{_F&}^>c9R46ryw-$}-;=eNhL5%>689}azR z2kaUVJT|||&iEDA$^ZXH{#8?~wY_)Q>fP+j8yUp8oi275pc=IancTVj8<{3V9xkqb zF#n|Es5?*zRt>dGP*#qqY$%0xe)fXOmhbK&*R?DD>cRuZW~X(X45nYm9H_(oo*Se`~LD(I)U6HSpT}qWbwr0en+Dk^))h?clwUea>YsV{_cR019NyAV*cXoC4oY`|1 ziN0%K+GQaSqRX&TFrsdO_yKa(f}weHg=^Z{Xx@yao~rsfRRX1CS7nN%@QNQ!Xe&k7 zDge{zmb@bhVwaPx%p(edt)|L`Wpy>7sWH_T5d_TWq2DU6Woy>fRgT1@U(krG4Uvxn z{=cOcyr4b(AD0g8(eVXUy85`PZUxKLDufz2_G*4p1OeZ(7=EF8;qFuz8Z{1$M8A%$ zHJqnHgti-2DI`+y_=_;w3GA7?pn``lA7W}D-&4V@KB~2l*7leS0x5DO5;LhR26q!DQ}dLeIaJ(*dqEyJf0c;Zt=os!-?CazDl_r>DA6kCaSOP zMC(ZBZo1fxR}(r{p!4DPE;R1TmrHRP3 zzejs2LSMexHsB12LPZm9en`l zd!xqz()UI$1{AtCTE)e^(Yp}Sb`!(m-slYIWyNk%M7^qv`{9w;4W2Ip$eoL{ZNG!} zjezzUF6>MEnlxD4d1Ml$y+WVRG@SiOW*=1Ovzi7=-IUSDM4|ghv-P^m(M6`xc1z)Z z*2Ld9;$<3VVhaC46Q6XX%C0m7Q}_>>xW^GE)2AR!;?O`ymi_^j-kv&7i1S(cCIDaI zPs$w#GOZFMywz$hCg8xO>YD+e(o)T*0H8g)xZVPQ_Dpkq4*>1i)zxRdYR`1nWB_Q- zZmypJKznAm9t419%yj()0GhFf%UqzEG0Qa=Ks_!Ecg+Ss6Wm_Hsq)7=u9?V7egfxO z_@O|jn|Bky9pUCH08pU8=1~AB&`?+Rg{mCqxF!HVW<|oOqS<8dAqJ_!cV7yxq(ph1 z?OFhAmF}`wr4Q7&Nz-7#U&1ORYHZasSbmP5hZ-bm+^1>rJ~@G_38KamnwIF3=aWWM zIGG!)9VdMQM3k#)=Vj-1`!n$Pgw@`^3ao-Z>G&RQB3@N63E+)OeF}0DlerjXZ;7&( z5dgq4!_;9N%0krWu4#6kJdODhHTr5AjLiBl98qJirg?nwbcQ1;Os0(T_03~0e}Yp8 zLK;lYZKXOm%tQyV2t;kuHO-eSb4epAOvXSGgSP>}^V2ZNCjpn*yBg?^tJvKe0Dw`3 zx$gvk_C4GE3IJGU7r6fk0E}{uJFrMG%5e8t0MK@Y?im2UC?ni!0ieGZx$gu3MhOa2 zvmWOW7#kWnqf75J0J$8hmVXc0{c#UJfteF2SA)P>_M6DO`b z@EYh*CUR2Q8YN_-abg>s+J1*1xO#-lZx2x3_&>iLriTMTb_6iT2bBazpisfIAT<{P zG;G(?C1cr203pOA{Fv8}YGcN21Jr=3ZwU9(UNG^Oz$K=dB9VKg!kvIb2>8_<;Ew`= zK`Y$0cYr4;YtJNQ?TO=%Ws`8an|FZY7-U@@+{w5#BS~3%;<#honSlAkXOgn^#G%Hz zK?8wYST|@8erD7S%Eiw`b%O@uXJ*|XCQwl~h$+kpjvZAoX;k?L5l>zG39ks9w*SQ1 zQ#FE1c*B!dBQjpxZr9q=7XU|3YI)&J+j@!s9&?lDZ*9lNHX5~PV@<0D6TXtD_?3&7 zG_1t2+bMc^5}vg7vJFFI;cJSD2c^e6twC|gYAMML;c;8NL-7wq#a~icxoAWKO1`#j z$wPiBrsgwpobYu+hYrsK7qU-SURifZT@{oy0lBB0l)^*U$jHhnS@`BhB?ZgK@T3m6 zO)4UUN=mW0@NJDsYHl^|)kbmNZ<~hpQjta6%ZO*$O&X1;ev~eRtA1s~L5S&A6Q{us zcMejNbznCc5@k~`h@M=c3}%ys7_uxg$!wtQ|X?6BI}{p&C>TW@#l#(niaY}_kQ^^uLMCE&e^-T{l!&-nsfA$nry#lX?E z)81T*#-{1reEgkcjeRQWAhN2o9(zv92gl*M!EoK8?(;37+SM6`dh;|H7n338YIDsh zyx_e;EBh4$MO5XAC6#j<@R%bfbS(%rV8n7h+n~rAf@&%{K4d~ml!*9I(qR~yGm?Qq zbAw`fIOoyD@>hw3Rh@ImK5z-uQG4-sl5xqGZA1cVYSNsR?@g4I>Q=c(Rtg1*$pe)# zF{b|#iAy+f^?VeMw9g9Dqk~1Y_*OJcyDk18J)C>!;-s`mx$srzEq-d25RYX^QPAt8 zYw>v0L1bg99zVLa4yKA#mKBQi@!jQ{ZAXOmBE)R!H@nC5#v-B+oDe?TLsHaKUZS=) z+0iW+%#pgRhN}c6C_*51S;ON(N?73|;$j&$C$xXaMNbQYz1aFCRW+!A@s*d9&R$S8 zS8YE=)9hF(hVRX?ULpu6T$&}G@YGBd7D(YjDnvr4^pM?7N&OrZA`FFZMhGp9^d$=4 zOf?*%sjSH1ILtFG)QTOBV~ZN^LBQhFirb1o*lNUz*NUM!YnRN0A*vOt6~m^iMyyz^ z7~UY5Te}!bt;%^}brD6f%ZkG1I+H1rIM?#LEBoZM<6<c&nGOhrcUvX7B`uzsNN)WL$d#UDVX*W;9wP$H!#k-!QoIGrG83 zLUG8)opZ=~aL9|xq{v%-(s9VFHXLG^>R2C~D(`5AJ*-eMdE<`QE9WQwPdVcaG}wQ@ z8OK%dcH~sl+%XM25It~(^_8CVcIMK>J{$gQVji}+?8Xu7!h8xoG8Qbx8xZ)Dw!t;r z@WPwJ1h{t$?VG^0TA0F;z`f&{0My>`8USkV_znPS@Ax$U>dj$UtG19%F$V%rd&koO zsJ-Jx0BY~}VE}6H_-_Ez-f>__Xz#cPfZjV+xrV>y0Ju>p#ry#PZd6J& zyVRpR*s3)L1HjEeX=W(^H@0d`Jg_J{4w-H?0{DN}d;9RHs%w9I?>RGP0?CAsOfUi> zB2u&p1P~ElA%FyVGYKzJY6!^yfsn+^1Ork;q*Sf-U27FzYSmh`YAsc3t$Mu{tF^XQ zz1mtYRcpQ0Dz)mhYFqt%*4pQsIqx&6efoW#)88MnXYaMvKIiPU)?WK%aAWDgl#Gp3u=o%;?qcwTlCfF^!zpCrYXPHVY?^}A-~b?6?53p9>1|kb zocIh9;tKpUu?8!4@z`vje?lC60FhC>_!Mm?!V0;+j8g;$_U_LG{3>~s1jh+wI5tbWi&*0V$P;}C(K9j32Dgchz37jb^1 zCXbkm2Z~i}VV|H6O9WVo?3yfA8&@2R4~f)jV+pMx>VE|j;%Tx4TKc^K&_N1t!W}_} zFq8&ST3R1SA)Vi%@vXi%rF&5wTux4DT!fHT^l%vvR`hTxH&*m;2@qEFZ~;)y6oj;* zhl_u(qK8X=dX7fOD|)!?hgS4()eo)c;m~bb(ZeM_w4#R_erQE+fNe!DNjJq7xECrZ zCrg>erxu`tjzOHI2qfRuo6LkhTipeglrsxGToJmTE_yVuO^iQ))IU_q{tsIA5F7|9st7y9(jtcn4LXVGC2n*fm_db*+>;^i%t*`QgB8VmwLv(HdB2^D=D2nR-qNtuJis~(*(gkV{s`e@@ z)oS8)s&!5mTwF8>1?xvf3hvZ^EFI=RdX1!-|- zoSD8U*EdoVqHef9u3REcz9=QPk>S<;mqNbD{zAmyHgY-sN`A&T^h|}9;BG*Zu|%5g zu#lXceF6s3gQ-GRQZV>!U=!(g5mu5kdD6}Mwm+>TXoJ66T*SQWQpRjM7UQtcRy>!Wt8O0{EEsvWCR?O2tq9UJs9KF2-- z5;`92r)LU@b$}?dKR(Es~e6iYm8TOvRtC(G8U6KO>`DmOKYyZ%iNWdk~!OBeMz)) zA$VcD0h7xMaVQtwa;Etf6O<0yXE6|7h6PX95;b^}Cay=1)#c>jv@-8Q@1oUzgo{TE zeP}-Nu(PEj3+Ij>{k=@u0Af4yW=|pBOdJzI-t0UQyy=?N*Nwf!nVv;Bz+l3{-W+D+ zv3Ss%$zr_oG?}b05^(q{o~P8hp7IOtQ=BB?r!0lH3rV3HQlKT)ckqjtrc%Q~_M}lY z`pV$7W3ynrB_M12PYYQZixJgwYD`u)^*6ht7wR+wQ)AU3*qJdI*PJe(dms-P-$xyHTVwM`_P97`5)XYcdTeGZmBy=K|p{nlYW3KK_J^ zs6huQp8{@d7aJk*#LYq&Q9uuG>*~yi1-D?#LlHnGtm(=rOT*xNibg|zMdI~YZ;`ON zYcGPkNLV{|eZNnUu&$afgR?~VnwYml7<)Mjgtg0j38SH<9)}JvS9YTR& zV|PzxBYntBk_>Uj0dTE02vm5P2<|(TkFNL^-6J2;sOd46Bh4~|tpazFh{}jJy zDS`HDV-RDtFgyTq@yslHN{;607D^nV0HYIO3eb{}BhkK04QOBZ`~^Q_9NfN;cZ=oq zg8449MWOzWy*c4D+JTXI%iHd5OGY`3EU3q1dt3PsYO=9r95&wX8`)dNufb??ek07S z(M0%uBQ-EqbLad-zh=PvDCY+THvvm|n*vobvkg#?f1YjU=Q)gf9^$g@6H(d1toyV) z{tW)^`w5`$p%CL?Ht)An%?>l~7mme6Eb!WX7r$uL?3fm8-kImhzMF+l$&N7lZp#r; zzdJ$={8n97z?={C82D0CPg(PfO64-{my>I~)3~$LU6$%;B1^nOp{WD=9aKOE-hvK1 z&?Cj+*ogXXr~?zM!l&f&qI6(_^Xvd;hiQ4J4y^kuI`AljRD=%vjmQ#*L7LEkPw>+O zxr~I`fw_kY-eyD9A!0f}9bHGKDBsPaHb$8N+G0dyPvLSTs)YqJgjj*up&GF4vuMCL zs@R3Cz*-_poKK;t0e>o_0k=W}%5zd|#qZxw114By$0c0FXh5h9m>jABGe3(441sux z(0~O*me@j}5VY|?6JHorzy|1t;W9*w3+DDkP6OTt2OL$J21a!l*Y|XFSY=MhQm^Fg zgduglG*sdvKI_o#4H~XF>%Gs=ZVUtmXD|wdc!P!hcp;&$hR|OA}91ex`mG8 zlo!!a&{ly{a->({7FCG2M}~@f;%BMgZ$cO@QTuiDMnYaPF@r)O-eFl!I=Daue+;r- zd7%`y;TJIz|DIdc%rmown}trvza~7byMr=B=6?+xybt&+GG7aU6e08Lh%9j{g=Xje z`a&`v@p*LYur#+Fzlh1)Gr((UZSCFA+kvH?wz{<~J!^Oujam4V+~<|OZ;lWh*cYk; zAHg;BA0FV1gMfz=k153Mo%m_uj6yo_G<4vWol<;=U&M6a18~66xm!c4 zW=+_HLy|NLos!RaW$&O2k@<6>GXE{yy+6~;{hbhsOYT11yM08J_<%xF?7u4{_Rk$I z#KrKBc^SWd8?n>oNwd%?`FM!fi84g&kB5r=na?Wrt00uZVt<~f5_>5W;y6rZXksB| zC_*j%R*3z>j1=2eM^5Y~f&-4)Zrq_pb=@p-O5WiWx{WSGdUO#I-QY+hA|3*#0yuEp{rUq@q4yC#JN#9LT_P9&BH!56k;CcyWHZbnr{twxk=y7(Y{sRbBER;tihL>r zQds00i7K&`LQ~|I6%zS3Aad#%5D)%ML{7EWEOJVIIZ)&UYWbH#MSk&T75N)Q^$ft7|krEhO@HAo80wNHL-_aw4ZYG@XW>CjqFEnlxF=#V|Cf38zC$wX^Y#a`y zg>q8&I${=sCQ*IVhYW#P;*@L+QlA3$qBT@~I{U3YE`iS}%3kaws>Fp93UO3|1pY!H zf!_sz-}ZUTA081oflmVm90I3Ph+2Y+(7R=&neoel? za=olLoF49wP@Zflxjd=0`w2zSO%PMV=<==r%ZeeJAXa+G>}!Qvyl87-=_)VIu?X>? z7w(rAeQn@^J4RD z^^71S<($jNFuh#H6!xuip*!<75_w`9h2|Bab#R*s-IwwDcp>gT1efZ3E^4Mzqx(Z0 z6%!ltrrWpendO#pnC9J5;tr`2S*DMQrcQ`faj zPLI73?>4Nl;IxdNNFmP2!6qb49032Q(CR+E7K7<}DPEczH7RNPzyXJpxVftDvTt~t z+1`W0X0e?vYwgT3xlt|u=(De`xMze&^^c*O>uPWu4Nm&%roEV|w$pYbTM{OMQngN` zk%XDZwQtB^w^3aNyMMA7?DuKQ@_eix96OVS7`B79!W&UQYw|XNUY}3FA>Q^au1|x} z3H~$~9=}hZ!+8AQYRgkkt_j8Ql!e{gJs23mpzb2QB?yNP^SgwQviQMiH`v71M&2_e zXxC*vUO$$=yuuD7o7(?q(8_a&t3nphu*>)1eA`h(dpnLR?S7OHAJ=WbS?p zb2sW*DVp$$R->dH;qKj-y2OKyyxFtLUoG2x3|vsI5R=v(YSMBszH~0wZiJdN)au}z zsJp=y$5kBjv=uZ{)C_t++<+RcJ?eBlkK}I81$ziFwycYPD^jcyaEw ztpZxwkHab#dB|1U*2HjI+t%hG3~k%4WO7G=-EG^|OcK_%-9Z%kBNXC91#a6eDP*m# zgSDc;)=K;$*0!y1w{0%FQwQe*^mx^|C6*B~nNcmzE^NB|9}!~5&JML>J7avMNv=QL z@&0v@UG3XkNZr->b1}){%Q7O>Poq$Xhw;-y3XXQ6qxpBCTrb`u#asAAOSxi?f&-4~ z$|pRTh1KOpt|2_5Llonq&~f|UrRVsRz2K?T=o4_P1J0Uy)k<6ac((<4ok-$uQYge; z7U6mlVc3Z)CruJ!_z$EQgQg8Z+wDlza+f-F$+^)cI6mBxGet_=Q3ez6KH=f*d5}e>({q zXIIT237bs7#>hevwr2~G@a#|t*Z<=Z9;zg~o9l2L9N0q5@Sh;zjkij16@Jl@aO^&J z9X7j(4VdfBS7xjD)pDaxs~(UkM6w%0+wrr!)2y4pdl|oyLLp#*(R_ZZklgBV3?0er zf#}H%`s-{yO%d?C!#s2Mnpyg4c|?fVoOwc|c0{Purg){ci=}qIlGyUb99R>W>m|zLP89BM2Jk=LS?$fE7N-+7u9jHI!Xb> z5RVdRd=G^}+{xl^EhPTGK>TmsB1QSPBPagv1&N=Gt+@fwEPJ&)C`8)!93jFzC{(zg z_X>9(I4|R6;61)onc4p=B(VmZLbM0@=*uHkVFS(VNw(AWvR3J<<-ib`IrD@_ZD6R> z(q5@O$x?fRLWqLv*}-te3hmT<7gB5cjuboai1f}qPW3eT zP%Vdq$S){&h$M%EO7cLjB-cV3GQOQcA$GAO&nYCy$iANEr07%%ffPo)Ue-%*04W#mceK@m2GXyxeR6^jg@`p zGMI@pTm+oUU?$SY>6#{dAJUh48uEwMyveoti}3gg)tdXDH5F)oXjC1oTCKh9uGKuz z=F}Ve)RD=Clw9nZSSXM&L~j;{PAx2hWws`d>N+wl>X=?NN2Jo$1d=~Gk%rtXX+Kd& z+NDR~QYYk~qW&97+ddy;vLPiG6_&O=V~DgDg-W~evrD^NN&9qO;yw~ic=7laTrJfM zvBtiR$fx*8nSw&Jo&iufE(ZGwBDlG#GIV- zd0-!C={~U8h~S2>nq&texFKx+E>1N#g zg}b$q6A?+{Z0qDgM5=MORuvs)?GvotVDx1U<*HRR&ppJc;HFNF^J%SbCMGYm5}wx zV-Udu=L(&vHF@&Ol>HQBKbdIC<^1Gnh#>pI z$SJ>p;4-2qmy46%Mg-ZHCU+x(?8}lrCsab7ntUA*WM7_q2N4wK3qt2?aQr`wp7RO? zU*hMSmK=fzp0hG}Fd}$POY#^(CFH7PBO-WCYx0YT;5lu$D}!*F%-lkc7>N^cI|)!O z*Ce+ig6Fg+FG2**S(n^JsDxafyaf?Fr$gvWt;r4hkUg;mwdFpbMpekJ*fW$1m(T4l zPba@PN@~AVu-JYwOX@>O?F|Ks*T@`6my+6_6-*x@dr3f))IL(Mk{Y>@xK2qeww2#8 zaDRCQv67Nnse+Xam3_n(N@{5ZE8kykq9RfEFrGPPs-y#qHP1H9Ok125eTU!ITjHJX@8+J zPLo4N03*MT;Ao&gd|+}RA|M`_Y)1sd2PMxV6xoQI5P?JwPCkYRG-Gt~_lTgv9FqJL z5!BK#$)RU+E&W{bI7CoO$0k=Gf?9g0(D@yjJnUqFToWa3>?4{AIX-p;BBTc?If2Sc z$=J0D2K!k{FiL7SD_Cr(oJb|4q;{Kv#fQmBR1iwW?p81zhxJijN(!Cc2L2uS2omyi zDZ~#5P%ft>|AX)ec}&Ukh~PfKV@v*o2yO^Gu4Ke^zEALYp)<86PdGt>_$>sQm<=Dd zc-+|pbvO66b>k+faZ~Z|NZk>rAAmwTj}({El|Gf26XQ#mv^3F|5dV{h61&pl%yi;t zP9Kjjmj2z@prRWE6AKyI#83jn_=>?8UojX<{~ugHW9j3TK%4&M*A0pXVI?$i6Uo~( z>NDlN0P;Tk5-GaziqhG$dx1)o9%ZF?$-`+o+_3UDU-_ z7K!iTK`s!ELpLCNas9J-3Ql93==bKJFT%*t{srzYg1fit^*&z&x9_koa*aQyK@p|i zNudzqSbs;twIoP?Z-@S#y9pOYP*wuU>-r3nN477E>q{<+E%p1fxW4SN*r|;1ex42l&^^6;wGITr zHJA$K0=abgbttAx*sJzLsHqcjq6e~!Ao@lM(ba(xXd*o+*k+!M8bG@@??wM6Vm5O< z3U9ReYcidg9vqrEy|c}{Njbx)Ijq2Rq0vleti_2z@*;a5pxEsG)###tKEZ#<5$F>@ z?fBJ(rg9t=$N+OYO)afGjcR1xH_YomGkRCAMlGav+YgRj0BRyA%zi{Zg(@{dDR_OG z%^)LztxJAi=4!v)UxsSr_XR;;hISiZ+jNYvTQ|<){*CaRJ$1QC=g82jOcO ziuO#|B2c(0)HBd?XZ5*lEJ2!^H)Ok8R<$>0J32a=r;5p_3ts37hSF=SR`@Cc>ANWu z;&h$r+Qn4Yk`6`a;2RU0Te~)Fp!<2{Gz; zioJ9AzBOzcO{ zAq3LX?;+%L>Jv`WslEH94*|X$u>=nfV}~P}j?ssf4G{a$ZN4c2>1pcPCDH^)@L(~) zgT)#iAlC3bzBPQ0Zw=q$Tf_JG*6=;PHGGe64d3Hi!}s{s@IAgY>K@-3b&qe2y2rOh z-Q!!M?(wZr_xRS>?(wZU81}O0&3<}vKPii*X7LXcgX|fMdwi3_oX=639vk))A85LJlY z=0wHO&%mer&5^IWr;9JXs>EgRu6!nn^J!EM#Neq3Ar?<>XlicG(f!67u$*0<__~z$ zLEl~QcpC}9Vu={M-O9^`wSG1Hv)bqqZ%oJSl9Em{SC4R``ALeeT=c3tttYV-HTB^M z*GZ{zn;_1GtF@3w!i30B{02~Md`dDwoOfm#t4Emtp{*;Lmw50>)c zL!_*NBn?1i4h;#8QpjRXVn}?Olw{Y8G}|~W1&(mBVP=5S#2)ybxtwNPjn3)EMXk}n zWx_AQ#XYw+L;I^UVwfC7t%a2q*HEPsZxd^r^Ib01+zr+|bGj6>dm`5Zz78yy$Gwj_ z>U=a~?1Up)H?((V@;0Z9yO<^e2FWf-ZB%i&!n!$K(%J2Gas52WGh)U7@>R^U8d3Cp zRm|+I=2PhR(tu46HAm31rGJysjH5T`eJ(nb`6p2k^C|RNozF!t*L)UHnsF?h=elw& z9ag72pTcZKJI~Sa#Dy7k^*>*RmPvgk^bECj0juX4c(aA8=WwhNtiD=`>+p+Kw^5_@ zEr+6+ZO05XpfQU*T>erHM`IX98>WiL9ftlN$#Y;Gd{9G191iU=<4{I5Bw?L1qEJJc z6C=%_e`t?MZqEuG@@9o*I4E%Z!qt{;C7`~GLLnCN0OXZ| z8g)7}>cnMIl$;tljcNc399ojK`c@eF^Hs&@ni%S3@?g09s#m?jGKMJ=9u(-W$BbJsvjCNa=LmhRJ$j)aP?~H%ut2#LP1-?WpR^wfS@e% zV;pK4(;DS>GY)mm;uU>@mB18-z3{@rIJ|J6ouU}V!5Vx9zEMdQ<#2lw3!h^6`ku^& z7Cf_aO?@X7(Q1AC;CQ`_#r2(SnLan)6%b{s042S`D7SjsQtPP;l`48)XGdVRmG1ha zojCYFLju%e_d@@nQ+ocP10ONV>vtLtjkx^a_%Jo>GVCyoyBq*C?q(Oj)g4gk*o$4F z$YUj3misi=+VEo!dYB^LC$q+ZH!;Ft(OhlhFAF~WRi?0yyhBeU_?XCb9c=@el!r{zo>cEf|hDD-mJ8knf(*hIZh&_q296Gi71{_5n&nWz{1 zP1ItzxpdH6+QJ^1twL*WF#!8&WsueK$rfg*j*y{-Y`K&ZVLA4}$iOJ}ViAtcPZS@* zY}nGHr+ikMfnKn2e2VMfH){3$G3Yn?cPCFR(x{k+6!zndE3(ufCUH1Ur=ySb$G`*y z9Y#o*f^aaHeqEj5F3=Kl&H|k$f14M#I4r1xXYdpq)TUe?Y-^9tF_J!TSKnwKYGgl- zVH%Fg+Yj;uOitVmIu>vVQy859TQdduACUy4MR=9!x%CX?7{WFBi^MIT!wpt;YJrTXbp4-zE0|6DU^x) zGia)U$~J`%i7-RCk|~PrllBpLatDQ2@aC!Ry#-C#fzt(F;=6Zy1{?FPiDqS(fqVA4Q|hYdYz|n=5Xox z1rVK|f;~iV{Ur*8_zixVSPpO9@TTo+(1#J<#JoR#5o_A^f(4Flgt+%=C5kIf;qTA!_rC_jWAy#Yz9PgU_(^#Z(4)`gPp;OELIk^>hG@$W!ME=h z-+~Cfy+$OMNR#{1rYUg@9;}JS>7ns!LGpz9i8Rp z^V9cBPCx`tuPHeh5j=hWl6FL}<7jBfWr%He1cI@ z==5alzgqAt65>i`-%_~q#WhETq{$G&lL!8O?+{lb<^^ z0g!3h_9WSpO|mDO&Yo;Kd$Q^5$)>X>o6eqWI(xF|?8&CHC!5ZmY&v_g>B^H$SDtLT z@?_JMC!4N3*>vT}rrSK(#G5fv?5~q#oUR{E$yCh5Lg*K8VK{!#l92W`I6&PzmtUD# z+BA*{2yib8(d2kK1X(Lq8u0MQ$9l25UVhpThKqdZ_)Y ztR+P6M`0@3_7PMc98x7PI>4VvXWwG;67g`V14{H^Gzoru3L_S8rzY`~y;ukHg)k+P^tOoHd-QAd;;E58my!*@T$3U^kdV6TR_SaCW?fVC!Zsj9k zHei%Lw;odz_=i#M%$&h5r8eA*(|m@F3P#ezIH^us)0HDz)YQcXaPq{63j||H>u4qg z<+rC3S3<6+E&H)9JRGhIUnO0D59|&2MNAilI&{ID&@l^JDW^%NCYTg~vYu8Mh}!bc zRs&kf$O-yDj;JX;8^AWrWYh8`kfMEpz=qmFDE&GLg}8)`=`qKKHfp10W5>eHnAyND zVyZ!#Q}QOjoToDjTPY87sfI}rDF4HPRb#40HC(13u?`Hz2dM$$cStDlIt+!*0{>$_ zK;(e0q0i3)#FHdEcp@P5;B!M|9=SENeQgnabfku}1F;FP!1gtbHgbu0x*TKqc)Df)h3h!J<3x)8_IL_2R58*& zW5_8CIfugoIXsTxr5sLT%D;15a(o7HKV8A$x8bS~Pxo>-n8P{__cCRUX>Q^0*9?D~ z<6j51bPqnNN4(8mvN7}jC<5&+@mhz9(5V_sLQxVU8Z`}WvWMA zrh3$6sz+U>demjAM_p#?Q4e?vA5yoWZ9X)Q_AZ!POEbz<37WoA%EppV8tqM#HAWRu z8;6(}Fh_%7&GfXln5U@X9t|UznVy}B8v#U;d~`nrKMK(Cv$YrL1y@5Q#DH79&$fNF z_4J(Y)4i0Q=MO|hb$yc~SM3z_`8x`~K#{uN0GmLjU?wT7bLPa)6nt?GRA!A77vdK! zlb|KQhox!(#Gw_#hRL$I(LjvGuT6RY96rG0dIg z26dc}uokBc(LZ|iZ8#aB6G{5V1PlJmc?lzmg&_7A|Kv(E=GO?@Xj9$%_H)kwLP8HPZq&`}JpsZ)y~T2c&A z9}(#nP>933V0Sd}NO85`1=NCDzbeHC_(iN1Tm?SZG}>lsPy;f##_mjO`|9@A8C`9g zEEY)l>zJ!1gyt)#>c5UTXH)#D%)Wee*qW~nP)<|-ji{;=qQa;nR2_IpzrJlTw2-TU zJ#8qs`ABHA_mPIyTaV;QX;X0I@K^AAp)Vc88^>GTj|rn^-YT7D)N$5XJQ7E2x-%E4Uz%;NmFP#qYdx&!hIcRYr3j^rL#3oX zf zPwt;`PO~Xz22QrNQIaj$536ZCkPU4y4fJa0O%V#ZvpBLFiA;ZxLaY_D9*>${lyMa& z3-K}9|7ll5PLID5rpMEJb6uEX!ciFuJNcGi)?||tQZ5MBWdH01b$LM%y1cS~ZTxUk zmy2)X^I3{*<8^39xVEafrZGgPPo+?Zovequiqpe(=-~sf!3uc||l? zA!TdPifGSYP!n5=(8S*UY2uLnYhpf2v6{FC`caG~zD{)dhZG92jWuz|jG`>!Gtfk` zhMVz=m?oYRriscL&g{)?s@v4sp;~s64^sAptD#@!f;!k&gbtqHKOH==|2mk@QmhWn zCi~`|wsg$uC~LTy==44cg}8uq@Z#ch@R)hRi} zwSH-$?GXj_@oPosHU@SP}Yo3(@KKQz*p!td9fhin56}K_6+P zGx|%B)5jl$>En{d>9g|V9Fqf5-WaZf&TIws?#3eY?nnI_;WU_fhvBzvNJFc@wq!p> zIMxG;9^pJy+|cE%;>b#%c~T!mA@(k??(Qf~clV!<5e}xErlBtoFotCsqie30_lLh9$uTu=p{EkXr<-#-<6 zz5gnh&r+-k?u2F(p@KIMnSMWoaG7Hj?3-Cs%l${FAgSNS_(euG_-yc`2=!ZC9NBgv(=Vq`h(EHHc3@vY5i5+3LQBcPt#WPTv~*vf zmdbEc;LvxYj>1B)K& z?DF$Ib4&=a8GWcYvKNaZ`+&&w3aBj9{mZQGuNSB8M=wOT6x~^xWR93oJ~vR^8#1T& z;#R4dnOsYIM+WYlbkn+;S~6GxjSsQR!TAd-eG%pvw;T7zvtwXWzk3JyEXDQ?c7icQ znCBaaOuwH(A?WT}O{~PGks|EwjZnl(afi#x_(e<+cLge9VaPeek~1a$gHvJC)H45gp@}Xqo1za1y%IOB2=`# ze=0ippRJ_D?a#{<9U+dSKCt*-)HfZX`1OVhVAwIor;si&M-$K{08s z1PLZ$ig`nr?IiuG%k^~FmDA({TsaCWr#o{&1#K-tLC@%)f{yxUE2#Crq7^h=oPv&J z1)ZT3RNVzN2Rn6&u$-rzg3G31aktTtIp8Uk`+)rF@`R}z`NnL=}5^k{MF`E#h}a@bGW za~3i63?3MQ)-dadK zy_pLt=&eO4=!5-J&=3FF3Ti#DXayZgI#*ahk0&yH8HKp?oqM167N?-MLqYfDq*&1# zIR(uIHtw@p*LJbRG)pe!iy>D>Q<5B?oW);F`%QqJ+5 zk6>E^VcLSqhDQ{nxi-evilXC*Lql+N{QfwF*h;9Kx3-PArvc^JA>K^8Y9DlHq0h6_ zgr)T?oc8E_7Iv}OpXEB>;9_WmO!za8+XKh;`f)hDB#7F(cX?U}wQb+&><}`ay@Cy4 zk(V6Vq8a9UK^7BI9-mfe+ci{`eGdg`duMQ#hajCnd5V_X{>YhSb z+)gVGg=Fw`Gk7v2L%@3P^C4M+7tCG_$z@GI+ow?W6_dd==lpSa9`{V34!a#x_ly}w z_uNcncov`G@`#WezC)P93T5ziDyM{Gu^RmuM5HgE5NBND92`yDQCvHBE!sIcrE%2y z$hC9d03ZBKwRszjS#T+D2y5z0@`5cHo>GwJnV7^)^R#4ZHAG>jOZ?Pm)acr5&tY10 z`o0%RC#0BjH#iN+I46b9)%QX@9^*8Sbv3VOHmON8zl84VEA~r*JucABuEG&Cjrq6P zk~qqcUqO8ga@WUYo#bNWhM8n&CfeW~tqAFCF(!0CUG4bY(0G}!j*9Y@=XoY@on&Mq zo1Rr$g7z_;zm{LV!>g3fT$#8_-dbN4{on%g^b&Bnp7BXGjs^WT-?9sD9T zAeTJeL3dvrlWQD~I;#y=LzyM6lB4B)H%U}oUovL}bMS4n>kKXjaw=b;k-?jmwqzUH zv$*<}Pr-FUP!(5qwB*c7?*!Ev2LKhunS<(}6XMdfy^x~R_fd#@C2-`NCT?O4*o5;O zPlu>uZzHn!QaVnu1Lz+jhT|j;(0+!9o{%H7cM(b8`UPz`?%{|hTJ&R;cP)E(-3k9UI$ue=@=H%^jJI%M=p_~EM;93BONN+gjhVimC~d!WjN15r0D#{ z7c48ho3D|Esv6BpJ{j3Ih@Aqw32B|04F9GgBJ8p@QZ@%%t58IFm zrgBo8KKVagc=MYHPaplb3vYfk;pww~=E9rbP58;c|H6fzZ2LaCV)t1W{zx01uG4(M zg`Z->9|inxT==7G_^H7E)`g#H!ygU&?_Bt!#XuJB{8{sf?gwfp)54n~ZDD7B3AZ%J@hMg}9wrKNfq6tPZI& z|DVD78#YQ&1|da@_1c{%J9<9oc%z9o%c!ICX#ss1J=&kq&D_0oD7WyaJB-EhLL{!< z!6)CYq7_}u?waord!uK7!FOv^5Kg5wu4aqUs!s-te)lCF*%Zj+st*_i3bS_Rf+ zJJ%P;&xguanCi1KKE-8y~1U9JzG#Cjd$>Djg}Z=7znHWWOIFEgH^~%d5+|c2t$2Eb&h!#g400VBxQ}u!d(r{$@pR5 z9o~h}5E|;Uh}W@KkkFTcrHgT@|BvyL@;smqx&okb+`Ts$5uD$@UwjTCboXAo84--7 z_K$Bw1Q!tujbDfeE;|?&{~jW^>|l8O=ZN6mzysp%AhHYD4vbe`Da191jf_u4j7DRl zM1o(V$%A<`wv|8Y8UCy$&|FKO^(Z2TeVsll2lR!A;j;#7S0jSYs?zQxTtcR`#|f2? z)!M6wU>rC^`xp_74ENIpU&Uj^8tpJdFnZiyn~O*ipDyD3L`@FkFZdR(h7EzozIB0s z$=OvM?Hjr=A{@62uZh%%uzUnnzt9n(b{|MERJ(r^h2t71q_g;wu|#?TP$dfx#I&zb z$Vb#4M)ZmFRKn4CFQ(B;yaaG_5`$^PSApe7A^8D(p8r6JSI|iggDI%E4A?}P#)E@t z3|a9lGhZpD5P-P{q4%W!N**az@<_3gM~am^Qmo{WVkM6hD|w_?$s@%|9w}DxNU>6l z6f4z8u~Ll`E7eG`QjHWV)kv|@Hd0L8gt?sj@qx|FxJG(W52mqJH+89NQWtb}uIlJ& zT~AXjdTc)_i>78F3=pXjOySl~tZQz}bY{DHaG^jpldJEV)z^)~&@(-Yu;XXKLcVJb zXXs}|O1oal;>nr$BGpmw9kq^k+)(Hpc5>q#&$-`$1DRTS!bxEsq5|O$#mw_h+u}P1J&B?lCLju$f&5SF`7gX zWkVCL^7UZqH~(7Oo9^;?QvfknRaIZrTfXdm%Nn=V&1}aF-??_&Cm^ad%vR8yERI5j z<;cHJlnsCtc4TyMgH$~KGF$m}`@FQcyevW$aB&AMnp?jBZO+fj;q(OC!bt!ZE^Y$! zmll-L0MD#%0Qgx8Olg1{X3;aAx4@Jhw5XP!{3@U{(BUM2>dC*ip!{S6BM-wPJ~Y9T z2rPympC;a*X3AV!aW_+Eof@@f3Pb31N76C|?QP`2^9Wh-5r%9wh``Y~;LIR+<_B`- zhv3Z08*$kOe$i^kW7|-A?x!?wY}}Nc-T@c=g`HMmb$NmGVqN`8vzv2)dk|nEF7phY z+rUT}zkovY5Lo~l!URyZT!?$Flj1e}A|`i{1B0AFjX$hy4VEeDGxKp58t3F8)z zFs4vVh@VEGSsxCCt9zh9x(C9z{|+gh$1h^S*lq~}>xXJj#zH8(Sz2Az8**@<14K|C zB!c-K5j+T1%J_2>3PGz(n)phX2(&Kk3DyXO2Yh@blOG)PlHj!g^lo_EIa6~toG5RaRa26C}ZLi3Wb=*x^!2VE+tmL=MJY7y@OxGD)mCAF0pqaX_Hx8U4Fr#O%_3b zK7AojpVs~B^=TL6)en8T+e==YK0QSl6Z=G>n z?CROj(lMi}D`%Bemxmb4w;==Ae@GDfr+V1`E{(r5Rh#UCj}P2%tDpF>4WsJcCw7Q6 zjMpI`^U0RJl-YpRpp*I&6*feEdKieb4dLiw)YuSKyEvSH@sSi_8ke={l*J(yblGV_ z48^SQR{SESO+T=-$&~Ay_BCs*((3Yaj&T46os17qsm}!t1E&4!hXErYt$qvxCVR|8Is>qY(+>0-*4xQ9YhbKeWo z+$W&9q_rck2={NGxm4@T;_C8jui}QZrDq4~?dAV^y?wx|A7RT1PkYH->J*^2Z+bKO zw54{gbxqI=`MDx;+wsh=D%ywdKl-kpXY3?g1y{(;Oi)yu| zW|?()rB{6|ssP)2WuOjY=c9Ym&5JbiY#$isP5WM76jh#mz8G#XJ|R>*rdri6v4npd zCgClRFikH#61^#=ZB7Z#z?1+jyesAvMwTD;B^o zc*}csQL*m9mHy`tz`a`~516A>#kAj80-&8#?JXVcn=@8fbzJ?S>Yoi6!2Zf0_SeXv zI5ETUeH1o7NK9rg_XE4OpCX7fKr*Sojz!wrvDg6~ z%lO?C!mW>Gb61#bMywKI0jNnn5t9w3>Fo=7&26|3E7Q}}n{8fAw_;I`$}G7qHK%ZV zXal691xlyXE1d?G&Q`m0Qt*HctU0GcI>SLt-}&z)9kyp?(RKNeVb4_6aY=`11H|)D zkXgeK4(?9*NS4k#C7mm{?yL`!&SQ|yTiAs0F@6z~4q0{8%+TUmriV}6%2=fxAm6jE zliNuGbFaE98e|mh;1Py>z(k|7(S;Qni zfH#X-yHqQAtLi1dCel|DHSJOzi~*_2S9&{R?nda{rCPRs(RlG~J zig&42@h;UW-lbZ_yHu-qmui*TrCOzSsaC07s#R*2YL(ihTBUZWR@ru`mebuxMR)!6 zc)xb3k`M-na^1bVGju-kAKIl_zOLXq>}!W9?FQGrPR}RV$j(*B`c zs^!z%yGMQAWB_|x0Wb4uKL*6UBZC@_in>M|nl+($4)%PWRwgCpEQJM9NIG+>87Q0@q)@d& zA?UQJRd&Qg13~9ZW$cJaqQbVll^(=N0M#Z`+TN<5lmSPFB<};Ek`p11$q5V$*EJqKWDQU$da<18tjU)e{V` z`tH|F>RR>P6BYP>O)#hNY*m~;SYTD0TBA5`ns5aGy@B|niBJF(2M8+XTP8vQR1QMC zZ6YX#V!*6Mz~3?9we?67UuFUNt_{k-*(U+|ejbW+#iGf)srWA@l#&(Tg0*{?`NF%0 zL94j44K{5!;P*Ca1_u@Ym=fwAS2 zx|@LU`zaLSNtVx!VENn$`CJKEQVoche16XIY3WgyFFOQemN+FZB?0-;_)6%~00~`} zmk{->t@#mpktrdo6MmfyXm;>#w88Adh+7CAzl}m6E@o-I8Z1q1H73?UORtTXG%q7* zW^xTJZS7sWHf|L(C3nT76Xh$rT`_-q_N^Fdmt)gtfzjr6mdWKxCYQ2IPQ*5W01Mav zncRZfNR>5WGNCC^Fn)d)RyVRrC}v4hvH~^BiSw08ML>rw884ww2ql%j1xsZg zr1CMioOlxm%SKeZ&yrZN-%Nd&Btpy%uA2rH`RBpfw;2!)U zCY5ifx-uuz)7smSG1_~xtSPyj<>JKpN@jb2WWL&8$=n1U%lKmy;xJs6OpZ2v_)BK& zTKGR;uk$_8+ctiQlFaNyCrwwi#Vlt^?q;dvF}@Pn9Uze(^;aU-@s9Gl)sFHdERkn| zC2|HNaue2YcjFhax^k+Lh%xVC7BVHbaYJu_ePyvNppD-_t;s#$6rQZC&?tC}2I%@8 zaCXlUJT{MO$)d^jd9leKS~Z9}$|RP02Sc(b)06vUxK=Ht!aejlJ!@ zfZOhiRoi_PzE2Z-gJshS*}Mu`>T5)-*0^P3jQz~grsQi**@TS^Uki}UANnVo*H|`h z*kyBUOQ1#j9%S<(Xz7b1E*oP6XqGl5_c~=0HbUGRAe-OyPc|>HY+km@=IUVCd0}j%D*JyKFuTmd*TiSOfqqeR0HPV~hsP z(xxOXQnj~7VWY)o0%Y?-|77zN%jTC#Hfn8b34B5WdTG}{HWP4V!vg#wCL3BCGkEVD z5t`*q$($t}Cxvf+AQvE?FZEA8lfh{jpGTn(m*c02-NEwtBjnSBS^jnSMNB?l&&wx2 zHZ;qclDAs2$zy%xa%+HG?&_ahmeE>Dd@Y4SkavzIDq92V&9wEfX&7Pc#M*wup< zrKN3QXWiQNZr(7GwaTi?`!!fJ7uHuU_iO&H(2vk4(&;$-G&m{aJHSi4`vT^DcQEh2 z2HqbJIgzeJjQ1Cz?A={wWO^2M^2pLEXG)IKa4fA2Lf;=wAtN=|hL`)tnd3mVuqE*n8TxJQxK>12!S%5@VkVI}&b1AEs!z17v z70^n59#<~!04;GjVjRxoIc&DUR#8)OxW!`&>C5He0bCwQT)tFsS$Sb~26K5cxSRtm zaXMmLCNC_*dd%)#(_$4fC1+b4W`r+yX9sY1E^&9e;;!-wc_^5>Pk_60T`KiB9KMEG zLz=pbm`qx2GBND4S<;kj$qOaScDDpbB|}nqOwG2oF^@ZfdAtTZz7DkX_K5MAu8>z& zW%X*yKAUAt$wTs7wy?h1e@FnI4<$a|t@ylx`TSropYH{q&j&5NKVp1tw(*&*v{}xS zT$tx^u>D>bz~4sV?=HpP|6=}@!TH5|JP5BUCpvLV&rm6zIv{HN)t*Dy^Cy3t)ZN~d zwTi0a&UZJ?SBX#dAMIQt9p{4BT*G0Mt#d)_VAr`IZ-VFjI2Ys*h)3#AQYgem7V1tC zs{exYe?zD<(SSEaugkLuWycX&OWW!@bB#DpJ7X1efV@X-_;R9srFxI_>=EYL@B{Bo z?K#vDiZ@Uw#M#XG*Mm8KaF-B|&XVHk*-@)bu^o!@>;}+)MbfU$#vHC(U1OCuC9CDc zKS>ggm&jKP)&6d?vthrSGYNaZQW<{=OvOj6Wg*OlJ4}H3pAR9tj!nRS!!KfO#(I=} zHM;tBEgLdDEsa>MZq3c>vPzqhPsF4T-k1AN1kAAgoMzZQ2Jb9hUm48nUxU|^Q8~!m z{2TCkPPA0uARP{u{g8owUQ>#^NJ{1S2@-HsTqY1TN?*|Mr5 z!d{|=}HuX=02hjgV;yh5!uD$bu4%=y*eJe|JzB7PCGPfpHHV9uLG z)#ZJ5&MTxZ=kE*P{9|6uKL#GcCyzoQjMZPhX`&2^REP%Z8)ePL{Y&S&e-gBtqj;R<-nTGM`VGy0NTAoErOVg36 zgD5D+E#Y|3xrC>4Rm*Ak#gqfCWel$T06k^Z(l6^2K8dh`&sDA9b5$$&T-6FbSG9uA zRjuH2RV(;h)e1gWwSv!8t>AN2E7ZBF73y5o3U#h(g*sQYLY=Exq0UvUu$`+~dU?Oj zRn_`)t}3&=L=0?d-;il;#!?nV>O1Q)ow@dGrnRfHEh`4bhDbRD919~#1szbBT3pA6 zw=JE3!`4naR7%=CmWMHVM#EA%iOq&22%{R7%~(7e$PG56f-$m#akJE0>-jXqui7zyh)U83ap4A^W=U1u-}FKiqjj)DLOT&h!{ydy zX!*G}D-M*ER6Fwk@g8&K2gH?_uR*KYh{H%={HCFXMT02dWUbmVMnb||WY**nRsyxFttHo@s3{Vc%dA|E zN5o-_d>=u+9F9l0yf}0SQ0h}Dgj)iOy%xR~o<5o?MLWd)0D9Ul;TJ8j$Ee4|vZXWW ztU~H?nao3d1-{JfU!z#H*3)Hp2uzdl7bz6tE6nPPf?54Tu=>@Tr6|D>4iRJZ`6jDd z*JfJRPj6js6*ML9n}>FrIc_0+xqhF2HG3RfM;n~U_IBh1J<5p2on4jJ!C0Bl)#(_} zeKY}o4HiY!85os=wkdj|pz$(uyQgm^%*6E0wnkEav$QEWUs?ijkvNCwO6liIf3e_b zZ+8cJA~By2F>AIYJ&$1V1`36EjKy*)yfXrf(K?7_Ha633#4lns%&_?&~8PuBp)bxst4$*HuJz~bxCPnX3KnF9Ry3{ zC=`OGB{cDqU^zYxIgYqViaGd2Opd!uIp(-}S;b7rgYsfDaK2JJC_svny%lN{*ypZL zhx@=zBv^blg+e^V!Z{dD1_71qpgx?Mc^*7N@QavmevubWLuSo%bjvc?tX0^Q{M4#w zxjq|#ube*hw|fVEhRU`R9Cuf?OMPH_2$p!7Ld-<4JTD5C=LL`_bt%ZgM@*g%nDT@f zTixEXK^aH0uqpYDB~J%|uRP!Jm*?OAaobtWZJV=aGn8P7!zncF>skUj!-n^*RZsW}>BWCsNJGJHnK+R`A&%u~ z*k^-8JN=(#-Hv~e%xLH1hp8iT{Wd>>O3ePve}YJyA*p->3w z5NYBBtp5kh`c2%7>7Og4_z=Hn)gSE{)5!JU3<;}{DS1+U(vLB|b>}31yS7B)G9}!+ z+^;!5%;fp!z)YV16rXEG?=c8R>K{;O&glJ!MC#sXrAF-ML8R~8AjJr@aM2QJenyYB z$ytTe<)O+PGSpX`hx(hs$(}ik_rW+B9}d=m)qA-1?2lFKfZFpSSlx6jj%L9xTCCQd zFl!GjH}$l1W?Ncw?X^RnK5C;QB%yQ z9qg(nD$#K8jM}15#Q`X|bCT4v zo=c0CqO7@Dc@H+XTN_(&(VQ1Jh#dc#n^(2BHa9lln&&m`Svc7?cXc*r`cNNn4;E&e zLhw4!SfHglI;-Bk7FR`Hg6GBg(o8K)fOwjF<>|XFih=H3gjI=4Vq(A#neHKkT6!j+ z@ieKYT6?DDZeE6!E408=>zwDI)k z5psIK6iy#QX)0gkY>H9;r*aWv79&hAM=)R|0xeAo;8he}yA?Yf%RuB&~JWSF5$_ zYPEJMj*Ac$dYh#u=Hy_sIDu+zQeY5fE#XWb(` z2>CdGB6SJ!G+>r>M(^s?r~{}vr~zs1cqvc0&IiLw_^}D#1uLgW{g*5M>YhxduB*2* zCrY#y$wc*N%<^o<1@glq)1}~l2q%Nkr_z)>ih71hA z;Kg;*>B>6xdPt5@xIB!}%IhIzLlT5h^C>H=UWE;*V2n1MB8J$|3dU&DDPn&cTEQ62 z_dkxZ;Q&ww_IfzPjsZlWmf&l~+A&KQQEQfQ$ylq528{C6sxq#yAq4Q;|HOsixhR&B!-En!k4QG_GR(W>h>=>hrwS4#B8FtJPA*iL(#4T{i^7M&~ z=KZBFMXh+!SZU2)U?xRm=@F81(ZH232p3AcOW848mEcc?K;r z8DxWsYSy6lLm0FmiVRvl+0Y>B*Jp66=1S^bu}&$7!I)uinF^{}Ux^}Pat32+O~!06 z8Dl_1Ep^_+j1a~=0>(T!Q;5rFMXqX1M&TDX*3~ypuWhbxY_N(sM1CBTc7$vAXISHp zV?+EA2~EmTTI_V;^l-xDAmvoDIMc9iDn-5_t0;;QBlWzj1m-wtR5EYT{DqyfXm~=s zZzsexiTDg;g=1N}y4E*myVY{Ic#&cDo)~p&1SATt23z-!dP#E`>h4HxC1~PO3WcFG z-wRQiHD{rBhnJG#L~BYRmRFhytTbjZhe({Iuarh1{B`3GK}z#}?Ej(Cl=vu3g|E^~ z@jyvwwlUPLG`k6!_$h@#Jj-px&?xe z3EN0h4SMe+u>Kr{C>1v#yF$d;3bBq{DaB*>MNF*Ar~zTI=4f(p1MIU|(sH>(+5~Ii z{Ux|W28i}jOh*~A^=miaq04Q|yO1_V4A0zonNC5IHw2@&A$z|^#N|@wBgmK6$mV>+ ziq75*voXNuC!29B3$!z!UAVO8aL8LG?9EGl_`k}7BP+6*p!%Z}3ULN2Rtcb#mF3$SD@hv?;~v$+Tv$+0ZIzxxC!2S0>tDtu7BzE1bqwQ-oSQQ$VdSzY0BQ zP@mW)hPTFqJq=9?>hQ$n64pBF4Tc(e757y86TNR(ZfajVs0-y%O95?hswMS>CK6O% zLZJ}%BP z@D2B}mC@e+i5E(OH6*aN?2_nXbXbf29EG@Dlg&m2T#|y!#$AwI#ZgjpPmP@H-nPsJ zbuyH-H;Y;=_uAT{JlO z+9_Q!9RUG3YpI$|oy+i|XZia)kD-E#3;Xw!2R%u$;lQCVy2NwQ{9Q*wFCjq_LN<(^&3 z2IsEvZmyjJCQ2>82&7hCItUu?qfiK1anr=>A@=8dNaP`GH7UbFUbG~ljdR$aTC14l z@|!N(Q|ms=(O~*F1Ny-au*(X2C#?|~SQsM;yTig~TW25ls0l7L?jbj^)$NXaMu#|0 zWsaBf5OgT$(ez}@%Fr0imUNk`pF*B8VKj-B>D_08@>jBoen3!tAf#_q;8pPd3#!2T zpe_x&;GKbAwA95_fhRC`%%Y}bm8}9RoPPzb3aY@1y%l%~m}sxSYCzjZ(D)7t%?kVw zNyNRylw=4ei&^IgaodGbypLbBB;u;T6RcvE%bl(YJRzV0?+mEG*T=}`%v%wS3OvD6 zf%6db7`*w4n9b-<1>Ox=dMohrHYf>Sso`FN>hDr0#F#kQ`)P2Y3R0KvKwTC!NHMuF za_Vv@3a^ab>W<#*+NM6Mpt>9;r4!{}dxv?BwlHd0la!-FhNz)q%cU4IE`}?CIa9%L z3^~yk?UxrYG$_c^mt1Fpa8Ou3Z(qvd2an6<96Xb|Fatuf`(`{Y7xVWvV)(@c$)}+F zSOdsnquiRNKI{B^;PmIlsE4ur7VaTIyEchXN z`}eXKs$4&=0w`zlFh*4N?}1~9T%Smx5T)ER+#O;m#_Yh+Am~O?CpKaYOS#oE^IEdGI@)+`@t|BjVV~{pVzm1J?a{SnSp zIkZi!?94>dPAXYG{a{&rkz}W>$v@aM%oLIL?MTkVpFzY=(}Q zI-mn@G#rLd8&=Kg>FMgpS_LkrBWCjpBW^N(LEjf7=*QvT6w;XZ2pSXVEb+RvEuCvJ zZ7vO+Vk(3`x_?@NrtBYol}p9q&=sjqrcj6zS;g)MQL+DliXDFu1{e56OvUP)DptR` z5p6FWcxe?_mw&d+WU_|YsQfkT&jE9p`xjI&zcm#o8Lf%1#o!2RNRTmtPWe3o%Hw{7 z?>dc3Pv%14&bg@k;!FqO^c@rmaWa0I7`p{#D&BDwd+0V|h*Pmf zRKmeIaUK@^zYjoJg*-U+AB2w`EcTO!yo%~h$=H($7B7=yXlaR(u@@9f-%pMuI!eY~ zRKH5GEa_OT)tRkD^ofs$JCYJPoLm7GX0N{S@q zz#}GIiG-YvlBEHTmCLCm2N6CYj~;LoB4;J!v;m6{*_x2Y4Cq7TO9^@GfL(}eNyy^{ z{0AauCgkx0UPokOLY_Eaz%}qdO33L04o4)HkTV7>LL{4zbt1{{(B#Zt;|-#l+4%&q zGqw>VFAzH~K;(V=q;@e#mhHlKRmcf)Eh5Ch1Leg1U~f3tqhRp^#KzS^6OF4O) zfnVinTr{uE=Rxw!CkwY>kUsbTm zYB}q3_)JdzMZwZla&|3XoE!jGd$4CnwVXqAoE)lPHPy17V3ZW%Cu|1O@SU`_O=QSV zdOU~Cr<1!hhV>OY!HGy6s8uow@^pFvdG<~;fduaR#C>!3!dTK#KD=%qZ6z2m4e5CL z1cU?0%U_?%>4i+?cKa`7xBpUh`!8j;|5A4QFJ-s?Qg-_*!<1s$o%3fKivOPyo z{bdTx>DMW6It>-%)UOE9@pUO~#V=xlq(zijHbIg-Q;YCciPM-}bMNZ0k%dTZSeRIk z;L)&JofSu1W-jAmJBG2iYfVKd8css$-W=%1+DNFmw+OH(AehY=z zBFy#vo64;1}bkErV2|0yMAAAcz_4_HrY4y}&5#!)u9FL7h4^KZAE$duF?!ixLO+XL1 z4&Vw{se=%qKJ-92kUFuPJVL=@gJtPp6oQf>PC3vIE*pV_C_RDRu!-JKV(@B1OMBGu%oX#$j|!Rq)YNNXP=5apw-Gyz4;2k#>n0h8%N z5$b6Ilym2hx;Yy4vqbrFgmF%D->2r+A0Zb3lj&xJdYS;`+lXo%0<8^!D8JZB6HwHA z_fzB|U^0yfG4w`{gM9Qffy*Bx08YaZ8az^wmyQloX##@wO3>E4Dm7903;@aW3kdZz z0m?rl+E)>1FCh@+C9u6JO+e(`6xT%R2!e`)CbZ)a)8>{#RUST56S3c+J1lCB2Bwl| zlIe*E^)vy>8z~dhABC7G$8f|*6Hp9{Hzo1tO$4PFKU$aOaZ>8@d#0*Wx?jHn<=P()M|6%3d#VnS3zRLlu6A?BPDX2G0uPM9(0teA6rP4~A> z&D3=JzWP1)kNeMeeIAy3uf6s@Ri{p!I$hOW(@fsjLZ+U0U5ens25MZU zz(nh3zDWAfsdf~rkf%N7m^4yLWEf8eIVKR%ahSP%0DpJDMCWC`NRzA=lO-~Y=Yv5k zB6?7&s{#LVz(mhyzDScy?Ld}Djz1X0BBEcUdLQuL1UUY=7GI=ER_aKW$S^L0K`bI# zTB-!_D}aes&U}$38P=IBkzu?V7{nr?9i&t6XBBJM{x)bnk22AvB=8H7RZCz{Gnut4C5jg#3G`BQpJED0VW!i`68LAmL*GM z7>@y&qadPfq*@#BR|ibAd*+KY$@YWE5*fyOgF!4JIzy^M0sjENM3-m2NRxcopDdAK zybugx5z$jp-3s{E115Si^F^AZ?+~&?hVgq~5Q~UB-Yt>)0^k2ws;H9rB29AcQe=q? z;|^dDi-<-@)f4c$045rr`65m7m$F2L@kB6)MMS$vH5u?H0VX;m^F^9uxUxis@!?<) zi-<0j>IA?)8Zgn#nJ>~LYpLf&hVdO>5Q~Ujm+E1_zZWpkXPGb3Bp)q9mdG&v8Vq6) zQJVr;|H1cvkSgk)`65j+PdzU(jQfB=EFxM%s$~IxAYh_RGGC-gE>zEp4C5`pAQllF zB-M_9zYW0rm-!-1(noEH4C9l*AQlnbDAjp@e+Iz(m-!-1atae~MPwL11_rT+=o6`) z2mGf1=D*ArX_BRtB{Gcv0E1XW)U`-f0q{M5`7iTDnxsj6C^C$f1A|yZw2@RR1O5nr z`7iTDn&gh9$r2gHJA*+iB05H@y#RkVfcY=;MVjPWohc&2_(CvYwE*xh1(^Rb zU!+MkR$C&&_$4riMMOVI^)BGQ4lw`KwfG`Ua?1d+M22xa7{nr?rKD;P_-z2@zswiO zJgz!u+X4SZz(j9nzDSeYtF}aj@dscKi->Zp7II(V`=3Y^#hEYCBpawV zM22xkFo;D&qonE$_+0_kf0-{5)#T-UCQM=Ss^;NMpc(&Q5Q~ToQpS#ezYW0n&wP<4 zIsbF60U{ayU=WLlZj|agz&`_E{Aa#MW`iYUiDdkP%mxtACsI8R_)h_h|I8O@l1twq zOC;kT3}O*c*AiI;!1n;gf98uc$=xflUm_X*U=WLlHj-*(z#joH{xe^sN%E_cC6e(E z2C<0f7^(IG{M`V?f98wiYPvC5A{qZ6S5t`SeyJ7!{-prpKl4SJq~9iFiDdkPK`bKr zNvd}N|8;=z&*${i7ip4@)s{%cKN!R!qNSv25BO~W#((CEG|5hCOC;kT3}O+{c2Z3M z{51f^f98uc$yLe{$@m9@SVVM|REGinK>*`F^F^9u(57UGWc-6cEFyYFs@nnoMu733 z`65m7nc5P`_y>bnM3iG$pZf~m|3s=N&U}$3*;Q?cWc-6cEFu~uRd2xW3NZdNUnC=6 ze_5uqrPy@UTiQu>y0R}F?(Et%w)=cx^09QK3!NZav$w?NDR!%ir5{N&dP`4bgm=i^ ztp6Wnsc%YewX*K>N~zS)vH`6h6Wqs*zk%;QS(FkdXAYxQZ)dwTeleGi<(5V`ZXXw4 z-PyZ4dwpkL?d&a`?N;Wcot*8~*QLFj{if3#DckjtKfJvfJJ|)@lDc%hv)yvLbd|H+ zqPcX7v)zKa^nkO|+^1!GYxCLClwNbZTP~MAa<*Gam%eqjTM(E2aJE}4mx^uFKW@oe zYUgaX94HWru5ErdUb}M5~nyq-PKH7;E1ua)wv5?X4|Eed8@N$I{QIq zpYH5uoPC$GUw8I<&i>fh;WEno&e?;V{im}xbaow|sB?Zhw`J{}{gLB)I=g;ZV9H}N(luL`Teu4sd_iSRLUp-wR`kIu!Q@*Fu&rP_ zYzKt#G_ZUakUMxkZmQf1AeEhWvHIN61nY8V!dN#I<}|%ET4q-n_HGw;T+t-@e??S2 zegJfSho_vs7_^@OtK_z)SmPKf$f(bWtjisP&1WyLT#4D9-LYD>M|PsKs*(^Y4^>>Q zr`M^O@~WA?tn(*jeoyC5Yw>+|Dhb#?sS*|FFhka{Y4C6h)AbwU^r%H7&;9mon=#tDAX%dMl zBE$GfFo;i3)*`8H0{jmE6TO!CB26MuMPwMi4RZ64D@yd2RJxq{?m8MZBrU$X#wHR~ zM22w;260b)ELdKuZh*fYV4`uEFVZ9uRYZpI+8`5)vZhP5G2kBwnCQUF7s;(4Wr+;q zL%|?^cs;gozEsBo{#}5HZpeI*CXuKjGK_BpgLuVhWW6HQ1AzZ6V4@|NFVZ9uRYZpI z7hn)SIgzX~3xnLx_$IN%jqC}#K$T0p77{q6-N>=AiWaR;WdB8-2GGC-gB&vuE z<7Gj{ys|csYDK`G4wz`$%ooX+SC+^y-Vx-|tE{`69W1D@$Y;p9co< zC!@)_N2)6T{}sSQPiMYJlSot%8OG0pK|Ey)S>H?b7T}jVE6WE{U!+MSs)!8Z0vN;# zlr=!Awt&AHV4{(kFVZ9uRYZpI%3u&Lw=!8%q*@E`_XkWgGxJ57M52nwFy0Fc;$v4K z>vXAR1O9b@i7v~0kz6eiRYZpI0+5^7W663_s#^g6Bfvy&WWGpleIu%f4C8mfAnu_o z+l8#p@%_$NCTh%lktUI-A~KBIgF*bGdSkd$Jpg|Lz(i|izDScuR1q1*6Tl!oM7=RX zs!aiZE?}aAGhZYN7WIb6Fg^?n;zi23M5^Nf{~o|ZH)Xy^lSot%8OFDRJP1%9z9!W} zfd4&UqE9nlB##f&ha$uHD=>&Xjl+f}vVO()2Vj|~Tjq;2i9{8VVcZ+!qpqK0vDvMTYU_U=XjOEj&=FsepevV4`C)U!+MSs)!8ZlfWR3)$=za>p zS%WiQBwL86B9iBSU=X)uy%23E)o8$<0r31U^F^9OqKe2c-U;OPCyV81o>a2{{}RAN zXJ@`hZklREEi#NR0E2i2>yYR^sjdS2*8meeoB1M5B2h(T7{3Sxal;X0{V3Htfd3a@ z5|I^=%zt1IkKO=P=WeL-fWJJz{FnJ6O(Ic6B=a8_#K$OW1F2R7{OJJmU*?N6i9{8V z%zt1IzoM+UQtbiw^8x0+%ok}Ai7FzQ|G*&bJ&CM)q`Cs|Ujdl^GGC-gB&vvH{sXy& zDC>Kv-U9q`cV+ot>WkzWqAZcje;_wWl{G-Bwt&AH!2Fl_BDuAyERoEAAdk{FBx?$0 zZY{vyA7K8=e32%Rs3Ma259Fq)vQEd$%?AAI0Or5U7ikiSDk7Qxz#x8lO|qWE%-sU` z9|6pNnJ>~L5>-Sp|A9e#^?0&u53)YT_d8=T|7E^NlSot%$@~X$sg4KydjRIY%ok}A zi7FzQ|G*&rO12_zDScuR1wMi2lA+CZL%7AlJzUTKLCsQFY`t6fC^DX zB=a8_#Aj>2#!0md;7Wc~w#cq?t;fl^Hc{L=yEzswhD5{W7zng75b zK1y47gH-1N{*wUnU*?N6i9{8V%zq${yVoIWiByXL-}X}0&zUchhvbMVBANfdAf7*g ztR}R%5b%e)tihQt(j*d9L^A(@JSbJxhEk0N{22iAU*?PC@v5>!GXH@={FwG@o>a2{ z{}O=tFY`s3M52mF=07lqZ`OX@C)HJe{~Eyjm-!-1B2h&o^B)+*-)IYel#NUkBu5*fy;fI-||Tez)M>j3_NfQk0V ze32%Rs3J0q_W^_Wtpmt9Q>r7fCNhGR>4CAX6ipN2)dg3b|(F-E(0sJok z6X}C|>WgIcgs37ij6VUn39hUnpKo*DNToXo z>21M8WJP2cukKXG=ySzXsn(NfHejN?GhZav1bwa$8O8^Ij3d=PSE?fc{}#YR3o~CN z<4A3Z4CCv;AYNTri>0~?@IMDk^j_wRG>JqNkzxEX7{uFX?hN~q^)0^N1It7mGGC-g zB&vuE<1SzjhgwyPmZ~4%Zwi=bV&;o9i9{8VVLS=sk&R~eSyF8U_{RhMiTKPH$%7uv z?jpnZXpjff%DPIbQvv@Wz(jXszDOQtD@$Y;-wX1vcq6jjk!lg({|cDs>&zF)BW6Su zkzxD;$ZVmkcKyiu3*TP`%S3%LUnH}IvP6dQK#=`X);dxx5BO676K#?CBH1rxi45ay zK=w;nbEKLM_~!y9Iyv)2vR}#)8OCRT?AOL*-6qw1z+ViQ=&{Tf$$lZKhz#SWK=w;n zUrO}~;D@?#9sQB{BH1rxi40>8K@iuCB&!!@t_=92UDk4$FVZ9uRYZpI2(T`H;I9QR|7X5PzAAvIB9i$Z z4B~f`HC3wh0Dm^X{Ga(EO(Ic6B=bMWXPe{5I#;SA0sj_&`9JeT^4SJaMI`e-$huEi zi>0~?@IMEb|1)1C>po?PWd2tuUdCNH=dMp~c`1mWVf}tstba0Jq)8;Ih~)kk$b)-j zttQoAz~2gB{ge43dEBook=*|RgLn;P?Jw2#fPX5$`X}>6nna?CNbY}u+~d$a-|M70 z8}Jtatba0JB=v0fYF+L&+-gkTCZ>zV99{CL${$8UJ7qZ>hOy8L2t~{#pRzKl4SJM52mF#y=Ru zS4<&ms#NO%zI$Amh^&YV<6WHU!EI0-E7jgoxd)kv$cjkT|4y~ER5wUg)jYsNvol|$NhGR> z4C5m}o(O2xzD%kU0slV0M7LzVNS+92))pDYcY<6Wk0R?0sU87*_YgM`SrN(SU#Hqh zePDT%nfqKS_jorESrN(g53I}SNiUzhz-X|v9f0)NXCks9lFvV2(qSk3(X!su$XpXE zh^J}4r(xzc0Q@-s<3IC7nna?CNX9?NXNNDiex5JYT)@8#VEkvkNIp9ts)%I#gF$>b z?}3b7km?@5{}N#QXTC_TJ%}nI8UG-woUh0#4k7D%e7_eK>;KFb$tnj?MI`HgFo+M( z7LJi>0N`&1m}tGs7ikiSDk8&pBar(x-;uSqR8s)|M1b{A=8NRM4Wf$3Fg^wh;`_fP zYoS!91O6ib>z~XQX%dMlBE$H8Fo@6jnymMvdJ^z|16coLzDScuR1q1*KY>Afw6?Ir zP_iuG4*^*JWWGp~NK_FS#!G=gJWyLWQL5p9KMi30lldY|B2h(T7;gs#@pj*kb+}YB z0RMb|^-t!DG>JqNkzsrm$QSQ*yzY?d62N}}VEvQ%B26MuMI`GVFo@sQ@%mb-*8sn` zoU;DPe35(wM8``c>mLL`ysAc2AIw|>;E!=x%V)kwlSot%8OEc)ApTQ5zlBue0Do_Q z=U1&Do_}S&NYIT4n4`BYw ze32%Rs3Ma24-DcJw1t02wFK}x3{zGaOns3ik*Fdvj4NOe@1~w#PO2urp9paM&wP<4 zk*FdvjK_m~&e?$(U}vc|1pLDRuK$@YlFvDaDk8)95RfsiEBA#`%>(>90IvU;FOo5@ zE4Ronz8MVSWk!+pl2rEr{?`E4|I8O@5{W7z!}v3huPrL8etEKf#P|DPasM~-Me=1w zWr+;q?jT>e@u7xfTTM27JuAYZK1+`O+;+XDU^fUjR_ZWhV> z2L|yN-8VQNGdCCTZv&YBGGC-gB&vvH{sXxKur*mPNOce3e+e-EWxh!603fP}Wc~xW z^Ea2Q;tFJakMFy$>Lem7BDwy9LHym0sFsncBjB$EF#lz~NRvoZ5y|x*t8U4$LpwlB-OKk{};geH}gfBM52mF*1sTk36CbL^9Zu? zfbYJHm58i}Wc-6c{NCHl24kffB-IuG<3IC7nna?CNX9=H#D8c%_LXW|z&{z_`A6o9 zG>JqNkzsrs$Q@&C(KS+?3Ha_SVTs6!NX9={m-}cxeK+M*Fo-ujl8kqhu}B&2i(`q% zipVhj5abtY>!HezM5S+&`R;3EQM=4{UolH0s)!8ZP9XOv`Fs$qC{-UI{d!;`vLcfE zpHB6WzV)!JRO?7}Ai(|4%ooYLr*A!orAQU0R9aC_dhdVB*z(1MI`q> zK~`DHdRnU60DlQ!qPH?%B%@qeBE$H7koyhF@<);NCBEN;Wums3FOvHW$`TpI3CQVSUVy(L!1_1yMVdsSib&SKAS;CT$eJnDW`I8rVEvo5;NThH+nz?+3k4)|yfc0sL(N?tf&yNWLG0s3J0qw*;9fly$IF(*XZW zfcqbrFOr!;St7&u6flUdSJq8Zoe%g=1Kj_}e32%Rs3J0q9|!rNh_XJF>IJ~}S5nrm znJ<#>CMrv082V`H~1pJXMYnjX!X%dMlBExtX7{s%bwXsxV0DmUH{Ga(E zO(Ic6B%l94o@FTOSgG~~{L295|I8Q3vkYa4Wc~;FCW5jakZK{|zX5RnBlAV_O$23$ z4C9wURz4q+^|Ms(0e<6XWrbksi)7`4s3J0qOJEQmK94hguv8rYKmA&%$cjkjf3Tx_ z1x!cx3Yd=W6)+v$D_}ahSHN_1uYl?3UIEk5y#l7Adj(8K_X?Pf=__D5rmukMn7#t0 zWBLl1j_E64I;O9H=~(p&nD$e6HRkryO-KD59DPBs*>B5F$0tplCD?YB{_69dyfD+0 zecnW?uju{HXuHWP8?*DCJI@+5YSPSortaz9^fz(a-L{=Jb2)9?D^FdAUmVbNCzP@yEk&vStVV{onPocz=fd z``eRRc9gdX*xL6h{rxQgb#;GdD)}7mPS|bR8B@)q8~HmaGI;arhU*)B>zDuKx1$Sb zvY*G9W#T#XcFS9Svfehw@cx>Mt@(_9|9ADaH;~=derEfZx9zOHJ?zN8_h!46KY*Tf zO@F(B)!*Ekk)EqYzn*TfeP)o>dBF95wg0!jmUlm$Yjgi|c6h>t{^b;HKHZ=HKj~Ud zf+@L4oaw^q${RV69BI<4c}dP5c=crnFs6U}puSpunX>PLS`m;FwHz9^q@mKjjKs zQWJPV0Vyc(5s_cyy8=&Uy5|We7sGomYYRTC35-!d3JUZEr^6v#VL{0LW| zPfg%z1*D+BH1K)(uE0dRw7|-QzZJimE3jitpu;5uq@aMhawYk$zzLadFTz`hztk1D zq9!m$0VycJ6Fzf!R^Zu8w}9{?;$L?KKB)qt5nQj7M|1xw3 zxdIDo0s|C~f&yO>Sy#T>g%>j2VT5OhztI)=q9$;v0#Z<5=^THWDk~7wv$nQn8!?XEy~j4SX>O<+X@q@cjiyfNFzce{|_r45}# zc((ZaU4bDrfy)$-f&#OMJdqXHEYm$o_*3yexdM7UMOs;bhARokpuo*UhRJtZa89QC zo$!X@mwF9d>86^%{t8IJ>l81*&b70*x*y#ZGEZN{Y4!9om{#xG8c#oYX^rUzG_9U~ zp7T$hE~c$9t&>~5&NZHX)YBTP_4GBL)|h@S)avQSMy;NHE7R)fhexfR+oP+~p194| z4|fXxKlXxt1x{^^k%E2PFX^2V@5{65m@j1YxW+TiGo>=xbZEYMzh}B!rK|@upVkB(RX_^bShr}*&oyo6 zvS>=3;amGESxAQa30!FyfwY^BdDt_f6}S_FpXSyCrYax>ZQMxYIQiLrOml6_u4&^M zDcsNMN@r!I?x(`@3Vh?*xS=NS9|feK4ZS0x$JNzs=-OyXAJnw5suVh7_-Srd>L)5p zQ=qTjXj^JWrE~`sI8gx^v~d8DTWi|T<_?82Z$kG9ivO2MbxUZeP_*^=s?96qHDv#`d2RDu*wJ*KWc_!N z#>amp9oUi-$|{s?l&{*ShP=+izwJ{SM{1w^Z_*vjCAQI#^8FuDGDvL2k@8Kb!|?xI z`Cwd`RWl9c3bs?;ue&xq{&lvq+XVT3o0RnGY!^q$FAX9uJu7Zw;^-jB4Q^^#y(X}% z0#a~69*>>tWqaf`O$N82TTjs@J2LMkGkpdzr6b^5PoC|haKDW$ou3uH_$klqufX#d z{4~8LaH;}Q&_?ITn5*SC*|BLG`j}!$dhtYS8}~_}3#BPp64Jd|{b|p z@Qnge(8g>c#p_%fYo%>y0m@JF;al72B8B_SZE0#&>W61Mvz!9GwNft~QWKb{fE2Xx z0g)ZkHa1Ax&>Gd0uCHlhe<{-aSd^6-Na>Rl*xa@8eobJ30#eY%nhnN0B)`dSk+z{v zWTq6ux9-O)Qn=qHmj)9^`|4GC`x^xcuCLap3DjRtKnmJeNTiSaCcAywhCZ~J(thx* zZH$z{{odKVnj&o@qVyyMR(5SH$l6d~h5|BZqoIv4bLBVL8EG3@iki}!HEoBp?pi03?Wg91BYm{LTgv~dNVR6qu8%p&rk{3g41+J-*0n9?fnt^4t_6z+G|rOgPW zrS9d3MmG@nN{6tyN|(a7wy}{E>G8NHE9J43(-j!% z_T%N6z>x|_K^rSJ^1gZbP4>vN4fkQbRDf@7;|3|*@5@U)2&DV*F}?k`0`1*?jH(H| zuYeS^aUqf4C<+$dq=4Z*3#G5rzBBdFe<3X&c)xGW#fSk{i1h)C9&TAO&ss z6<+5rzsa7SwxN%qru1A*8`GuG0-W_vR_bUr|1bq^cl+T{DQ#SV^AwOl8`Fr~BEQL= zpSGb7S-hG9zI8tymm(dz6A7fHo?6twXOk>BJu*=N%> zwAeMJQ{Y?Mh;BxaE;|T^)Lk{xNh%X6F5%+Dfn-7<}=@nIgBfve=GbG$6)ooh4n7~Y;F|c zZ?M|O{Mp6-h+?tT*|t0Lde6x9!do5Zb++xr$@SW#91krzh?DDeNV%Z1O~lFddZ%2W zv+XEOt~Vs*>N?v_;^cZOrCh1A?JQ2Nw`R&kooyF!a=l3@*QT>=5+~Q2oN|@UwyQX~ z-qtA>cd*@ly4Evt^WE9e8RBin^F6blthN{?Ke8rpyaG~ic+@Ys(01>tew^+4@e=i8 z{$fO19E;WVHvS$6|E%2{$vas5O_6qmuQB+WA{~mw+uh$3Ns4_j_?sdfi|b+VH$^%X z55$-Q)y0I$%lTHnHZ_(*WX>m+i)^pD2Qgl{`SX0<_9?!P{ncNGAIcvh>07M7!O&MS~64gB=OiwXw_j2Vv+?m+kU; zZHip~*py=zR?w3Px&9d`#}awCbaHbSrd%-4j?mW1tshSD>%`mj=)60zytUMe_3PIJ z-c&#e){)v4c6;OlICgJje<&E)RSS)Gvck;UHBBfA&G@Yeo5M--%@&741;deitwV4p zM$fy{@MywEVMX<}5NhA_>RG-cryw4z2)X(D0N?9X*WQj+mfZZ}lq+?#D{loSxA-w& z?Jr>6*=#^^w_Gj$tk=d2#`7m%fVPhDU}m|X-fv4VIJ`CZ0>Ou?gW*f9!EXq5xJPB1 zGYj4En#-2i>&>cz#T~O?sV~7xaXm|W(T!Q4ZX$tiU7)#SoBX}aC4KjH;OScZ)*XWE zAOc=X%MGVyvJd8SYjY~H6dJEn!gVB+?yE}Z)EUohs{cO|-X-C<>V)2x{cA$`M-tL5 z?|wg(U%H59%XL6Xt|szXk@dZRX}H!(v}bEzrJBGQSsCN$px%McXSrny?_ltma%iF5 z0~Ber%Ng$|;uG+QuTaeTCFGltM=-X$_756!`f*stV0_0v zYv&Q(C9w?<+Zm<6_#KuXtYBLe`0K`BhmhG zrZgRiP$KRo4O3CK-Gc~`wL)PW23ac>w!BY4$6;q)?;XzpwSf4Wra(4=-GaQEs$H z6duKh8tsvVH!&I-?NNmvG57;ga|_{+ zXiqD2!)R)>r<+jyLPwpUcgtH2mKjNij=G?*5e6MKzpxty9d&WxXoVW>C55vw=%`Bz z3o+=ZD+>2x&{0mgUz_7a6JZ_ac|*4 z3^wDw!pj(J#{GrQG1!a;3icVd84niPW3U+y6$WFl84nl6VQ{=2DQu0w@p`nd9|p(k zvBIes9IwXjDU872cs*N~ zgu(H8uCO--$7^xncnpr$^M%VWI9@Ll?#JMGy;yi1gX8s5;X4eD*UN?a=ZxvvXkRHT zgVC+gzFOD_qkE%$tuPCtN27hca4JU6M*Bu#0YZxw)-Vu1#0_rDis{#e-=uJ)>{pBE1uocMXOqo>3E+r+^e3Lv0@${MGji4znAD ze6!1uP`L#J#-D)I{dr@K=3lyw{Q`^2M7zQt7;YV#u!hmqtGEJ&TgPsL;nuOoW2EcY zKzUpY(sk@5q+U;qLOlx)W7Owu@51L8*Rz@}R9>XZS;-bw#CVfcY`7i91zdvq^Ry8a zg$7Jh^Q*AI^N1DN*ya6mFx1159j@M#>tC62G&Dk-T>qw&V-Y=4oLv9DlnWv|N}Sv} zEux+jZy#Xxdl}2SMbluN{^(h2;Clt6;D~Em*tiw1$FVygYk0}+ji(5We zXx7$Jj9(L}$Mq$OoVPlG_tfKeVf1>L3jSQMjcsppGID)vdw1Epmc;WQ*sIRLjTjt< zrto#~PX61uMiFWpc_@XR(4dh11}34R*~77SNH4_~)Aw)GN8G2po7KR@3Xo z9LYax*C*jqEE?_=dT+RPdxt$R7$SYbu^22)`i9$L@KK>3-!wo?Q~lL_dHr3IBM8;& zuSA}Mp+Qr&%ih9DR<3_d%6VlwM4Vjzft2I3&QNi3{g+ZMDBI=4$@M=?IqrcE)2S-g z|1IT;&7Y^_`t@(RcI(P^v~+Td4QyB}-u}UG>W1b0tZ`NBUlSOsfD{Zk?FT!y@>V!j ze*|Sa1tYs!xDN*7V)gKJ3_5&Vc!xrHyGHmr2FtiL!{9B~Q{%%C7%bz~3a4POj9WXL zi@`E(o$y)=I&p#tRGPLXu0S)kp5~t*L|c=>w=rm9!|+cG8r`VS{cSfGH!h6DU@&f8 zn1R8huw~%_3h?b1Awo1UGyDL9CUy@C@3|)S2$#m7i9N$f81&1maBmDM?-ibjLFK(o zpnMAMb0D?MBmDDCkGW9Zok%JtVJ-8%F=z76`oDo~_)=R=1`izCbw$s$n+xOzZYw(F zdtw;Y{=q63oZ?Nvwit9z*WhFfdbL|{4+g#3J@^cRUhNZ9K6Jg>H&_9KQ@nq$0|qDb zz~CedPUu0w-5A?(iU(g{OwQY7xV1n&+rF$$@v!m{PJ>cQZDJl%@r;_a{c)!*QJw<#mV)rO}Xyf z(z{A>{d-fcXFJ6Gi$%XYlh^Nn2pjg(uuo$Vx@T>qPtTc(}uEKaW9eu>+@ zW!u{>n(yWM%cb1V4z{V^4?OD-HzwuA_p;rVaK_2?*GjnwJ#6=0e8QLOZZ8_4iDAVHfd-3ij(U@ZaWKvpEWTMXmjU5TfnVojtT!-L`&4xfCVT~!*Txq8 zdoT>oI{jBM!lEtt{%4#@MO*g!VE9EF`4cgCT-)GJ$7m?pHvXv?ZHjz6y#b?J(N_Fd zF}fFRTdu2hYQ59Z#yAo{sbyeA*7hZGOc?7qu4u*TS1}`UgLv^rlXKU~wg5OjJi+^On zx;F`q_(pBgJ9QJV()PGnXUqv{;9{|NaTutPf0KRb(Gl%PN0lGWDk^?1o~~AF2wq-BX_HpxPccg>%p@uGYq% z{-gG8wBvrPs@rZWd0Aakcn!s^)r$6uS`?=66T!Nls?s}jljl0MzDB*FesmC&n;yno)L<4HK9 zI-&P<|DJF!3H|=8YN5}n^8UGnuSvMOI-&1N|DMo2G-l#oRW0<}S>8XlumK4lRwwlT z?cWm)BViB2Uqx-{)&a-K`{x#JA|bF<2?M*!`{#rYNjSSYVbG2Lp3tsf%s}SvY?GE6 zC-0wISc8Q7suKpk`tJ$*lCZvC)xy$S$@}LPt|Vbmb;2@B{xzZQNfLI*sRgbN%kCk| zRo4>Fdyi|Hsnd5IuWykIc`}pe@?+|I6j?{)RbW}6OV(o>cRBdmA8JY6^m3xVt#yOT zYrg&reW4}a6t*DPD^Stq;Bw>TskkZZNATS0;IP|UgQpYp!>Y{Xd&o;O^|*RQb#R5b zS+M>wg6X2^S&`!|q^TR*=S>Rg=x|Ly3&jRJ&+aZ#4V&UsnAw3J{wQAkRCFaCFJ^R`?s)05 zyw+!g^~WKbUoC6AJ(Fqe;l96Z>hD2Tj;gBl>W`OJ)1}q_+oQzN%OqSUiR+q|TEwRG zHGvhlN0J8Cm*qxUIme+%kIH2tPu938>%&S)J}>fEk)@#kpSJ0CiMRpO5?H4uFj4_m z#(29D*%6;de@hk4z~HX=(uI#OxNE))ALr>s-`q2gAy(+eA9WagD%On{ow&DWtyYtV zU{!d;T&LmH{NPzZH`vk#&$#*ffON1eyO=Dwxy32R^P(a83@JDFQ_4l{?ND)Ya~;~c z+&1mf+fH)B1!E5ebE=J~B7i<}; z_qGN*(;*?BL$ZM!CV0)6BM5F+9V|?54Q@>E>gr(ej@IBo1pmTq9fNHd+v%uj9fQ&7 z$WBqfjg{+LB>XW@0%3=iz|ykZScx7Za6%Tir8V#_fp$qt#>%qNj9&>{lm(t>4OBQt zgFCilY$VHNH1s2ocJ9q0AJfol(8K4Hd`IL1BBPCg`cCRSiP~c|2Xv#WHL$7zu8b*a zXw1NGWIzR%aO|6hk<9-!go3IeBr~WQJ~D%&Vv11XGO0jYmVig zwK~VY#$pQQ9vbI?{>HEI#nO7H2mF3wtmSXFIoLMm+_u`Eqjt!MCe};n%If zg#<@-Q=#U}!m4=9nU51ZygFDsDGS!UMNpgI*_TDSNi!&S7tvg5I7=N@s_8a| z$R zWbtmu({Q=njDKNk;H8?tlUW&KejwtT9go#v{Tcr3)3EmKWz9SMv-W4gtM#^~P0L|* zlbyd6RMliB*WX{jw`>yIP5tQHqf(A<*>u;Bq2(56%AA8??Ny-be@{Vven{k17ipQZ zzLdh9g25vMm+hmp=A&fC;xz}~CwORe&^xs?$impXSRD*LYz;D!P0zknW&I&|&1FXt z+^sqo&Tb8ELh#<|VBxXW;4FfFR0oT7{j##>5F97BWmnp4))K59S=S*;JL+kLm%E5Q zDmaU%Us3TT$;HR3vC@0`}4PUm;4gTXhg zL7mRavDV2BeYiSabJ>pw9$g(QoZK4p*o~*EgT>ccgUb=@xDFL&Den__Wtn!dJ&4xDp$Pq|WW+f#p9-MMp9 zu4`}GOMf`sxfi6|z%I78{w%t47o^;%uC|Z<=(%(6O1U+<*uMJXYK`{_@Q zJNLDe+pd!xFr8`2xu2xmjvefvk=)O7?sww+Ufi`DJ!yj`7*6kSG8JX$Rmm{#U zFF5LenB05?(^F7{-2CGJN0&9_a6Pk;TYOzQ`vq914>hG>a$Dxr9(d`}rtV^b(_FCm zv<&ub4eCS9?bX3>QEN~iYU-C)+2+hbjMrRNA8IC62aB7x2069OS-9Dm*Kl1+@PB`| za0?RpuTYiHab-N$)c;O6j)YsQ6M8NF_XM3y>khAKq4zYre{P}lJPBzZzb|3E?i81n zWMqB>WL{*w0S4e&E77plfIiT)1|}=u${24HkpuBrunj59$6&#>T;UZA7Hq>fCNRFa z>v+aPzQQBaG>kgfKHu`u zPOiUu%H>M7uYNuz*FQMrf)2L7baMTpQm(FK2S_KkegVZ#6>rC~lNVrlE4saZs3vf` z0#a}()3)$jav=M|_nO$F#SjUP@N;itXye-2A=+rUxzAIs)Yc9aC%2yUTXUoPQt}rl zZx7d~dMw=<1sYc*AcIEL28}Ma7{^|VY=DA%nWVS^hT#hhbrUdnCOfKbDhAJFSFAf8 zgJ-fU)!l%>GuhE~FJtgbcICR?FnAQZN?q5Ltl2wn$JUL-;M*3f)=kBjmA9*zg4&?b z)z_c}^GmE_H;c<*E;ts+gF1Hk(bml1pY^s!vKY&&*mmU)FnF@oAu=noO-0)!>W*

sbueWL?04l3Gy(N!38h%LoO3i9|ayZ%^_@g4=9Ax6a&%3okmaYVT?hSrL9 zWO+P>SG1$b`(yB|ZpHFK44&1kRDK&HU$mpk$tujJMZ0o&1B`8ob`?`pMVc79yP8-` z(R~Qf#2WR-V(7`<`1>(~E=^*YuD_1#wGc?Syjj$ij>+i$* z5o?qBud#l@+O)pQYS#RWHMxEq)-PC_)$fV*E7s=qXJh>bYm53vuzthZvi@tV-?6r; zPgb|)53H^0SHt=XYlP0n54HNMpsNN?}tHePcNT^L2u6}->Xp3?p9uc zL2u72H;!|?y+?T%2EDy!d2bkUw)ejDSdqP?KpbscMZ6zxUjbuoGt z?fmj=j9x{1N%;zl-bH(9`8f>k{9RuD3*)Pzy}}fAcsO2Hz0JY#uH|?Qo#2kwwdIX5 zI84`ckr7?AcbTF@WZiw2 zvO49A89|64@j!Vp2I7axvoJ`1xO^hU*+u(^DN01vqu(lPO|ou;AnVEUOBiH5UH$=s ztY=J7F~raIL+9-U#H?!&zgQlMf%xU}I$G%z?JL}-z(V}$MiMUorl#Vz%5zikJLSt# z@w?@RG1#8>Oi?1T-k+nacY)6!XktmZem&R3r{#VaH1Sz^bqx0Xb5oRvtS@d;R<}Gi z$O)14ZTYBF{C)XK42ISZ<)<+2D%u~*KVq=WKbfM`r2qV-(kGDKw7yIKy*vg3&7b8h zF=+HJQ&0@Cu}dMebAba=b>5cFNadj|U7hL+w)7Czjztc!DM(0ao!y+Q@N?i@7%#Tt zY~I^|l3aj#+cm9DX!#9`k<=+*Z@ZM&m|*!gV3>x_Y67b%AO%+&Riusa{49_**5k3z z?kW)5i8gnNEZS(a>sdW6kl(O8lC+I=sIWk##<@1utqHuUfE2W$inOu5{Z(z;gf2hH zwXtz^8=JPaaduW}@x`9$j@W+^!!+Dj6IfFLDQH6#X=Ae83Q5?3Cp|M@=&P-4{v<5z z$5M8R)yX8k;g77;7@mWl4dsu-Fb(a=O?Oa%#}$x48>&bf+t>%x#!2XY5)<30HrKRa zOJ7ZM`yoHyDRugz%0V!xh6=`E0-x#Njv(a_h1SYm8R1buc{(B(w zu_wDJzzu}iS^Xm8Yeg#fz6M%@UgnW*kpep@AcKZoGod}jE{!Do12~N+XX}~OXVTfN zXOdp#k(RpZ63^VGQkP(u2EELqHSn<-d(Ha8JV1EJC0;M$O%+bJda{Bols<>wDi zNpD$ulhw6Ve#1zLrH!7;>@yF_Ki$nwlWGEYDv1q(WcB{yf*lAvJ-G6_A29RFO8GvICHW9{`7^Z7gnWV~~BpYL(#HSd^98j0y`> zYD3q?`!#{L6p(^8RFO7bw8yKBHOrh5Te$srt+kDT_6=V7(%i;iBxzs0z$CCdV*hD3 zO{`H9n5KXfw4sW$@uvM&Z7f80R@%mUt!)glA6TtG+T^l#z?}3h~JcK>GtE(>NY-aZR5wR)H|Ff;}H9=xicvuH{C%6_ESIxZKxt` ze8EDJHjYNOAZ_DYn|l^3J(Iq7Cyo5vt0~Eu^n)YiH|&ngyff7BRCM>jFwf?_sw;iyX;q{veZx9gsW}{%PgUwbcjR`c z33S_8(U^^h@_UWg%TLGB&JD8dJgxiW=l9RZ_MR4M^7C_>$=c zT`13jH6^79`x zlRfPqPlH%~{Sl*|M{&bjetyf8tm|r*cXvhP=XXrWQg^$8r=cjnp*zLW zt@)K(Q`4dR?{$x=VPs9<7zLzYYt%MdGu*qABH`ocu7u$m%`17iyRp(Uc4c?s$Zy#i zud5x?x;2ld%3MFYin})?zv0@f(K#%JUV!osbjzj3Y69OYAO%~aw%MAo-gqSTOKxjb zw&kR**tNYIHSXwIo6de<5uM?crl!_zUg^}-n(38pPp#d((h@9g-0b0%I!|-fo?dBEYR&RW z$E4O?Ug_S{+S@Drnp*pKrM^44Hum*O8>iNOUg_x6+TSbPfyJGm1H96gDR-b(>bA4X zIEakYI@l{6nOcWguBj5%IuLoBxRFt2n379Zdb_eu-X=n-D&z0^9& zD;1`vcaA($(2!t|9PPc#ATf9Ixt-TFpU550+%kx!oP~7^#&`U)!6v&hYWTg54R+0} z!!qlv%(^zS9?q=SGwYko3TCv_>ylYRGi!WiZJk+rW!5n*R{kO^lh{cmJ_GXD4bRH+ zU&iv&7ty~V^H)Wzjd+&*r~EFvWquFL`Z0iSCxGQH6q0N0PM~+h!<;hQ31C{z=r6o;aO>AD=GP%^qwKTjB-G>G&gtVo znV-3Q2U%*`i-_HYI?G`-Z;afnaHB`EHrucbM@hSi+nBd&0yiok1^cdUd`te{oAdV0 zn%fV}V7ckO%iR<=8itYX`x+EG6w2=7n$u4;S_4-rAO%;DSFm&4Sa0gNbds;O2pGw z_;l+Jxy3Wx_d#(jhKYLD1lCbN3QFxxWN-NemI&ywOpS88TW;6VkX zpp@<(e=fhRUA20v=4Tn3UCA3`_eHTGhKcU133OFJ3Q7fh)*2` zkVT9Xdt&f+f=Fl$Ojke(N^L;oDEUqH#OkdYo@IP-hi5LAqRX8swSG#9rXMbv4=4!3zm-|w)eVVG!0O<MtYc_l4%Lv^WZvy3Yd{wBq%uGC{SfxZV2kb+We z`7pD-{3d&2bt&CLPIvHDj?Z3Fe5?Z%RY+(JT&RE)l-ioeqO{b_)umR?GJc^`zmlTA z>nq(uPD?4!=|BQ9D0LN)aq^q&E!Cw?%rcgy!Y)#5?Mhu)6F5TwDJb;=kq6RJw^f&V zJ0cb*TV8-N69iA}Ll-M%1k)@Ph(UP-;4nu7}_^*}JPtZIETG z&Bm-M#Q|=scBu)>P(TVw-Ad%lwA4M-rOwMTo}(x3lES#Hx}_%Yu>w+1%JPx8&20Q8 zdvA5AC0RyHo5Q47-EEa2A>DHYrYInTQWJ>GOG`alU215Su?b`OCMk~6ppMq534Ex4 z6qGuXNPH-MlYOqb)WKOscZ4fTvA!#HMonO*0#Z=weIgg8r50D0dOXWG4&fpx?slc# zs|ox^0Vycei<<%i=inFYI(}5dOFLqzn>@3X_$@I^)UzgVrUFt>U^gPq$sb@}^s6qU z8)X@jnXf;U;%E&1PJB(Eco+dGD0Ll?{_+dw!tFb2E8kMwP@e`Z~fSr27ak0V-i>t@!0ne}^S4LPz!w_|4glv&Fi z)e_yk#R`96+ZyJwMcRz$?QBc`ANIaHKC0?`|D0Lw3`r&+nL&u4Qv?F2KmxLf$`%%7 zGhq{vF(ea+ge1;PSX>Yhm%5-;+&2V8+^r%mweEGVRcftTYpq+YqP1?duD|CwXYQSQ zXC}j>e(N9kHJ?w;oacSt^WJmrec!X)bI#rLh)c{S{RKquoiGPu6B(4ilNf~=oDVGp z`vB>C@G{s#&V-zyx(p*7j1$SA1iHCTBChX2>(9+t#aU+Tdn@+p*-4uJv2)N_!y0r$ zeIvm_JYcxf)0%gHaT#))LR)}*Um_2`10Q7_Vg%k~OumP(^NV0;_%(@js>mN$Ii3jI z^<0w?7|5tBM<|R+gnoGt9$<|XTVus8w_-c2*iI|kJ~l z9A{W#r@jC@3{;JsE{2G{?F*l9i7gP8=OBXbWI7m6kUc0c0?O8$Jzjd=G7wQG>hZB9~KcjIxzF2jd|!C;|0vBaSmF`l=T>oj%oQm@;DDqe$gGAF_C@=_}r5>3HD* zoH$Cl_%-jyBM!ziGAM!Ex-pR#*9uPd7609m+lF)-Nq^8hp%@ zC;ND`vabqqZ)JCIO{&O()Cxa3xb!)Y{Yav%nZcv`$D?Y`WD3?Je%~*OjUe{gK;7mlt`&N)wdUOw*hinw7T`a;)Ipz zFl6d+(vMfUJJ-S3MFu5O>eg#@e}-Jih2RF|X};petW;xg?O~)hs@%QqU@Rnq5-D}3 z`S`U2-~O0mJyoka-B;WdNEbGUYhOqDM3uY!9E|5w0!Qvn*XmAy+-F+dHNN5+E7cAN zciRYc?dIs{Uc@Z@CDmE=EKY7eGvxn~eR*U?ipPTCHvY*CJ*(Ai@fDwErFtA%J|_KhrEZ&p(fwjDD3MaP zMXUP?a^uJi%Ikc^Z&<13L%5FgGnKl3IT#zrphQaDbv~Z0?c)K{_h@z3`-%?$(zj>` z?#yeXAH!QzJjucETml9qQtGbP>Mn-d0ptedR$uXnR;u2(_AJt?RPHWvFpejK5-D|C zef$K6?_J1k(dusS6+dgG`WnJdkUmi5?i~l?6EY}~Qg?$^cL*l-dt3^x9|t4aW;6PL zu8X}HvpFLvu~W_W9PD5$B7+jh*~#FXs#Tp(SRA$Fjz!aZ9qE^=HhGPM@f;bHfP#m? z`AjRgwy=1sCD#?*y&jiAZoKLcKIC9bB7+i8ATfa%BgW@UIv4-Vk~<5n;f18%kBBH1 z5YuHN<5y%b0tMs2c}pv(?^@j7l3R?3JApLu#V4Z_;JsFgMg2%ymUMpDIwfH7W?ozNnCH*O-;4ufI*A-w;0)LO9OM~O9 zeu1f5_Y}~Nz6`Nz5b<3JA9yi51NxX=nD2W%8geFb~qS2$)E(f zMc*Kf4~l)_=?^3#7|y%Jt$d0ud5si*dnYzGxC}lDZVx- zbBGx^){I<`j2K&SsT}~AHC*jK2jGtcGW;u-c#E-FhzS4n4o1OdFerf=T8_A9yj*=W zfWgNzoXirO9s4SPRyG%+^GH5jDf`sHIGGGen93^U@v{MpvA9uNwXzfZ{Q$JGb0GR8 z$qy)HhdLPlAcGR7vMKU}!>J6NbkS`Km?b#FHg2VP6rv+Y{!}T$upxOBG9qL!Vk$da zo;aS$UW3@_TG>hdhpjYULG%Wa`?DwNf7QYG9T}7`mCcYRjiRzLkiOK)*7ySex|oBY zW6$f5W|30X&%rp93`&^Fj*x4HP+0<`dNNCJ9`6DxO&vtfAbF!w7I!diCxa5Evf1+F zGAd)0{IXWI*3VbMI%k(d^j{=Dqm;3&Nip`h9t=vD%I3+n+@xR>V-|W6nI$+5_;V}G zDvSskNZ!Vwfj{*fzQ|W)}V0=LaC0KsU zMeltBa0!k&{@fCq1@1VK*Q)dZNa^yEv5X8xSblIe>hx#$hgo8$gL@CjJ5>7V4#r=} zpajbgPQfL^a2!Aoev;s1wlfeiS%mU{GV!s?F z{X9BJ%az}V9FV>rBEmn@!PrR#C7|FJ;E0=)f|1g{(vtfI`umgqh04MC4#qq(C;25@XzuLigj|@sc!A0N%ZvpmW&AR^tOYZm3 zKZf+*svK-|FqV-)2`G3OoXfO=Y103IC3h(FKSKH_m4iPx7@v?q3AAW?-^w=WOdL1+ zGc<6A03k2u;u8-*y3pI7!el$??;s-lJUS`GIE@TSATNu-xtX|!d{_FXSaJ`eC-*Yx zpRh~kuW>N^w}C+k{IQ*Ni-8xQVU?pnuf80yixByaLav(I(X{O&NAb8hF&R(GEoM;G zXawU$%075Zwa^*Ll*_ttXfz>{RJ%4Tq+IV7lwowVrh_4kLpS zscSu>w42v@R-@##o^w&T9EnD(L0|7fU#MhnKz*%Y&)^*}Rn{RQN=7&sSCc^r^lE;E zxTmZ9*yleLGEY&LA7}rUG*~Gv{S6j0GR0Gfh>~><238XbHzn{SS0D@nWBI|Cg`QF5 zVEI9j{C6SW8WRV9g~a2?kW(0TAA_1U_<}_|ox}n~`~bwqmE`5XIs>1h*Ff%t!K_0yTl4}ys9`%Y8M;Lq;nl(HR z(B1SbaLM;pMrHutZZXgg!c~6Jdjlj4pE!RYz@!C}LesC5HuaZA2`1X;PPzkCMS_h&|p! zRLYMKcHR?xYrO}$KVqHdDoCkg*y)yRoX$Y3s5^Gk714BfcZK%`%BjK}A0UO;^Ed*C z-~^zPRAGpNJ)q$=O3RPQRvGBB2Ri;b&;1Zf=4UFSs}M+eDx*4UcQE?4qJE0dmcxDT z1)PaM%7K`JosC%6^KiA}6-j;8)z!s)CXo9WjuRNUHQx8rs6xCqjSo#^(Mfa35_=xQng&!)Ky69gm-LGK&V*z!mb3=V! zI~a{*Py!d_H9URf3>02?T5uyy0-;M6Ip4ZyPdT5{llF`Hduy7y=v*YyB|Ua0z8g>7 zmm?y4%?`$;WKaSZTXS#)QUw1SRsxb$3AUJFwki-;Kzb_h~R5 z<#XBl*HWC0e`zd&st*|JfqkkI0sc)Oci|eI2k}^X{vJ9490#Ttdyzp2xZk@7%7JkU zSNr))RZZp|3lb5iBoG!IL7F@YVPUh1vQ9f5v4RZ>nswTRK*en4bb^}!U1zb`3A|%v z<5=KFEe0luQOZ|=k&Shocwv@Hcs>V7XJZ`+ghk$mn2l0|g`-uJ*_ee`S~glhDz4(q zRZ<%fx?Wb77j$9 ztNSsCrR8ZpNX75r@;bpPK-V2APd`|BIv@BFi-C`zAshI#!9_HHdq5w3C1PD4k>Ys# zO9^ujZy<&{SL6POB=y*8*Z>d~eXhj5M_AbPQ8RD75c8KSXg;>#K*gu8b8(VKNc;AbG}Y`B1jSqx#!LL8561s|JHtHFut89sqDtt51pXS;un z2pgC}c`mzighl5gkn(DT#V0{l!+QW-^XH>sE55)YzDQz~x*_PhCv#E({E@{d;wOKk z?2fQgxr%a$-JytK#sEcFfSA9R{J{2{J}{q?Cz(4q{;n}dpmKMdQnC(V;ngb2n|23c zMb9btCxivYZ+KCr*#oiSiMWtXHxkhG9{oIUGy;9^o&cU_F|f-I>D=O9G%wFe(C?*r zy@1F_+&d|+MA%CnB)wfAcQ-(BFFDrz2l8+y@u3Nt525?dnucY^Q`jgFy5H3_qqCe! zIYReGnpV(R9!46W@i}SI|0HhDT`(98_XAW%&A6yf$CyI+pR#1;QRaiYN#qG*I^jtq zmU3Z*562aY>j1Iv6+*YC7@bj^6ys$}jp+0(;&=}_!;7A_=!Ac_IFo0@xJ#dsV%SxP zB@lTX|I)*O!`P=0>xFG@{z{+-k!->$(_;~HUCrgDe%2Ey#`$DW0;)D4xLYfDK>FFp zYPs#Gw*Nr6cUXV>uW>NGC4&-B@F9ZU&!`;yTBcmk|Du(m5hgkT60R$0yZ#RxjAdj{ z0;-1NmRz7!J*ZV}0$KQbg06FwfZyH66xY!q{RcW2e$!*3!^E=Xaa>Qx8 z?_h*~2L>hZXJBEDTP$KpjR~NSxEir55OHJFCf!FuWC>$?%ac2uh6oOBImLfHA~?!r zo&Pbiy!fuzn~1o)nA+nu7`IoRCfw_gv_BA%p4n+KB1n3ce<>nJdbWQZSzdXLaD9Y~ zTt(!Q-xskO4G4zbr$EC~;Y##BBI@nB)51Lw^&X+|Nc5fN6Q7mB7ZN|2!Y>gAey`Fm zfxZ$%y%SUTFya$5=Jie|{&fmJLHxDGyqmNTp4j&XOTHVT z-Xk>T^%fCdlET*$|0RY0Nj&&vmHue>@MuK6$7#&;rx5=-g`Xt;HidnE1U>{o@_tSs zJ}HGyCElLGj}wbml>8E0uL#kCi5l~9O(9;D!Y2~nlEQZpzn8)v6Zd{q>0|mqh!!kK z;TGcSQ}}k`cT@N?;z6%j=|>@2NT)vz5h;6P5%h_Od8)V?x^S0+aT^(wKqK)N#=D}^ zMgxO`v#ce=Hp|*fY_qIC5!);)^ailavZ{$~mUR}f&9a^# zwprFU#5T*S_zSSjvX&6rEbCHYn`ONOY+4qdN70+WNy{Q0L!7iM;zr`6Wf5OPoU|6S(jIM6_jXfZcomlIKBXS(6-$o^OFc3DdH0 zo|gJVw!9W|p3}jFWi6CN{GxTHWvv3=ZdrE`+brvSVw+`^z71@%tQo{M%Q}PDW?2ss z+bru-Vw+{{`wpItSg9Zmh}R$&9da*fNhp_FtBM^d>*aDNy{R>o;Yb)#D5@8S{AYYec+^J z5sx8GS{89DaniDgZz4`w7V(?JNy{SM>+i6vGZ4|1H6M0U4U*?fWm%gXjMK=VglSnp z9R5NxlHXuq@eXidS!c;2wRAC~wfrmicFXGd0kF-ojv%&K)~Uoc%esfyW?7#Q+bpZ> zLtvX_9Yt)jtaFHMmh~HAn`Mbzz&6VoMQpRI1hLJsZY8!^*58P2meuzoV4GzvB(_=B zrNlPN`Yo}|vOFIH+bnAovCXoMCAL}CR$$Yz_&nYqPFfam@jrl*mPLFBaniDgk0VZ6 z7V-7ONy{RBgE(nf#3i2qCoPM3Dsj@Xh}Q!ba>co}tjA$D4}j$PTv^uF4#vl1P{OpV z9(emhGZM#v<`!Y@IF#XkN^vK9f+ryIHvXk+@~23MuLg6quxl1UcR7NKgI^)PY zXmQmM>?ucam6@xVpo<*MSv=Qjo#r5}@N%su2+FaXYIAKM=qW3?y2^c-<{ZYpxqAyi zi9Eatz;y?~9&#G}!1XJFE^<0sZTD}q*bIufU({eGrzG94YjA|({7r+oBgy$fgLw*g zK2z73uf$3;I8rI-P0&>?*qdp}HRmXmW}F5KRhlC-IGSl(H3U87BHj@9a?OdTG{9p&&oziE1)k5LxSe*vPD{!0! zClI(!A}Ez7DWf=(ptC%;kpp}V7Tsdbr8K$=!5DH4Vjmz<^#zS?2SVJU{(p|)iye;< z;85ES2wv1+;J*m|qQQQiIKW359B@CuHyR9jlAz#ArC{(&1U)nu@>hcX1l?uDjnp=b zpobi~gJ7Hn!yY4;p}~PK5FDk!h|{THDM6_mc_G0H4MuGuSg*n8TLHv9s<^9lalyEW z#r+VG>VL7g_aMac==z*(eeK#St z5|O{)UwWJIFem(5im{kSb{~xhCylzupZ^P^6T%{{DXJ%3E@OBG=%T0r#0`pgA;VWV zCM`M@#2t$G1Vg_1OL8y@PjX7W28VAKHK)@t#Ohp>dc=~D1GO^s$OI4>4ZnNO6gwHET;g<=&wxIYHur~rJ{|Igw z;S>uVftY`Vf*hxuh*;qz7&c$6NIyq{n-Fs`r6|0^Vq6UTWQy@L81Gss-cK>muS_zS z!uZZq)u}I{Qd0kZh$SIqrV%z-+;|F-dm*5IyW)CrC+-c5dD1Q@H0EotW=~wqSggUxv?n8`!CGd+ zI6;F`mksv6is9gV<05ikP8|E>w ztxFyzv04$-9`djvEGO}Nr>KWZ!zF?6x^d^jcx?Fo3$;vBTDoe^bhaYKJ_N;bhRXW> z8q8E+lm@dDn54l{0-QX6G$Fa{MmT`)C=D73j5>l+*}`VRXx893HWS_|JnG{?z&pa# zt}_u~y;dZTXUByQOZgSeUo1~xH;T|d5{WjGF0Vu>Ze{E_M1=nc2jfXHD1q$o8aTrE zM0B-<@g@N_;HXFOz6NX6J@}L$AUCM;d`nOwf3X@G48IGYhrCQx*5jcP-*cjY%5Grv zxE8SnL|(+dbRFo1Y|mtm?NEXqa;$2cClR3jS3Sb7p%<$%xYEW|4aRxYax)?&SfU~2 zN`&3zV(C5`kpuDZZuiz?L_UJZFdQr?Uo|8DL?n!ZB=N#K8JVgg%cMNfjNGmw%cXqN zjO<}hxLI;@m5#(!HzR*kkya`9@=*qnh>EO|@&+^V4;48<$`O9bAab&btda5w zGZN@T)+tgRVn&)()W*Wkia2p-U2Bi~Vbf1|<0*Ax6sgG<3kOrI2A{e2;7Q8yb zG`0rU-$pP^gRKt}9HqexI|+`}VB0$ct2DTYuWP)gXmGQiIXGK`TS^Ho(%{zp0p!&H zW99AA`%6-L$~(@0VS0b1!7mkfLW8>$_`L?(2|RBSl*nJvVdVz^VH_wZ_bbv7ZzCd} zaq`g@sWMJ*n0)Lt0DLu$)<2ilZ=485!Dhr>LS#&U*3YiXCdT^7sjhhFDmdwa96>>h~c~##1@Lhp=C9jD!Bn~67=sQSm z1eB6O*Q6NTaN|>qot7Hm^K?NCC&zlEuZI;IY{e?A*a9ooY{k}FvCFL3ZC30tEB1;N z`^bv9_Asxzrxn}ZjQKaBG~<9|7x{qUJ(4lpwG#QDu@XfjF2bycSVV@J{auEbn-5VG zp-!|huCo|{J;8WgrFbhv+}|RWbTw5JPC!)3nFs@TqC&%C0h3Rp#v-0Z;-F`Mi;hR2 z?{P8kbt%S$4#r~^Lv*5In95&`TTz%!Zxi*A2k^UHqSHS#8ss~W=o^g&`<4*-OO)gg z-*H4CjmmvT6ZO`p!gm?b5RHcV4kbEBqhY=ih$d@vps$*!TBG5<^N5boXoPPn(Q=JO z`c5M{L8DQ=pAns{(P-a(L|15ZkZ%joO+;aNu+H^^8Xcl@{d-gz2L)x7I8I!s^hUX2dd z*ZZwT)AaTJs?l_Py)TJMm8%fTz$P3BAid9)2-F$NS*E%8ZFRQxJIL+^wsasXrb2mutrBKouaqFim?w@CwX^* zbJ}La4(R3*7vW#ZTi{avMhu;}(eCbWAuhz&LyqAKeZo%rkfwZaFk*pP$k!kuWdfo8 z;!J=ok0xG9VktLn6k#upcu+}xjR~x$Ek@x#6w%!s%KIXalGoY~F(K<=RaJ;#F~)R* zRf1miR7Wu&P)Q*4B=ZV$ID!>1VL%{xD`n*=2wg*-hR#69BECwZTB#5iXc0dp@!_4! z@dOZcjyC}pVg0IR6!b$>uN@kSnEx;ZsR+wHTr+`$3?n#}%wBR))|@ZOlJmt@&hN*i z*C@5;AWY``cNXzI5_Qfoub-5}F`8&C{=l4Lu$IjEJ1^lJF^f?!3Q?W&DTt-zyaps8 z??SMK%wDotEmWXM2+uE=Qr+`r5(opwK=gXj<(&wVxoowFg?pK~Ea;19@{S=ExXh9{ zoHF7$;3C|=WTxMI)+OpKhLDpmYC8oOSz4VnORKFceFi0$LKNRmqXPZNIs2iBMo%kC zeGt`I8je_Ce@mu{GFQIHELDQ2E#O4p<1B`d{EYYcz{t|6S+jJim8H`mx&@+A-a!RA zOIKLLPQ9!w?Te_+QaNIQhb)MY#}e1ydi@&a@WmjNS7*JjPqwN{o6h3Hy{N_id?=({xAB7Q)k&XNIl*AK26Vu4kb z%n(4=Sd}I2pwU?h15dXYLiR{W%#Xxs&LF^So#`cCcbT0A1MweqdV_wr72-lrSV<>&QQg9>Ip2(VC*YI zg!g6#;}|k1fqagJ4V^;F-25ICTW&5Vov$W@hXX2GZXQZ;d{AJ^&0j2zHw=!>&G)$0 z4`d8_lDQe>VEn8P7?eP6o&sk)F>_M`V9U)>r0d+UOJ>W>+7#y^aBR8RWO2N=funOX z44HVCj5?K@CmoEp$e;vrGZ&$|Z!$M{GiA?BPttX6Ffz91W?YJcBHMFQV{yD=z|pxm z7S}q3jLTJS<~SHz$e;u=@(#ksiFt2M0Su9&36AaF^tL!& z_Q`c_HsM<1$#_BK=4}U~jtoj5H<(cqrx7zZJju|Oo2xC&9-e(@%gtjc&Y|Gga`U#u z@p4V7&dtlXmb(lWF)&ev7o849Uot3xzj9_tOyjanIT`eGwjj0{k%ImZay23BBKt`9 zN<`2J?Gt8iW&r-(;$$ZBoB~F{b%^~5kqO{PEZ!302E%kcejCIeisqgOU{^P+ER(Ikx5(qoZAWhCg=s#9Pxr8@?m~n=J%r3ik z=KvL+4ZS+S7C_gx&)_i>Tn8fWo0P8u-)AudPT9uxA7EtT?X1~&+sek95R>vlgnlN| zcP)TeS~m6tsjw^b>I4S^x~4qKY#?be8~uUjS`4hz#wrE37>f5W9%Im;!SPt_;FUFr z+NE{PO9s_qi?a}}!AqN$M+Y~=8sdW|M&rv8%`JoHHOH1UG%bltYHqBH#^QsQ$7`21 zwZ;a|OD2s>ubwq*=#atVT3X_RCp9)KS(>PBu1~D2iA60LC|lgRB(kz0u{2WOShGaT zo*LH4!jp%FCk&pj-+ti<&2`Zw(Wda6riNAF73Cubl~)X^7&L8mH8?G+W7He&UppXN zF=WWl11g4;j||U_uBwTLr#8hCvDW3$rUc`)&9Ro|SWO~Yhf^(j;E614ZeA9Nw?t}} zMr)Vhemb$6RgEZ)MCuyiHH#agk%p#3G!|=ZNkB9k6{69mERq?-J?_NCBay`owUO$o zNG!UfAr8%v=B7w=RRguNxoey6GFTIaT$5qi)Z`7`gD|vV2JoW_v(EPf@9oX-G&Izq zq1E8Mp?GgA-XOe=_5|O6PxxHkAl{B){~3zwa!+UY_9?IiysM>d7YP1QinkM#Oab)1 z1g5x<%ryWfVin+pPLPohgJ3ln-r#(MA(kpw%h+&omMcz-cp5pZ^F2XELtK4Oc&_4K zpr|Bxf^VWv;t4*3u$!DUYXZU}s%Igrs;)vXTvd~W&YdeqL! zR3|hqUmlM{60y~@VlavN+0D~xnqdAjnwu6kHrLW2gyGs#%DknOrF9YkdxHAL*7#EB z*~_U%lRJNj%uI>KYFitl@nn8t(Regboq&0ZJw10zS%iweZ4vh?e7XT`n)B+WHYFz2 zG&UmZm32#^KuJS4+?}P|oseBiRYN?Bk}eJ<*<^~AL=!3-x&)ovSj$QKagvi)8aj9A ztmc)`SXE6!qcGe(P3;bPQg&|j>iD?EM!WpprhEo35Q{cOYvNJ!zE$y_;tF9YvvLAp zr_26K$_%Qhx2mSDq1ja0+fr&Ho05}eO&(_o_OS$0R8wwxbD}v`Zb}ZYB<*yEY=tR1 z&?%dwJ7kBNvimt@lXQpdFjIDar)-kmnLFPrSD+?7qBYtYjYL{n6C&t6RLV+JVd)Il zldRWDW|dE!i`sA|c2h1zHK1V0>~TXT%$^4F?YPq8y}t1)EbZ0&2Cs8 zozUFcl)w(CJr`YoZ^O31M(Q9^CrtSXu)~IUw6?jaE_DYFWQ_dPU|6*Lo9rkQ*NGkFd@Yr=RUj8G)lJpozi^9WRLY}Gm6OnujSCu;lLGfQ2{T&~aWTp!p$O<& zu8cJ#qEly9u4+;J3K6GF8cn*68&nrfpaG1F*N_7n-fV{3nyxo9tm3jAZ*)uDfP3OfR6(dNqpkBGJv!YYn%o=UqEVbNa5*^fq zrrx&d4ODqqTTNBii>G&DC^g)hJ%j*>GCyHAqo5l72{OyV(EOyhPo zSVg$Y(i3DT#6pb9-QsyZm@K`mEAU{R$Gd^92X(XuF-;Q;3yNO?+asrLlQ6<^wtFWXI@*A>WHz>s1FW8AYFKppI5I93K^&B(p)(U-oOK z=LL0F>gvwCu+NqwFQ~#Y^Md}G?b>NsNvqx7fzh?2{#l22X6+Eat$pIJwNKoDvq+;0 zLm{vq0sb{*Q}&8)&l`o60|m6m@r#gR`@yU6h_S+niuMg}iGS z;sv#O_V={$>|62d`P?7Ie+PT^r=s8-+{cDQ#+65=VyfFLXji#iN+&Dx@ovxd%zuk# z-aV})JCpa>o&J!oCe`yGL&1%b@W1ZY!vD+;W1JJt(`#y%HZ(;CS2eGQ#?+{IP;E<# zcoGlA)1lrP`MDO%=^N>9jaF z3e@Y30{wcUK)>E7(62Yp7vk%U0{wcUK)>E7u)W?8|MK$Lo_ejVZq4;<|JLE2EoR$# zKaZoj@Cv7r>wYd(7PXukR!J$mYlsk0;1v#Uf8>8-rkEg}nM3>_YsI%9Ta z)r@h|BIUy(&V-RsHA6=Ztr%54jOj<3$t!WHio0Jv7p$b}sWT==4zH}76&W{e>fFlY z^^NvlzhY<`>QsIP=98a{Z1~!rjq+hmE$Zrn^0~T|{p!l9xl<>Yx5D54JX8$Hrc33d zBA=W%GtjC187MEesZiG)p3ilyTu+}`T|IT?jHEFXv_Av3J7CkLaxyxfoY)e<8w%T> zf%0;j3U%E>^0}^c2dZa}tDah&ya7f3!SzRFQKj-RKA(IzE+6<0EO8xlKhSP9Rz?oChOR(PuYT zC-8EAiB-_9*nX0{)2bdXAL@{+oKYPqACjv0D@C#=mg`1#F?-{=ga&y1809JnG24e% zTJRNCV#}Mc9_vaJtw;4~kICsXzYXY!+gdZP4iNgkBx)T7>;KwRFt8$2xul%}(|= z*Vkj#TrF^lQ^*4$Zklz_g=+^DdgdYQfz9KESg~G8Qa~NQT~_uv@Dsp=JeW@u1W70g zQY`c-2%gsw7!M=B>L5%CYfPdjo3qIyN=Xa^eF%$!B!v1?ic7_eA_UM#YJXBo2O%i? zl2;swSRi;X!h+!GU+{_~hw4D^%s^m_M<7B83zI0ywr;@{Nel#6BP<9myupLCB!@Op z_ACU(8U!MAhlNQLWr=H%mc&5tZiEHFVVjwj`fh$X*QD!XU|I zZ%OER0I@*u5#rliz|SF87<>_7L6C%^AjLvof#7)yf$;j?F9Xh zVoa$PL4F-WVWm4sywfD=>vO5O@j#&&oQO#X5#$luDMj8r`a$KRkP$(Cd^*K3_-#j( zdlCG`$>EAE5iG^P#wJdpElt@@KTi`;1@DPsNTXPiZXWvQjr)4 zE<;!pBq4MTrB)y?S`diPl@=xuelvvSM-=5p2oC`v^eClnL11h}fbv_IL{V0I08)_{ z2>uaaQILetSCo1Sf$=&5*guxFYD}Ui`=~!skr)UD5EcbV2o0iCcLYXP1R})GP-{%0 zDC<{_R3rw16A%^!NeIU&uiHXJHaW*%hcJN=Zchhp;F}Lg;cztw&(2K_Egm zS(rpo_5)Lq7zo~uuqa4E=mkpMkHFZDK!o13Fo~jU1XGb12)>K3C`dwxpP}}A0&ILh zsZciylPJoj^3IbO2=0ZjC`dwR45j)ZF!*_EEY7qriK6V?!AM17AjpqX7X?WO#VEB9 zfiV|>2(7a)iK6W1yz?Xmf@dHs3X%}oMyU%B80R1mp?fV%qA0tDcb>#R@Ye{7f+U3A zpwv?cj7JfO(8m@gQIz%NwMYyEKSNj)Bq0>+gjC-H8(&c>)W^akin0p^A{B{&-~fb0 zK@viTQEC_hV-NxnT3}%kMcE*xA~6t*AS?=!5L!#AV-Xm22t??73zI0ydhs5T7zkd3 z5bX@_;SNe|LSS5uK!l#KFo~k@PAowc6q96&OuPOBo0^#)uo7WWkc3b@rDh>84nrV9D=bW+C_938gTz4a1cXIF5<*u}>U0Fg zS_C3=i-k!PW%Cb2DiRBWzeHFRB%wfsWv{SaehSn;@VAObLg-^eJ+B}zb|Mg=?=4KC z=*$K_5~+#BYF4XWs-9)^cfuOFn2o?~59pS@u?Kd>IytyJmx`Cnha!)m+C|mqm((c& zJCLHJMa5M=vgAa@z3c~wk~0-u%WqL}XB({gA1Ey4N*+=IR-10}ZY1wz#Zz4n_7+6R zE{ot@(~ADV8|*ohe3zoC{!GdKAbV6-Bh`&i-I27wP(6>5kxE>(^Cc5iT=fCUcn3;J zC=5!8kkamm6$X1DbPY%Fj)&16BZYfBeii7Byz&)k84FQ51?0lubcFpmUg|d= zfvW|9&qHDloRYK#zuh(36KR>OKWY8eBj}c88k|hI9YGflg?n@soxcLYpsTSa9=92( z-MScq*6 zUUjulod4bMW8no}yWb99bS+ zzSvO_b!{UHA*4)u`kkK5rGITwlImJj6$U(27*fvc76pxBoc4PFyNv#3P)2-FP!yg%zMn@rHFWt zgZUuKaDTBO#VVfP7m2KB!MbMCH+n;Nk_1*0Y>q4s-G&~VB#Hj?p;Brq4DOGx^D9d6 zishN522u;MG)YGONxkH#Az?i2B;Tj1JsMN z0qVus0QKT*fO>H@K)pB{pkAB}P%qB#?H;^18=zjC4bU&n2Iv=O1N4it0s6(+0R7@@ zfPQf{!1m%Se0vE_g;`!VJ-!5+g6gngB-T*Vi1i^;uqp*F>7^H|hR(x$Ne&rf2I^)t zhBc&`$0iN09XkvOa9TL!O#R($j_OaAOKN~h`{>Zzh|Q#PI0!qn2-6pw1H*R-M4 zE~WLZ;XPpIGpYQ6Oyv#nskoQAW`GlW?$H~P({HI$O1WORTlXx*pV+*zi8o+kO`-;O z;CF50)ghLC6M9aqm=LLsHpQD`sJi$#8(`6sYg(5?ttEA#f{SpTgxf9hkj<`dQfstP z>9lTuUZxo;xFm<>wo+xk2D3W>9f4SLBSw6e<zmqaZsf?g0axWv-Da}vS5Y}hrJ2wgi=khcT>2O)Kn2m}L(G{pd{rrqCC_FjX~}S> zZpi;4LJindAhH*T4=Pn2XumOs_B7$}guR5&n{rc|b#3)f$QO|~_#G!Is0}t*WeiT8 zdjp&#XPYF#KhMy)N;zN1w<4P|%~V=!Rl`0XL(9B6t1n>n7IaHtRxM&r<4Szcc=WNB=t3 zT#Fi>8`?xkC+tCe883R&4!KOe9&&R)Dtaw$Y*^kB!P@QGrQ>T7iJ48p2#k<2lbj)0 zUk}l-nWCVl%g$-3%RNAdJFN^E7}YrC0K} z4@&?80w*b{!Le)3D9nBefvGJ`xR<5V!ANS(*mh?WwtZ%Sd4(*A_OY&#!R(dwJOiUJ zZ0+7RyQb>qie7lyPKr^8ZSfgYQ?G6Rqfv;BWSQF{snH>|uTp0tQ6jZr(J1Vz1X7e< z^({+kCSWonR#S~lCbfwv4S1gYq|8Fkke${H*|JPo(0N_888fcSZWJD%u571SGUnL} zh1e2orc2T+8S~7A!oew-B+ZgZZsRlxhooeZG)u-jW1+A-C6lD}YTq3gu+#D zQ-G70l&Y_{i48TyY*bU5dKgeO%#>-;6ibgOaG)trU+<7;nuJFL1;b6gCRpi{Y_$41 ztM&DYVqRb0aiqtV>ttDyBuj%OGRhRGuQz41r?YQ?Nf~SbG77QzD4l5fk6r8_%W+av zJ_WsB2zth-2atrlS}|r!@eY>KPUwY(D3+MO-USwvrSutvhd@bo9?~?oWJ_`=lVoFs zOZo{hXI#~6J&+qBid}Q0T!#*%ooH|cg7JzPt}%>-E?)nb65pBmJJ-bP(YV zJVvHA*^g5Y1x4MYWCt&oQ15@@>bbXp8Te@FZgz?pFLU7i0%lEAx6-z(qo<|2&254O z{{A|jyBF=lBR?ishj;uNBYl&SWSNI|q*xWA&s@EBENs3k2q$WAj8quil`t2Rt*Tkv zu%dkQ=*)K}siwLWaoBp5%3 zBI9TTdy1bO2uaMh!(K(V;R0~J_C0;_QFTwJws}wIsC&AhJ@@qI9r2zv{mynz`O0TEH+HnX zvDIzf*g{MdyTv`cvF*)r8fxjn*lFoIl1yvQ_@DT=Hp`w*7zT@O-pkHzBr^RH!P3 zuQss8VRxHKEGt=(uaz8^W+kX5`poJx`#_4$W%1c2z&dZjZ{>Zll@lc9^o;VHmFDuIvt>q0nws#)XOO2Agfftt- zy5`AEd_PvrT7^@z6I&CjRdqWHlQ_+FR@uXHnrB)dM>SiqJ5||Cwd(Nlk+xTE$@gVd z<)dsw7>rsbP(312wK(6FdzvR-XM6i3L5`iSecZ} zmarl&*Kxr*b;Qk#=0rn%L#=xAZe|~62J-ZqtSlUL(>)$-s?#%ESw)I4Uf7L@7l+h1 zI~{VqE&INE+4Hmth7Ku9@-h0O{6%-vD#+>h+=&I!I;FGV2hzyL^Xe(-Yh;N1N~)FE z?}m1?5`To}y>XWmyYSz!JkK3+wi1;vH6G*JSZuK zql;u!y%{y}{QsmTUJDP%uO{9|N#ErR@ijQ*b9-%ThtFLOpL-o^fxpLp2lKf)o6l86 zkHg7zc(cTFey!!6X2HYqZ0~+KI_njqOrOiD=O^{Kv%UFN-W$E%F8^n}pDsDNI5}A8 z{RDT@waKgZgU(Lc1Y0hjTVVBYa&>p!hso#XWM5L!_bo#q4p-fsYw2Y9&enYkC;R+% zY*WIA=sT8^xp_c=y`O@wt~h%;X1T*M-Z@uqXJjrd**q-Y&Q3gEe_4@zC_G$sc82eE zDEuuRu=M8Bdv?JLq~T|XLjqNu-Q&h~)Y%JnU>P%NeD;+(mN|Kjv(?!cx7zwQO}d+8 zmOCtadG5>AO&V!d+1b=&v#0-BFR54Fy`=vC>m{{kygHY?p1j7Z$5PVQ!cd4+%HytS zkH;<{~fEfb6@T3JWXy+%){KG`6j_EbXcA=HCNB+KwHnrsUn-(<=bsKDc^3> zIxoIS=A0w4_04TjesjRli&rlf+8jAM->R<1({IO7+UG0re9ZH5N*dQO#8wa0G+agV z%y-i27ckFh*Gh3b{yUa=dKTE4h6(tZTMYBv+=95gIkws=b6B=|pYEKaT^MGz3+XDd zS?7PP6V{sduz5{K9yaHks><&z!F(8ce!Z?3C4H+H3h^uDTKnGI4%hk&uC;Zo6#i2> zoNGO3bFFFIwxwLl+IV4>IxLUyUYg6fhMUfnspKbhuOsqyuXsmxuOt7HKG&TvakI~* zHW4XX;Le;^vU1cGpSQBIECbq=mCdbDUn)*MEu(-q;@Zjo*t?2XHkS za|de~?@V`JOfp#a-Yj!i4)QL^<-AtQsGQfP;wN?8L3z9G%>TJ=`WtiQOtuYjc!+e| z6}7A9SGqoU{IvR6~mcO63^E>$i&_?GsxxNzAk&yeC{{C6;yy~5_Q zd`jkCX+6tf7CJ1uc!%fm*#pf6H$%ry>a<<*cG~^_=d@`~yA8(eXm7cb3|rNo%0^G_ zY~PuUN8fy1G4k=v_bBPx#ZU;IbBuMt?eWdV`>@O9W~^4je+To;aZcal^O%r`HJVe9 zW~sx{@OpDOr_~#VbEYZzNxjp^+dGTBY1<2a%nG%l94}&Xu<(wy%m2kY+O*jnEJDlc zHS7Y|bAIE=dP@2l8Jg>h4!X4+t=n(mLEABl&nfK==0R!ei)j3&_n0LP%a1%S<(j~^ zuky4h_(?tIqrB(tJ^yRh(%Q9$Vb*55wpbYe8nxFliD&!BTu7z7nzO5Y%;tn_` zhk9er>~PMBW$xB%?TI+wNZog~YI?k9mO3mi^^D8qo>rGKQ^`;2pqJ+DpxgiFplJ^J zwQ?vuOVjpYR;6$P(~Y%M=2269GGx-u&f?_HASINK|Bj@j?+}LA&a3?Qx9#!Y!N0;G z>F5qu;J<@4t_R!vS8slZ##S`cMyEH|MXfT2<++|NxxCkET+>zjq`rG@-oAUW=l}cR z;NBeG<+Z45ASHc67@89*)wj2!^*bNlL(k##LI?96`-F-z{llZtmT`>@E42TZr4Gw= zp1mu<>A5YJ_gE7uy7e&?{G^_>PbIwDUrIU;ZWJgg&csrf%R0s?R8 znxZSMlR?DmIB3y9Nb~Mv;T-vOF3+c=?_!2RysO-C8PBxLcVYF2UklOaBq`3qe+P5N z_nq#T`gV?PD9uubrOR_>u03vccT7|Ale(iTZ+G0Q1G!`7p5*^z_2)2{w=_~u4_`V< zeWGes1~ccUn-;cDyeUK6cIkv-=F{%3p``CjhUO^ppY3t?7c|M#A9ChRspPuWOG-{lO2z=xXQDc`lnQ<~u^uOKz&?mC#KjIepi ztXQ-KLuzgJR)NFvukJ4jb8OKoHz!;i>3>qc`D@;O^TGf8<}La`UNih3Q_}Z2Lm~dH zHea8L^M&(1x#k7<&Fs^pxC#Fq%WvG@;%>CGE^nER&&^JXH7~bL*EP!VEGcAVDu zd=BGmhvN){9XrLf;|x-Co8yem5X{*QwPc8Ey@_fMncuJzuZuJ?%yLFnDx zN9Ui{TJrd2z)O@g-e4%iORAmyus!ui?}vrBZJ`u(M|Ze-cmLo5`1Qu?rFa1U9c=K3u2Ryk=d?67G%cfFC;QN5 ziNmtH`_^1uU7@`?T|ri#&c7?rJ#QZ_b9;k%J6}wFg+1xj4uEcf#?zurA{EQhDxk_pd>)Hg4!MEYFUd_7+weD6>fWT!KeNj#c`O<#F3J>UKpxhQp;Oa;*}HB^`rJLiL!LTQeAISda|IG8JG!3TyT@y5mm@t~sR z?KuOxQ-xhTIiyr{TVHT=I$@F`Os$v@sg5?qn`4+3FdsK7nyJl|t6K0inP^N*%eY3) z?&bLM4ukL*u&w4&ScGD#8Ie2`}IIW0q9&daaQ5KlhE^viE- z`||23V)3o|4x_j{Lu1Yi?933?8F)E818=pRfk~~=#>q9UOYq@y)`Qlgct1mT&a8yd zIAn9OK8kL86hjmt>!VQFNVec{F+4+K&I~kVi0gY1OV7ZX48fdwcVvibz4xc$i#U7T-sb^U-myQ>?$-Shiy3noSCSfIj(-9kn1?K=LdIae#fFVNN7 zUvN%C2h~APA24pK*XxyYofpBk=q%lA`z_#=^Brp6?vrtyBdxb6j#nz)wq7!(tv((C z`;A*a`Uo>c^e5C%NK**NDc!|?WrH)e?IGPEeVtqdn-2;%bw z4RL&&(NQk3o^r+phC+-|bDmGPrvfK=o;p{Fc)e$DLY@)oP4 zVLAMk9G_<|Prkq~)BPB)A0E!L6&;oNIVaou0b3NF>wJ@t=CSYP{b8qFlr%nND1=bP zGY%)J=G}Tc0ORSlU5eiL?_kE`#@(o`X;M3(%^`oF|*M^J~V?}80Y{|IU+o}KiD8RASAWdk?2#|HL#97pipB*p#s?_f4?uvLNRuGd8N zUCpwF$)eE^v68>6J);C$QtP_%D3;3R*&TDOr%vZTk*K1v7Mpx-OC@m zaZuJ%fm18f&Q=1Z14RO4#sjOQP zwF->yZ9JXBhAPT+9h8>*$C%L(`PM_Tf0Alw1D?7xu4X8GoB1Qe1Z6~HaaLg7)zCq| z5z2rb?|4Qu$!SEBYVcMdX+?AymN+cuzL(32k}v+171`4N7&DriuNfWrlbF$Mv>f9> zhSK*ae}uq}E!0I%(v0$*mb?OH)O#7~BK&u(y2yiL%#(vDWd^DiGK(6P2gw}o{mPRc ze6tc(F0PtU9VxGfO_+>&`H8r;CnAro$MP$TqN>1I)=`Hc)kw{Cdxi%V)t7kHrOy44gIC@IHEJ^M~_rH(H{x`sUd3dHgg-UGoz2JBVh9!}2RR zCx>5DRAg6>tzP}FeP`~gyt{?n+}=Lp^(?1FQ zbG80?O8)#seAR`W3~)if(&F@mz*r z&Nn44IGr;aTCbt#HoaXl1as=0k|D13PD|H2UlB}~FgI*EmZsNd=*oHN<0)>O&(K-2 zoT(mA7s+Qm@1vCTJ;xB=lvd-BRXFr5@A~d`)OX+4;Dorv9j?AxZH-5;wIG^sRCZ>O z!}1jOj662HWoXE=rptH8a!TIS+!ffS@*h@n|0nxP7NKi{BQR?kTcctR9Pna;T=5=_ zw>BokY@cE<+GgF9Hd|Z_18j$fOw171Ed+9G0)R zAJ64?*7+Td^x3@bzc%i9C2ybn3$~s7pN)HhImQ4vSX>gdo6djHqq`j+WSP^L*LHUX za~sZa5B*>HlW>fC(ncM}bN7jF14HS*fImXaQ4X{b=ceWDK_%z@K|Nj=N-hAuy-AEcj2{L{r;Fn27+azBf^5rt>WZcc7(G|P#NDc*%$ za;%)KuqVsrSW9OezBJ$N-o@U0S8DvytG1=Ae*uf2Crp_cnNm4!Vr7-sA62;x_Zfjh z3Q;tNP^5b5f=aOklR`F0MeH+@;-B3bU zm+xqgFHe73sKb7~igvU{(tRxM275f(lg*yIRoYVdnER$2UCi>4nTfOcbyfMOd36(( z*G*UFm{^y|^IgZ2%sOds?0v+IZDv(G&u)o zk7tN$AA3sCZ9euA3C70^rSD7r2ywZW1G*774k+*b=sj??uH|SpD>|C1d9K3UXjEJC z-~|(~K45W8?J}#drSevJcdljfBQnxf;v}G1EAnkFZ_RsI{Fl;;ufw}v9wuOM)A7c$ z21{X{!ReY7>QgQtFvI3$V*Y_Cm+DhN_7t#ljJ24cZFZlbc&D|{vDM!JaC~rTr++Gj zS?N|-{_z2ieAq-&Yx(?npSwf~;qvwhAiY9J8z1(D6FJWh&*|s$GsLx@FI04!pD$Ge zt17R<%!EGPB|1f)*0d@^Q_c(Dks+=xygmKG4=aMLhO=GTG}5;+l;ym3DJmJ~J<`|S zThVQW9!P@k7=~?+9)4t7xJqBNjdPWLr1H~M0j^dB@ZZ88A^xV;Z#~zZ+IjLbLOgy9 zPGrJlcgGskcs}6zt>hUy_WIc@ZmB#?o}a6J9+f3^W%l=W`B&Pf!>rQ-Yj*gyvuuXj?sL@@V1p?8w2FMA@;7k2lfHOI}kmM%|qGUXCcJG z8$8KqpYkE>h3vF=Nf$U@_5CTV34O{{XC{W;%F@MR*k%uY`jl6&`=Pe~sG!ZS6`;dW z(-?2A#t;haUo5d0XWzut%C{`!_D&4X&!U6%o_L!_aH7{?LvT0hnz3B94rf0!H`O#^=xTfUWtO^B zb~dicSv$3@BwOuNG2GU*bX;<3-K?y$7mM*%m3O7q*~oVe<7%IG|NJT+wBMLJFkd9w zqFI*%;^o%<79n*;dJrlKX~0e<>ioSOf#x% zjK#QBnmX4;b%-ytF_Pj<;usrIU$IHlDVllk0h-I0SgT0MJAfvIv~%pV)T6q zx@}X^BqV7mh=|IIiWg835WyFemx}@-;*D1kyde4_S1(l&5fK3q)E9g~5Pr{d&dluW z?#%A&lFSy061j5=>UBl; z4!q6RgUYpMqo1Zg-b3@{;pJD4VY`lR#Edr4>(K9b3 zCdIXe(7D*qLam}sYkCoK3`~YDP*`LiZ6=AwbQf%Sq>(n ztZn4kn5G>>jLGO)Dp4BkICvwQAw(j??Dv~01DkDEBPxqJ3hf3 z^gt!EP7yK7PQ-1{hY`IuVdsLm+S{Z5jSXZ35pysv%4GO%7~P7ELx~ay{|qK(q05O9 z2>%);YN3Y_B@liBCSsv0h!O}tM`NKYiAvz_KtmR~iYS5bKVdWrJ)9_k@T)L()E+^U zKvXP}Wk7VUCdOnq1``XRWOxYQ$*Lm|-UmkJ7U&wH1j4gnWNv{TO;iF)f$om0GaN&d zKy(ERFa*|GUW>`-I)%liYwIot#$+_3u&U|W24YM`&sJE?H0^jE%VhW>VthJlrfVng zDg+{o>)n$TdLmH*;VZGLHVSm=bnRrGl|c9gm@4`LeHT#z;jhDJ7J3R%0+G95&gRwN z`);BH!i=;!*0nKRJC!H_*+R^)&@Q5~g}8?YFc0wUX3hvi9)da7LN^g55PlS9QVhNb z-yWg_?8j@L=~{-Ee7v5(4*1ng*R~R4(thOXr)#~$g6 z+P-|k{~$Vls59 z!a_-H{TkF7lc7xtizT%U#Fz|iQCL+{JDwPmp&bgVNopI3F&R2jVbhb^2?nmgWDHYo z#e0csu^)xShq-kiHbm?fIXgbb9rVDv{$^}PW@x9#SL$s{)M%&I_9))#b3-#rwJb2t6L}Q#xE*iVK)F%g5yJm)lb`Fm4M1|ngB%YZ`le@Y$;o4mzXANd#SmK$`&aDx` zjZYfbvIX5`S)0T3!gJE3F%WWgh)^3(8TkPUSSLhl_5X%MicrGX54Osf^rs35wQ#!Zk%OVPs(A1_AQ|dJV$p+hK%xsgousTCe+JM5G8NjL*Tw z4FcwO=ye^8el?6R?{m@wMe7L0Qd0yI#zU}G1_y}a24VAM`aS`p{}M)+Sle%<35wR` za7__R7zx<8LBO0(uNg4kmC$a%XKN3cm zXFF+vqV?uCa4f-u@jlop;~jVs;|5{#I{ID=qn{5WOg54#O%T49!nfKWTxF0Ox%CMx zEK>I(oiKhT(OW`18)5TB0FlRF^oL=D8NqJ~Doqe)I4gn<=zc^wf~+samcA~ICWXKK z#5e*XT9;x^iarTrK5X0|U>=Lji1c5CEn#*!X@X*Ugt2VwB+4y$YGGVxr{%dV@D>|X z*FOsH3jMxn+w}2~Gw#jtiE;c$e;7W(cp_(yejeOq?uGGxxqB{Tk&R^3ogzLMu zk=GP`5=K32+#q1Sod@j;qc_6{bB&WGhBg{*jG(pk&xw$xsV8Zw;Y}_DV-a)TxVf4?#2=k{-nxJTXgGUie7!Sb44Fcxh z==B>I{pT>k6d18rX@a8lARa|9VMJl$1_5(ldQFAVt6+qAppzyjT355?2_}rU!Nv^& z<|*_#97aDBMwoq0nxJU?(*hhtFkzel8#f4;pQ6_}F#0YSVSd3$6BMl^u(fXgPd4dV!cd&7TfcZMTo`%t%fDvZRWIIhzw6^nF1QSLr zY}_DVE~Zx#j6MTKm@Az$LDBlD{c#k*gs~bnZV)iH(`y5aehduSeuA!5HNp9ue)IMJ79$Ql#?bXTEC4KS&Cr7 z_zP^@AYjI;aMVAM*8fH?v%yId6s>>flR_|Iw7|v<0_I`#nhT@v3nR>RPMV--J)YMh zm@rO&jT;2a-SpZ7qn`pJ%nv(hf}-{7`{5{p3FG6iaf5()3%xFf(LV(v%sZVlLG&(I zhXfPG4`9)|U>!b5ulr&2dtvbYbJ7Gw>&bI)6v2e?3T)gUV5aaMiA4Cqd7WP7{!W^p zXnj9xo?yaQ02?<5m}}{^3`SoJgZ__`CMa6(xKi-}b&wa^IbDpX_e1?4tJP4iMwlr~Y~N z5^DdHMP=Wm)&Q(BknJ+au1B8HWiO+)S-Q)2dhJ}fE#LRkBGm?ywTDVfzP)SL$Zh#% zZ{@|(1gZ>f8hzZyEmiioL^T#I6k&GjG3w_|_;AA@j6a&j@K- zh;yWPqH5zTp7Y1@oEa=@D0ND|pqo-Ng@Lfdi}8EZ#>AAnb1&uulW##iE+MAuhXQnU4fl5C$7I|qr;JI4Uw%%Vy5?8$BziHg zSyZ$!w<%t%%2>dg^Z|KY_ao5NwQF!>h$j#{!ToriEC?Ux{Rk-Tif|Xl4=hNuu@O!2 zY}LkxV5b~3T^_fiutbJeiCC{5CGw2`OtZr0amBTKV|*V?tUYgdSN?YQ-8Vb`r+2fKd75wIJE7Q-HoDO>Ge2|5t=grS3A zPaIkTd(zNS*pr7a|Epbl*AS+6wPPkZW^}b<&UnWn{CDb52T#y7)WI{Hwqo_Fu63(6 zEEg>s5HQSRGx(;Oy~bhWUC=Z(Fq|_J~ew7l!33G4sc@P-^DTmPNPW zO=2FyfWKDSO_$@RGxs-g&slUvRV=hm?x~A<%h9fVM1wmoYJyiRRG)huYex1@keR^K zux3O)rfHnh7WfE#4|@+77e>#TTaR)8r)eKk2>VxCt73a|sQF`)zo}__8yEFb_1V-@ zc($GWO1lXPHyN?d~^B&IiNn%557yI{UbOrPl-QLwWCtSIH?g>LN{T-U-2AbYB1FQs6(?Uh@LQxYP z)--Bl#AL%X$^*~y-%1=J}w%<$>JvtNLa4=_f6j~ab;UN0oTP( zkHrcUNNmBn>fx#4<&~tE>#{t_4PpEmTI}NGFeF=fxGzW^Tr|0;0W=OpGf@t~uFA#C zBkTQY!fuA#nm5TX^kn=Zsw1$_ja35=`CdCux2QclSJODm?tAH=l2!7``Q!9W$2Ry? zf{XWB(xNtm7Zkq-0ZD4*N3?Yd9`L=odU@u{WG2HM{x_i^qnR0 zyT~eS{-ItG;=QKL`iU=h6izhVR3fvoKb4o+wZSr5aA?5Hx^gO-_HXg4%)y;I2Dzk# znX`CK8p7*~XRTvN;Za_>vPSQkZVGgDr=!;pKEC+%I~TgIZy#4I2RqY#<@e?uYY3lQ zA`4?lI##5qIk>e{LDpi4*x>_1)+G3b@M%E{l5?O}WsYi_`AW%xI3?IpyaXMK?R%(> z81toN1DXB(C;U?%_O4BlLQ#f#ACP;uoRIp#&V48vC?io*32_K1u6 zsAvcel_<`EPDK21l3W~HA z%aaB+qhJ>nFW91NQ^DaHuAgzLMV({Ji+9(40q)qw^~+b;&BevVi`2Q$6@kuiV_uAp z?q8}Ha^mLtK1|!Rn(<3Z6vVkVxkrw9QBIx{tSFhGUA;XSt1w?EQ5fg7stS`mcFc=2 zZ*HmLtnBXJicU@sW{r+mLtPEw8%h+&X%Y&L9`ho-Rvra+}u*4K+YY? zKX%NE^U%CfcgV@oI<7vnOLTjQ5*_4f3FLykO!n|GFVvOu0~Cq@mo3j7CCcM82&fL% zkz-zzfdv7JvSMVYFI$|uN)*R=f~?}Wjvn(O9l9_;k=9T=$K58}Q=&u%xB@Qs;4v@I zl#Wsbk{Lo(uie=4 z+F9xjt>7<>GE+xqb_@)ig*&vTM1h<;lz;4)7iSwdVv2w4Nk-O&@MFb`Fc!qoMTR_< zgP^Z?w%29O*qIr|cWMq7OGEg{;^pXczI;4SFxK~D=68Jy=H?F;$?&s92Hb;j4a@3v zP4t_2GF#OlbnzNHcd1vFBgyIMb_YUk&}28+a9AG zJjm|`c;?L>bj@b(l@i&rek;h!Ufy|%!?&bHuaPM$7Xa6dmvrbDIS>~+Z z_+mM_G*FJX1}#5Jua?NtQdgy`&o6hGisdPdWr^Mow(FEf42+xrjg4#-y;dSWmgc6c zqTGXv5J>^p7x;Q>$c&qJi(@gbb*O z^KnTR|Nj18pm4!(Nye^-(RTJ0ZZ-Rx%H&Hd}lj-=uzTW=RT@$4263^2f z+OIa?i?P$1m79MuukR-aUR3lBeW;>%*^~DUMLXxBA$4tn1Ug3;A}4`?n5-y7cB|A2 z`BDUq{|nhYJN-&}#=bxcbt4(KAFMcT2N1WraVp-)2^P1cg;8-UN0L?#5AV!4Wu2!D zelTd0X3yZyp2jOyD+<)XiUM_{Fi_jpwr%JX%9aYX^B6k5eLr`oT|m#+$7qH4vJACX zD-N|s5o+JMN)ylGZ-Rx|El#M}!+0yZN4lNT&ePJX0|%Qm29j=ejGxjvC5M0~`hRu5`eWM@s zD|{59bHL8u1PfOX(TSe!e)(yJUsGkfCg;M~<(;La<^~Pe&V^p58nuv3&8np9*PPe& zvqE;E4B3SuuP3-s_5@E+J;7J8P9Q9PS8?3jj<~sCg(j|BIpN~wbySUdqi*O0PxOXf z5Zl>Bou|#)5;SD&MM2J4MlD+ARn)-sN7In@+=X8PU5X$gzs+-X09~7r&>7R!N_g^U zs4ZYd4=QRa$N>4Pp1o}=1v+2Evgve`0&8yOSdEi}2>ecdUGE$gTt8`V1NPSOzz!ef zkKFH`OAwq|H1JaCyQI6TJ-&}X>`7YmBC;A6&r7@tVGmrb_RL?k*~XpG>@@1GuArG%KrlOa;~7Oel4vK4@LO+Z~jT8uZ@j+g!sT(j29d?;U52=qiRNm zy8DNvP{)RW6S}b>rys5!ShaglN*$g+c?YKg=4ns8Kj?SiqJsjRd(@hWrz&bHrfJcA z12znnENIY&{lsmyo)0+zoJ8KZ?ZpT!Et<3RUeWjyF@Bdsyw>jD>)una zM*lv!w}3w2K?&Oz<r^@149^vusc37~h87{W@l#wE zvnB3oNEb^WcfI_<#9|w1gMGT4N>_awtq?zuec``U+^9W?M(xULHE|FACRkti9#oCH z;c?12PrLrRfjcyv?o*6f6Loz>P1MbWpKGpOg=@3C?nqukbR9w=8;M1K3VSmx`<=W@ z?1!{MJTANDJwL7V-Mrz~(2X0^#MAhjU}5}6RE@RhTQ;@!j264N^R(MTLEpq3OFhoy z71ZU=6su^E?DmQtg9oBb!CurH&Gl5(;z+KoCFN|OZ$C-NG#zXAd1N0yA1m+Sih$87 zn}K$4FS9y=*`3URmBbm=q)rkqjScvJVvNk$5cN6}t+azvbHe!2d z{d40Uwt1AU`ct%+vL&DKXZeg*^vm)?c*Z}EpZ@qW>%@A-BYmhEdzQW&yK#8*<=~B7 z>Ur94)&_ml85BqKQ+B@agkC{W{>tY{MsI#o(F6ZvbZXAe)V>;?kkQ*QyjAeeQ#daa zI%Dc)DV=uAzzAjs_HMD*hc>ZPH!*Pl*4L{lfSCPo*!^Lw+N~FQH*j^SO!ku!V2P>lYpl z@|odn#}CS%$eluyyYGs?58DCmUSiG(y`Hs--j%glMbA!?7QE9~e6;@wgo75f$&$D# zS3D&l_ZL^u@1&RM9*ZEPpz<8&fB1lrZ-v->l?Lip5U3ZNtcgS4HQ@sF9#qZnU~m7i z{XH3{jPtZzR|oxgSz;eOYC*WGq8R+Iz#}Uda_v@xhSaUFHaX}zl+Alf5(xY>yjFOLe9p!i z1hp1xrphK}Yuv598%4 zCk-C@TO2o`X2H)~ib}~Hoi7jydWb7#W?l}*{2B3wfqQmzgo3921*iAY|9MV3j?}j< zT_7+0pXa>ve_r7!Bg{7_4bxKphfu@!35vAT{~?$#CG!U*#kCrwbKrT!1Wguywk zmh#V!>Gf3@os%Gh`70+)P^6{u55a^%CfO?Ev(Or{^ncKPh{#`o>VKfGiQa;hCMeQU z|A%10pde6={?8%w1#Q338(|=osB3r~zPnHD`~$8t#_z&po+&x>#i6PlcfCn6y;>p-;ki7S>Y!sg9x; zFCneJ03%F_0;x1Xkv`S{k2}GHL8*YaLBL#2uQ@P!JB%O%T_n z@=ulV0yKWoQu*iCfD^`Ju$J=A8$99}82yhh!lWpWN)r@msr*AQVNe<RGOejOXVMe34_u=mh#UL^y+}o=fDV)qChH5P^6{u z55a^%X&_7a=e_jW3Zr+!2$P~fDoqgm3JCqA2qp|l16j&HU!&JmF#2UM!lWpWN)r@m zsr*AQVNe>#QvP{{UXQ@&KZ6k_MS)bBph!#QAA;!rz*@>bGx7F`Oy+AU%=eHG?1nIb3DBcfzg-32$P~fDos$NrScEKgh6Q_OZn%c^x6rd55NeMZ%36T z2(PU2Pg*MfTn`xW4{Is^{ESC@6Gs0k4C3EO6BJYU(hscs^PCokQbnGI2Hqx8`DYQ% zWGnw1!fo~HuRU3A^Cg^p-^#uQgfHkFQfJa=`P>twXe!;`M#ePshy1TM|An#t~KShe5a>* znHB<;<`2)KG=F5@#?t&@q4G6<-pzw-%^xXfo+4CjY=V{PmK`!Z#56U3THY(uAF$J@ zk7G+|0Hvh{&{cB(7hpsG4fAA#n{`V>_{aEPCT8H-MvhYis*U?#Lw|y4jc~IrjkEcw z|Ils95%Pl~UunftA8L;FThAzI4dWaso~YVb13TpkdCp+!Ki+{i@Lb|L3F$inLV!A(${W!dmJ-f52v7^&ijc=V-q? z=db?roYsZMIII41Os*hLaP^<(w5`Z=UVD(I{-eG|v+6&WCb=^-_N z3e|twr20>rRR3v{>OXB#{ijW;|FlW(}#5 zKbd1Et=Lj;=|6MSBvC`wfktHy1&=I2?ErO~r!<083oU|n}_AKV&jrJfwT zVJHJ;u;Gk7B@e%%W}y93-K=Szdu)F>GtqX2$cE+Yf^E<2OvG4qo8y>8Z9n()#8~xg z$J32l3ON0CZjsSWTLLEw+Fok*WUP9zt3_{CCJ@7=m>LuSXIXo$`zab-(G!&VRS{H4#j>Z~9-JZ>$Z=xAyIsd~RT zNFH*ufTF45HDIqgmP$shBa75T(|*2sJoeAqIa)x`(a{1@HE^5nwez)rqH{+}3y4?F zAGvQ_=&Qz~9syaQN((4Dnp!}z8k%nPy}FMUP;|7kfYkMygK7aq->eppy6u1Qy`D8C z^91s`ZXS@jkCF{9x_7mJWXyQ|+R}J#2`!-f_5Wza@MbF3e%jA){*hkKFqs3?PeIOL zkZ5c!A^zhfPZS+{c_LYd@|UH?M@r;y<-nQ!HV1?K@%6M1H~xutk!Wsfs2vtuq#WSI588Ue{zX7V@&0Vw*m#jA@-N=v{R0%wkr_gf_NF|Me=*)D zSq!;$#U)P^-MjKc{zZ9sPN_RmxC{sP<;oH*-k2}qDbhc!evPk)= zNhr{spm!+$*fGCDUs+u02~vtn(Y>L#QC-fulqfY<0jOqS7<*i{-27p zpR9UO^D=L4in^7b4k%P`vD{Y)afZAFn<~5o=T5|1u=YWh^w5@pq2~NYR}MvC?pRKx zYiU{Ow&qjOO5Y_b{i79D`Xdvu(l142IMa?x>OJMu{I68F+iFimYo05j!{T<r!%^{p>#oQ3HaQPW(-*mM44|D#o{+a0=b58P8%_t*trJ>0j4ns64rA*k}$$i{w6L zpFGlko73WyWYkmPDM^YSU;f(_9tuy*JR-J`7PHZ12+e(Dy71Ph@} zs2J6sk=={ z);WjQ&`Cg2GIx};RL~&xME3_H|0ghN2u6OAschTS)**uNd4dQk>A}c9!)D>nVdM{; zQKy(Y9R_n3n`agSC6rWAbXve%=Ke`0-@y)_lrMAtNq)@zCk0~e{|>^}k6M3^+!vTu zDz=EH3hdq_-R%xhKDDU3g>RFdp6UXH3%pjAmy2@>+!cfNc`A2VDT0qlAlP!Ls|!wA zbUEFg0(X^%NAvUWG=bP_v|6-axFC&IDA+4=Ha+!DS|M)5AVXMurotxhRWyMcHf!QZ z{7tZ4+1F4pZgxdqZGsM`2IgoV)b0t^G%i{a?A)W&Vt!Dopvk;a;~E&3+@Y_0olQ*~ ztTD@@yxWA>(V~iY-@R;bi^SE!n4A@W+g&@d%h38In!B!WNMdevfL#(PT>E#n8_zEF zJ6FPi8?{>t+|{FeyTo0TecvY#dyqERGrNbb`V+K5OqS1V!$XyITZaB9#1&rz^*;V4 z*fSgVe`Y&-Ru1%MoPy8Mc4;>UdsI7@`aG)Yl%w>7?yBSoeSg^`tF9;XBv=0;ue*`= zgkFnC2^OZe=Xe$w=6F->-<`Zl?1!|r&gvx$TosvEMOTG8FFa`}#^k{e-tB)VCoHvY}oifGcSgMtJhr*|b9ZRyN}ChbwEuk9iXG z!vmUl4Sy3XZXZL%c*sRK#hs&_q+Jj&eD}KUggfp}swD15wDF-j;d*g^uG{%A&3kbK zR-L$}A?m9-aXDf-`wZrP8op(!6W?bxV$ad~=f?e^`Zv1j|Dwf9MLyo2uJG~x2_Elj zPuIl0eG~5S?ncG9UrWBd3TZ>Jl4fcek=&HBT z3UL?uH=tX5q_P+2+y5lQVK-`GGyW#n3zXVyxlh=LEvt9}*0`<%rTtl1E+D%S=4kh7 z(}F!@i#r0Jew3cGdn|^$Zs;%nf1t z0VzEDC`ItsDv98G%6L;K5fxWAE%^8Sb%>!dhVJh#a98d7!xDG3?~hBM*kkh~J!1c& z4fY0z$Uat$>SJw}Pfy*?D|-XfJtf4Y+cc5top4Xj4&SFIPgl3osew7#=e6Gldv*f$ zu{uZT$@zRGPtI4%cyjQd^bQNxlT+jaCx2uN@#FNdBpKTcE@aCV)xi=sxxju!>2|Ax zylK;Jm-_wi>$XGiZf)52%O3;_3>YwvXd!i%-$S z)wL7uX*(AcV=EpxWt^j(z9!h?G#YA2?qP=0EBLABI4!y);7>jHE!B&=29+#U)-BKk8I9LFy#p{h0bUxvM*g^U#ssvOK>|_(}3UTv$9UPB2Pv1 zpDNvT!U!g2tnD5i&TJN(dG1PbYJnrFE+-$jl0~kU*S4kbw3d*fI#Id=Zm2FVa90i0 zl@fO~R5ukk7X1bNG3lNoVVY2?(>^|F~Rv9oDQG)tGu zlLao=o&tAu^B$GBt66%kz_Dnv)HJ>1yZ z%tGlB_{MB1JY#+ZZlOzTH|^M$@O+sc*HiQf1q4ufyo8?m=V^s#$0FabnDq;M><3hO zv>0OK3Y6(jMAP?Bdwxr?9Kmn5?4!L-%h`!IaoVVZ3Rk;0eqL)p zqA_x-iK$aDD(xi*x&1k0vXma=b}GpXY}o>;_pU8{-CKtt5!1vIMp!todACpwvW`%~ zXoZa%1k9D#jLe78XTu0{gOesGS||irM=)WW1ZxRFo=vaKF#4%5!o1K)6BI2JSga$M zFfM|P8wAW->2(E+ehG{)`TK-Q6BI3!R;(kKFn$D^Bdz!xeSZm~{}e`;uQ_Rg@TIh3 z3q=*{La5Ay!77a#1kBmkj6j-K=$!r}%q32mAdZ!Citi>WqDG zoistwLJ`I~f(hdwSWATQM0yp-K}JEtFrZ zBbYF%VJ-Q^x%5iH=u=^Y`F1BwP_$5fv5sKESPpB+FK(jO8W{a>7-0@MX@a7K@{4r@ z6ULdami*%7^!fmdeh!Qj)-{n_(^a#rx^?Eg1ba7-2rE&0Xk=yfrSejyCnKPOF4v`~Jrjv(4U zSWABKQF`42qu&LC_RmQZ6fKlrtRt8({tj!&FHVQfVdOQW^?%aKOgm|Uc$>2h2_}qL zu$KJdk@V_>(dWVl^F$|2P_$5fv5sKEcsHyizj!Xaw!!F|V1)SzCrwbaP=2wFV8Zw` ztR=sAJH0*+qhAgq%pW>wf}(};i**DO#!p}^`Ne1H^>Y~gei&i?%SjUyEtFrZBbYGW zfVJcooAG9hRPhxW;XBgg+f=0q!YeDk*h2Zmy0-&H{KH!Ei<@}F8W{a>7{tGmCMc$` zlMq;bar>213pC8|GLhKZScxD!mJU8rN$ev1`(PgKk_Jh)0b^&THlH0O- z0QJSIWJvI|iAb-68H3!yqf)kY1hOgGobbQ9AY4sPC$TkJL0Es}edz=n>4c{;+)8B0Z& z!j3Yr53aKYt}TB@4(oaVR~y@4L+^)ajc{{DF%?F-O?d(a+GKqglFpH!%agT(mL148 zPV)+u^ncc4 zssAsGFrRVK1VsxK80!cojOSr31;$-dSQ&#-@h&UzS2Nk8exsV#<#Xiswi~$L>Pu>} zt+j|-Q-wqSis#sd#1u>TaiEvXKV2iiC??e)?s_7x%@5Q9}Dtj*OvS z89go_rhH7EB)InCX$-pjY&w-}NiUwpZ`3RZA#Gfxj+e5O7yl@)n!PP~%8RGH1IK#` zFP_FvbX#{Z&8MP{=c+cIhMjT=#20bcj^2Xj%J8}G9;NZS?}e(1GALv*eMA?x^CMn5 z_-HP+O3lSqskzuHH5Xf@=3=Y1VQ8^vm70sKQgg9YYA&`)&Ba!!x!9^S7h9F)Vyn_z zY*m_ztx9vTRcS7^x-=JOI^-wC7-yUj3bs9(_DSBZlQ-C$GsT89R*9K!PK*(kW3wAr zi?LpqojrGQtRzp_kV1Qf=V~ zk~*PUB<|Kr3yqRqntUfV3>(F-Y)@2GdTF6i(@RrVf2P#c9lf;BjN-g(9f9=H)Kzyt z$I<)tsoIuz-L01v8cn@4m52Wgk_VUSnP>=Mt!Pmdg-%!QT}OHji>v-&<3Q4{COq}h zLZhRXrfT42-)raVrG-XKFO65uADU~}1r5cL;h^-=LZhjdCaag;iDc-_>ZPgM-r*~e=%<$!+PivbGG@GnQyU)fEsA;)y~N2v zD@r`YRy$UBtk-kAw&OrH&_@q%9q#IalE>!EkQyY`$wGTyoXo#SpJ@qDB$tX;|HkgVof$kRyGz`ow?drEzgYe0@`~k% zlZD2GIGKOJmbV5dSb;cMXzz=Y`4_1fqr2W860WBzuSm8yS!le7lld3#&q0dk5+@7o zO>r{+V%&y-+2VIePS0_PlZE!KIGKM@{$t-jMR5k_jvm;|7H{v1lld3v#95_^xjDlgA?3FM!~s}Hhv+ji^s#O#U?aV}N_g~k29#3Z|b;%M%LVt;uC z$4#h(Vh~6B);$%8qgnML=S^ll19tc`A%8q&A+NF>OV6P>->)UU3Fek8qHnt?^eNHL>Vnx@oO+8GAvfJ;sYw9 zS;xwCsn4R~&xStM=kYhOnw{{msF=dFqINagg>Kd+UyQYG&a2cz8O=JR3}rNT4NnfJ zjOIQjo<|&L^8^0jL*B}0AE3gSql{Mcz3a6^_G3Ieb|tM4H_CXroADG5CWhqB`MSTL zrN@a_y%Q^*A~zL{C%e$iTFsOhLF4I|^<5ncT`?L^i^yH!H5G){v}in(r>ilr3$uHB zH$xm#&CliBhkJwXL<97#w_3+y@u?~L|D_FzLs2GP6%r4^`t^F6l+Pcx;1an7edq7Sw z_c5~zb=6#ysjkgPZhReuyQxLj(h5;81LUg}21xojP^98StiTBtAfzhj&+Jyy@t1GG zOji8LwsR1J7K446k<74D?m1d>Td)SLb4jriuG&>W>(*RB+_dJ!O^#-~y0Vwug$R!$KdXrk;BR7uN2DJWW6#QvU)s4plG~-8qaAx{z~FFxAS*nb*Qa&) zv+Bz4tQ=cGbe$S)%XxQ(w0FCjBG+a}J9WqKR>8jzmJMZw2M79xGg;ArQ0R=d&6&Zz zfwPVo7y&JIPdCSLF^a4FitN%tXUtYZ(Y{9?fe(lhE>Z1x$vf(Ln{RYw|AY&21OTJj z2`tIwACAfrMX_$m&S~lsZYc%rq#`+|YmwdPV3f%8|6EkETzS2XO?Wo7nBCj(5_34B zfAfkRo5w0Dck%lAd9)aPly9SJ*xXd`t@aX{8|nmIfxn5>+=Tm3FV8vM zuyy|xD=lx;#BTgeuwe7lySB?ZM@xMxV89)yM!>V8*VvVTk<%A$H;|ni#_01Pie*p<+~Y*uMtK z1)_Fo=V-N`3m9Ze3QsdiVOCo~n9YdB1JX2G)WuHkB3E9xcw@H-0pTBw9YL#PJ5LiE zq!nThe##At$-k|vHSBm^NU5`-!3h_t)PeJoJEO82i#tbKd{D41e#c%{J9EFf7grG8 zM~@G!vtSQRV6C&}oDO@%R&qeZimP{mGv9!F;eBUtdeBP1?Z! zgm?<`FT$ezQ9NK%iVw4_?(ZFuKP>L^0-Pt*Jcjgq)I@IUscE@s{qzJTjHN#gNAD#x z+249dUxFI;8<_C=<-=mKok>cn?oEA}F3E``IazR`LU5XnUg)GMH@7X>ucGlU{RP={ z!;^EUZQ&Gw6Un=Ba1kA1S55b6J7;UFY6NE1* zaI1|J@OJXv)=z;$jbXr68@GTJHzDb8lW*g3?J#;B49f4M3Bs3jxS%sd!raAuk`(s> zZ0TRB&LPEZCn;_{eQFFa<>CSal2`H|>3<%!MDivlO;FTIo?7$!MEPr+E>ZJWc3P3* zD)3bslur5=qsT-%GNH^b;y9gYVk9_wB1MWj2R_1Fkh4dB2JVU!*Ib#q=U1#iv!@Vr z9n(%y+xJts3J=*n~kK8AWwOUO-xZ21X=JCruD%Nu&`AB)P4x z$F3Tq88%@MNG_-E92mVFMkJ4O(gblVNp3-;h(xvV0=RD5NqAe|gEYzyn=l9@KZ4B& z32^ltFety1CMeoTcw0{p<%ex2;cY#sZ)*%LlusB0k`G`rLIPaE(n=l9@qhNcDkN{VIhF(e2NfX4=1lrYlf_VO6@f-n2zKvcaz}08MApV^+LD5da z+j@d{{$Udaf#ezVA_1;`JPe+HCrwbalkm2lAfA8Ngh3#AJ-tYPtA7+mB){pT35s?S z-qsVWF}?$vFbE`nM=uiK>UYD4*1i1S3Fe3SglO`zINqAdNu*TQ}n=l9@U!fNXaP{B8h~#7tyQ(xnymwfK1Z#{M z*n~kKxqx0Iz}0JEMDh?PO;EIx@V1^{jj<9oVGu}W=tTlteKm|o?sU=wMLP*^>j~Bv zXTySumQTv(=tTlt{e3VZ`DG_fP_&cqww_>(aVu=XAdq~BUL?TPzYZgke{j+SMLP*^ z>j~BvPr)V(0!h6JN09(m{|mj6`#5QWc$c#d3Dy`5uy~iV4&Om965#4BFd})hlO`zI zNqAdNu*O&in=l9@hv`KET>S(Xk^G>OCMeoTcw0}f#`rL7!XS{mkzORg)jtj+lHYdH z1VuXuZ|e!x7(@gi)(Adoci){Bq;SAT_G zNxmsnnjpMLcv~%PI|*;=JK%u$hfNp+k|*#865#4@gF*Z|X@X)ZI{+Spw^e!kkXA45 zDzFIV?ZM?qcx!xzCsu^F#=YEDy#V8na+~kt?5kIHJMb=|pYeuta9-v1zGt{Ei5I*& zk?bD`W3B_J^)otqzs5VVs9eBe^ko6L6okEpJg!^SDUlrxW4CmduXp2oxh-G)#%H)K z%cQ#5#x-)Me4`sT%We6#pB@4AI+E?YdfV5rRc&z7c5mfSO!X?CIO50dG(!-kHB zc{0My)DjWy#{V)=hi4sGsV5LOw!nto2QwqW&D1`~6?gB09{bMTzLDPku3g<-eZ9jY zB0{&Re}M5|zMYg88;lxFdpPA4Hv3+MbJX)hapNhTb5RY?nNNLNMj%c-OP;}t`nH_2 zeBVBc7xir!CrTJ(wN389=^{L*{tpRaDXM5yKEQ?bI5$yRdTGGO_&DoI}@D)wb&>v^$iV*zi^ zQ}Vhl^4m!k)vX=z%W(n=!YE}Iigm?eAY65yxTv>$ZOjl& zIcisAkrc7&b2P0G&h^Y!v5Hlnmv>OUNApGCt<5=YzP6TD{kW!4tFx$=J{eV`&!pko zDz602G|yNyR>S6;$l2BWI&$K=C0!UhLb*--C{5$|L*Xv{I9`t5r=q19G_>8Dd(<&i zRr_k1lhQj7@uFoNJT~?9?iiFlz1@AiXJZQb3KS>k6*rSgQ}qpQ4RlN#UW2yH zD@qXC<}Yr=Gki$y8rl3gKxHqBm6>xsBt`R|N@S^!(HEH-dp2O1O*uf_e0d4B+P%vL z>|`|iJ~}4VYQL^AYIk z_H;5l8>7euta5NmNfKRoht>~fdN^MlS=g&=!1B&{wti=pWTMR>^+iEWE7ACkDI2hV zK{}iLx?=XMj+Jr+0ZM>gYB4_J4rl6yI%0GtZ213d*!=I3Ss!O?!2WmP!In~Y0ZXT{ zU!m&DqhTDd0s9x}`gDLIjaN2c|6-ljT3)fn85^*F!PaB^*ZV`$ZU_*9dDOXR6!tzF zuz!&{+siM~xMKtMFWxIbiZ@=^fc=Z{!+lHLB{dbWFOwOx=yUfj8?b*-E}IpoD7gzA z#{(O%f04G#4pb!9L`^gbUnt&F80$%%Mfwa&_bXMLaY}CNe}^XRU#duGxL0iJ9@?5& z)o=G4_BOe(e{p^nyg1{H+}OWRH_QoekH!01Ff_7Zz#`Bb zZE|CoDLFT+`6b`{r~&M~!~4q&iss9LaM)%!iS41;w}kgs<#0a_7TLqFuw>aXSM9w; zyuT_(-wl+bw~F^yNaWj@CR9j$ARK48U$H46pjQE6HlIku734Vb^hiA&91RHLkW>mbfG%nD)W z|K_+#w7wbbYn3m~xeP3REl$PSCQRae4ATTlkoR)-h+OH``68Sr)Jiun_V)dxEXH0r zl}6V0yg$2ndfj)FKC2KTvW6FzQ^TK`h&9~&po<;W>oLjJ>F#IUJiH!tdc3UDcb8MA zFHgiez2E^?o%%BFW-Imt6|5G|u1Cd^$0IB*V8xbLSDwP27OLiPbDb zZbofnSFp-zv`cDgiHoqN&TBa<{lJ}@&vm-?ojoPEahxhmm;o0Z*XAwl2KCaG-l1Vd zawz!ws4J;qQY&X1tjlx{4`A$V2;`^YI7CDtYBQhS^_b1StDWdNQ{IWAm`@w<#CdD4 zFF?%rla+a`3H}6+(66Hv;vF(t6^0gm%HwKe=>eWySg{wtF4PXeVqz8 z`IyE0)zICrvGe67(pW;z*uk{u)5!ojznlO{{SyHMGR^rDk0LdU+VB+Mu*;j$%o~d| zdSxhY1Z>~TR6xfWc^s%{2uTFiDe1sEMII&UzLFAkuA)S}UB;Khz)7q?lv_LD{0lf6fYPXG1y)hgKW1J$#!cIzR4Bijo*9ldECsLSo)^|0>sj5^o)g6EUlEW z^jJBubm0F9aWBpxYj{G92854rVkt{?>6EouTePfL12`HanNC}_C}tz_uzqBd)@M6re`kp5i2c$yV7p5}~JJYB+YaL3b? z3J4HSU!Z5~23jHbksKC>KT$>twc%wbN8o5y^aP8i6;3=I*}HYyhRlvZr=-o=yvAbT zwAkuxS;xJZ)@feQXzD18Cia#V%eUO(l5e?P3;}lxovVNVF?2pXV;9m2@pkYZg~gra z#L(@Cp|uM%F}-8L#n2(BjT|a_yPVD1AtS{isMCGan~9%8g2vAmqWcGAa}J#`y}O6{ z6lhYz!rF|0#d0Xqy;*(yag}v8712ON**h$po_d6Y&>83zk6_KH==)ucx&+>yJG+PE zFzwD^!PVBTWJEiquZL43v5RZfodk9akKi!2{W(8;@;6WKJvgLi=g<&-a`imOZy)lP z>EG;mh!+lK-pvF38Nn$Ias#!|+i919%l)&dXzobfsdy-~XfKA$)gpSe;C-7!3zpIk zNjSTB{cM?bFI2xkBH6VmU0p>P622kbUE_$~mp~yqz=QdYj}~0WiwNS$0-+nF4Q$m`yx(D6Q*Kyk_2y?}rthz!{8QTeuH1 z0@NyME71F;i|bCDCxO6s^0vZD0UtL@Ti1y2^gLrrcXud zkN3y9n1K)$tNw^SNKNq$moqnC{?c~lD>!08eQM8KgzCs`5DF+}&%%5LG4tDS%wG^B zS7P8tET@*1EzAB|SFjTSZ2wwUwqT^iL_4(#{iR8h-Au9|su5A`x|ccWqH7a=Yv_`s zJ(F^XWZ@KnlLx`<44yE;!eK3bntZY;LZI1$tukhTDmE@@W=#&!MCQZjX&7N{aMA=t znyj)Zf(hd!*tn#bHP5EkW*Gfc7-3%MqzQ^NX=YOd6UIfbaY-v{-b$}4VDw91gn5^f zCMeS6k4+Iw7(arolC-iQAp>kaN8ew<=s$%K=4(!xAbd$HTP0~_)1;M6O~Tx>gpq)) zlC-jMNh@oDK2AiMVD#xQ!d&U33Bs4OvPLgaNho_3w)DHnwDvu4$4Y)RktTm^iarUW zA2u!tWzCCtkn|tMmN5U*NfQ*)CHt%Kb)u3`R-(pF?X==LRs@1 z9<&8UKMh8hA9K!b_?vm*r!Nw)&toal+BM-vpKZOzIKb30~Svi0COF^_#L7j2qVl*PMV-dlVdhT zFkx(kjZ4y5^TYHSg3CMeS6m`xE(7+1l@CF!hrC%tZf(Z2vA%=?`*L6IiM zY>HsQcmy^sNoUO$>Gc?lz6VB_5z?&6G>u4;V>U%FVN8aNOVU|$e|i}(dJT*)mpN&I zB2A9j6v2dX2y9%E&YGvu>nIp~C5$i!oiss_CdX`wV8Yl58<(WB=B4yH4@N&5Mwr(* zX@VlXnl(=_VSE`jE=gz2`{?xz82wflVLs}l35qm1W>W+c#vfqgl62M#flM{>9Mbwz z^fISAX@Vk6j@cB!gs~57T$0Y3OX!t`(Hmfdd8CsjDAMGZO%Y5ON5jS?>8#mLuM=VP zbuhv_*GUr;X>!b_2qugV!p0@(ta&ZHJ^`bD7)F@4J86Oj`5Suu z5JtZfMwrh!X@Vk6j@cB!gz*AwT$0Y3Q$eO0`4`gqi}W&^oiss_CdX`wAP8|`j zc^kd1gwZdBLHp;V35qm1W>W;w{=vp2>8$xQy&i_q?}I`6=cEaWG&yEd1QW);VdIi? z)@%ZqYGe|O9)c0(d?!s1Z+6xp!Gy607H@U{<_3Bl45KfB5$0wmO;DuCF`FWoFnVF* zl62O*kX|D&dOwUXuW-@?MVcJ5DS{v{hK)eF;Xt7Dkv4I%$F;O^(?V!G!S( z*tjH}HUCMk$6@r}zz8#jcb-ZU6lrqIrU-&a9~R``0L;1cO2X(}~)tV%{EHo}{z2 zkMP8bbhh^Q+?JgHQTs2s&3AV8^(?z4AaJB#ts<6nUibDsf$l=>JQ#H%*@qCdD;z+r zYnaLYaP5XH%CBxw`@t+ANoU!^@Fbm;os!y%q`T|_)P7EG%kIInNbQX>C13NkB$JJ( zE_?{#k$YCchTaYHbcCCAOGUUB|I5S-TxShj(1vFYU6)-%0od` zT1YkPbw+$Mc%5;|1@a7DRI}xrD)8~g%d%H{GTUR1MQXF((~=<>6f{X9iRC&7tdtyxgC zGOH!u$gA_cUeblg7d2WW4CO9@0qr57Oc-7c{>aPUCWlCdN_KU5k_cQ zagGi51l-2mB{*NRQy#F&7%RGp(tHJ*CZRfJjn9|3vhyQoLkKIvie5L!&!5&+1M$m_ z8ON>cgf+gLEF3;nH&OkJJJuYxG8auFzVxnR$#JV{;NQO29y^X(UO9hEvhh9sEU(@D zoBJ~IR*V71t-1xT`d(fA1~+ybx9a+*`*O~XHpi{H?Fag@u#QuXTNyK6Ezys2e{zt_fwGjAp;eMdOkZ9Idj;lE=~d&f@Qe&PD2e6ddX`$6;;9ft;{> z^zhc-L_q*pA&M25Jcmi5}94MHwa~&Y88ze15vuF_dDM0>xMnp3F8gt)J}Slop{#$Au1E(c(s(75^)J?NYk9>Q zXN0o;1v{Ld+gKXvo+6??fb6CjAvhihW&MlPji!|;CW&MlyT#(|87eZP8VtjMo zQg=y?=B*z$gtGocxo}pgqKs3zQvV{IG`m!h&@7BMx>En*%-=6?amE{6sehqf2~w!> zL|5uxl>7D%aDP~o@kUqbU!<$%1Srz@qbv0lo)0O%btSPn7uVAB3SIS(tru8&^$@kiC zAzi7=l$=%6c(^Zhs~Y3nJ9MSYplE!$yu8^1e{Tt0smkHmLC9X;BDzwQqnaQTuj+$j zqaludT9=Ykq3PU+&wtNeOi1ER)a}f6pvkgWv!=gD-Uq;qCmlQkM zs$HV-QwId9AukT08Ii^^vND!bLb7gMD=``m!IG@}u@sM*Rxw^6COIS0QbxhbR+eOF zx_+~&FSdlON)Nz+EBdhDC@lW|BxdZDV10GgR>>7;_5a2Z6KVw-s9zuaQCZZlPK|H| zoc8H=#MC4xMLf4Oy8zAcTO}-(-PE7Tt?%sGDsF}L=o=kaFPV^_wGuF~&539OHJ5g21cmT+fCLEjAkiT#v;44&>3;{Q9al< zaF*xMH=|7~;R2>)hXV4vx5db%tgf8Lbi6;pSksr#VkNJ9CbmCS?lbWqo(Vn=>n7ea zu}}Up;j{+wsjy4ku6=Sw$*1DLoQEstL|)&a>)zS1+U{Eg2=S-pz`-w@)0i!^aR{wCJD zB1}33H&2pN&US6rtEIXX9dDLm$$55UCvI0+p?pzvYCy6jG9`gJ$?1*A?ukR4^xZ}5 zq&UgEuF562rUG6LP$^9+qVfU7bagTqWp0WFA zg&@mlSZw=qxxs!lg8jf-HL(VN6D-(|LY1f?78miVUDkGO{@o=5el*xubAx_ z`iB!r*-=`%sO?(wwIw4d&=_qwUEb!h0%>kE{uZ>J7vsi*eJyW&+9eY8UTF3OxzBFw zihddf8|MB}&IyZ!{H^qieS=nrQ)I}W_;k6g=Kv0-_Q$Ccj{?2R33>acE=f3Sm$qF? zeW+yAFHy~}`vhKH=CXRgsj>pU$-4zzC|l5lC0o!VNoelo_*|=i034qi=@~nPR*1LB z_2?Yf=wJm3Yd7*yWw68QV)m*r;iQYUiK`$Hii@}vP2wq8devOA)rfX#&$jNNtr`A2+$s54 z-RX$dB|mq#SMJQF@;auEA||zH(Z%rsAzQ|mSf_N)Ib;5U{B!6M`vh%q?$L{-;XQqlZ!VdM|byQfM`g56F-Irc4D>j4In8k!O0o< zf8@OjoD{{mK3u)qGu`a&Yzx$ISy*~q5D^jB1rZQ0Topyc1p#jidl_JL+1oRlJ;oU0g&5;equ=vX_tf;v&NWK(zaPKf zKGgfnTisn%Z&g=USHEvHKBgAK>BOeFr6Z0gs@Qjs=+V#}Kl zF=u^y5A>l+Z!P`#@-S%O(ix^?PFrpTTFMQk^J65b=>}770b$EiftGTB>0CkGuMo}z2~1?}3(bfa$zXRi*zdQo^ag(Co=1 zMWu3kSzSk#n_ARQq8fg;JXsyvCyz>!Uj8q^x1VXy1C)Xvz@vt!rkBmsfy(Kg%Cw*( zs=t=@iy4Fa3w8CP`s(ywxL6{pf8L)A_M%ega|-5v$RYS<)mv-m!3o=o#ESZ0nk#eMV&Zx4<{@J2&YfWB!x@YqLQR7 zPXfAhEh^7e@_9f@xfXT4hot$Rgs%gHbBC5m3YV@$B}rS}4YZVNQRf9}JxsU{Ae^_g zOcEm(99&A0wtN?eF$;t<91bZ>gYW^hoZYodQn++2DoNUM63|kvMV-T_wGW{IAe`g0 zOj5XXEh3I7cc&O=%z zDO|c1l_YKXD9}=_MV&XP^?Sl^0mAuM%Or(M*P@c7Elqf#w3KU6XE!8GhcE~roV~S7 zQn++2DoNUMHqcV8MV(`)wUBTCKsYC8nWS(Rv*tQH2+T3H>u@}(lSYSABVe7NfP59&{D2Now?N7ldu~A75U6Oj5XXEh}DMleZ% z{R1uKTGW}wnN2NWH~{vqWs<`E@4w(4Koa&3v?K|qom$HYhXG*!S|*9n;7`a!67~^IizMtHXh{;z6V&<{;Why5U&|zg`_nln7fIMZ(2^va zN;pt6|4!96spX8)GD+cv;C)?^g#808Ny3>+tvv~J(+T_6GD+M`k3=q#uzw)#rXZXX zsntw41_1llGD+d?z7n}e!v2AlB;ovkTHhpm0|5KiGD+dS!gG;?{R1sY!g+~Wza%^W zfcywZ2QZ0s#BhGD+cf@LVKe z|3FKUaNefY9|%tXVE=en@MMy(e0sHw3?=K$f+H@|-b_C-TctS>PtCd2^M(jZ>P1#6 z1wDsP{&paL+o*o?9#Lpfkux<>PRFn2DVX|;$kr6Ao?jxrND=z6K|OwCfT^A|BEM4V zzvjF?@&}bxbN&i5EGb6bRGgZtM?O$#HII*2@SJF>DLTrp(rTt2aaCH)w@Y z<}j`5$a@ry9ISp+Q|!nJl~&X5$XbmeWwT{q*rm1GhB671ztI2ZYZk1M3-pC^=t)|0~$C(~1BF`&Mb;ro-Dy_O|ZR>3A*JqWHVvc1%P% zRr)QJ{)$So2FfG5;V?}3mHD6Qr)%KuN<^+w=_i>EOa2h~k;lM8jc{qOl0;bE3Uq$U z-|i%gp3U6PF=^I~XZkNHec&EU|3js(pU8Ci5a^WCr?7}POq)aYWO|fJk5zWLyGn1J zOn#=)XJwcku~-qTE}uA35p%!9%57FTUsE|Zs`R2MJjxc8?ojEoRr(^8{)S55s?z_h z($A{&bt-L6W!@jF^hA~Zxk|sj7x`bR^iLK4dzF4srT@ru`8h4Tp0`zc^=hX7sdTCv zn0FAK)J=0WK7$aEs7k-4(z~kk$@`GsOQo+?=~*g${7mu-Rr*7fK0>80m_`0LmA+f0 z+g190mF`pNcUAgymG)ZeYbss6Kk~XXo-rgs%71h<`?vBc?Ttp3VwINs5q_#vzg7P> zsa39OzxvgrY_gOJMD=@`RHv;pzjr(y-w5&}b*M}CEyn@30bTlrmJ&8FW+cFtV}RAO z0Ol#1vB+{40IE!f)o)ei0r;`f{3e((4uzi2>!Ak9!Evsv2b|~gdgvhGl9Hstax+lL zW6o6axj^IF033qpAs=Iv@<)_SU&hgX4*5W{6(<{d0M5Wfl}WPFJP&C+n*po;48rV2 zDtWz3yXLu-$?C;c)mvbr<5RFWiZ`M*FsD9%T&kEr!3VFd3-PBqYz zN#gMmN|K~4hXO5m7|S)CT4M-H0m50JWs<_Bk|b%%#Xw8`in)%b)(XN|0O6dZWs<_B zk|b%%F99ui0drkRt@8-C1B7#QXd=M^ohd$3C- zNz#^o0a~)2j}28Lk>Opcjz>y3qqR&@xKxrPZMiED0}FG_qt+zCu>j#TX_+LJikOR} zEmr|8dGF!4!p+obAzTCy&beA9DO@T^lD7OB(31PEN3I*FbqV1?fN<{8GD+c5Ns_eX zFMyVO_%P&pnOct$J^~2m9W9d-E|nxnTmB!=lDE?~YB1d}O~Q0eJe-MICMjGhNs_jl z0>rWuZvM_PYRx7b4-n2;EtAAz7L+7OTgHKw`~q{GL#=MYl>p&ftYwnIrII9R%l`se z^08Lr`YE+ILo(IW$azG|YTD#dNs_eXuYs1lWFB(upw=^lDtPJ?P8raXNeY)rlB6vy zAZ(twCQxe#VIDv@Gqp?-HqTrnZMh#1w`S&AL#=}en*qY<)G|rj;F*i0Eqj2Le04wM z+Dffc2{!3W>Bk+unZuaMOr2)Tq;SDwmcMQ$*&%WTpiR} zNjL`}oRhUo5_d}|Ns_ia9f(ElxyW@jwazE}6d;_Nv`i99<4}?$ZTSe} zA?yGM=T$9}6fTt{Nn8FEXvx2`Hmc!0(|nJr6OaJHw0%}br ztN{pTg_cQTLc`i1Y0IO4mVAi0PNG&DVJkp5=V_UwaH%9o+Vbl_yeMED-bk%W3EKg} zxm(L5@p^%ENYa+~0WDcZJA8#&j}gQe=6YAlB!x>QNz#@d0P(2IIvfpMGfbGFa!t}Q zNjzY)4oTXw0cgnsd4)~XnnUOS2&YBMB!x>QNz#_;qbIBjzE_#nd{Da3erC*JzofaH%9o+VXoqOFCyE*CW)rh43UmxFjV>jDJ8&?so*V zc2MCNLRB4)T?X`IlES5uB#H44Xvy=KYXY@~5at0e{%M({aH%9oV*CSI@^{R&21)Z^ z!e#)*KP{6KE|nxnjDJ8&j%z}$tw@@u5^exs{L?Z?;ZjMG#P|oqJ%qWoBWd1Dco~54 zPs=264`D8n82^A+L}f0qD>A$W*{nedIsl#y>5S z#A|yfNs<`a{sApn%_}^KT5W`_0E~ZHCMjGhNs<`n8nuom zTnZ4*g<2+w*WJuT(w6@T#LMIr$aM>~t|UAL5YGKtCW%+jP?98V`7jWp1#`VlttScL z3C#7OmPul?U@nrjG@yWTF;_j3W))$M%GIc4k|-B*k+kJLK$MHQR#R&pApsE11}&3B zxtNQjEjI#Dt|O7_0%~n0Yy$}AaxIfYxu7IT+Va~#l#99UrPd9EX92=_T+1X;F6JVM z{a-*!R?I@K_o?+VL2^0VsQ`L1N#RmSlC-4*tTYe7suJ#aKxYPZ>j-Ko-6bhW+HzkY zHj(h<<*`&)MA!tt{a?!@vGoK>k|frDfR-HmDso*!t&<7g2jKp%Ws<_Bk|c@sAD|`s znCn4m-9&g1fcw9eNeY)rk|frDfY{c@Tpv;ERl*3q25_o@o=g&(0hx;=)_;JQLE`IF zXF9dU5S9XP|JO1}%pjp8Nn-s6Xvu9yq0Ww{)(XN|0NnqzOj5X1k|eSI14P>%gIrfq z>pX&bQQ?x5ByIU!rM2I2(7K-rHxix)VEsqSBymMhk|b^U2Vh7}IF^gVuOMxyv}5CS zhq(i?_u|8)f+T6n2+)$(EW&vvQ)>j_V1RJ;*D^`rQc04u<$RzeKV+^pYAq$43J^}O zmPul{lDSCQatqLsd!L6~ms0C2!p#7T|5_#~Tq;SDw)`Q`lD}ZC$EbBX;WYrpe=U;~ zE|nxnTmBJsZ410F3`yCW&VoC`pnS|ACnIG1oR~T|~GCfbn0;Br)$}E|M7k zfgu&U&yrtWhP*FR_ff(}0O7o&Ws<_Bk|c@sFCbp*Ggl2>Cz&Q;I$ta~6SYhd+X0x1 zB-X!xmR!VK%cwP*a6AC>A1#vX3r{Ynh~QsU%6l{(+XfHilets5PFTUT3-_B}rS(Ra*C~ zg;om{mJrm7PM4%4iTS_MnoO;8sgNM3SD-FQNfPV7O6z|wfYuFExP+iyj=CfzNn8F% zY5lPoT8~rVE`oY(>XMWsasN|VZC{7h`&4+DpkAoDBqd2(eyp^fIT~7ZczJ485Y($y zm!u?V%iVyMyeST?MO2tdSPKx&N-dKVE|nxnTOI?%8v%~mCsS)3;bMSr&et+Yyb<82 zP12U%0OJ054szW@t;-1NC9g|TlEm|`(%Qf}c!~=55Y+2mm!u?#`ya5<lfp~U+ zD+8yOT5AXw0AT-GCMjGhNs_RCAnrYXMXu|qwUux$0QRqClDPLkNs@&912M~a1G%23 z)^@`C0L=fjOcJvkC`po-{{t;~60dMrBQglWRDf{CYnh~QsU%6-a!(-EZSbkFvxHhR z2NeY)rlB6xa3AE&;Zz9*N)ViAR z8vy1%S|%x6DoK*I{3Xzm=kf~Qpw?3adm3|nq-B!ArII9R%W^1Kaw4yA9FiuThMN1U zT+_8oQn*x-ByBkhXvvnhkn3n_Egy`i~5jSuMmb!XRa!sCzBK| zl_W`94hCBCBi4K)wMG+`0Py}x%Or(MB}vkj2LUlZWgTvyRukb20N#ITnIz_?tV5Ev zJOyaU`&oyVQ|ny9tpJRFS|%x6DoK(U|A3a9!7F^6T6YoN0O0Nuou|JO1};ZjMGw51Egb50vZfCH&Dk#IBs_kS&u#B&amBuQHy353n_ z&b^6RYY7(uaR1jbN!UE^+$3%JRiGuO%to&7Q|n^F{Q%tmwM5S z#0mhEBuR{aK&v0%HxuhBys;&T07Q3E4&XB-lA3=QW*cVOj5X1k|c5e z2V!lXS2TxO;|VJP82_|P5^MXsB9fT@0SCq%BWWTD#!2rE>`t z&LF6*MlMN766=3TYdvQmcTr&*;VA&t|FldJ_aDwkNMijDh%49+x!$4HvxMrI%w+;S znItywLP?Uu{SRo#uKCC{ky?_l0D$#BEt3>3l_W{5{{bzzo%O$#T89wSHYt~+B#HU2 z(i+eE=s8sACR_=?{8!5)@z$94QIeSd0xfwkTkWURx`yy10P|lhlN2tMBuUJFfmkIx z7rAy&>luRDtmTrFBw_zb>jiud=8TvHg)%}T0QRqClES5uBnkTmTJoPP$5Lv|By0fS z{fCxG3YSWfq%B*4STW`mokguqg4#0Xl9VK2|G-M~kDIwS?g4$T- zl9VKEc?S?*xE&6yXQ;s4W~SO^=De826wgNn-sIh}{9tBUdN2Ruj$zVEt3eB+<@Lk|eSI z3B)XmxxPcK3kY`sgmbf&Ny5sRi=-`Y17f{_xt^xhy@YoF!g)>0B(dJWTqJGzCJ_5* zm}{4Pk>P!+PDBdxUoDdqE|nxn%zuHHA-sTGi>Nh~uoi&%ua-$-h5#i=67yf6B~M_k zlc}|ia4`V$UoDdqE|nxn%zuG+v%_3BQR_0oBLLytqh*qKv%_2@ZTSEY9~m*%tJL}p zp==Iwy{Bc8_%w;RNZRtBK}i^%A}V!1{-lNeY)rlB6xK0OCUu=DM3&*At!wVEseO zB(Zmqxk%db37{n#UqY^Tsr5Wzm;IP44D@7@!ljZVY0FBWC3~1_619dA76CB+Ynh~Q zsU%6_`45P98O+r}ttEt$0T}U@G1c7-&!V#nGcjCNn5@IwB(szL60~0M}{}3>TNqEDM@1d2kvSt zTQ(nf#PVgprsYk*F3~Uz|E)8< zSTMu7j=r7^B3ub4@%`yxX`kn7=MCYi*9;^3Pb1DhK!}B#;+?%m^u_z)F?<@{-rL^X z(S8!5#8>QQ7!STzmg{%(YZChux$#kqxI5!82sMxV2lmg;A54DEEk+JLFzLg+hf(QQ zbRi&ed*^yFq`Jm1xV>Dv1elhl(BFZr_w_?G(;<9j)cZ&YQSXOk9xRJ@`IHyoem{y~ zW$*`;EI?kjOUjpU&eI*%-qQmIslhOa$&>j%iDBi@z^V4`e^tI>{u3?teA;F^k^hqz zW>)4uk*}yuRAbLeHgD>R7Q?!NXP_*Gg#w2Sx_{uWIM&kTv4*LsV=P>DXsh?txA*x$ zzpB$dM1p71q!<x~AV83sQb@@3ECfZ9B+daj_yhH?@A3x-sqcsCk9 zw+EUV4Fnbtc!_>YM^|feM_q4MU7!^`{~@u~?(XAe&-Mm}zUD;l)D@fO^{rb6*BG@% z&BjaU_I~N~X|csiSHK6?+$FKbhFI2v#2VJ^-LP)P-Ys4Xf@x{TS}6P`IlsgvsU9>C zn`Cr}P12NVl2NC8!X`-`OE<}nN^Fv224s`emDVH;fnGBD6E=xHmTr=#OKg&D1F}i5 z*Q1nyt08IG7`SRb;lQPjg(jI&#(RnJdTIBPzYoYJ!Q{5sCPC~agzoCaBz$paa!N7S zsN?5P|Jog8R+b|!6u83~|I$@0Q2zSkZDO!d|F2)v%+y6C4+xXNyKtDy1e#2Na1%i< zUh^spF=T@wF2>)$^5$jY)n*_(iC<`4*b&CKU)BbqOa$ke-Yf+ZW=@ccpURCJQM~Td zP*qwO2)Ii|0EKvOQ@pvStJ8med-YNkRw08$;05J1e8yLjF--8(U1Z*j*bJl5>PEQu zhpYN@{Q^%&lL~4FC*d>Fw2ORtS&*J7=QGICbiH6>dyj?cNo#dZt>A^WC@udf;N+li zJ_TzlQHX772*07k{`f=m$J5ps!d^e%`s4RdAy~Aa%faxtuV|C zwpwQL-ZA~JrQJK~D-Cf?hatvq9B{T8LWQJ)PaN6V+uniblD!?cbtg+)YdkP`Ox_zv zV;~4c@DQKGMjxmx-bQ~L8l7pQZSkJ=M7&M)I%T10M7BFingXpejR+a5yAti|+dG>( z)G=}661;2mBSXfq!Hh}0OfJLLZ-#ZH?oYvc0#_twCWirp5W6c~v(P%{J*BB{SL#Lg zxo6Xl9=zLlQ;X6@uvgL#H$Al!l35EosA*NBKN`hV+c2uyN~J*Ru5e4P9L)#Cp18tsCO4Cx|gU{sYdwFGYoTVGmS8>tfa#PmIrhYino-T4N>5i8$;d-J3)3=P! zh)k#Cah_Fp2+L1@Dnj4zexZMg=Us!QvQCL#g!?`|0j74X-uZ%7$;r=!yPA?KNCMC$gH>VtvFXo}3} zm}kH`(r;sYZGN$0i|&MvQa$_%G0@5T-y*3%U_`XJ-2v8k#H9MxOeQqda5Ru8lx z(k&dV!Fo6%umS2q)LP~y6mLgM`jZqom7a8Fbi!=Go(*h7H@2>$d3_JHOlr}GS=tYx>}?*>}YDh)o zyTA&$J3>8Fsi+XqT0Ekd7Qp%dKZ)pGS|%y#85N?2WJERst5j5o=yGc92e25vK}1`% zOj6We^KDbqkc`L;z$!^1%IFIw136e50V4V>Et3@Wy;mU@$%wohSS3kBe@3nA0M@qw zBKj*WlN9xHuSPDC5f!eXLVgS9s*lF()J ziV9g%UM}hx!=i@o8X|HlutMHYhR;k@B#Y=B%=cY@^(}yiKCESu&}AeG`4(A5vas-< zutrwF2_3hTg!zg{)H9Mr4Rs>&@4zY*$s#%os;1I^pNEQ$*D^^lM1`G@bI8(6)uG{& zI4P@R`($5|^v*vxjEne>$|Ou!lA@mB6lzFD-li?vJ=wa;v0$<`bWsAuGanxl}4$Th$!6*(dLB_z#ufYk~R(XVTnq^M`)gc_1) ze_)l0oDlsnwXOhI-vWr}eOe}ob2D;6g?tmC6Y3d1q2|}1Bl1aLm5QGb{ReZr0I>c5 z5K#-w;>jdMJ>w_Tkc`MGU_Ij})C^bhXke9!pAbbHZ(;5ZuyzHA=wVtWDe4(Np@w8c zHUXR9JL+-Sib;>=$l$5De4(Np@w8cz5}dM@e`s^3%NdqZ2cd#qPuCCq^M{7 zgc_0&IT2W;;wMB8rPkg6YYIR_kI^zoQP21ZH6$Z)EwD<(Pl%pQtrGxN93Z0K&@xF; z&-e*7BqQ=-V3mrW5d8_Yt^!#91rX5(v`kXeGk!u1$%uReSf%18ME^>y-vO*&14Q(n zS|%y#7qjL`Mr4`ITqL4nku)O!%L0h#G%b@9^^BiTLoy;~0;^Q~gy>P!nh&t{1Bht5 zmPv|w#!sjr8Ihg9DiuE=`gLk;0a!f%5xqjoBt<>rC)ALP$nOBFRQ!bKebo9Pz`70~ zqEBdGh_0vB5diB@fQX)`Ws;(v@e^uDM&!xBDiuE=`rp+0 zGQc_=Afi9eGD%U-_z5*6Bl0F-m5QGb{Vlcb1Xw=-i0DgNCMoI}KcR+XM7|2FQt=a_ zgDQ~gZ;-9OQY$)A%OpiT<0sURjL0#-DiuE=dH}Wd09a!IB6_%%Ns4;LPpBaokt={z zDtrC)ALP$QEFgik}cYlUf@A)_Q=5^6u!#B%#Il z2^9+K89$+h!5Luxz$z6#A$lKk{19MW2Y~%+nIt^#VSxigay@w7}X?15;duethQK7tJOCC-6#rDcxrC5VS^Sn}zG@!}r zHW-P)^GZE(kfX>o7xh`}_KCWatq{A=@vDmu4&emS+vHzD3 zvm3TotHZQ4Z^Y7WbH~4Wq$=flE4nX^XY!!dkpK}rRLdkqJza0rkc`M>zzXGh%lQM6 zu~@f$p7Z)*bqRgZ)=zjgtBmfhJ!VjM7efZBN5l&LbQC&rlEVjeyQniO9d!Gy7N)~-Ihxxn=( zBcOc*=s_y2ZUE4z;u*NckYaIXK6-iYEUq(MPPr_!_@78Mn17DIIlz?@$9oDnH zCl*^D?~Es~;c8J|N5?{ZX|dtpIIty-u(u<^R~p88EYTFHZ(YH;gTd99QAm0BeZC?W zwJ+eT$;j!d0`d7<4?jBcK7eZz;m}VEgHwXMTGpAY(9vnDc-^188-$!k57Hd%kyhl_##qxh33pbjB4+h+t#|gd1H4+d_h-dTvU`z@Cudr zL+wkrg66i?`FxeWva6#PL35Yj?MO!t@=WydWdB)JuNd9d-orkCwqm&0a0S{rof?g0 zL~rjeew||&DY3SFm=H(KZCZhzz|%KvZfaSWNOUE7M0NR(4daaZ@*F=~T%)kQilSPz zUU?JkJ;5)(=3yao_Uz=Q8zHR{z5=YBiq8~ zxhm)RH>d%Y14g2&1LvKV`@9X)(vuGb?u#4We zcm7ImY|NfB+f_6j+Awof+x(6G1mLiEPY-TCO%1aGWK+DSyQ{M&zI>lpQ_^O#E&JDg zoUYXziaj>t!{};Gw+<7Vgp5aqVBGdc{$@Vod%kOm_W@Yg|;|8vUDIw%kQt zWvV{Ymx1u{np@zK<1KybGp_g00@pjuYY#Pd4QBns7kgEKi-mQ^dxK|$0W2%-V*6z+ z@?z84->u74ncaOGyJh%HP&?P$!2bRn5!0T# zblyhK(N>~Bac1b^^vk`|i?j{T#o6Zzfs2~k*W2Yi4<6p>ePA@&+FYPeGxO!&>BTx7 zt6HTLYu&nJxlS!mu36d3E%Ucv4Ff&utOBJ9nqWrmonEAA zyO&<1W${FN7bmahrG;4VPb}|<$GiPu{Ne%y(QT8SbEg;Ol0Awligq^S7w579#nF986(=qCPA}34 z6AKk-L38JN%obYX^O}3T?_kk;wiR2X{<(L0k!J5%s7Sck&fn0SSRY@AkJj-dj{@CL zpg_|DeJ3sNPA`r#sp#S~#n-1wbaR0c?bEMBsq8zwP)`?AC>mU`H7w3q4h!K)Qu8^X~NGT+>jfg%-AM=t2>m&0mBDJ*rWE zr(gD$5Kth$VKv3S&=>E)vuba1I~)r%#k=txEXwh6{&F6M_wN(fZkiC%J0&i1uTYJ~Ct`p-4^`xuB)SHd>@>}yX zf0a1TL9!J)x!8F_Y1fuqy-Z!+{}s4Af6+bT@-mK-?+On@EP;Zxw{UYip9kQ(EOlk? z=fAQ>|2?$2vVQsVUD4x3U6Fc_%($cv3S82xfI)cAlfeVzyQa1HsI6cv9n{sk3Jb=m zD*CX%_4uzURTZUY&UY=><62Ji-_XT2cHtFeS3-nrycnjl*M7gKO)J*f+&00tRBG>p z^)R+lz}pdaZQ-5n+t`Fy=&Q=Wr+Qn5475-6;4g34b|La?^vZ1er1L(tziW@b(IG6h zcX>O=f}gv3)wWQGqf}L&TVhqeFc7PH(qls8-JF+Jxo5tsDmS@3FKgwlQI-2YC06d_ zp##v4$NVZ#x!hEmb^Bvl4Iky1@A7=+I~?2S%Ei;H;X|QeWpL>oZx{5ymciyjzyqEz{p>l|R4YKabv}kn6@ktw%$4y6XeqALBExCH*m` zf4#j4trPfKKVt*z{Ko$7z)oY1@Fhec7GW16KF!|&(>C%)D`||3_XEY1GfOnMcVsJ1G6da`D!8pfR?1)kV zZOQtRQTByhyyvEzD)TYw6;MgKn@e>Z<;c`K`>3~-?^936a0_=MjJi1gW{*-qQWKZ(9FeFPl)~GdRI!s;qI!+z=qk`_jtq4AbN|e{kRA>~#!B}8Z~Y~##sTrctRX~r;8zcEFLM+r;UR8p)DS0KV~8v9H?Zax zDj zl={}2c_&VPDm)9#o%^Y_JlNxn|7D0*@HfEh zu@4oJ^6I^!OP6!3@$j|+<`{4}yCUn`!$N*f0~Yph36FbE{adW@b~LsTO1Gt_6j#h# z>RD=rUnUB1fU>&BOSHOoVRaQZ8lnz=1I+5?aTLU7J{@uOl5BBL526Dk%R1ILud{&V z`LCc-nX^4;m0*46m0*1rWUO^zEF8CN+={8f!+s-RhWpJSXwBS%TyQ!*f|}tmL?Nar z6I$~3(gv=hh8g0mAHa-m7;q*u0~ONR+^N>7u%kwqf?DoMmbcazK0Ut~HBQZTfKO;j z!%MiW*7i50z`Zn(R7O?gUGzP)w-L6{;xL=X@zSka+*_jA+y=9mGu9Bd?l$1e=69$N zZ{%6gzA>Iy(GJJ%$)b)m+#~W^O!7-lo%a(Oi(A6Db8cv&87jX9+bcG-2s(t^&@!$; z6ge#``@%5KzXrYYcqzCi9?^=bSdRc6bVHC#gCBWfqP;i1`0$0ByH)TM^?N3l^e!Hl z>fzZcmyyEHaUXZX!U;b=w@;?wU3`73&(rUM7Vtwy@&|qetc8r>^bnY-5z6#7uvD?x z{Rteae#`C-V6*xyxT2ERbHz2Kso$07%ukngD0>`>UG#<4DfQqM4fw%mPjg2xwX`E1 zNcHeiVsUq~CUyKG{c0piyO`_yse2wlZcuz6n!@cQ!jBV6s6B+L&Zunf@YRYB9KMD` zcrwulAE^Ed_1he=PAMU(E|s=f_a7PFmp)tjc{|0;( zu~xjV$pT62y3nr58nMSX*B--9rzQQJg6Huv!Z#ChUrlf>e=Ak3dx-GMq&n|!O6w4TpEO#&sFT8W(;we~+D+%#*EcOXzbKmeA)O$_O`xlHNn377KP_;KEXGnD1l#)zi4JLE=0ErW;#^mHq%cc?Q;9frds(wsK z8NKapn41yG>o@9UrBd`nWEhM$D`8_UF!4N}Eo4B%C{w;Cm8(A$N+4UvfJnBG0Yi95lLgZu14uupIRRje28ifVEtB*^29S(M#tHC42J}*E4ZvCr5Ye-=Owtb-Kr$j3C%_LG za6PrQ0;~%FB6_=)N%|oJNJiw(fPTn;=c%P2G6_YX(3>H)xrpA2NVsL~aD8g$$tYfAds; zl>mt7ceG3rx|tyZZUh~XKL)0S40wk5?gv=614Q(7Et7<<3K=jM?`OS`0lOk)T?6O1 z{Xzy%CnCA&#Sa;<4>KwKQAi;of|f}pLk1j2mR`6l#mYod_Pz=5$cvMtQnD_mBlbF6 zga@zDeVn{8O~?DxU_5k$+@AJ}^%2zlkO9x7|FW4ymLK&e19`lV0n~}eax8fGAp^!C zX;uR)8z7?7wM-IW8wSJmE6E7rDKHm_=+V?#0I>E4i0JWJCMoLU!;y<*M0NqIB#G#S z)H(@Z^#VlnN-dKV^*=!{wHlHU`CVX@BoV!zS~mi$>j5H4-~XOW5-m-wv1DtW0eImF zUO_4%{{r;G6VUg+`7UJZEr5v9_rE8T^urU7j7UZR@WT_#qt+yVH69?M^!@M2BysM{ z@C0i>M`SC|4^MCwb94f%4FD0{s%4UXcmk3U`7L0*3QzDIB{NQdAD&=4lIG0->jr>` zKCNYves}_s5y?0Kes}_W{UJ>3wiMRO)Qaw+Ws-h)0+JEQI01fmf*I7R16VZx5nZHZ zl74ssk`c)`0e*Ob4r;9gSjzw+da{;D`r!#kMkM0|_~8kzrq=lY>l}cH-lS!ces}_s z5y?0Ket3eXsC5s(`YAv}U)3^6KRf}+h-91qKRiJ-T;ZGVLAG{KD>_EYB>nINBqNe> z0{rj<3#c_2U`+ss=n5^9^urU7j7Y`_@WT_FM6EV}wFV%f=V_UwAD)0@L^4i*AD-Yw zYF!GjwgN=-ZY`7a!xNBQxd zmY`Go=p-$Z^urU7#P|>N!xJ=7YYxDg0T9s^EtB-a6OfEZ#tHDl6P!z}1inINBqNe>0{rjMh{qO`csZ|fKMgv6jU@epM!xNB~r2~==^IgqUx0N6j! zR5C$0oM03ko*-h}Ik=yTZ`@NOF1E~p!7&<`{-shvEIqe@hE5&k&M-1JNB2;(+PEWFa38`i@Lwl9F znm-Js|9{h)TMRabUZ5m3M;LmkN~`(9&}&p$%>strq|$1JF!U~!R`>a#+f`c40lYv4 zB>X@IJg*nXK+U`SKnARY%s>W1P{NEr2Ba$GaG)2+pkB$lQ&xct8kM{cFc`?-V8tE= zEL#V7)nszyEK#1o|4K*?WUv`@r91^#b}?X-$z~Tm9e$!dZyX2E|OCOnb%85wRibDTMO_b(H=d<3)}@28KcN%e>Om zlRNAKfeZ}wM4w{CSYB-nPv!?Q2&3Zi1Trv;CY&Z~AOkq_RzIoO24XA+-5MUPQdR<; zJJf+U6(7hTlC4BJEueoO1J6EGS-rQegH$>Y$RJ{H66_oZ%$;RtAN!$s{YI7N{!H%ksOa5rZF^{^6a4pQFT z8>^cLGB7<_AbdcPK?b-o^T~q@Jc6sqyI5Rgkb&!2UR7w`)k_I7Fk{%i8f1XgD{4ZLa#gW)J1`Z=d7qr_b6|zp|NZ%k8z-<}8Z01+c$wd-$5#`F`=$1*>)Z+M^42 z?$74g9@qG9@{6x8G`0R9YOO-9{68bV_*pOZ+5#8b^jY}D*Hlp)Ax(d zOAxi!7IpUIwn5n4r|1{oyMpez{%@VB^`L-5aYu_z+>FNILQG|~CMQGH11=Dk8+ow~y6Nx-Ud8ocnE5He7 zYO@M=z|cMKXYUC=w_#m5wumBqUOnOGF4h(-HfL@(N$>b*sX(zlXP)qL7mVR-3l=QH zH{#kh0#Lan40?mj=B@N*aC z{0YSsCE(;}v~_iXdy;m|;#ET`?@qrf#r7yvoc@07VP>Db7yR5UGmH9SkSZmr{e{m zR}t98G$waw0nfKmFrL6p^MbD~O6{Vm9hK87zqj(7;XGZ5$xjwXTRY1^JTFkx-dWnU zC71tFm$wrg#CunGI6iXE{tO+cy?zef(L;8EgLvX)L;O7P3%DP~n#0{3+<~IDbXcqT9fcpiAoPFOYgizDf!}iK!@_H82ik{) zh+pvPy(Psj@asdU?P5EYTRGwv_-YH2@e3xGSk>G}dqd*Oz`C zHBwxF8vbY-oW5N*&}zDTH&jR}enGN6lZ72&RKJUl`;uP~Hw0z?zG@Ni3xYLST_Aoz zPKBd(-pi!b70<@h1bX4h;> z=J^>O-3wgwS(uj;P|0x0J^@`YkE`XK{MKm>&u%RuV*fd2t>xm>_e&c~j&Qw@DB&vy z+*oo5DkN>bJ9Hkvbr40}n-Sc_IISK1oMIQe#A5qgXVGrm^WvVNgAC%UW?m$s3F-I(~j`(?m)jUp#!}bvOl%J z2X>x2Q=Xp?_@Ju5EvdK;R8)T%0@F3DIwJg5tI6qkCH4Zh&Wr!C_JRS|3+ACha_oX< z#1ocyta0x}1-e0F_Cx%;`@y{>^n>61KM??=xPFj1D-DJU>NhJ@0YFl-(o_JDw3`lQ zuX%cK!C7gc03fB$N+-h-bKmxMZUB%KJh!!mD8yW~3bM6H^ zjg6*exSp7dpKxx8M)W$2h_Mr9;BSB#QP%hg$+C_$PT9ABA$=P06N1KcN(shvdVgce z7C#}E2~A);grXcmPNrsfIx!hPLHx6{ap>?}y)kJ2fj17#z&MmG{DB&CS>9S>sFB}{ zKDGD>K~ox9AbvtncSL_v3M?rFlIigiGH>$fW7H%y^33r@o-^Puu3T&`(QJMQv$Imm&AU())*Ccu=v~Loht4e#`D?VTbxH^^F$%z$CUTOSE_Pu1jv*TH4jw($Up= z0zA`-x`{k_(dsjmdU8_+w>0$&gm7SKM_f(y@H(Oq%3h>1N;~3>rKvxt)Qef+dQ@o^ z>80ci@374+U5VZpm*(Fm5tbOz=<__qk0BFo^!R?8ELN*u&rrXHFZGm)xz@|6YHcIJ z(~DY-`?$nWxVzqSmVU;v0XGV#IZUTRc$RUjapvm$!|x|?m>wK<&n#isy<_J)OfPy= zOu0zkNeH*X>O%_B;s=mG1a{zuGon0_$Y-UuH}gx_@aUs3bp zO;oi`BMNaZ{>sHUA7OrM`tKt8dfPjCreNeuA~cX!W} zMIG(yH}o#=TGxAGb0V&FaIluX^|2G%dpE?^bu_ORD;C#z+3F6ORyTjj{5|)qo8Q$I zUmx$RJF>HVbKRzfnUfnDCpS)BvSK-Y>E4pyaqA|u?orn`b?UUe8mBhQtXmP^+}u;Q zxU;7>(YG<)*~@fmSE9Qsfp34?gki^TwL}>2-$l7Z=|!0&Q7#9eLJX8vEGr`svhd3u z*bHV9EZn4^GZ|>lpgaqyGWj-c>1FbHY!oY#bmKe7Shj3F@QCHhfKAJrfXn9}1YD7r z4m>ikH*jTQ25?nkAK>c5OyE(8S-_(c4O8*oF^Pr-{C8}kp%MQbmuQ%V|JEcLcz{@< zfk#+7fAPXt)4~;Vg&5BZ6ECnGll#-Mwd0fl*N)hbb|pR=oV#R6tZDJmgJScJT(oFm z({eG?sCxd}R)1a~G$U%t{y6YNn60KZqNax2WQg(j8(5ZKemQEO3B7in>fNyz9QU=& z@9OL9)dj9F4mN1t*|qYF69-r1`SEbWMA(`{i+B_bga0tiObMZJsAyc+H&pX%D%3nb zNAs+`-VmqaZ-6z=){N#^*VoaZ%NjQJGWe-^uw|4&o_gOaoae{sc^lZR+w#7FKc6Bcm3SPRh zt5?vTM!3q`Y4QivIoHA@^xnp7W9MnGgF56p7JmcG4xY{EoUj93RB3F;*8ItcMA>R; zL%vo&<&(C05zX7En)hfTW-qFnKU1iA|A^*&`I}x753uG9Wp?v;{Dir^y0p?bqJIl} zDtUVE5&0TfwY8pT7g?h!<{&Z^OSJO7}5eV=349|aSywvjclj3SL4~PgamdcLx zLqAU-J8m8UeclWLB5o3Vao*(JUHoJyhNYqI=9c!@#_lcc;$)bB5x$%##DA!J#QlZL z=XRLS(^zcZfxiJ}J{M=)BjOvod$;JqhK(8hW^kTH9s`<@Zwj|x#t@P=IE3Ev-e^3d znq_)ffnGfr50cw3wsU+RV9oMeMzdgrMi*5YU+UMX`Foxw`BJ_N`))$}vdeMz-T-Ug%*Wbwi8!{I^RYHr;0oh_ zevh>&tvqdgK)%P?Maj1I@8Id(&qhU~dAw0^OnHIs_Yj)rBSfy_%EJI_p3G5EEobV& zO5>J(9njOr(=4~->w*q- z>fHDiIYRdgwS`8_+rS|BXl}Ap+K@xQ-hJ z8fxX&kZf8*&R4ihVHly647K8Gs1@I^TJa6572mL0@eQjL->_Qo4XYL3uv+mAs}e8b*~Z`fP$4SOrTVQ%4%I`!S;00C6IAgJ7>Em;IX3oR3Jy~+g*wQ^yTTid}4MhHrd3wCFt-ZOkGv3o9E`_lLMBFxlS@BR8%!&uPfNsC6 z#~|zC&faCc3Gu3TZePOm9ft}0l#*~r@3HYtn6#I|Zv<8k^Q&LfjNB+OmtI{H{v3~9IK3Z}r5H!}3 zN6Td}Bp4vZOe|L2L<3A;TI_A#7{`htH?t3{!7;=|Lvsg~Rmj1)5<8 zn<0IdsNW2)4!CB(_RuPXVQ9q;;P#$40ww!99czs8Js!3C^J25AqLFs4Dsu5@!h|0i zVlw^)mc^ER5k=?MU9lKmeKN7QbAGDcdUUZX3`f02%cq+*hxDz>Nq>vxvqKECd=e@X zCqGBk{Ruhiz8!U64^`Ix0IU121nYj87r%Q&SD^a6H<`)OOQXV=4ExnhkULAZmZ(U7 zapt!KLQ%^g!PBl`Dz1TZX$YVU$uj^X3u7oVCiOE*X-G+>NJ-3sf(|imiNxm?1DzP)-4w!SH5P6C=XC6 zR{|>}iJ>PVX*L5w#{h(_*c!4?%)-RT8(v4QFC$ec&j(gW5<`E0q>0!5BE;R&V(6V( zCMncq*d|pGo!VBfwyMp+-2Y&D=NbGLl|BXESBb&@Q0cJAbU7wTW@wH|J1U(}=}{{E zflBYL(%bMss2Ds=rJq&l15~<|?s5kos?uvwX=3myl|EmkTUGihpcvA_^m}~mrhao& zC6AnncQny0_-T;j({0%|0lSz?O4K6np;1zU`8l}y>9vo+Uq!QCVvR28n+c&LpIt97)hn*Mx+MG1h7(J@MK>T-DK`QmKL^BO>-sv|n)%gEb4Q@0B^7-$4ix3lD&+lt#f7|p zr1>x)q^#IhYz^7yp8zAN6nz`1O8G7@vKclVi*>g&_rwF2P+ffOhxsj24|fdMXr4V_ zxE^73tI<8qUn=m+M0AWKg^PXi4P5L6IJwCy2&rynE4GGgbSq#am7tdK3t zbuW_U4S`NCTPrnb^x9qdZcD9M7?7 zF_PvqKuC=Qwqk3@Mh^#!q*C-Kq$=eaVB}W-ytQrbXXsTqs+u;PaTS(srDSzK2Bj2< z^%tBa%2P$^P~G^pI5~i$KgD93y7AuB??-21Oz;`}Lbt&D#Y97KsPP$5!|oR4u?ETA zfE98WjcgH;=2SpP4Slv^Ysf~I07gwC?JyXnb{LFOI}Apt9R{P+4uer@hruYd!(f!R!(f!R!(f!R z!(f!R!(f!R!(f!R!(dckhrtN?e)Dg5u~=K*#*JH4z45*$h8XV}=iuUEM=$Sfn9=X& z(JTB(Lmj6y&R+;`wr<{?E?W)Ay&DO-K!w9l(mm4+%|j%9)Sd^@W2 zo*xz1^) zB$^Xj1a~7Urmc}LKjg_|Y=dko75Ag&jqsyHA-1VjIxVx6wxN~SLeCDgR{EaT zN?9yCS=`~qS|g4pn2d(XZs(b8wbmFOXsdNawABpUKUL$=u}5&GtX7pCS8er-*H&El zDHk7Pw$-a>s|WE3!n61rP(A9>oNbjXuE9ic4K)>=s$j>--x!bJWOxhfuNpo{Df|pE z>C#|rRmNa9ezNCXVm3ZS7*I_^2L@RNJ9^S!Sq&yK+9k_#%YvdBCI4tPk*Cv*(nu*h zlPJVDv2IZ=?qj2bKHj%Xw4pUjdrq0?#GheYgeTwMAY~6SYAh}d@S$9kf5;ypfh9q4 zP-H)5Fv@ljmP*i27Y-5GR`?E>p3Us za}GZ+dConMsyJMUYk^gd;~<`R4#fYDy)S{2syP1des6kaXLn~W2ILX}5kZj~n_U6R>7mCiLM{}H_9Ph7)kyeqmvOKOZvL~#Sb|#+w5DQ~ zPd_J5Uw9EJJR7Q({~(-`tH-+~sUG@7wGK!!S*mkg>H@y;J+@Ul*V|%B2?R^BvsJ$h6CTT_~Xg@Bn+!B2n!6;}y zBe4AL`t&U*go4rE5RCEiPxx{V$IZ%G4}+Wk2C62(r3hM+ULm|_)Jhssg79TtgwmT4 z^C-dvxPK`FO#tfBgq^PMnO=Q&;Zw9Bx07B{g`6oEeUo5ZxBtSI+h-~TN5aj&5QRzb zECj9J@ff+utJ~cOU*bh5T>|!WKfZGys6a+2GRD~DAD`ZgtpIOgAiaH0r$Zzq<)eNHDu$$nM^2{R)q^zHybT}-d z{^+H9$4eK%(}&8;pdu)PV)!HjrD!+6RznMblssr*vCHbIaQWG};e!#AMH{+@5k0in z(Dm)+E zQu=rJEs_v+I{%6g2Rb-AqXfu_6PGOvQ6V~pNg);@Ks;Y*+QrS6P@dBL5h|2Wfy%Ez zsO17RC){kSg~m@z4}Ke|o5iTElwn88CnvrdZvLxqGHFd!{%&%m44UN{PVeHN=o}Qi z28q%@)%A-Acch~7hXKWbt(~xMYX@I`7ie%Gi1D^|5JR|fw|1iO-(7C2l4-~+L^(?D zMi|nU>Rfn3)o={cL4=`Q3EJ_?aJo>Uj`+h@SHX?O z&qkk@d`@nRrN5!ZtQcJl)=todmxU zM5%#{taEmYtZmtctdBFkTAKl5-~1HQ1z+fJU21=qKrGXiR-nTv z7 zW8jgt`XSXV0%;PP)Pw3O)($LdXi(FJ0+>azWIh%Zsybu3fTsvkZnK;*#@MLZ9ody2BeT}KnmFgq)==?3dIJb zP;5X7#RjBMY(NUd2Bgqu15#ulSvX>HU45!5S-(~l>wcPQL#7|cyFkZo`m4pD0jn8d zyaU2m`G8g_{ACk?*k1q^S}Zo)mTJAxF(OsX@Uc-h16-W@J}L&esM2^KWLcB z>VQhR^_zYmGvm)zc_l!v-7M=7!?cARc?P`A5OQ5}3eQjQr|qSPK6Vy-UG$pJ6a>al zKuzs*EglecQIg& z7yPk#Ivn`Tly0FI;BLUT;=|RL)v7mWtQuVQ%=*g8MqK%~jItIlF3+i{s9TY$Qndg& zUR;6GP~XTkpkD+fVyG|CP=FT;c$gw0cKv1v$ODXH38>jt8;GFvxxjGga8S+F@O*+l zZ7n+kqS#@2TnCc_kxT-UIgpgVDPfA)K!F~*Zkt(pee>91k_Ma#a*9|@BoA)HJngR+}lA@Ns;#@*=EHz>Ta#;({@9?LsiF5H` z7k&IMfE?>I3Ut+@UO_-z$`jIu^r79nv+L^X=)~X8D6cH$Rpxs+IcPl)AzaJcOJQIH z)?D;DM7!P<_AK|u@$pRj%ju7|&>wH_!0m(h%cg#@e}%R;XHV2-ueD)a+Jb*^g56MV zX$$`4pm4RHf6+2f_!1F9bN)rd;PEeLIf$qA54-8W(wxZAfH_`MTTxrquwH$P4kFn@ zhWNLrPxVwJbEN_~;>@gdYsQvwT~LqJtBEj-P+G&ChE5^Hc?0?nO+ z+#Y!VmZJE}CVhfc&16uvt~B8_7so@qwifEXAcYpuURt20Z=pYQT!0Adg!6h|#kz_z zToqbhr@jvi(p*x?nC{()MqNcRSx--XT?s6c*5DNUWfPX|a>lYeWSB;U+tfll;?WXO zE>fxrU0;jI9ubK$JX5ATPe?R>lrtguI7aeCgk)XYR71z6Do0eU<=OTZK=uXS#=C|1 zYwrnWzt6UV8Nt2>0=S)C`+(jSaehJ#+t&gM$b-xpZ1p%JtfsMM$Vf(2hf!Kx3A()z zfB*BS>gh*SV-0Rjb(@yP5`+B+3fb4wxK()hkr4E$i=bgc89}E3LGNCTS@N1JKv3Ui z2&zfo z(R0CdT0M%ttP(~q2@E-)s>W+)To2Myv7q!gI4*WZw2P8Kao0CKKxaCC;U;U*CTsB~ z>MsiG`OF()o5W9?fR?iKJ7K(KTZU>WQtFpmJss8<-uNLwA*869D8FG2;&gN^8k zZ0do$L?s^tR$XEJ1@RyFb^y7(5U8xIX=pu;yHLK?b`%`aYCM+O=QTy9RjmD={dhb6*%~yz`~vMT!L}%5rM(FdLF?z z_(Opebkg$)#=)NntfZ4(K-z2ys?aatTAlS0)?$-B!&cj<#(H^uJ*^;59-CeC0VApb zBf%ybQ>A6ApjsZS$&TL%sw;S?{LGJl)j+^w(CqEPUp5UCYZKaEDtUr#_e{kL*fB>E;Z=d=&liw8-LCXXDPhKK$m5$ ztSC$2f$fGSQby7*Hnx4YWMzCOd*r~;1BbQpO!o16d?wra2P*1oyj!`j9!7$bixby_ zCJYPv0%LHc*t=*8TKsQVlGv(|S{x=MIXYE6F1v~&p#?hZ_VCyEsGtLYqezO|$;%#85;{rJrz5H3K2 zb32?Uav^XrZ(0?z=}|G89u>3cQ8Aky6|?D4F`FJ0v*}SWn;sRj=~1zm9uM;e;g%-V zS)ZWw3?$rLf=pk|sIJAJ?2L!OcK4~IkZ&hXJ8jxrDeZVYQR@rb(tHvAl=AKIdQyv| z{#+^3iL+-oj9 zuSHUcDe*X9ePb$7#!q0zLPK%Z!sU!Hr#vT7O{jP^1a zdeZ?WqveDn{5J4!RXr|FTw9*<5D?b4f~CUH;&XiC!{M!dZhD7*-Bo1k#Z(lYM@nGu zC}I@;u&o#IIwL{$Wk2efqtYQ;FO)zHkB@Yugl)Z~roOa1QCeP}R5#LZ*OnDbvt4JR=1!Y?g zQ6R2IuSUQzwB5xY{umK;^x?QgmfD6tZG{&jtz-G%qz!c^sw_c7&UmD~2%fj`r>$9M zB5g-K@e$xn{gfx{ew5Z)jEF6i_Gx$qFF{(n3ei`=mtUlZ>#YQ0xp&Ms)QN+43M`bT z#}bT#_X`ZCAWx*N5DKc$!*DHIPiAwBA0XQ&04OTbr|4%Sx$2;&cSCXxz9cZKgFcmD z9Q>oeU~DksrznboD)c&BWIMA7IVwmQG#682?DC3AvK<==v(&5_f^y$7UA!q&B)Gi-6iDb5Eq0@b56Wx?ap1**>gvDN=E-8kr5l5OZS z_H9GZZb$JD)MpN<(Kmrn+Ki+V6o_HvC6ZkMQ%J>3fgE*ZoI3Xsu1vuG zAyI`Dh3aY_4+%CyM98w@6OpT#2gl+rfzUAx0g5>jzftO@a2b5LyjaTR#ZoRWmU4Nq zl*@~yTwW~Y@?t5M7fZRkSjy$aQm!nPa%HiUD~qLESuEwsVkuV^OS!(qQVv&{9?Y$4 zYG8S;&|NmQh>^7AxbeEtNjXAmY89tU!_^?bY;`Qo(1)}`GsA&`tQvd9zSQOM6?MFp zq?SUfQ(sw)g(c_$x^uj>>kL97j8@XABN%0K{U}=sl+j}W!||6@s1xO|+qAGQb51%r zq*4}kJhcIaq^@EVT}LRgoD??zMejp7G5%}Wg(90aNvMrp>%!1cFu-Z~2`-YB`jI4R z`qETWBd?z@Uy>Il<&Ll0K+@ea5bsvDWMW0YqYlT()#2XqGf;kp@{f_e8%cr4IC3G; za=#n}3YHlnv0_bWl2!(9W!ab~e*IUp*U-j*$H__0iKo4Z<1Hi{a5s54Agx&J#c&L^t!M_?sHs5!qSYQ|dFNl%6y^|AUn7cptDs$jI-NocWH z;J|=cm1P*QEgk<84Vc&Agy@2?gK&i56BLX6UZy`6(O=CnL}MFoIguXAtB2|1^gl*o zD00YQ&&557HM#A7F#FnHN$qz8^p3DLVGKB7MVlbD8WX_5AAtk9tbo>zS;e6TqOqhb z_FC6LAFUbScK^{GT;DN%=^=nBiWKA2M%ERC`WPx&%FdRSQX;hqF% zxa7Mu)E(#X1?~`0zN^w=M4Y2sa33Wca zwwm0FW-*UahD?!nARjy@yC}vc6DV2h){7|>y>>~hEYWMzSS)uUJ$$S!@w{98C zL}i0|e=O-o8%R#4pU=GD5?F+nRjp!K-tijgh;vY=4nIJyQgjFe=FY)R_!>Il6I6IE zOc1ka*xFB_wSrHteI-yG5@kAI58GqYh_Ch|o{k8&iui>%91lZ#M!e&tBfoX@+AkF( zzHkV*#X_kE|Hy*M?fgCj3m+p1#%D+{g%eEYn8E9%U#@PYf{%$QmO`d*LR2A6%LQ9>uRr0tK{j6n&aw zpMhIQpT}NtebGNr@UL(rxy%uT|0d{Xl!$!MC>k3pfTL+b_NI&?RuUGmlCX%Cghi|* zEMg^L5i1FcSV>sKO2Q&m5*D$Nut=1IMWQ4u5+z}gC<%*1NmwLG!XlrNF!u>UJIxSl zlc_}gD%HgvBGZB&Xj7$C?mykM?ojArV{hM^V_c}DR+KZ|?KzSs5QpT?I|)a$FkkLC zExSnH{s|f@CX;USN?<&~oQn-@ISylfMv3ctz|XdN65FCJ_fIEc!XOXqTZoSxImw+s z7BVrT1t<$8slR(C4*)9$^9HBGFOY`Aqu!nwL04Jr#aUd|$FJlmwrmi4=_zrS) z zUONr;58?}(?i9a1WW+`k~y2zE`_I*e@1OT=)9}SPs(wu|i1V)zTN1$39oFFi=G$$AbrwEKJ z%?ZZAQw2tr<^<#5Jb}5E<`l%Ut#HZG{8-dR;o^8u)%#TaFt}5Fay@v*W@iH3vSwG<(+HRPvvlV7B_KP>^1abz-r z@m=^&VuLP0ta`qwPa%epT4~gnVK289e&FT#m<+z{arzAgR zj>PU2;Rn|O_=&|#&pKks=?`%Qw8D2E7U`YWfl$1#vj@|UuwZ#ZW(crA7eqXbzib*h zb`|>ExrNkiUtAw==|#Ya1NV?{ycPHSV=VvtP1h4Og2EK>PWIrU5B|N1a7!^HQ-cau z)Tt+dLycldcC*#yAh|UF(VyH4QLBM8NHtc>39dw+Z7Yo6#QiqdhN^6 zS{l!ZnrfUMNJ3m%14Xsd(wKgUuhR`gddPiA$2|YrfoIf+tQ&9!4zdRE2*-;Rr{lZR z4h(aNJFwjuWK^a*aF5y+v$Xwkuz%*Ef1aAB)ix|&vue1+N$Esa zO}nk@pdYp5%4x479<@4n{;sy41Lb2}(90U6O`?gy^+Q$Tddq|0Orz*bn3=ATfkhr% zeOcC&Ojh6uC>m_89}`Jk#X5npC;Tir1o|8w%M7D?G+$*L7~vB#gQqtGI|O(&fy396 zt0PoV9*|hQ(@<%wE7$VvWh6)Mr#`zYG7dIHZP`)B@mAijFsk=0|P<; zQAK^SdPQ{|ZkeJk^a9XG1_vFKg*x8q&vtK${t6f>P?zX>**0MZSfrD3kE4|yyxbB0q zTLBdxEJUy*BBFMD_ z_pv62@SbF_46U7BJ|N6vPGK@Bwm@HN*KLs&6J31yz{tS_nmPhIh6T+fCo{ zJz$4}OFY>2)qqh@Matpg5ZLW}FG4?jZmV~w#<~U(=TMD*1JA@|RJ~i_LfIzIto2~F zT6_$pEw5fPWMmUxHB|(y`AP_{=i#rtRa_JI_a&jd&_?fK8#J=XYg+n>AO`y<){uRU z2=6xVYpa=rp%Cjiq57Kx^kma~<3C|Bfw0A@zu*ZAhC8ai$ao~G;XQ(`c0%hTmqX0v zplmEqShfs|WydM8#ajn*k^+1jVY0f(#oVsKOW@@3rfD8;n&MWGIkN$oGx=n=bCbj2 z&P$GfJ3l!R?t*J$YA`OnH(|%KTDEBhT`X}0mzLwPhgd4$4plT@ZWus!O1Rzd0A48#4C-xK@EajT)iOW9INxN*m@Jfr=!hZ*Qh~0QUuQY2Ue` zv{rSa?LlIPE+7=2yCO$LXbus}vk%EfmS-Gs2e0>gy^Ln;8{;PV2D7wMs228@F*3#@aI9(F5W9Q=d8x)ufL8V6X6+<5oe!^9B`$&1kn(8uoZQ_rFsVri)!cz68X!JUZxN8pHed`RQ34{F| z`TPu)5=I8P@h*cUjvRq-;%A_*xu1f25l4>H1>?P}5l_51a-kb^G`W_&Ro0)Rj0b(2osBE9)wHx zp(7WMGjaN|ntI$D)I}eY{y;#2pxkqvbePu4k?h!XGKNU|(g@4F&q*)#MP2lO^alb; zV?^e#+}}7~Kwz$}gFzk!uUB^mCb-MZ1#MG{pl&OzrAiM>r*vSP(n&tfNiOWJ8%|Pa z;#ZV|fVe8@Zh(9Zl-jD{IFe_AgQw&SomGPeyU%q)A)W|#0Dm2-FR6k!=!6|iT$ce8 zld}&KmBZ448lI}x=U3Anyhw72E>na_I$?qtDvu7Z(^Qt>!Ee(-rg5^c4cfFY++Enh zE`_+QaHD({_^@pU9t9C!=_zn>L>!E$d=@APgV^J{1qF{_g!5E8z zF%|`5EDFY06pXPb7-LZ|CZb?WM8TMdf-w;VV5M#Ke!R0p8` zk5Z}yn3F;lu^X4Pif3!pfO+Ek_{*jl+a{}WV!txOxJ@j<-Ec%8=@>sUCYAU@0TGo9 z@W8NK5!LZxHSG9?*5#-)u%$6xI0Xc|YhJGxuOgrr-nz80nLyzOICbPv`hgmn`NE&6 z^O!HVLi8eZUN&`F`|yQ)nwg_C*8CiTMv;k^!955ZqR<`kE*0#KLo7u7RPJ;)xkpG{ zt=2e16~5XdhZxF4wqcOVAzUK+07O<^ikHgpmrcZGk3fUd0-D>zI4-Rr0!haZPjHbj zIqnZF_Ag>dz1EULw0RM`z{z8JGR;sNC7ZK|or@U93;yG*ekr-T5O&tQ4ilorINop_ z`mhBPdW3*MCiH{@a#qNA5~C(DN$D-L1j0LQ48SY3dxucQDIX=k2rYOjE!z z4S@=1l^Lyv&;Q-I2%9*q3=1jm=-1%1|9Pi;T<8bGL09DHZcWe&P!TtrhYKN_i9vP? zF=!$_u-C&;c~`l~(@f6Z4U>a-tZZtzFgYw|N!WRwh?0dJhbYg26u7xjs{$;UvxzwE ze6*MN6)(u$7MAF#o~XkS#JLLs5k6KIiT<~CDTAptu(i5M? zBdjgdbvW?E=?A+Xf;ma@B0$84EobM$Fkr5Z&J&`D%pLX@z6~7(R^^PLpHs*^p@bvW zBo+TY4Rfc>HwYB|ls}E+qnkk!*dhQiEFa=>C`tt+Re`Lo3S@OvAgikaSzQ&#>Z(9iR|Wpn6&>{qtfex@PNd(o zsnRNUnwvb$R(2;lK@?K<3OJc$rxAd=tWAAHDU}-PG8~7-CczLZf2~$)@Rv=rX8#B6 zC5A)o^jhd&TX6(292XPJaGXFuY$Aq}L2S}z(K`04U&vAP3x*>v9uf}{A6SX=*+od? zc)^1x`PI&6;6N=uTbyBW7DorQkc(yzFen$zCs4SCQ%6$t1JyqBm&>W|d2uG%L2#HW z(EHic>wX!i91YJT12No{fk+^7WgxrRN%K1pr}*-Gq@Z_pOY8+&UoKxz*uD;a`+iDB z$C8M-2&>|2_oEF6n|Kpk{>WohlBS3>^}zS`7eVPP?sW3hthJiuLm8pdQ?HZ0A; zNbwCa-U3UDrK`1i4u9E1&h|*OSeO{A_}w;^VD58OM2@Ck7@32Q$qp-Xf`OX^8^FwP z&%8S6Jgmm>3)!izVl4;hH-vKuW%aeVm>x%smLZK7poJXLpXq!D=0@o$$ltlI+spQ7 zMcoR>W%wimC#ym)iP%JgsDVPR47J7$P|QX*K=(jg!GWNHaeEr(Qsq4a3O_-vjyy|0 zN^M}W`3I2=b3crI?5u!n-U8WV6S=rIaL_r-6VPzse(4)HG|pi%{PS=>%pAhjh(!v^ zk_(WgA#CELo8mK=&DffxspT|DxCN9?^lUiof4(xWpUZ_@^2i`}k;uprlDQveo zt2y))HBFdSzRRPSX)OZW1*jiUN_G2imuY#__wfR)I$fdF68vQo71~dt#l*CvrCuBT zOv{NPrsd&7n3flu?_ctfYMWPX9lq==`M_Ej(8CAFz-zh!x#=ZZPYN|#q76;MTq+qy zpzv(|G_sg}T>bV4h}6PFcwPe!nFMubHuau=jn?k_UZmiTl6-a$)@YwwzfGL4?fUJ{ zwFCBFWNoWo5s|S{$R)BrfXJ3WkbDY%*+gu%a^xFssMkdQDotXDQMkyE9WXbv$j>HP zU8tS-l~xvN?jG4ONEBSCO?N(nyz}`MYUSvp77Mk_1Pm_J?jTV3`gD0oe7{6 z+oGXRD!Br3HdxF+%qQ8@>p8SJ9{w{%ksW^%u2^_8H1Z#W`3;ty8Wvs=?R1`W4UpA4g{Rgx*C?2}a?4TDnvwiTevABchz2DEO=vXqA zR<(E-OVN06{aB8X=%_{l(d>aXRkEV-59JI8Bgq3_VzYq)>s9v|r6r_sM}-h@7e#v-fw_jdW&a@ci|cuFCm&KtT@jRqzb_+YGklDYu04AXUv%e zm(Bu(c_s++Oc3UoAj~sCm}i18&jewf3BocHgk>fO%S;fKnIJ4PL0D#juzx0)$;t(L z6b%utAI72|=<_M;HG(>2`hr+M!@_e@L{L1i z8|cQcx3h9!M@R-VG_cth`WFR1h7;xy9|AV4coc4=0FH^n3BPte#(EFvC% z93JaAJl1n~tmp7p&*8D2!(%;%$9fKr^&A=NIWpFBWUS}NSkIBMo+D#D$3NEBqF7r! z;f;0fn*1}ddA38Vjrhx|vAzMVr7;antlPc_?wcQUjSO{wB^Km)bj0%xY(5R9>eU#0 zf*;zYPuAC}G6dNZ7$QrMVwxo6K~f8UoidjIt*A(fQ9oj|!)9@F9Ev>+sLv*pJJTJn zjA&GZXkxQzRA@c~dl06#Bu{TmLA=)i?=-cI&$j8UNv1ctm(XoriN0Rzsn;{j6TF=# zo9o+sdfVD!dZSs&!2nNiRlLPhMrJolodpAN<@8E~KA0sa2K{4FBFUhXq?pL*9e$QwQ!*J-t=^4W)CLZ@bw=VV$t!Jmh zawBgpLHJ6bF7|h{Tm@ti44M|2Qo~j#z7RqBU4~!(wY;%90LUH*P`Z{kb`FJUnZdru zdVaEMMnN>p7!(d9pOQUghIHp_SabD^X~h)&y3N-LkxEq zy6`Rc4e_q9@zJ-tJ?29BPITuUqQh|oA`e_AY;8hnm5Z$dhv|nrrcW>*)Bgg3!tB`^ zGKUP2Lvdp1T%tUO9>MeH4*?|4p+}+!+kDwdjG#H+gVX-JKe_^x!<6OT!V!F;!i8E? zM-{yospU9TSF=ozCBZ_HrImUUscZGJrkKiwx=+S-$t!*|c-FBAf zWlT!VqCK1}EAhO6Ti(5iV7p8N#Gb*?U-g0uof{JH1NPqXog=mhqMJR_FG&bFOIY^E z++JOX9&z}5lD*QImyg7IF~h`*BJ>6(sosetYv=;TXC zrtkblhQ}wu77)ri_5NE{Xvw3)12`%?fqx>W(2v4P@YFf)QRjqLRHR@hAXkY@#5uEU z>X^JvXe^jQ9qIl`tVLR%k73~g>`M`_Nik$?ydSS87J2C!6XFcQ6gWTH4wFnxoDxRZdYC47 z7kVv0i9IktKBa1jwVsLJL-B6}1AF`mPp|llP*5OCURf;Iw zRwGVq-X(*U%WSe8d@ZZGT320|? zQ!vFXUw5OfMmsi`CTEsY*b^haG=>DjmjmWs}hvIv6TZURS3>+?imX3u)e= z0CVCLhkRsp5dp&6$i+32U{SVufcv@#4CE{5W2*~1=i*P>-c4YyQBZCIqXuyB4S~5g zfpPF}0;8M2)`G-1_@2P%Ca}u@RU-;A3q6(ySo`iB9 zJnl6CX-#7T_KZ`c?K`O~%jll9yLm(cQF@G>eUT5~W3xG)#57q=Sd;|Q2oX$p1RR+k zr;?ANcv41uHvn>JLXALU<7f^-aY~kVDxByUgV1 zFPk`J=y5dHX{Oh}67WgtbQhjR!-SHw|1>{`B#T>GKf)M8{q6x$^NL?vtBVqq^~u`O zl!|YGxD3RuDs(Dj>i&L8=54hOn<8~Q~@c95&oH@FM? z;()%t3m-uj{^^^5-I-loXp@ke0Ja*v=HUWR>OTRdd+f~ow11hu_ekJqWTdm{N&-*I zpF^m|uk7vdyhQU8OjsHfbweY(iz&e-Cn1CrO7Ieb^vlm~V%hLFU|feS;2gCireLdE znsv-4=$O;6ykCyLY#LiOoqnP|fQ5q7JY41Kc1)Q&yf6>V@pVk#ybD{0id`sr;w*p1 zkfo=xFr>(sh-2KIFw0OHitf+L)RIXc`EbJFe2Lm>y7Odod3K>XH-`3tb%25UMVU$!n&Z~x$aXto$Dj;9C@T6PB_g#JCz8r|^+!sLr~=l6^@1-p2bn}k zNf%p8KDuv67MUha?I@TEC;wE}7oF$%5)=V>OBGPM{5sbcT?bz%PE%~b1@J~Mfg@|( zE8#QoYv2}8*W_=5qaT6OQ_eLXaS+zC>ROaB*moZrWhFwE?UMH*g(+y~I zqM;#KUzRAZu5Vh`;59Q}U&lA?2V-5lfPq{W&G&`Ex&GONWPygt>IxhZKH^cVm&6P9 z1>Vzym-^`8=!J;z1u@H%Ch%6xF9Bu`?Mjw5sDkfd7Q!zXNlP}zq;mw@^JP&M%n`4D za7M4YIl{o5a_ZvcxM+DPu6U(k#UA3PYf|c3j8FPS@?darFxcYj#OkJc`J6q?vcq>7A~u4Q=opY+;dlqb9H#Xc1;S5~s}w8R)VRqRXfv-8_6nF!D?zwfMVntE+5{Jt zUU!?AuaC5O0`+2iRCuKAr%CjnZ`T^z+)FA!kUs-C&@ZSl6NxSj5FOU|Ohfb$d$8&c z`ACjx;tSF<>c~0@3Zq{<&7O&77c`^7QWkin2oilEN3E@@NLFxF#Ro|XWRbu_Nhqx} zRi9+4Z3ZHNi)O9)payyL9JA8390-o$ySxN6Z{>qhx-HQ1_oda(x(dKC;@?$Y> z5U9tWEmuK@gBx#c645acoPA0Il3)0&H`INY&_-NynWzu<&#T_lr!Nf+n%*z?~ z4e%F+@L-`TqLDOxIaT|YubSYFRIh1Hy_jr?e*ILqfU4T4cBE^i7ZZylsuWh~nvqg* zAWgYzWC?$UcS9SSYEn$C0f0-h$AIc|_%w1c6?+rPj0jG!dlLU#pO|DWGK$f@F zFPW%Ip=bOeuHLeqg=b_XDOuMcI;TXRq_3wSl&mHCWZJCa;8uZICHfSqHV1DPSg1r# zBNzwo6Ii%JPbU$df-3YNT+8Ui{7e^~hDI&ALjM-hKR`r56>9M`JcCzIu~)&h4%6Ex zN9%eDbkes_HB=LtV5{-;A)hV5L;zwNN1wNgU9$om&zv)B_^`n}58$&ih8iAXbtaq5 z%Xu-p z5PmUl1-~T~mhW54kof59$cYWp1K*l~=n=GmOrUM`cOEa84&{*L_N*K(f5yO&f%11A zDDTri`8S-{FNraDFMfk{7gpXWB_{dd+k6cCg$W?@oTt)cERfLaRMfk{7M2=iV z#7R%aJu4zbRVhPvjPHw+JG!vosz zfHpj!4G(C;1KRL_HawsW4`{;!8o~&@ooHl0W3z_dPBb#0jSOfb1KRipbOR6QT|qo= z0-k9wZ_Bm;O$ufj&@jw!+gGILXxU{Gcsmd1Il8EwOI)^_0X;!#-8CY0SLWr`%3hO`hw?W zQU|!5N92d?ePzO@8KwHmfB?T#{~#d*61pq7-{{7J36v{B7imec5B)7lsLW6h3g}s8 zZhFC+i3#ce%-p%FvWtigftmX_9<Sr{uup`^FVgt+a4@~mh_%(`#R{i^=s#Q z`_1hGa44=#f8d z#@@}AEE~hla+-~2-3FFuOY4t+!z9cR?L4Zic3)5zw2;4f(lx&g&b|W?c64gKG0jQi zZc@IOg;*dNgker5JUVmok@PvtJ3vFA?Qij1@dYBZuy>>Hoj5U;O@f{Ox^1WkGhVmN zaQEaL9hC7b&v8~}yj;hf2Jx%|>lr%tLN5wnr&Z-tz!77fV}RAbIlNOTp3e4)MG&bz z(FGXJD(8j(lrNHZ55JsG@!t)`ds*ZAn<@U6ZoExVfc}u6ZwH`m)Qc3APnFAj_~oC7 z*L29vJAKCnLAeAn@uS$KQk>&0tdwZa_gU07RM1w3Pba?Uk?Y;HT8-Qa6AS!h6WQ9g zqP5aWuYD!B7oMoc0ed(&p~Umf_KO2#ILhZCM*k6;g7gFvwgAPGhJZuhn8S=+#Anuk zVPtv>U;>bfZMgIhIEet^xeN|3f5e#oFBo;v zci`laFY+OrFrCZep)SV!6oEmb0S%9Iqb#V_ltoe8qloVgfEe?SgHNsj2*oK`-V8X= z+2o^OWC@&H+Ch#~l8;1}NCSK!e#In@ZUl>*2j?Id_>V{D`?uD2XW+j8)e{5%e*y*A z`GiBbQHm@hZ8ZQqGi3S5=kPilO@mG52l&e>GWr=Z0kS!8_V|BKV9ykRjZa)t1hy$4lYjb@P5uG#O#TUo?S8g~!ph&x z`p3RvAZxf;|J7FvbOB_9@CnzYCq4dz?$qJ;$yJIh<-s|ccYOuAo=yey!CzK& zJx%^%L*X_ra5BKx&1dHO0vXN*Q15tW15PDO!+0ap*#PP}M);BojY}?KGAJX4u%c6WL>JL-k&o2Yoj+{xu-=)TN^;%sEp8Y)jvWY5fT0?Ooz2=qZ z(L5gu)J4GP64w_v6_okH3rxZ=(4_fw+uQuY1$oIb21YPMHS`Ov;9QDvCeoxIHFZ9` zJN+T-=jnqAKT)5gmS-Tpf9iew6w(DA`u`Q4eCChVdf~*;XX$VD&hts=l^j zP<67panO{C##MOPb{XHMIj^pIUC%W`MhzS? zbl}jQlj|GSCn=|%{mT0H96EULu;Ydf9x|%u+=_LjjXkH;fipDKR@9})Usj)Ns85!r z@c5bj1~=?dxR9_vi@_yHoBrto*0k!nvYMvyia|}O>YBzujTOo2(wgcGrK#%rx`9`B`Th-3PZsqRnf#uv)mSVj)#MsI07U^pL^yGbmMG zkLsfm4Y(dIIVe?qT-l1$aX9q=)4zn%F9T=HoioU7Z{zyLL45OHW4f7FaLE_%spS1i zT5f%s;mi_Yyb}!skOFe+JTZ5NHDv~%m07fA7@^$k8EEi{3 z%9?5_8h2CjJ`$KLJX^G9pL4}IxOC@@VUih=kz@k=wVWp+L9xSPwcfX{7kOoaxA$m; zw`VBZSZ_dTG};~?GiKMfO!OjSo+MX48Ma^3a4EyfC3?JtVkM(D`*lRK>Jh-h* zroA@c@)`|X?!4JVcN+67x%wGt|G}JRWbX6EF$)mh1b8(!`!cu(i?MkX^RYIn%~f2p zuO7sjwPd+euRYDo?KVM`Ch5Tx{--sz<}fWz*wX|RWULVF5_D)5VmnE4p7bWc%H)XA zqldTP%?D(zDNk0fq4mS^#)kGOuvLM41(P047~lo*R(QdRWPMXzbD4bQ8O#etffc-I zqTe=V^r)9c&X~^sJ@L{@FO8Z$<3~pK78ZV{zo>$?7PT(HMRh|_mzrpqF$0cyV%N|A zHqYqplKn53ES#21YHRi&cj9XQr5VDC6`81&Q)tYKrt>Ca3Qd<^nbqlSfqnw+BNe~r}7Uxf~MUs*9+zCz2l>zH0>DRr>; z^;&mn@2y5XCPdSStu8z$m2){rX?at3$-^c(%9t@GI+IkMea4u+qfBoI z4yT!3N1B)w>tLd%n|yoC@y2`!NxyFNM>2;JB5g&@KrOoMMJ*O%p9j|k1;JGeaQ>h6{uhY#NsQ~G1b*YPnD zY>Tb@VtXwvRyE!2bADijdYB_9^0*ZyZbc6>#g9R%T=AHlLJBKdVqy&dA?Zphq9N*< zzE)0&>GGKA_#+ejF~njFo*n1@0QC$lHPOfL8!j?>MF#x#-U~#~*+3xTYNG4k82w#Y zuhjVIx;1s#?ij?==X17yp(V>M)|ky81e%qnUSy7{Hqj^Goqn;=1EjpAzViOFH_aex zLNw!IyTq73nCJpy7JczX6Fmb5D5Zo$SHZH+-26~dYI*Vu$!7;sdUV$zX-R=<)Lu#< zI$51w{w!l|wO~(5p#vf@iGqddLr;QLRwP>pYX3vxpGeOwgfZ&bam+!6!EL!N$Sf1p z60Le7(JJqIOaHsI&0mk>`M)>TVa zQ-mE=`ifJZi{S-}`{HHH?;fG~>lLVLjG1eqDbs7MiT>7@wX^3MosyDd=YtUQd8Mpi zNdvFvl3v0D+~IZ8YpRL9G1cg+WrIR?KAg;3)6ne(YgY-|{xf9`{ERXB9m)7#e*Ao{ z2`E_W2YPa?Uj%-7k>V-(YL)4<%0&NYy3R01A7{)!)6?o$Y`XtwyE**v$4$5G7j55e zdR`0xpa`@2CEIsx-(I!7>NeAJyD7fNoMxXp&BQiZM;5I##nq=ypJ6&)Zm(NmS7cbP7>{a;gjtBJj8x*%=PQ)E}61MTkr<(ZHa zOQrsXe=b2a*zk>KbHm>wc?mM{W@G;H-~(DGIcz%Kws|;)*|yoEkK+ zd3rokTnPwnqKU$o1_N%Q={(tV>1mFbXiRGI#M|+|iDLydaqvX`ckxdr-;Vztp4iJ{ zD`ZJ%D>}*3a+WyIOL|u#fugO&9DD$${){T015#cqv-9WPy!UG%y}5bczFx?rCwnjd zZf!?7L)pf9TxO_;LzvfpZK8MGbZgVCxA8Pi`|02H<*kOcLe?4cehHTIV52WYW2TeU zsmL7mqUkn)2t5B*GayNR(0GiOr;|+4eJ1vzDNZ(;j!9FTN+wNgl3lqP5CLF^g<)9q z*z;&5X=+I#i1C6HiRp`I>cu3+iqR81Vs&=SDmPq9VG}*oKGO;VE9E9y^D(MeE8!NPR1U*6sH8ygKy^p z1>ihm-(lrVnbC&{0`@I;dN>ogzY@%SA+8SEAG!CHx<47reK&P)GjSAv)uQeXQ0_z= z|6$TthAWJu?)yf1yM*+<>gL{(^a7Y~bM0R}mutV(&Ho?G2z$Ptuv=4WWu%&Amvip_ z$pda?88g++{mketf|t4eoZC!~eJ|jg|3*0zJ-+SHN+91h<74}UobMkgU+T?wy?&Gx zfU~pR=K9`t5$F57TVJECZXE>?bM^@lS6spw|0JF9XOeBerl8Gu_^5)jy-V;=3}$V0 z>ty;)H$8fr*jMdyPBi9dqYI>{eM8M$LCuzQ3-%Lg27iUyaAi7U2Q~YK@m+%PFSp26 z78?$Qv>D^uYq_@XViEx5F~%{?95vk>0Yy1TalVJ{eXITiss3wJ4vie69jpvvka4Xzxg1z>{?e-T=oB(Lq zi2&ss;ez%6UO}mY8Dsz@C{^x}{yg1$XHrzR5fkk7Tmu5{?r(xAwja|cn&@Pxrtd#z zHCC|CY6wS34Bu#>h!*eohi{vw{)dlZwA~bjybq%cOxea@4!;3EH{EDr_M?okV!P^k zp7QHV7b~yurn(#IZbH=-T#sOW;g&iMEe?bbM>0b2gGH2tzE6KpPGR zZ`IdYks@>W7JQLYj0x`RdX)$g0S4P3x(rvag9=Z}MR=HO};b#5nFLZs24zaGbqv?3d8M)mTf~ zoiW_UNdss3E79f#PLggsAC(}h+gGJwXZZ7MGikhn^Mz>GznL`BbP=fN8EwT@cbs`c zraudzq6J3ZE3~$6d3KUKpA6>d7nMF~bK}?C!S(zgRBX(1CVJaV+rVU|N^SQo=W8YB zyEEk+z(Z@=*^E@a#|~8T;+c zZJg&HXz)6FmQ~f>7G(-rn7y{o6z2hhm^XcGNF@nA}Lc@doa_>Tvny*RX<0@Olc#%yS(Rb%?snj))17ZaQkai+_SrsEc%RZRLO-+*Z`G}A2F(W3((AM zyWj$D+mACD-t}r}cqeLj8QiTJ-eoSW$IV>YZ!IiKGMe4(Bk#G2k#Xo9KHS9hIyl?^ zKKY|Lr~f)v>k_yvIej}$KxwgvDzYaDUU2CsxLR9m`zJR~@SSibQD7%FLnlq4nLFEb zoMR3fYC5M(pA^P6&dS9um~9GXgAcDh!^GE`;&oTsUpV98PfTnuWbyTb;5*D-I|zsO zX3sWyuuMgJs`e1dX%=vzzwqqQ;K;#*_&z@1WHUKi-@rpw`D zi8ba!7XQN7xiEP((PK@~Iul#Jb`dsv7n#`cCRz&fvnd?-C5*$?|J|4~jUFqC13|si zLrrdlk7laJN~*`nq&~v6NI?A6Ci)_d^MOm|Ote?NV2<8J$Nh@00*X_!Ovjh5x(Xez zYLhwoMF$>3mG1@Y)J>-NB@?^W=yRo7vZj-2eY{7C2--hQxs}m#3^a^!6WxXN+}R6( z7Z?I#)JVQQ>Rq$F133wo>4jtGK}T42H`CCR$FicxP;49%G_^ zHF}D0!u?XvCNAibaBBta4-`HtyPLdoYJRe9733KxEnTlN5L zRe1$+pY;N@JVYg%@qd}0x!+p7W~!A!KbC%bmJ0oT;L0h}*XXxf_S@bT^oSJn=L25Q zm~Su|KR)0EZIFV#h8@}6qi%l?#`lFVwo^fECXBru&>zb`7>jPfU zBT~?ttrjGUrhQ}kW4^=`_&BWbNS2w+Hl~Bg#*_x~MH7dy6)9;c8vSfzFFEh!GRb^K z)PZAXON|*t_6(h8aA`Npc#FJdL?8-|Sn_F|5 zQ@=Bj`55B*}l<#3oXROPn6!zQAKi-=m)^@hP@RGeNd@HXE?OVhM0{SyEf=)JfKFOG3bL>zP zyWAYs!Sw8HdO@>y-;`lJO%z6RI8jYZ?sTre5V%;awYK(KTTVBk$`*_#y1#HYx4RGY zzponoLy?0HzOu$&SKcn7wOWE(N*nC0uG@m!JD-0WjItfhMI4*42uDZZo=TwmT0H&4 zbniQKLgu~s4Br{6=zd23A4&O$OV@VFid%N&sTRBK(u}!nUE_A9d1dkXwQJ_B@&0+I z+ZOn0`ax!L$(Z*=H*(&8Rfn;T_bg))w=P+FE-MP0Wsg`8JJs%&aVTWW`l_jl6f~ER z{{4j=xR&4r@87rYF?!>{C(4R7xR!SiyNT6J6-~aqqJz2r@2ggN|9>WHH>T`KyRo;U zqQvi48@ShsbTAEuvynUB8>1Es^K-MS5mJqYb8agXkquJ z)pvfGTTNGi^x6&^?Ngt?-4FPEReFi!jJ?nNYFVcJ#-BMb;m>^Usp^iKx#n*XHZGn% zJxx`6-(xRGkA2)43A8@NHtVt3VqW+@Ww;YJtvIvn93PQ>+9nbR%MrKNHSXBMe)aV) zlVU_)n}POQp9P!M^U`}5m*)|w-h<0>UyuytRD_V#r)_HZ-~1`FlQB)J z8ybvmkc{OD$GxG~u5#Mvc0Wlmy;fhGrr5pD{v65v(N?qH`w<)xw)IP7Z?2jB%503_ z+53u->Fc=f-u73S2ie8@1tSkg_UFT-!ebCEvfq1*yda~P?zCx!k-#u+6E)u^)chkF zbv|kqtA8Q7Pck0_+s&N#;5m%q5*RkG?ALFa(Ft0l=}*K8VDDMjyW2V6mmL%KC&19;Rh~HA26crG^TxVOntTQAITafHoXnbm+%jLf zpAmtUnB#ABa{JM~<@T}E?ZW+&+dn0@PYH2o=|0x&P08(}U~a+_+fK(@<^0J7+^HMW zGr`^x$@L;1Kfw9nE*fX48OW{;guGoC_IW(a(&Ba?yFG~8{&Df7oaVZMYq!=r9TXtC zHq`DC>54aJZqG?>FcjJ!B>c4G_FOQx0159wJoIO1x)65Mly1yrx!76f0#&k`mVp@ zpV5C8_O!P(94|GzhuD*^hJozbfWWI{kiEp&EzOL-He`39WOw6!$}T0@J=t1zZJ5PY z3WIutv)c`WYD0EAgroeCvzwlo-?bsT&63@%`zgDPlHD`SvirGTtjKRwxgMCZf8Ui! z`De5gsp~tSZ{NPh;=lg=2MirK^t6%V5FR+`7`T0xPwYEj=-5f4hK@#Hfb(Dfq2>6m zVrVsB^d0>-VCX1(i*!T#_U+fV9RF3|>x$u=aOm<%Bt6>qhiy6>b=q-u7pVAmT2@Er zJ%GLC-&2INcFx@5*y)JOdcZ1kLQ%I&|9G>HG<<>4 z+6EGN9S?A!`9Ed$v>VB@4RhFV!NFskU3!KMFyl64_pH=zJEPQhkbZCTdqncPsd;{Z zE^mXNJx1ijUBP3Udt1BrMZNfIs@*TQZSmBBdz;^5qUU&s^GiZx52zO%l57L5?6{g~ zWpS_x2e8zziTg-boneUjEy?rj$jmo9!g z*u|oJa!}X?f}SlW)t}@p*}5g&$EW$(L>u~Kpk(-ct{!>=4bCJax1l>y(jEV5tvlLK z!R<2Se#I3`GZ;~Ew;h3_u4EegfDri1)@|FiZoQ@PmaX1u^dwfkobbP@d}-xqXnP)T zY@-T<4taYjkl7v~hxCW7j||^;#`;(~b|j8}y!hLb@$VEmZl`AnZwau#%HyV)0I6aOcW14O?(A>jXabNE2}z2s@DT zKv_Eff>fT*nCOuh4r;KaRYOjld3=xTel&lA({&wyvA+LxHvw@vZI7bQ&WB2#?) zJ@~yO&O|{!IKkjqa?X>l0}Yx()MjV0gUC`=ui> z^-wsp+kF?#Na*{;xiI zVNLv7Vj+!@z#_zp>8M_O0jAZL}qH^1SmcIHd^l+`K}ZD36qw;&=G`I323Q=~TQS z03S|~BZ8ccZ{LEu=kOU0R~8|`nzy!@*n@n6eJS3H;X?{!NPC07nq%5fO(oTQgRA+V zRPzJV`Ag6p`YZW8eul~T`L8vHRQT(3R`HBG$ zQHrH^bH>wU8$m2?mOCCE)i}ZM$Hh3>iSt#9&t9~F_@#w2p2XR|;&1!FHnhFxGM>j? zAmN1X9ek3mGmc)%hB3G&VKW|v{E6w(WRAKPEsl1iKI&qxxdt`?h`~#lXI0ZdRvd`M zf&Q;ZWomqt`A_D9ftg$SPr0D?8hX>_EfWQm;PHhsjah2CoMetV)5KmdxS21u!I)(x zHXdhjrMy#pNFwK)opBjLi!=aRUYnIL_$9#Tr5c03nt=Y_|vNFy#i+;RyR> zT1Yn>9B*U1imIQA_n9o`Q6@Qv;9x!T zF{jLgG;21OaRZH_drY4%nBFsC1ZX-X>7tQ=_nPP>+uy?NFL-QY#`KY<0Ah0jcaz)$ zL(Y*#zbRcVLar44@3u6sfVv#YNj%PF{$iq+88au@Fxy07VY5&uTI|s!>yKI&Cxf{A zNaV?f?2g9#%|tH%OIx|33RieQrkpEzm-|VoEqRas8dv)t)Gs&$gDYrHGEtZW!G(Xu zB@T#QhNn?^=sm5p*E9GgM%hNVEoFuSEy{?*)9d<~EoMOn&**x002n7v9AIe_83>*1T`%t!9-SChOK|W^YdgICk*0rPXx< z%NiPhcy*vD(dDG=wnl19m8L3YmX=jj*HsLfU5{tq=Ln>(bOpT z6&VL)@hjI7wY-sI8`tT&gHos6(Rg)ZV|9I!kv8NxkYxKY6el=H&y6#|&La$<6&vfq{OeztD{r(M$+yoLFa)ITgt@)nx(P9)jdLt*$yS;J0)4 z)385e$TcIG9*RO=X^Vx;Ay~@{WO?YRdPtbJ6)iT}p9)2cXnFOCCo*r~%B|j0<@V2l zu(W1HeX=@LRg2=dM7dkPk^Snk;Ld|jg|L50PpxmLNTiab)hQ~F%UlE3R#cr5#CE{63Zd2qgXDvT}K%%KJhWt_My94M;DtQ zw%(W?ZSBL-8`n1u!Z^p3TIrJ82jx_9qIuEn(`bjqlqQp<9!qVXlDW~%I=bDMd3i-; zdv~&f>FWB%%C)q`)c!*n9Idw6+n;NnA?>sp#4WRl+wd>LV=Iys+kvAtHZ?TVCsTtU z^Euvh=eG|U*45OPmDW@YO8h_ez6CJOs>*+6zPU{%kIA#8lv1WoN-0fgOXVdbZPEv% zNl4NMTA8NFv!Z?|L@%UJ?{6M@0*!S(h{_pZ@#(roO91T_uO;NJ@?*So!uQ+TGH5%*IA7QTTlNs zS}DSR;qdtp>Vq2m4bTVvkKdDw{ZU+Qu^mJ(+Gz8>OlgUH4oL;JI$ySbh|)qLrDc&*sf4| zsi_IS#wu9sw|GE`74E!f>Zft{UVA@jfbMAOSF4LB0**Ul0sCXDbg(%RD<5Qw zn`vdYG%^$CJ2WZX=OA-C(TB{ZMPg-EWD*dQ&|c?zqpVEAkqkKL57|3&(cC-rmM&IG zm%ZnlvoE~x?Ds0=%g#Bc?Sk{q$JY7N1fJD0U!9ky?RW~shNYiUiW2r+s^?M&6JI6S zIr+g3>e&l8$=~ETgQfAyF1x(%;6wP|XSxqQblGLt@rDgd-AE0*=Ilsu96Y-2Y~?^? zN|^t_g~^lETlwB6HRCPktq6A93s+&aJ*@n{$YfUe3S)P$7!DS=`|)izKfVoVX+Hzz zkBWSuCJFi<{I={y0sS#$3S(bkvEScu?b$zM;p+s%boZmI;21B!U%P%)#ofNfA(jx- zlnbgU_JR-;2$A#oN@=06$h=;35mU->ENlw|_O!BPi}CXk*_`5#A0}%fKRFi2O;>;AMY6Q!3R5vp zESAob&PyYOG}#u!N4vF}p2%CGS-yA0=ndqj*IK*MtiA&$f(?(*(yUD`vxeH$GhhQc zib{L?(7=xVu4JE{x8gk`^Hpba@xog4@?Z9Tr7kLvlUSc%iD!B>H8RkBl@DgpIXUZML z#HD&{U`UGIHZjS0hpbNwZ_pu1O!;r#+qyL6j!A0-lRjxYx7_w?n<0mkxpHeWYva;ujd&4g)sahT)EOYv|qYZ**o`=OO!qG9~Og>QO9QP@Yf6c zj}rc8edFIDxBqm<(2q~CKXMCi|6PRtP2ev&gT+#4|KNf(YnH58qwHCLBQVhLln|Z| z$cUZYexHb2KF1LsBE&D_xb<#Gaqm@s;V+`*M-%h3qL}Le{OVP?hq^y2o8=Kf;S)G zLiqnkDN8Ld^-Wg8>#c(v!A}W+kKskmg{Ig3n3Z1Jd@o1**M(JV-s>#Zz)G*{!@P-I zi)^zPX<~IyHDRV@qeJHW1;=%e8W|~yv(g{2*k%ae@R^$*S+U@e%`CQtW2Lzvcf!#` zyNj9f|8NLp?C01SrYex!A=od3<2Xk!8shzeK=2C-0=Z+dv+>*M-VCOE2?waezODRz z_Yf;9WoInMnE@XySk6j+$6{Y$>^&mtEpl*FaVX429A4?-SpSNewL!UQ&v~p&IRLz; zvw6z(1*fyvwUL=sI8adF-6Dy6Xi_$KUtYuU{vKzB#WubC@_(MmSVG{CCzVh^HaNbx znd5kb(ALqM-CGjN;f77LP{ z$KPO+{}-Qw{IgW)e}h&0fsQgLRj$Az6rZw_e=_Aqq0b5)eM@e@ylfh9`zgEu_n-k- zo2q8hZ)S-bSoMvp;{9wUj*57ewJO60*y69UiV8MaSspnxtn7)*3I6~mEsR8Fg>mpj zyjmHeH_BdoclvuBm8($Bi_8vh-i#9yL>nk$O;gt{mqYush7xoD08?&88|FR1Vl&yo z*IDUKcIHeL8)57Wp|L4lOGlU0P-(rGqk9!gOt?C5?ow8|>M-r6U5Ka4_!BK+kiM1! z4%s>FKNAkta-e)s_peOgvvP8$&;lG&&INe*xR(eY*W?~%Wv(7kEd}D(%eY}x^hoaD zKPli}kHalS1^!JU-1AT5tATzT&q$lIb4UL}0{-)6`0@bxb5`N1S=aFHy{L?xag5Ev zF7S1%^vzG;KduxTMROMLUEJy%_MU8X%7axL-P_b1k+QP=U%~0`ku~L!((~XUMoO#2 z|CO7*>6m$@=%J>3gB^{Th5XO8fuTVyc%i zed{%S`%@SO-~lYXilI$8-nu%;YE~RPpL6SnG%H>cnH|Uf+5E`tDw-M_*}ThHtn(p# za-@Wr+@Sq)2Ss^Ue05uG*BsPH8)Iq>-`+VJ%nM)sx?d5ybD?E2FCs{o6G+tg8iE0q8 z*}@@w6;Sne{do5ztN1D`z-aiZ5e0O?=vBJ$`s?(1FBK&U@UqXLEC}my0K3}Z-4+{6 zRPL}A1fFLiTX5W(Qo9A@bUyajW1WBf#Mis7$CSPNHP#qAc6AP@cxrqsr!tVsi zx^UHrbY|A8pCtqA3|4$IW8V?+5CaoV-U_tnXe&Xife_3L9e?-fgfWc>FlfoNYIEAm0Of^rRK4ZH2-|2Xo!AdV+3uhx3%VKXWnLYi2>3YyatYE0aDUfsM zNzD$F_#6Hk0YgS_>R1K*5~ve>*oveKnX<}GCv zOIhqn#+C@y8$ut=rS7<&YboVt)Y#{ct%3vp=u!(4YjZcmo~L7_nes6T82@tBmM`PX zV$nKr1e?m*9E$$?IKDSYe_YGvFJWiQVQ0_5LD}0`#oWj#Wo+_Atm51`^Dq*WV&vt4 z0ji|`f}7+oWnq$QC-vmXAlIyzeA|b4cL9XwVe=_R+x~VL+450WqfLTn`MYDIK;GSs z@s&V7Dqe@CBJ@oO!;As@*@h{BgvC*VVy$lCbi@3QuPc~P@fs$&IDuP7CHFL-T&li{Q8GB|an{sq9 zn*mew#R$$fE?vRqehx9xDahQSC5zZ^DPmu`lFiu3VvChiBb8ys>Vz#ZtamBeA8574 zgRXXwzw<#_zSuYe|IM0l#=OKIE}g-5HjdlA5!ue0s z-sC+wPwz?L%&I7JHC9)MT!3c?Ij3WAFBk{oG@k}{6-zexFESq1rf-wa2}!|aSh?Ce8Wt179C zoK?muZsTS?t*cdh|IlIFA46Bj%v5Uso}C_HSm;`Z_f);~Fst|;PtR(S9_~1F=nzWd z9wDr%Ayc6OB@P|B4eRRB3W27uJTeckZ$EUH?inik7ml$KnNuu$=rGZNjIa6169+E$ zBAx^UK7( zT;bZv4SEEHjbOJ4Pex{*Lz_0y{o^dbZ;Mfbo8m+^b&k%+#B;#&wlMLK-l|!6OL$}x zf@nlGjb6(%vgv?%iHK{yLINViHBVu*0u#qy`y?pocJuQ7_&I*WWuW9U2$lCKQAg-_ z(!i(&O5P>0)RR4;I98#(j;_vp9yehNnR@36@Kf(6j+=mTuko+oY2J{xXZ$J9+L)Q; zurfbM)9_4I_KRPwW^9c}5-{au2QnbiDtGBLV^S{OxtYY)xtZFNZAq{>3ZJ0P?6+3$s4?efe?xwcD58>ez7Y-+kegyiJrY_OokvMREy7 z#n2q1)5*ptd3UVrFe$N<#-+Gva|M)5)?;-1gA=>3sIft#RyKu1>5~b*iZO!~e@Rbj z+{(2!VSxJ{C{fc9!>liH)%{7D_rHx5DAPGvIm2?Hz;ZWX`Hq1_|iaI^d^`T-MSbH9ozkXh!4s+Jpnh=WPifh@_vR?r<$T*5OMF2J_w_Dg^Dbp`maxf7*{NqM``*hYpRYbt zTrh7Qn}K`ok*&E2Ywlgh2;?7HGT^^YA~WN8{I#nvY0f&q!dPQA4W}^+w6*IzZ7@kg zjTY=2TWYw)J+>qmgKli;7$4%{E*54jkgLO3N5vj?xeY*4X`_O6jO^htvi@E4OFkD7 zTu6}bj9tqo<68W+PjTL!^g8tpN-4HE0W1`lXCe!VIsg``^UV@2-Dv9o7O4~oLaXau{{KM`(Vvu8!aY_9U!ewea#Z!MV3|2Jng z|8M&2+4w*HtzK~UbT$(wnQhfK=zKA6%n z?T74)jqI#TSmocaiVkIGWGWr4RZ_kI2WRbC&q_beDmJpYwXF0Y6++e;a>*c|3`B`= zYpoEM`B`%BOY zcmtmpKS`MW3!66=*2KjmU@+yUi)dr+C+OqdYjswY|$JON1^=##jSsS*)6Q} zGncU#x~p5@5@A>sSD-Mg1MiANO!*MuGJ?t`t0Y?#$N6!^*mnL?JqY`_)GMJtC!jer z;o{l6SI$5SwjhSerqm|b45U5o{Q<4<# z=&;q&a~94zhgFMoNL0$%x8q{U14Rq#GkZvBu#;g?ec&|jcvIi zJ1bUeoNmcwV-k-xFxhAbcEpm6G8XysQJSMpmvazIc26Li(E)y3>@B&OY{uidwV1ih z?SSHWVROI6%{Z&gy+xnUgCgD%0<-+Q9Krx3m17;}B&r(wlz9IKVpu>_K z;6HvA?~iHJ<*YQxrtDhIW-Mp1Kl7dRIC%Q+Sp1``wBsO~rd<1pE0zg>if~oxmhc>m!OH;XgS`ga^zmbaH-JIj5Ylii=t7S1deV zfEC-x1X!0W8V|5PrVDh!3f(Hf=x7F3(ax$jG4}N*a6>u+sUf_Z7Mba%{WjS>` zLIb~GVH{|ceTN(sym}{1hcwH~3M{n07qla5o5sPf1>GAYkbk_w(W~}g$DhB<+3|Q7 zck5Jt{c&V|e~E>!5sgBS%43bCUL=p1^u$*?;q%paCzeqRe|@n&=4%1&N-RI+dN8+n)Fh z-H{enZXgtB!z?y+8atI*@pH~5YDGGEruHeJ1zh$+?|2BqNKao%6XS3gtD$N&3k|Cs79MUN=Bys%b-HuHe*)y2x>EAXWT2M36H&`>=IYcp_ znyou}db^TWr~0qy=^w7yH86C|@L)%0s%8bfuj}vHfKlAlF_KDd#80UqQ66!m!J5IL zfvz2$BQ?D}{X2H!@78mA`bSbj{T;nE!$Y0)qI37|n*J1>{==yvHY=f-{MpKEGlirT z-yNkd(s=?&vaHfudBP%3)2+i{1!o@Nwk%rYzgVjNmL+@MUi~>y{gue%o9_`zL1Gf4 zE~yNM_L$}0UjGN=4ThDMBBk;aNVUs-)LtMARlW8nIqmo2uYC%H>fmMI(}0l|@q6DZkZf zIrm7nV7yrb-jzreY2^BLh7kL4AroDxZH7$T!&^nC;M#{$exy{DiPY}S)F7FBAca%& zApT-UBY(DzA7h5lMlw{L{9I0t3Xw05(8?;IH1lk7@iRcCN0H9VZ` z-8($2nK&%++8}S@+b|GM>0mQoeqm z1CL4>EBm{xTO$RyEGklPDy!UzD^p2dnJh|<>?p-o#Z-k}So=hf>9s6<;7a0%~K|sP0 zO7C#*xy$AH9|iU6lgTfOs;!&=wW?Jy4)-oyB3C_rPdLX{@P_KPuc^TV?Zd5ydlJtW~eIR&78rxYITM>h7t0S z#>bF|_Th9Aw)}Zaz_f}$29OfEX?(Dd`jN(*5<1P=1r8sx`{%7%@ z0P@$Io<|)i@7OUiz!fDA8|vREAug03!RdtMGP1Q-NDi?l**!3DjWiYSzq_Ck+Xs}gzhto^4A%kT>OB}j z1@e2nw)5dMytQi4g7wAwUxaIy}LAz3B~OgGfwtLc`t zw^GQoq%gV?UGnR(Pt|lg#XRB4wa9O4-OuIn4#*o35<+7%MmwDTuQo zY>uRjp9QV3(y)6I#je21=wwmlU$M0~*#c?V{ydwi?Ee^>f^?2ZQTe}p{0dfh?_EMZ z#+`%F!H3;U{Dm5uW9Cz`XCOJ48tOA9{&{_zRlg%vUA3PTeEWVD-OQ%%LG-RSQV?d* z%h`FqV9`&pf>&Yh#ws6}6e)n78+WZH^@|IS$8eZRI>O5t8vyT7T1MLEjr4`p9O*-t>RCjY94VL)i6TiSQi#6U_bcTG`><{S#jkwo09Gy{Y!FKs zUsh-lgMlWR7nEs{*i>w!$Ffevb*x%B@JsrVfWgqr$@^tQsbdANv8BIc>{rKG?DyRj>7PGXNpmO&$qU+g5R*{rL!**L*C0LG+R7l-{-vpyLwYQ4U=AkBvl*i zR5L4j4gL`;7K!{$1Y@J`zmp94Di-}7!eWE-#1I~TjXQ@+;~Yn6>>d~%!NTayo=$zS zD;ysE3N$p7(4CGX<$ZvR3~lckl7vC5k<;oGCTL5JI`ONscVJlO7K;oX;(GXLvNY>2 z{l{l-c@3wM&>T3f8;Qs|dO&TY(fO<~I@5))y=;FBroQ3rnkEQ`MR;Fzq%D4|xh#uJ zKf>wyDO4kyd>gBHkB~a@<9NxxLqRwMg6|Cq1R`o-FEPF&^nRUf}Y*;p5uvx4=AR2P;F zvV!K@k#;bMm*2YmxlK(UQTCtHEM!df*50v9iQ5e8k7#(6P5}xl_ebEl*08bxR(SuJ zEU|%=t)CQ$VMav$1I%D-uEDc4XE$#w9=kOz$(6}lYxQ7@IViB1i#l~kW4~;8g2E!gpncapLZ-q!S>XMIrhOKw||N^{2b^DY}DSv3fm~GeA*Q( z`q!eh8+dC~dn!G=%fu4xw;-zJA7{~**pxPQ+7qns+$Ub#!K$uc^X`TU6h5Ap=_K=! z`21l`#Z8Vp&ljKdwRs}wEKX3uk)Yv0IK?CC#6^Wy>V*+uu^hx@DUA5aM|h8L4$fy) zmoPT}4Y61!tQEouFqW>cfq8}QW5IqhG9d36c~Nwx$W9>$NOrKqdTkJzxWR)32Q^Lk z2&yR|TE4Z*eZKm@h&ChzlY2A+EgW9N=Qi4O2KLmOhr79So~X5_x3S1?+IhF!R|QRT z6id=Wkyw~j{pOxF7FGT|bOqkr82&fq?fsFWFe}6^l)LFL;?tEs?7squic^$t^hPF8 zT4GdrvHET-x?BM*#j5T>NB>ZpeEasqHNa7s&AglNQi#>v4ln?v?JnX(vcuUu#nPQ77#AA6nsFk9h z-hjU}JyJB8+F1;1ZvS2uKgf#fX>ypXT>6VhVI3>_2X-2ogvF$S3T6M7l+>4C(Z!d* zn0sMAEi6TqN5a1lDsSwA<=X~^`Z}a7Bnxz|*ax+F(9p0?=TC|7Uji_}V~eGVWzbHO zLsdyfJmMr0j0B`^T*``(nSf9-o%ERw&*wPR!V$IlZFw5probn*jfuuQ3d6gw`T;hh zpB2KA|D+JTAkDFEIT)Mf92Cv@=SUeVY+y7039ad8Gl#@1lCC)qNxc)Yn6_inoLORb z^dB&qtKsvWE%Z#fb{v)4F)qR#e-!O_9qp*Zm}!LR|Fpjmb4+fF<@}Yg>62IP=fnRd z9Hs{4TJauMG@B{EW>p_xa@pEX>&{6Wr8$_akD?Vgu#$S}pgy%hXT zi_K?QzbQ9QlGf5J@|4*B^tWW}H?yimjMe;Bn5vg@aZ{&o3*B}&QE?`f*;X~O*X_2d z9mG~{tRm$_HCD%drnR~-aumlpH(G+y_liTVXw7}oZR(o)-(t=ES}Z|Q06qckzJvde zD7UX1F}p(SJ1kTRqlK(+Qei=1VPUMWXb#HIfA?+;hsY+5NAC>R#Y;Y<9Ez-nmq%8| zOX}j$?|r{6f#1@>qB7)HzJ>(>n&Kr`TR0HBOW>b?6LqC&D$3l2f8_(=&`x{`IE9r_w5abwt-RstB^)UygyzD%KVRuF2H#cdhmQ5PPyoV z_r;^s0SUbK!?Vu=&ZjnnxqJ(Hrr%s(^yrHCl1M5(9i;u8;F=$}Bqz}*;9}fT0)&98 z(zhZ$<*Il&0CF+$)d#fyqaE;`{Af5-tHaafWJP@1`{UJsC?wCnEFT5T%{iiR8R&Wo z@RltLhtR!hn-ez`nz^|!@}9~&1|_mchXY#H`=^E4GiOpL^eyW+fcglcPrCtQ--p9|j?l+a zmwy;@K*#3+W6^!`IO061i^n%?L!z`D!Im%4aSTY#}ma#ULo3O$wxhi--5 z5$&?cQLS=m*d$1VKiznz_8tN3Ls*FE!n1&_>9W2+?Il>R0oF5E$nLelx;8MZWrdK< zOVAJc*wOkSa<2v~0X(9Oi#+GI>jCR&xgSu^sOv7<#QUdE_l3*Dp+Dl;h4=F!yG^W@ zV0+sjQ!y{?L|V?(I_&Bz{n{WjzimSOsaJ(VmDt;K6JK|B<2Jxo<80x?5 z*)QJpkE8y790-TD8tva0sQtyE&=%~hyv(S7g}Hv3_M`s18x6gV_FrRezjys(sQ(Za zP&OI->oM0)(|*){7)!hqKoxRX-4=xY#U-K8owtTVEjs?{lo`J_{e!6gRtoyks2{-` zTbIChp)b7YKZg44S-rU)puIH>``}q0kd^!=b1?_o;Rx98kN>IKy)uxD~MG zz{jVhST2|NOyFO-d6IPPcTo4`wc*g)cos5k@+Fo;_Ly7=UvLTc^s-QB7LuZt=y3Tw z2Yo?alRx?vqFfi?{HQS;IWM7O&K5p9WW&WE-AMa{>525D;DhFrEUuKjwg6Q3NWV%mJK6z`5}5?D$UYx(jgjW(kM* z{Sx4OGl%?McpCVfrCd?_MgV7T4&XcmI8WvPP81Hsg~)E*4BAX`32p6neS-Mi2spPx zzuaVn1Nq*cfqWkUyuDeNG#(JC^gAB7{R=oZo)Zo| ztJ_z)Js9~#fb~+cEsp}$gR;#K*J0Jgr~HL%T1vKryFGv*5qcXipZ`L-bt>-|LTv&* z+E?6S2;TVjq3(mYU>rOW4v{^p!$3rw0yOw3t&c|i6rG7V zrvb469mdq#CLLxUj^3`^5s6$z;Y|sa_j*PPU~Pf#yGVnD&jkJn+ir=cZFd-TA4SU3 z634pUc%MPtC9ZhAV{cIeQ=a&|TkOrdZY}EG=UR7}XM6Xd?vrxgnRw;i?=bH|PoVB2 zH-|$TG+xCgS>oW{_1{AMdobs{&!}&S!+Z1l{Mi_jvR`7N-J544sQbJt&!&3v>=^2{ zA`V47;PP(5>zzyTI_ge(&@Go_nkU}*7$}FoDCr6lUhjVHLfzkF*v}85?li2|bZPC4 zPZ|ue-taQ&@As_l-Oq`+&=0QT%3H=ZqwZz9<=D?8M1ATcec)aH2K!Xmr(zC zR~hy0@2T^!PUPC(?sO;6PwlAt_%M@x z-*v6)t%s}6427_EfYmu*Sqc$sC&I@U2mG-K;4I3X)g3^@8Ywt zaRG7VLdW)c*X>2!KLT$ib&sO%?=!6X3hMsaweCF6_9hml%I`weTK5ph`Rsb%4cucxD|C@ z%&_ivQ1?d})}=+7@4MFZwqq_v-No=9oY!o<$M0^`ZMTeHOx3EsdMa%U^)aIR%5dl@ z$3FJP{RZk@V!@rzaeK?<;&b3DxXPt>-CoqaDZ{!)QFp|(uJ<^61$D1>9f#gyDFH|3 zQP;8LU3W9;-k)LJdr|k0Yh8EygJkH(sQa^N;m~g)>iDO%ao8WqP*}A<XW_uWQFT~tB33S@^wzn>N26f+X^{KpV-RQZegy?we=(0de$sY8Xf|iCtdSayzRG_QTIQvUg&JUdDoqepxPo=+t0o26kFVcx~m?L zVhyB&k@9Me%PsJ1_YuID;p)SA<9`8luQ#pT0sl5Des37l&%=7D+!vhk@xK^g3XC zzaIZI{PDzx3J(<+vEI7)tVjpXci;_6pq%I@Z@BgELBSlur8XY{-1|*AFK9E;75uiD zTMb1AW~f(h^_|0xolC;rZ}EO}XDvo{+JfOp_{7WYTRAvq8e)EvLM#gjA zkQ;3sBi^ynI{~LPgIFoi@B`F+Kl}E05giBRG!%&RZsZq~?i0Bl%sQBRFpZ&Lww*Lu>FX+Nr|X z>K_itaXqd-cuJmQ9p?$}Hr)ysy&uN~#5yg!@38MR7;l~foV_NS13Clynl{^FuipN{ zR1nhc>OXkrxVNM3Q*z8a{y43o)h5ukbYqF+?=IB;!Rg`9Yr6j?>6sPrMan?fl#u8L zF6pn=0r%nhaA>-&E7bm80lohrBSFD{=N)ss_`R?XV3WoHo68SAjk@mrO>Nwby3byK z98;YZQyUjV{>s!uUvNnuJ_oo9SB0c?vFY**hc&YA*ZHB5U`@w_eUREiJMcn!Ee z{QOJdkH~%>!2nPE&do%}KEPO>1q|w=Zvn;%*+w+-0+4TQ-QVpk&n2~pn_$cbm1m-3 z4eAcbwz@$F_7_>{a3329z`6^tUOFn}_-lSsb1=R965zanxYrcG)Mak1|30F2B_QN$ za@4L~ziX@$=t-=EE%Z4l#w~OXcG?7+m%9Py zu`K(Z`s*0rT$Y1&y#+YG$pM_&df1CO;Lojqvm^&_o&%gWAIZMIrZ&LFJeZyQ&{*99 zIGgX4?K<86f^FwtFOvQ8dBB?U7Y_NuE8^AthWX-q?7t0oP4K^HE)x2Y>ygHwvRw}w zVSf&Iei(3G$Py0m{KtUPZpsZ(_2aZ{f%GH6N~}iyXjeFN$jqY^@dc4u4OjxdrL$|X z>DUvM-?}UiyzAs7K0h!?CcXujU)&rHJ&tG5hq_HW5Ainr@D4xlsJ-QD zF#p1rA=m<*PNR0ji!b>iSepT>5NmW#>#($WDzZ5!?~Vf2?WbVhu41DLyi-0MmYA0S zzI6RT?Ry(A6Y$wvbowM49I?WnXU{aQh3|eb;$(XNs_mT>xi3h2X*}KwSU*c^yOemw zGhPCWDezB9wD#dMfq&_ELuIC3hWRtgu}E;X0M3&+fO8aZZpza3Cwh(p&O%82VXab^Yiq1U`F&UpwxABRBV8YokNFZ{51tupJo^3j3O>mua6X5mcNas8USbI$|CS89a&g6f-U5K_# zUk4lD{jzS=VUfPxAgLT*eL}n&1kC=FJfBGVx;7Z^h{kULUgf#r5JHAleNB4~zZaB7 zf?3@JKYL3!^dO!sa{zM9BaNBB>;}w8EpnTk=v)xFD=17FJ5K>-VGQRFOw#DI?_X5@ z6ftdJOrT!6u|xWIYBSc}KP#Ud;lm`-@#jtKLj{eWuV8Y z9WSHq?ef|uwIhHJOfcqPg4~@24B|yMU_4=6zgZD4X}85Cy?JpAa9T6q1=%C7qwc|# zVQIgsK0n_UWPYY`eEt=PjkO>~iD#P*ls5Av@OwIWqcXPw-VsxrfzyWAiB(qIV<$9r zp97qsLHX=NNoUR2DGxJWI*VwV(~5N{lN_r$3z8fpM$ij5&s*2CAOjn1GT`1u;{9WQ zbMSrP(35z!@qSY<9ZK>YZ37%r`+|*ig0TiL8qhEHZQ{u@sQX1ISGcTJ zo-BxbGZ;^3tW0f(4+X#HPCN@9t7Bza@N*Qq0P8+ejFQ80I1j?T-xHwY^MG@eoa2*0 zEQZF&8-R0gAa`Sg__by|>`Ie8sPSu`rdoWBHi+9v6z^Oc5(q@fZh zpH6oYzrF*Qd$Sn7gr{&L)=W$=cpC%H)h&Rt%5@B<8ULtzp=(|Dv9TERKZCk!J`oOK zNmG>>s~@q+iYmA16d^e?Wh|~ zi{HJ!3C6vE@v12v99-^R0*q&}gpqhZaw@Wf(FGWXvxIRJF#5BALAv*Kz-XyKJWjU} zB;C6p@{*)_ea}_3n-P!5Vy>dTz6mg9eM#EWNInV@2K>%<1mhXNxG)PCG|!cM0CvG0 zaz2PU&y^V)724$%}!A_lk3IFHge|NekR zlCQBqHh3doJ=`njIOwsR>DL)1xG#7_+Y!L4ya@Tjc7FY(MqC2r((#MN{%e4B=X+rv z=&+=*KNaWpN{4d$fk|?8@fNH@ZwyQMlxlw_B3u2ypf+9)7%yYJrX0`0)|GNhRt3v3 z`2k?{oBRyOD7*~6dL#iF$~(}9_O*3nE(fzSHUUoI4f1-p$sWV1xOS>I^e6D9>qD~f zJ`b4Bd{{n1+XQn(d`?GT8;@{Dx5DmtSjrI>wiPm+{kNImGy={sQ|y(?L!kUVlB>G_ zrzi{ENibdjjN@74meP2h-U%6>9S-e_XtJq~=LO0IVSPj=P&Qrv(HQInyv3dHeef(~ zT^fTkA`L;uAdR1I0p_DkavVz6sRKcD1o5n-3vvCUnfsk2qb-0D&#@np0NkU1`+Sz; zlG=D2aEh|96R3^LQize?p4)Lqv>gWAqAccEg7F++B(fYk)!X3nXFi!scAQz$zAN!`d7kk!y2z3*34oQHzFQe`&a$d2iuDcJGK)LDNkoBGN`8>Q2 zaYB!EUhv+3+66c-LY}4qX3(}jh`L8z>G#I_66*fm6|c9POznX##2(>lN1EOFMq{uY zb+5+UzeTG{{!G7rJA~$ndjaD}kG#HYS=+)ovvx5_0_D@qKUC&*z+5;ipZ(AKbCpOa~4!>Ain)*)^fieAoSx-gO62cb02iZ@zyXb)S~=b4jimtnK!OaU3w7 z%M!-2Uf7|SL#JrG%V14$H(<<@^)SH*kb_O*@+rV*1TSHpIrO3Te$uy4_iDtqiX7{@ z?{6Ty%lhC?18>x^t~>t|C_jk0uMNs;52{VM$GVo5X8$kXybk_VI?~|15BCk!ErOj# zbE{n+d!JLWxF7jE;9H?%U2neiqHet_-@NC~qo{kMY*zw*0{{Hzi&s#0D6Ksc4!hlx zR{}iq2ViTj!UO(G;9oktRAw{k(1Kh$K7_rm_I0pZvZ=S!5x@%l{ z?yak)4`MwMbth@`<1>MO>Do>@dK2otal5=14dWX-(abv9yWK|sqsg`1?sWqzyB5kP8Z-jy-vRW!7`Ueb{dm8$`fusJbnsr z=kV@7?%QTxquzX%iTD2QeW*VTd0z`O`tg~- zKhgGup7Zw;sQY_4)?=#cE*k{@4b**ReK_&~zl}5=y8&nLki0(@vWnfYe)R#h>+^uo)gk8{>g}RX zG;de}< z;)6RhcUc-6?(#&u{xM)pxl_K+5xnm3&+7zWOx=n3YlrOnsqKRIXKt7Gp6V@tGabo^ z%K_7FYj~ffcLa5REw6t72GJ(^*Za(m7f`nn{@WBsyxzWF^)AGeeH>vb?$X-BiF> zvj_U^BgUOE*o=o=eRYz&y4O#j{;jD03f58SS(=j^_O^P5&&y5-2Cy?j0v=zYcJ*_Ao<(i%+AjdmoS--HEza zqb`jXqN$;1Me%A={pp@|(Q~MOP^xe4GjE@=WFKM^hz(S#xXpFF_YSW?-9O541ryEQ zdj2NVeZ}?MQ+IwPfa6=JOSjrne~LbYPC-to{T^3$KZ*EW_!o#L$o^%#99d4azWR;m zScCd>M?F1fGk)&`9J;8!T7!d6f|+j2O-Gp@pf24De=(kQUSOA@S--m5)fK2$4rk)K zvRxf!p|$16-N#2&D5R8ymKM|ZD1X2kRuNVT%O_P8pH?`x@V44w95FqQ7cE#64p%9K z7ZhJud{ObmC6|`0Ex(}_VS~c!ZwPacu^aIaDN-nu04(&R7KsR$72(RT1XmFN>8${& zg8X1@;Z3#0H`f*)tS!8yw)ocC;=729=rS23yA{Zk!iw;rTDbF*=vzhjL-ZU9mxh%1 zlH&7=1XQ9Sjs}BcZk)GEsX{reIe=e<_7xY47vRGb{92`cB@Rt8y#S{|;V5w= zZq$i5Vpc3~t2jMT8$FB&kipq77R(1t({&OH`PWj7;u!y0rhRoF&xTU5wh2cE%NUp$ zLnvGkE}x{bFER&3i;FKo*C-d^kr-k_5HTSD7i}2*RPt9QO#R2IxHw1nmtyfn5h5QI zBF{9DpQMR=0mwFseBtC!71|Y>43P9tL@K3tW~c_wC1N;~O2dIk!yzucmxoE2?LFiG zL#152CkXs|#d&D`D~h^a;WM}qKIF{%5gN!|O@!ZzK+6~3%*%_<*b zZ4y_1Ow*{|>erXPwM;oC?MRca8KJwAG;*Y|~{+R&}Jqd-R~D9}+B*imLZBZQ!; zY2sBCx6sw3vcV5wm7r-tX;YWjR9=D5)rFd_jtMngB-C{AB3KEc19cT!LhrcB7Aja) z<+93FRk>cTOsM8^O($0vs=AF=}}$%rr8G&1T~ylbHti@}OWOwdR3|7qL^ggmW=Og(CAPFXmsxki)Mf z(pL~$%D?I(Fo1OnoU(R{n#L}ua!?nlB1z&>`^wgX($L)UMf_1 z+^ovEvIvFB%x_hjT2=7Eq85tAm;}_CmA3anYgbv{b12o~tv(q{cGUPwIgHbqP| zrijrr!d9p+6)83?nd zCwP)#c3#%a(?X*>g!8)h@jN;78}McI=w4zhY2%>k!9e_|oiE5!ygxH;q7Z$6Ow zQl-s&vg0r(KZ|{Mdh)YvXNtr6sv`&dXW|50;I$b5Y zz&!1g&^=h4S{spyOqA`{+-;mQW*J|`gHCw{^U7Eb@Zh-hmf8l*7)$sV(<5cBA;Tks z%r&v{UnmA)%$nrR8>}VrxX3^Va~8781h+BR@;uGI8%?^2Hj9%B@?^wL z$TmMGVuIWHaT____&zb7C&qJt(^n?uXW=zik`Aq>-As(CiBWaZj;b*Xtc|6g5!~5z z2_D;AO{f%0Oe$!+D0sHKI9H=U_=|;xU#NPDst2j>Nh)&O5M8Xl6(?(mT}~xp@vBsG zF5|Lu=`-l!sAa9mRcU&}Ymq&Jc?{UJvfZ!~S`!j|c|6ZmKBYA}^7ux`{>hQF^JptXwc{QI} zb<%SN6S1Zw>_IpGxu(AOluulqO5RKJ`D)1t4&7@KdROx%pAtHLaCv0u`5F!5rzO7k z%H^P4*>Wvo9g>;hscHE!GdoWNE5uupv+eQGh3+Izdbm9oT0PTQBj5X@RnM32khbia zw(XM^X1m3VFLyNKwIhEuZ&=zT9dJLiCFW@LhSQ6QzW6>4)L43Ib^kd7(|Q8BcD{RX zDVgAVt%FN5zLj`-d7l{jxiKWtb9!R@oQ&h=MDEpGkNxouZ*===ytiJbFGmia?hN?f zq~O=SG+cvGm~r9Q81U`xYu2t!`k6rQ3BUZ%oNX6w1t)SW&=G3yOQo6b>7Drs91(;Eqace?-7@kYZx5e*balhx5mQ9_L}DWn>iV@dn|FMiCv6t zyK}>Fe}bJR;^AV9Wzd^B@Kc@<_i{|^cqXJtkQqT!>nyg62^Ch#&L|G+n^+83wR% zW0kb^gJ-ZnOUV>HkOW6!EYB6xAv9^4;rJ*){sy*VmU;~e)F(sh?Qi~ z5N6@2=ySU8+RW1ewTsHBi^Mrh`rH=7=;h4iy(JEFQJLLXysn79wNozjvtCLB0}NOW zy<($G3A!oKW@DrUDTy!FU=C!Bjj%X~gROO*l-Zijtk>b$MvAy6SU=0mDhs?f^fSav z!k`Xj8-+F^@_tX%=#3oi*9XSY8hD_0MT5hf~8@kZR4vHfn7yJmHy%pxs z>XQoR8A_W09MrC+k<=Naz@U`^(wH^G)?%xcviFQ6z`B-_beSsB<46aug@#sjF0CpW zx>TZCDkEuOl~;BhJSwd-&pVut1>zlrhE-a~{xr`+F{^$mk|!qlR(ozr$PADgCNV(7 zndQMKZW%Ke=Tk;CX{5uL%``Ka#7SDGNHi2^?=lrlH!%!2qRn)2yF!>@x=2X_N$VnG zXpIULau1rY>ol2$GN(Zr#%7xISxY;~&Mbv$lN@@`)Is7@ZCPX_!psPDb$kL^Wok=o z)3v8iSs3c>LZDx@bs^P(P~xf!K^CUfVI(~qD&Vv;Pan^f;? zblW7!qVQfRfMM}jRW+qHk~V7@6G-4GM(Q)$WD+&^kl9{GMSXtZ{FM}wi@uh{lebRy zwr!{lvz$uLb%IZqRy>6#32u90E%nUBAEnb#yj4T<=S_B+N;ps z@ZT$qX;^|%CBNn6s*N}N`{WwP@{}6Ru2b-VUeN`>G~zV##!t9K;smNeCQUDZ!Y-B; ztp#Z@YpwH(grsRxw1qbJdBzeQG0PxmE0m3%nA}T-<}yrbU3=->K)2Z%L)~O!at2F- zpMM{%hMHK6c4+|{E^vh!k&rtD!F)I{EL^i68%OQBL z5yUl^CSo?!<_IE&sC*VWzRCj4m8ON;lIg5=x;ly3Fez58Vn&Tt%cwaM?7(gM(DVY8 z6qAC)i>RPSRfW>@>0seVk_8ot5o0z;gk`21B)S;s7J%J2D-rspba809+AlV~*tEX+ zJbbRE(pT~~ov3|-4}f)v_u6pTrBmV)ZVgf6f#)UYmi0rP?>#LhGh#5`q^Y79$lJd2*pwMG4I`3>Ls;JhG zM!G5vfmUuoviSnA0zZetnQ}9U5F7&Me9nZNu_;_mDXUYhSu(5i<8+F#c*{k=++63>%ADm7WRS^{Gu(R0xx-qro`+_>21-an z`dm@oae2G!P+KLpZ*a(c%N%h9PfPX7NN;o=n;tMJVjzf_i;NHLikK*Wz#CfIFpE0b zo@yqA{g_lfD5r}9N#bKao z3Qccel?nb>-ioqC8t;oW-j`_kFr`{POx)HRW!!!*EQU>8PLK3ZA#`u0mLpT8rN&en zsWFp{)R-wohn_-_rKvOV=Twm&Gfm{joCg0*x~q=2V!Hkgv!0kR(c;t1Z+XcX^p48# zZ)ZqqS|q;+t|X-QGQ^p-_kv%utnWGW+2XB^ZH}XIpDUF6y!UXE`%Fz<=ko{j_gTIL zSIdT`S>Dz;@~n_iL9-GU-*_|Cd!{TZR#-4tw5kk?XvJz`EmyGi)F5Wc#peoKSLX$! zGW0|t39rAKs*Anw`d7B^PQ0p;fb~t=0s{0lGq`S_;>N7EO_LA5q{AXte&-jpp2`b2{5%bUlFD7{5WED=x#e`f;$OZh{iZJe`#Yutlwhnzm1lcL zQHyxvO&b--<2b^+^%=3&oA0KWr{k5eIpW4>l991J;YpN_v9Ix_a6B0~UPPUE z;+w6S)VMLO>`;xU3AqUyo`Sk$uJOjH!^VmDW~^^Kh52OEHxrzKINP0I%GxyVpWsX3 z8E>BFYrIC%v%~IHu{O_hDNBk=i}i(h4KGh$D=BsO#hjh5m3K%>H6_ks)jii+h5*vx zTo-fhYt+0M$00>g&3<#t;d9E)wB*FuAUfpygf0}Cgg+$OX37q@;q%qPgI#1ikv#ZA@aIv;)Gs%ren&(ERpgs zTg!Erqvblx9ap&y0j4}pYc{B7m$Bydq{7D>_aRc4+A2%VTAxe*(zAs@`JA&BruXDV zhqGgacRclIj%-#Z!3q+H8$~iQj?3jyzP*}1X6j5M%E{FWz#C7`!H3S#$jH*Ga+1&> zqTx)2ZV{1LtbcJ&Go3JxPIobgY=#mSG1W}c4WfjjK{QhsM6)!5NLWVbg*g)jk(PKk z2B~NPl!W)_JP9YvaiSHoB_mVA>_o-uJPSzqz5a$-w#^?WWQ4~>jXy0Y~MzSc48|<6+CyOWK=M))^ZZmASSd)U5uGqW1`{&G*QwT zLnj$$$0|xQfmhFj^s&A&@!7+=Nms2z6Z2I+XKose}+O;+8$7K>t`sWZTtktDaIbqQ;a>JQ)v$< zwtt2~)5OGhnwS_Z%NA_oTn{uoauY=%xIUUtwY@QeV(AHdpVuLPr%7@LaAGo`skQL6MP;oeAebi zbND>B^P@HsTIa_T=`@7&%led0AstDh&YD5v*0PJ3gSd4@o}cF|CqtZY5tYI*vur0c zv%g^K__S#zWh7+#!We#>p-Q%tAk zOmzu1o@#q9=Fe%?_Z;SF;w|}6s)ka7n7U_mx}#?`LwHtaXr5I<^Q>n2_N=t&K3z~! zrE83ejVBLne9R$ZMuj%=%`uw18y6ZGW>YvPWMscylM^z6MB_DXXv5QT098cj7vlgb zm+RN{lkiM&=_q~EPY24axAE>sBF>GsA;;8m;BDk1rk1m)Qa}qVW9{g)E4c!COA z?996|oba_yZeL5A>?WpunwFipF)>S9Pe{#IOmJeBR;NA3ZTu$Pe1gx9p0TRD*$O8i z6=P*JPT)PQaBkskwaB_ttRACrh^_s|;*)CQhZdU@XRaf>NVnmck6LFUbT~;&F$E$B zSEvQyVj0BVgpI7}LxIrZ!`pg9jTO2aBkj;9x(k02Vzb7l9p{-*;_F!A&TpSiw3HwI zeR7Ud$Fm5?lQiGEXug>YQ-#AZ5B5sd!wAF)3Hmj-%zR*ie2*Hx8#NTx)N({yGE$G) zuPWB(tf@WJR18oi~=_V*Z0Q#+f*+jMEx8KIn{}a&4u&Lad5o4P0Fw$B*hQG;~#6wXka^3q3l;ajE(g zX{lN)X-^fgd68BOqg1>-Rnx-Lv^D9|40SwRU(J>?sIK! zvQ>U(pmc{IsY@L1C0#qI-YRIb*lZWAW`A2E5@-0~U@8&%wY@so_UoUeo4~EtA3|U8 z6eE#sgao5>Dp%;G0!_IJEej|yO}Pp!i#NqKk~p7ts=1`JXte075gK-CF%3~49Axlb7u}&k8~$A|?r6R=*0@K9!2eTuhnrg{R^YZfPo2=fq-1TdYLfRa&ae zv|`GICX}Y!(V1Ln_9QvxbE)|T$4o=HQB#;!Q|IQzFH^k6=8{`1h5!n{Irmi7sZ#Iy zh0EPx^MEzU6MfMg2r}Ws1&1QOezect^8*Jc9+KE0_WpXIcrvBFq5r@SD z(VuD>hb6eBv0j!)i&-rKe1QvQK7JfTT}W^%j6Cs zTm94jEk>TC z0GN<!RdLAs-(xjWoJUF-`mCy>yv0 zOPkRAHc5A+$2~G5aO1aae)U)c2Pdnt8f( z_`Co}oM|Q|K-hbyz?Ux8Gr9`wiqEGrs1CW{;WXJZf$H^2;1wpT?wL66&rIi?Xj6Ex zF>#fM$ud*_A&n|=QCR6a-Vf)qot8u-1$-|wTfmlyM4gzlU`L6;yYa>}%eW9L=cGQ& zQ4d=_WYjz^M!^DbW3|m96>deb#_XI;-;%eTt=RBPC5y;d+W}>aMR`X-D$&|jI(`Ld zf<@A5@A&iExOBm5BO^hJ4r#0Ejxu*bIdS7g__WzF{_Y;Asu?PBvSg=NOpJjR4uk{k zxo|MvCe?h1qZ^C0fvyd6DeubD7k)SL(ASiEq6}&6L^6G~M+;^ zkuq=sac(1eAhQMYJfqW?n#Ww8j6yql93%k2LcvbbY|H{p;0woM4zoAF7Kv3vBsQuM zEVf`+7h^IIknA|FI_B0uvNj5ttsRquf9^ARL*7GRTX6AGWTJb8?gx{`v1KASlx8It zounxZ#{il`BvKDsne#`ivox6FklX6oZ6W|rD1=c?vyso>2-H)WKs)tSnGmm&bCx#t z>BIzAwcKDw&*a_U4F?T=Sc3`LGMzm55w&v4+p;c#2ortm1TFKRvUU!1Ad5m*4(7a{ zAaOAx9_*Z2W)7t}r2S_wb?5@3Pak+=viU_=EG8tNNYgDMOa@gKI3`J_%8DFup69Cv z5eSbv$1^=4#&IsNYTO3p&sf+N?B8|&0VfqY>&_)E>xdp}J~(alK=pdK<(1meKU ztQL1N@0hVgu8jsq<0Rv?jSQ?=XKhHwzNT3kPQTKUSLGPMlhKr%DJv^ytfQl9Jy@p? z?o0^gltU{QWa)Ed=fY^dibMLF)#n;}I-xUtc;n;PxkY!6KBJwrz$l3FXfZlFiOzPS z6$^K+{)wB}?dZ1{;nyq&Pey%ewR4@9s7?q=RB)Z*1U`*WAJcB;=7u=V!`%WNZ^-p| zD%-K)W`sHlzrH*#ym#onalDpYfwVw9Gba?P=^p4y)$|PY4A+eG)O2Eh(M=Px>U$)Y8T8r$1ydipzicXXv{hW8BD zBuDlPriK@F%V6tM!`F-q4AyKM7`mpXe|vJ(KyO!SXt<_txU;)|$5742j*-spu7T~z zb!{zxT~jwWI9#);w`Y6zNZY`+kzE}_DZNZheQN8D?a5s|Bi+euy&c;_?Q0XFT4MFm z#LAkLXP=!|Inb5bp6XAm@9){2*eOwpUk3LK5!}T5&a)Cr7B60U&XUFFo}Xw>?d}*( ztnD8j8QRg8>K~!!&Vix9fuW9(R97gO+}eB1aL?XUazs3L_K)z#&fbB}YkIo)^EM)9 zSUe7+yjEu0@V1^_?aOwxu=deEz$;vn+QUD4cMYn)^q~#>RYzy1{@mZ2>={Y*frkFx zp8jk2?*rSmX`joN@h1($P;XBke=*#V+}6?8(<^WcgXG>+zxZXxaH?~lze|uk($kk3 z0&xDxfA6~%U;C~V4cwuUW~$RUxMNp$PiHqTjxW8bovB{!%W!H$te1NP-7$3Ta#0J9OP2`b9lMhqkb?emi3sh>68Q@+*Ol7IKezSl9^~D!ZtL&}`i=Uk zPdxJ9hx$7DlS3(L>!?YmHWV;w`Y?9-x{`gv+fTOPu(Gdf9a@!4wt>w%hC?gY)nn+c zZo`ZAy7u+-xqju!hPF0`Um99ln_H7j>l+(ge_XMC)vAWpWP5XSvTa?RN5Qs+*0ptw zYu{JbzP7n3$sxM}O|ETfZ)k0*16qyxmFS~^{xzu%D5G|0t#uvSdpetT^lil;Skq8f z4;qr~SGF`H*VV0FyAm|7OD0z~uUl8wRPXxx#=7>EYwDXFB&B z)ztOX80o8f09itZF1X^ z$%g)}o{s+h)bMb~EZxcVO>OI2TAEwi(H9L(^=s>ztR+^gUG4Hqk3~`!Kt?0BdZlO~Qa52K2e-hL;k$%X_?7efKrz^A-#!P4!lS!&8(TO=G zw4-1Cwu|0jVi@io7#cBt6JIe+8L#L|??C@{;|>2te-ifh;?=g^fsT<-*T9agy(wNf zp+3v=P?pA5Uq@$mPk-uUHNe33^Z6{kLw~}9YBbP0^$}01`9Lq#M?9&v5xrC&x$VY5 zb`JH7^mKLzvqkg_f6u#(KcUvP!4VRWWD?J0jHr*&TNqixDv>C|zZpdFuLe2%t4atJ z?oFBM@~={5{#~lgziZ~+$WT|0Y6K3Yw)YH=qy(YEsqMpiIi0%cI;=mDjmLi@j_7Tp zFIwa1S!*3VOU={2O8l1_sQ)f;U2Y=(U2dcCLh3wGLjwWJO={cDz9bA^*q6Kw_%_(l z)g_vZFM2DJ+PF?8cXlLu!5h<@mF1A*{?7177npOB%}QtyjW&Gn9>yo{7ku*WpzfmI z>5~_r2VR06coBRG;h{I;2@gWH=#_ZNq5eZZbfvbPWc>ifsbgCeX-%GqecU%fFUU;H zsjF>vX1Y^DopA4lPezYs4ccaMY1TBfu5|Hf9Db6V8rNTKUX5!>v(+Tr8rQ;xUt_dk zl+)|xZ~^)NpSn!GW484 zh$3~3t?=ou#CTcT&Z7nm5g=?Lk9UcJ%gcMXV)XQ+IDiKVn?TlTpPq@}`*-jO`WFOCy4Ii04uG z&Oy02|0<~#uL4er#jAXiMXh+1wJ8;^!m>*7ET<|IuQGOZ;#Jx@(9@QchPhYSw#KzB zh)eOIt*HgC@~sUk*SEGI7#tEZU>a)qSSWgTgqq-LbqsAk$!ry;_`oQ7Q@gY^&y#eG zXk(YYs-UhCZLCkaFBCccC@El%-)%b5qpXu_ zF{$ybso_DmV<{<)ZUO;&ss)}|gKg=|yOdzf3b;tzcWF;HHZ-knUt=cE2HU8$a!td^ z%gG1xi)LMOJ&Z{k2fR>-rLs(_wA8iMVR5XX)i-(Sx?HlY;fnQ`FdEWStZ!&(Y`!ui z^%GeTFeTP@nQM~7uB}fd(N37XZ7mHeVbiU2F4NN5(2`t*)lCh$Ebtm2uix4>uEpvh zjFcvb9L!l~G(-ruJymOl)?7V`)~#=ECXXN7Ok(A3LtW!~zol2LN>^NkTfe^j%H+x` zS7K4pBu`qSiDX;RWDAyWn=K~(uGuFc)6o9y*t{o!e-dn9CyKU6D z?Qr3+%m;bGdY?0JV(H2?b*<1!4NYE9rGl*uv_P1yFelSzv6bzujXpp&(yDmc_KQ+P zZ_D~dXhd?29T_VMiXoY%Xv4}i&GImZI!=wW4W>GKw)J#c2fKhs!@a3l^sgDe@w@Kz z@mFa}wKQ+!qt9=_Rjb@ew$|0JO+%X~k`AS*lsmqab?cI=T2|M2vqLYH4y(1GJK}ZC z?a-v>dgB#^miQ^O)K8&h-i45h0`&p9+I*Kw#}EmmTGX8-OOs1C&|veFIjvAS#FldI zST`iwu53#ZodTqTnm5LUQ5Zg$Y3w?damTu*zIB~Ck0SGAHS%^;^v&*dxSW!NEruD; z*s#)~ISmT*g6F0wNUE@*6;qo~w9wsFb!-5&m2GZu<3MZMvL#EB+-YuTs#{^5H4T_j z!TPmrUM1yO9`*yGV2zDXIo{x1Dy2cCPUK=v^XLw9IahHo6+>)f&Dy5bZj5swcs(Wy zL>kvNwIEFDB6S{BMenwX`VhLhmF;Uc*la4JSA2uY6(F}Z>9dfYb>`jQ_VQ`ETFCTT zMCH8!8|Bgf6s8jlzqYk)?Xb7hA@15hS1kZ>k{nEA19x^~)vJFU;=^sJ-c%=LikYG6 zR&_GDacwJt|0Y4P{ECH$HW@>GNB{O!14Esu6&)iZ;E#;;bUam4!1LRmWSt&ze&T&SF- zRByNJ2$9NU;?{?R5B1GkAuFCFCx-K%Sx@U&tnU(pfD!cQVJn9%_#1Tehl|vB$5l{g~ zTtyMZ9YJvvMZ8&Mkwun8L`3C}EV`(O|L-p%e(y!Rh<9X9RgaY2pPBA_@jK)GMZ_P7NHHoVjKAj4f#ZKd&*CuaicpHa4>9>q8r)CD( z#)d)1p9zFg*8FI=H@8=Zw`C*zm5*Qr?yucOM5ewIh(&V|#ocD9FvVCr-L*+HK=Ey zs9`z{EgDD@v3Ss18MOw%LU+fRLxCiEW-8hoychcdZ82zf`+KrGP`QeJL8a&_zfygx z>vcx$Q+vZ;u-X-$>)LM@O@$o#2N?E-HQd8$R07;e8p`2&XSsq{`DKFtO%F|@|ru&gbNGqHvjCTNWeX?lZF zpL*j#Qmmo0XacSV!?3nRg4qBtjzpF11yqOq;1*Pfstdi=;JIJh3}}Ei8h}hjr;Dzf zh!45tydFb`cyVYT8`Dkze7w)cSQMi{rISMUWu;j`;m9rwzcgVBUBQjoIKo5(&1$r3~R@wiWSV-{Y*Sx7dSI!%QembnfwMy}X6myR4C z=F+j%D3^|84RRUi&M_{V#yP}|NfwT9*>v_;bvZO@e9I=)hPQNNYjn$lZXOttD|kwK zQWEsBEuFwUw58K%!xW#+WvHc57z10j9CKXDiO;(oa)`<%vPQLZ64#)Xhax_vrPDZu zv~+@SL`z3Y8qm_I#QkSF6HZ54pmSh_b>O!_8hxx(5xt?-s2?&Hu-QgkY&8tLZRtN) z4dA)stz+kLHE8$54;%n(SN8_9t(F8f^^a}2lSf3`^?Groi;GUjqMs+kPx<$ZH>kCH ztpFQY_#4aZ1Ftt)dkiKw``uCJP(~#v321qmB_X=p z%#v^&K4zJy9FO1>JfxD4FI1Ls6d}gqL>!hahe+ufl*BLcZj+H&O11uQ3tIyH;W{?- zjFl>N7@sawZ{mt6HVE4u?fD_{i|9dqebmQIO_5HRL4VKR?zV5DH?OA{h3l&#KQ0%}xW` zM7^E%LbKh(<#5_GnH{V#26BW$r(wT~GlUwhb~gxBZdS&2Yvg9BRG5yB3JAtP#Y4Y~ zBE$5{lbaFrtG8Jw(qAX=*Yq_0IyR-Y<>clL1*sttH1ZLuV5;1~6=sT&03|4)peJCY zK81qD&=m^~(H#wYqv1-kL#%>RP23n0SE$7H$E-L+6N#f4ym+~`$XPay|c4QLybb2PCzQQp)DRKj`L5_?&+Wc5jdqXgK43KPWJx|I$N!>xXRpcSpg01dXY ziP50#Z$yRMM)ZQHP?q)XKN_H`ml1xX9t^zYmFlUo@1OV8Z40@4;AB}|{3Tbsi&z73 zitw*FSDriP&z_t0$sObo`3G=gwBhwUM#a zr+!?m_)wLTM^A(sxh%QU6cakcQ#?ZT;EGiZGp(hpluj)# zhup)(4=W)P#Kg@>qB+xq&k3O%;k;a~Di0ZFHvAN@%#Vc;Wy}JF>Lx&>!4Vf3W+0*x zeHateY^T9<6t~gx%B*Ol1O z!xWW$stRVeat0H+_Hjb{zyu#bFwvXSFXy*1OI>n<7p&fxRwk<_fMT?m}s&MlVhCY=^=C5m2ydmwILyq9C(yVrBqTS zncAqtm@Z~&$TS*K;4-1^4k%SL5WH1P84)Zd#sY+rQr#qFc0@0wLJPejW9gw2q)g`# zGHU;rArnAwag-3vQBiq{S?TNpht)*>(jR-}D$ z;I^pTL}(W4{s4O;-Tq+-NZ`*pI=^B z#m%uqIPR-f$Z~SfpI$31_-AIFlt}Ni*oExqJ_8}qxLcTaT$UQI_yDtraIKYc`^{nU#)l_Dx zUaPQN#O)^vV3?1fyyPQ5#TksB=@Mik!4(A(MFBqYk-?HulzAyQ5=UCmgkeSn5?5P! zxwP98kqTDeyfcNt-Yf#Z{go;I6k3_TI7iD0e>M~2R3^q;CPu6(bUi4_XJrlNA-L^= zWsZ?)3s1&wQ460GRAG&zvQrBimgp|Qg1ZC@vIMcRlGmh|2@fYiZG{xsH>)tr^+89+ z(k=N6oRX`IlrX6emUoGQ!Uf-zn!0%y%j4Df)4PqUBmwRgf`Pj39MMojK5b)xvQ9VLXy(}lN9DLet@diPEII#&tBizzHc4=;5u~F; zlWDZAl1@R>yS@pNj%_uzbaXwmO$O%GXjv3$4acB|Fk05pqmzSvot~t?Np@^3s2|u6 zbZ@*k;f$Quj2-gP3=nwzUAiYS+SowYdM*>Bc%vS@5rJrkdN_C-Js=WT70+DM#VIF! z=mEbKp93q)q>!S$LHm%|B3y%u$XfVPLO6Db_*&uIyi`K82LzHR`M9Vxi}NTIQ_jRf zRFo>=$zU`|SR9r;fr)DdFvUoWB}&mtvCgB302n8B%jqIVEPG zD1xB793@vEh%h<(V!PABQGWq-e6(d5o>X{ZXh;M z3YNaaO+m}3M_q2dW@1yI+{2RLh=`(#(3sT@b1VlckDjkkV^Z`JfnN!e{yFf0ioM;) zsp620P$B?<*xw91`CFDW7D&6Q%=t%^o&@Q0D*q6vk`k+vjV9(C@c)UGEiN3@fPjE(FY_k0K1TgQE6#;?aWz(ftp2xDHl>~P)R`1 z$C3mTvEj)5Bmu`9X7rwLPvhDT``BAPWUXBVP}hs;0K@ySA$BNZuJSAe-_@&Ooq6|N zj#pO~s?j50vP8t-rNw)VH6G0R|6vxYZCd3V&ULC><(w6(OY*;id+LBLIkWSM+RiK^ z3iFNFoe&Pp^5p@s&1s~|rv@D9>TLlXf;CZjHGD%&v7tGf78w3Q^%RU^9X|vuS|D*w zPXP}dWD(4!L&!<-Hk>VtAvTQ)S8kIifS@p}W4YEhO?Mi45c6CZ|MW{{HMR^;NOECm zvs{$VM&YTK$bndSOsnk$m;%y>Q#akEWnNhqwmEEYdRp$lXI1$S9GNBly4dPCWY$R~ zEM+hH8EzZEtPIzCY%S|)nyqXnpQg7K?PRzVpySx-WaldXqtiZhMH@xf%k&HE&olP(bf=QTHAsp>KR(C|UCR-;K)ls8i-)TQ-sv-NLObKn&d=l3 zNoiA%LP_TJvsiXrfJ#?U{v)MM?cu>Yfqf6yWrzpgD)e~1Yl#7&{#mOvDHINQn@S1QBdRvd)JJ08SXnV@4`dF2mB{q7Wa_ z*@_}0!?hLpJ6(qJHeqRif&mcH1d1+AXdM@KK^G@JG_F$|7Tb~rQ)~@E`6yjxjehCE zsF35bD!MH35tekwNF?iw%5ba;9Tm$IW2aM7^;UzQ=ysqy@;3VeS%4dxP5Gl=m;dgx zdh$oJsjlGc@Q;4@1M0#u8FfhW05iCqI&LU2E~L88ASL~s%uq-;*H`=Gz7%Lam264|Wr zU{w-VfW!h4KA=fDQ@0PFKew3+urk+a(3KcwA!36ZPui1Nh%i%|;$M2Po9}<(L`0HN zfh%87(%5)-UGU{ZDKB#C46zk}_tL4x5FuYHCnZQRXFkgYifP5SgqNe*_B>o>y!EbB zV62+yxI^}VL95xrzLs1yd+LjJNN}(s;&oA+#{(a)q?d$IA6o||^xp81aMXvDg#O`v zFp8JaZm8;^v~o^E;EtpFJ*DB(+Bz?;bpW5n7^7MEnqVs4f6S-9CbzonV6xe74ki!q z%!fL z!imcNdnJLhN$=qT}- zBLPhocUpn!OeMBmsA01~-ZYmSx$*AFf3Bntjg*M~Lbh)myq>K+S7#pBdHvvuTNnqyz8ffHHw_$l zmMLDXlGg$$j%PX=pRy-lN;mA%jo7?GGr&tW>3H&$!feDdSRB%e;cjj*JI$E~p3iZQ znI6m%p9kO0f^9f^Op3pK+%*^-w#840^7kytSh)Cs$49v4VdGa%lNBL+SM6kR9&abh z^LRU*EI;Es-bRVe<87FA9&e+>ZA%-&wa;N=@#K3&o7^E=X^X~&&3M}HEuBYX2>iZj z1@qS0lJKT5($r3m*vB>iJb=k9ZUaPj*em`jf^(Vt#eqK^wVKJY<&~>d9BUbT)Bsc| zSH&DTj~Ev&_-VAi5aGb5JU*hi>a2g&S^wX+v%WIMjRt$TEOB{hfe(Fg=VNYmclAbW zO^9EW@K^b~NGRh%1u)8|&+x?x;Xk0eCE_qlI84#~6n2tBI}d*%bzNLZ+3XH0yJ932 z<7jixuK=_%8kYL~ZhsB|ka4}A62(srlqgbe#zp@@xiecq+}C)*Vr@5cSrg`tVe}lX z+KY@Hehzc{*iC>vXEx_MHt-5lzP}kDGDWS~FE3o2DwRqR z6B{T66*NIkoaJf?N+C@KfSEERPE5wks8d6n=#5cFcqowf%W;1Nxmqn+C}kJ* z{AJ-US5wi~)1?FK$ZuSx#LCEVJzWyOIV4G}3`z5YbWsG)AxoiU32SBu13Zr~iIyR( zkuD419HJyvhNO*jNdV`NB(X9iWt3mO;>%TfL3*A5&XFgHm6502bV&f`kR-7(B(>5d z0h~jU#LAGA(W&zFDT$RKsg|B6fOF(YVr59$N|yw14oMO#L(;``NdV`NB(X9i?WIcs zIEN&Ol_9B}E(zcqk|b7!q+z-wfOANaSQ(Ob(j@_$Lz2W2lJH2vh~7Hzg$EqMppIJV zw`Mf?etXo%e?`BGU|ujKw`zl}^2LRVh2vz5gqBuh`V7-ANl6SS6(lPqak7;P@zRyr%~VQaK&jnir6f+aQXyWtQhS+7Nen2pm#mb; z$yO@FlS=tR4;>W$*YN*3{;%VIt?BYQ%EP1Lhm@Kp4o&8D$F##dLr?O^JoXA@<>lAcL{PzXu2dcg@mRh zp_wc}fLs!G90GQT|4y9!P9k>!aWQw5k0>6ibdn24KwQj+4$X(8Il7@)^ut8W1;oYN zRqmqLtx``e^u#h(rkl}MFOue(Atd{T%Zk$=F3nqxVnIi3m0Iy)K@SuAU3Qlg5Et{d zgL#{nYj%*-ubs$TKwQjsC39)ONG`jHTm;0$WzXiam&ipxTwFFB8Qq|aYO}snaU+qr zfVh}99LyWUT$>Ff^F|_b0dX-89Lxh^u9*gsd639lKm_vx+bd?rU_O|+`p6|cW|{V) z+gOiWhD$NA>3uSMa8vepu`g>RE?0fyz~KPB_v`IL`6}jIy8$oWLFl@I`_Z_keWq$V zu-FjIjU@?axf&-Snqi}*Yf=(!=*H=V+Eb{hZs#nnjs|@?)LX1=HtS2H_Bw)|st7OA zQ9_26Sz249JI{-YxT%*24_}PQLR>8^lom^?l`zhXC2C>$Orn_6xMJ0#G=egYT3BI{sDe zl#`V%Lb?lw&c)_nfE%huw|cz;n*;8p^THXrpH#TP$}3Ln{B?gxf@dP|soEeY;cX!H zH65)>m)9_5KIpZ&donR1Qzb}NSCYiJLTTHp*E%J-R?heN7jdmAji@-~qJSr2)h`r< zcnU5M?BeJXFB3Le!D_ROzTB)|O5<8M7DG;9D8deu2ZK?no`vI*V}$KwIp{Sz%N@KN znNm(C7|F?DNVj?sR0;Q~yJ=hsMIF=0YD>I9N#%#&45_@P4OAyHoIB%1$hLT7j)qlK zMk>pb4gweB;_(ZOa6A#*tG%G!+-TOzjg`Vl6WGI1c;G3{{5Dn&ZHh%VjZ2}*xxxue z>S8b$;EmymQ`Wf!Laf5fB0L=NRu$eTsw~c8y3R#) z3^vXA@*Lu>Az~7o98<{(1#LLak69>^cP>9ynV;@t_@HHeniG+j1DjiUeP#Pk9j>dF zk^fX^dFu|-SDnUvc|9RA^{-@;yXrLV@C^Tt>NI}!dG(5V=oWw$=2xF)M|8UA-Q%lIvo9gA2EXeb zj?{SRQam*uy_c@ucE9>GyL=n|>eK9aWmerD{I z^=bBI>j0i+$Cg5Iig&uirmT7eUNZ#}5w74lSom^D8^=b6Y@tMNPZ+0RG?OMAhdDsn zc~~OUIuJ|5be)JLB1h}wC=W2i2lCBWjSPV?5tLwQ6$gCkTugs#AopB;p#O27yR^EX~B;k0+1;DKnR6F7ctlSwH<%GHpHIM9-gSj zO&C1Es3mQ8TSJ^@8fnTGK%{Mqf|kEo8*K*uFlhHYVx{;Xp%t`M%BbI0-Kz*-`{TAK8bK#!l9Mj#s!R{unK6Iz>(S?vs_sdUAbmVHH;mxAZv zG-bkQNdk$hEqWV5yt8nsIW)@*aDQdWKZV$1{^FcZvFv6uF-~P-%w=NCCu5LPSY-{b zkyc5c3_NL<$Zg9sRI!7Z$_}p{&7F-Tx=XO&F2RB?FE ztgxgugp`R>N(#;q#;B@5gx_C z8{Rh~D0Uh?4UII#G4f{ATZ&&3k zd3YUNV?Lp6pMtg_*Yu3I{FoBEr0S!SeXG&kJl(3{U81(n-^;xrePaE>1}eTT z1wn7Nh1ZbC&r}9}awVSb_T^@5(5M8xZhr_;irQ)>V)4)*r&R!PEktZZk;E#5Q=EogWMopk{&o3Ryubj34jOj`fCr(PT^ob(Rd ztH6QAsSdE<%F5QB^6pY7IJ|JhLF5&CdV0gZ#7Hu*+0BZ)4H7C``f)?ALEbcr8EwW z+VnEg;B>#+meXt{7>@cK9^7>}?Zl5-!9d4|+CG(Jw498@;cA#~Nl7}#8QcCFC z8zVZw7@3zJVuWMge2_Vxr-!_fl;K+n5vt3ZTivAKl1k@zLf(7Ok<)lKH@8-4+bB^( z+}5OP9A_0`3NI0Uj@s9E-V-afaMFS8E_%gJx4x5_OX1{}ja^!?kM>r! zF0O2QE%7p4F2*-lxFyMBxI5q7>7cb;O7CkkCZa2=E87>>RsR+3J+)_WOA9ee>#mDc zGFs{|Si&`{(BMq0m14n(?^4z?t`#M6Eabm_#GVk=ou61sJlG3Aj;l?{nLEIXP;ziu z>ru;!=Eg)-ifS~A6S%4l4Oca@DsGQm3Wz=T+GGK0aJNaEBJ3`wL~?J*Csd7pE~1=b zqs)p+ocY8~%hIE+K#zxvgc#%*d?yvCbP80h!*x%`x7aC(q6pLIZCc!={6JTp+eY7e31=3dq#p9tu z7SX;dH9H!15bj@;Qv>L|q%npzgwK`OSfk)hd1w`PiN-&K?4H9s2e&F$4&DT@oe zB4b1ct<*};Z+5j?*0DxE9X0x37*kD>?z@8LtFxtyhCij%V~D=LipU$wEo{=}9287~ z15oB1Zy2X56t*RykU?|+N;z+W$J$Ua9KB^3MVH6-SE2b@XA|>TJvaq-l8hD7Bqa`;VJXE)4oD%qf03!v4O&N&*@&q2T`j7%OpWyMNFz89W#)$c zR;EH>OG34gLK@M&E44reOgUQjF|FE6n*CKt@J7B@My)}BXe`M_WZ1alBnP07FqyMe z3M)>iWDxDIQgf}K)))L2gLb!{Vrqw_6ernVg-Z1;E$mBdv@V1_jL`O1a3#P2V*Knf zxzU8?nv-sSR11*F)o#{0wWy=H1aGaJ+d|B&`1xig=i>2XB9|Nr1cQ}ILj>=swT#ta zazUc0ClR@Xj2|v%9e)s{M($Qr;3V1=F^q)SD?YRK(x%l;M+&V=Q@2E3@@EQFyE-wU zG4d?ArQIf38#u(yl2=sc973K&mMMoqUgZ>YQmYARbm+B37G0$_>km^4la zNtTZlt0y)h0iGPFCx&aE{o4rl>gm6z4IBxDhWVjAb1iD|;;dZb5Ikq(xPf?VEjnGb zScSu0sz5ZNjKFcJ0m0;%Qz}b<(K2! zkO!z#KCT1&4i2@%f^&9*#%TBr;MQNe*9wM#h}$iklv24CPo(ic(@i@LO66R*_s)h= z^&0n}h?g{?|A(Weu@{mqFSPe<4zB5H{1AP5ti%g7SZHE9BJ!dWPILK2tLYnZF>~qd z>6E8&j5^p_>xm|rPjvBEA_J$myq(4fjF(zdY4d$5p*8tuVdvK=49JIxONH%AWgg-e zPhOaXQ#9P#PA^w{?Y@jJF4~OCu5j!$eCVoY{k0XpT3TIODcu_$z+$Z9iTJR`y)7QI zjSrRQajh8PZPp*2#`U)|bo;H`X%1-~p9?xeyuw+>!j61!Ve<5auPeC=@3|0wAB`~N z6{{kMdfN3pao)D}& zQ%#-}&If4l=u>0V0pZUy-|Yl>3bA-Hm4&mC5-39Nd|_7<@<^XPk&oBqt5MuXHHu@X z5e})#h}+!`x+C$VjkLRyo65|TyF6@eIaC?4#Yf|@7`eyOrC{ok!Y+q0tV_)LoZiRk znRcoXT1UyHjse*;yi!pUw|-LQW!n%;76DwTjbB~H9s8^%qZw?;JVWbmJZ!{R(rrZq z1)xjHzxbh(kN46trVN%BVh(=rDe{NIWR}_;B^Ht*dQF5VLUj(K!*oF^;XAt7p7l6w`F<9SG^mV4OR}_2OwH zLUr{yb-3=F04Al$2CYUg|Z>mW{L|L~5+nh%!BE4|B! z1I8gPB*0fi_e6^WqG&t@zFMv@wlIJd%djglFvcPx<(EN)a~GZk?TYs|K_*^bd)6oz z1*b+E8+bxDnod*(qG8g`9GWQ^*iFMIx6x(@0n-KzY`8H3nf)}bg@T3%GLFWvynZpL z55Yhz6iOY${0^-gTWIlkGM&BM5gi7s;cU1C2aaJ2L6Fk;YvZO)WAm09TjCwKG=>Eg z^Fkn&3Ycec?CksW#&H^%HJ;c-kvf{#==NCR#JN{T64kW-LyROUuZC5ZywT%&2srB0 zJS4apwt}IxWLbDxdr(AU+jkB#%;tJejW7qt%Uw*`tS-j@v$^D7QYOa9u$dlgs0=m- zjSK3|A&MJEc)i{raT&kkZ#=R#_NHs9N(b(qXy~O1!Zev3^>(EUQ(JV}G!hLA$wsNo zF?AYIEP*4Yk(A-cak#5LjjkAlScMrCWG?juUyJHQ6yq*>#P`6rh8ukZhU^a}Dd6QH zdtgUA;~?Vd2cG;b4a|Wz+*PI~|EM-^MeKS`5}5iH)mR z6iJlIc#3tPj{<)XeNo5N8OH$;U$R0GS6vcPxMvEe&ar^aR4oRu3*d_V>%xo2{B_~n zT&gVl3#Fwqh_pUGyE+@wPicbS!KJ0;wKHe^DxR?^Igu)-e7rOmzO3OA29z_UOcdc6 z$q#fSutCi5Sv)eTUI;nxj#sDWK_)q1tY2?8{Py8{?*ypF8F&X=xa;omX;4qt~&t%;Vao2sR`O zK|By;2t?ff6+D(z3g6J-UYw34i{=y_h7eCdt*UNks%Pd@K{pffSi9 zomxAi-c_REKLu5PND*!R{OrP7UhLDSv(VK8>!kH~DinVIXyv45@6P`YY&+%dsA% zXOhCbh;EU`*YmSWXD}mT zYDS}&E6L}4QfjM0Z5K~z%$HU%7nSDG=hTI>Y-Mc$BO>0#apzsVxgok_25M>U?6Tg?ja&5b&MvEz zx;q|Q5g(@f2p&FFmJcg@`!+r*A+IDZWTz1E^mziNe3>Ivs`0Y!QaYndd2_RizI+6Q zN;`>Jh?SMmIAU@}7nfHtk`~gdK_V6NAWi2%nn_2Z2YZD`JTa4292#C$f!L_YMKbMA zpQp~2Dw~nA1jq1_rAE)6OO}pdUMM6Qa)gW*EE1ZqhLbGy?0jWW&7*ji^UTuh0zV*~ zOe5MUwXi9e0Sl$M#O4|z7BUcN#41%VwVj=HjiWVlT{bH1qr*PW1K#x$(FVpOv zR^K*$Mper;UB;7I>5L=142IHlg5ih95msTDsV<(F!NgGj&8achZcr3|Y*a)L6Z~+!K8#CK}CRb zGp7bfQ=`Q;0yr6}2yQ7%*}`>mj-c^E6M{oLq2rwFg7BknaxV|{H3e5ysjY5PN zb+Z-AQH!5SjTgU6mU)e30b|ywZetI73gl}X#)t0H7gi+Zw)6C~)(hN}+KzEPY}!V4 zaWxLeJostAGrC=)k#w=P*{tK8^L6Pw;TB_%XDSuPPEslg7j1+p3yVU+HE|heNpj3N zgmNE-h@PHtm6l1MDUcIAQ4uS^v)88LN60yz*KlYseZr}eMXT$TpCm;$E6THaltB*_ zJ(ZxFMXPByGY(Nc{WwPSRsa{M{xW~kd0!!0LxrxZI2Kikj`9?sFgNs_9II?WC>Iqs?nnY}0&w5~^9f+Q_$(>!VF zT1MQ4gjsEMr|S*E*5oW2TaKQK{3J>FfZLxHJ$l+%IB`r}kGuq#T13I0>5O~&q^nv( zMIvNfmoaEk)X^e83r(E;2bySjx)S-&GvsT5o`nw1+EzMfxVj$sNm6u)RtsTUy&<7u zOjKQy+!RTQ@Zv#_yX;WmnI58K)752XY3+h7v4q>!B7TS=KD!X^CuaA~j~Z z5n?P!SyuprCW{w{D8QkuAwJEiUt&b_s@JgJMF2~4UI`PTQJWOf#!vp#hB8VLy@=4r zmm$DQc8E}4)gr=+1f!REbv+)sN0GHr{I}p?VD-Q;H9*65i|R?M`V`oODuSX-}C{X=HK=<-sgCNBXTlZBkhXQV_QSF2+(B1VV~-4K5B1$_!+d|gli zJSJ%cuYU&(;gn`_&ngjc3(IH;Cvt3>GN^F2?I}V=CCJ&e`+T@59)1>;;jBP#tDO{t%Z(Bt0YY(29MgT;&n> zmdN7n@|(yD zp$kM-ZX}5u0CE%A-Y!{U$mhaeoV_s%FTvj>n@oAkEmmU(g~rGg8|TuIvhPJBMml0#HBku|ENleh-8JQVRUEuF?O zq@@#tBU(CI(twsuRb7M=5c&P3qb-mNio();)Q8Qzl(Tw+FqM=_$W(;%K3Gw0Lx3wL01C)LWxQFxhIZ*LQa(Ypu<0zd77$>#XO4 z!KGohH+iAkzl7Vv{^@QD_Vi$~J*aPWM*T^?6$Z^$z<+YK*BeZpZs95RVYRz4+^O}0 z5NA>x+xb{nZTTCm+NQT!J|fAEoS8l{H#zsjCmtcQc{Au7S?e@+k8Eq&0@B;-6W=3` zt3UooacXM%$;GL{i6g7QZf$U++!+k}qc&DU^t;~e_qu(oP{bA5>Tufki^qMx1v9@~ zuge&VW@@A1O5NCSr8b+c)F5!B?(Vu$TP;`WVBkuv)m*7tTdvfL7hS1)d#==W+m(tp z*>KVG<|VUqc6KOLhRl?ZLecm81HTb$)J83euf!x4z^{udGA^63&i?v^H~8s1XAEf1%8x}_SP(Oz~AmR8|7`I_q*V>1ScDy#e|*oNlItbYW0SFe<-V9 zzGDbX!f^;qK{W*zr}SL%Tv=Y%1t;Rzg40lQ2{sld3Eb+A2_OwMmtbR+k-)8%U$8*U zCD>TVBnaNhFIb@F5-ip}5V*VTp)Lc0>HZ~FjxAF@X zsJR3iyBP_B+xZ0x)Lep%4W0zSyZHqR)Lep%U7ZBMd-(+m)RT4(o_)yW2h1shC>?XU|dxMK};30GoxZ3 zb;PA7GM;D~t}$x2_k?||E!v7XNgP#{pVHLwBrLl@z1FJr%cezV0&IyE+~ixtwk}xr z0|br?I`yEo-U@`_sAo3`M@qwfS-9*;WG5OUVd@*8u$*h1Jxx-WKiGSNjr}Thy%Xl{S`Kh_<${uOn^$J*Ym8@>mW<%Ktme$vAnzlpW>e-+#u&$r`qT zqO5({<&$!H7VgHLzglaG<1u+UrVK5ZkFd84BM{%_iL^uwPoi}T5V)ZQh!biDD{&+p zlEjQYV~G@lkwF;g6$4_vON1F)cQHC+2Oz{^JyL@@OEqg%eHpyQlRkZ$U1iR=tOWRlZ0n3CFAl2 zS@I-8w!9E8UEVNDoORC-P zEnZ=d#x9L9>?LDnNws^w#VhRBnNmZ{EUESwU`Y*occ#=3GfS#H5?E5hKAtHx#LSXv zj|Z02u%~BA4KcH%+M|LcHSF)1QbWuvsrJ}lNez2_rqmEKOR7CWSW?5jpD8uOj7!CK zZzGVqZ%u3&#yk>^*Wa;hFNtnNpWWne(@T z7M^p|gr;Cg$+~r!jvU)Eh9Ozs3hI}TWBA+z!yx8ELZ+&X;K*(gUM#!Vkq&m@$BE6~ zOTnJMfd!L4tZnLfO+ayEG#S&(Wif_`XgV7iQW+&%s)iYp3JcW8YqLLqd#;(;Bpip_ z6jUKt_lw;pr`r*lgwFQM|5AW)k~5_I#TxuEEm8c8mQfK%EZzq@wVn$&LjXiM)NKTV z)a()lNDh#p&!g`C8|r0uzK8{2Cieo|oNxey$Itv>*<7}p5Swd^)MkwaDU|YqTShhb z>&1OLU2un(1hiN_(1oQiahJoA&#*CbNKNRCI^o#p=av6()*^3 znL}zq|I~S<_fQ)%htz~#s`E@=^u9wCl3rY^#x<+t!C% z6Cma4OG^uGnj9x;qhZ&_g-i1sMNhW#5`&7YAS^wFUJ+g#(E^IRcLo85ghp(;+XUDh z--4Sv>ICLfAfJMRz)R%Tfc*0j(WY<8kMOW9L11{8`N=T_wDHQ6l1(kA0AyJ6@iKYf zj0eyX{E{z6gKTQ0L6qgBqQJiO#S~atY1_VOW**&@8L0$#oc(&O;qL^sOVkjlGS~5J z^T}Yh9`wWuKDX&`U28pE_`dCIN&h;&=wH+^W(bNv0D4*yH?glD_P&C_$5jA2Pe%dZ z2yn24Ku8Uou8lf$is)}6uhed3a(AbLm`c=ubv#YG7zc+AF^o_PxC-XuDZK~%ZpXhh z=yw%SvI=w{XyO_{J7VfUVK_wkwMHYGF*;Fr-x3iRKwr-ny^CBNbwN#84!wR8Uy;8u8I`;SwVXEULTQbTJ=L7i;RT zu>z(~5|N=4odhvzWu(0Qg@k5? zM?&;=;u1ouP7S?;J*(kKao?)h*+7u*ShvViutk{kW@i#qnPu!42V5G5gF!f?&7dY# z)246>@}girSZ`vg4vif#n`;xIW=voP8-qoH#WE%nnTrJLW_(_zB~+ME)|fx2Z3IL8 zUSAw^1KMP5H)v=j6Gu6Th~l`Dh!H;p={Ve2nsv+uy3u?Ojq$;-f$N}0w{({CU+xk7 z8qIBg=-o2v4!wTRj)G8$Q}JU0D%*xQI0_RefObpLqTL^tKQ+WCMPNp#H?%BVEs2nQ zf3@r*y5Mee=x-o&9etAHObv_P&VJUXip~x1){q7E`Hol;WKw5R_ z6i61;Ky1kN59FMZ83c^YdMQkI+^ULK(d9|^%eA+-Gk2cuIpAF``=^gVPj^3)bM@yf{ zt!_J*Z1$T2giigkkHd$G;6{g7ChAPq;9JwW<(2FI?JQ|52k4l9&U|xlEElkHDFqqX)8H2Inw;2?&>SL&) z)WW*d!coTXIQAk94jniSqbx$^o|T}+oOrsd%6O{M%VH~3L#$OXxk(~I#ZYUjP?#|h zF)b-Eq8^f{rXnO>BiOvnCSs|{g}wjd7j4e1k2ZD2U;d*PhglI>)7p?|GFTB7>AXaR zVv#ts8l(+@4MgE4ld;w8h<~v*XwY|iuql&8h`oqLwyQ*zQJ+ggSvgm4!pX?+GjeJO zcCr09S3YE0!og42yzpMSX8D2>pfQJiRY zdLzV8RJoM9@6M`oU^;5fjTLV<-OC+#&0v8_g6}oZ9I25nCQ1LXA9z(%cBP zxJ0~|yyNT5Mzb&9lt(D#B&jKA4%zA0aSi$~pu26qR<9$9eX<70Xf6#>u}uw5aHd5_ zAy+k(w(&>b?8!?aHPg3t#-J1%IohdNqq(8tLCNDNK4uHUM0uPMA7^?2-aOEvH5HEc zgKg}^BaW16Sml-T=S+ur7YbqMgUSA^1TcB1fe>wuj`4L7U;c9{k5@Com!DdWYm8#3 zY$W=rss<6KkhnmFD@C0F_F-@s8O@_bxL!3o+g)5Ir!cn4ncv^(!`&)~oqcBF+G^w> ziMenbi#Azn{Y~GvSQdxb-L~LB5q(u}9{bY*Tg~>N4YgmmLBuKa`#6-txzup473kZw zCuKUe#OYK(E}L}t4H7==ig}0*&2;E-hGMq|&2gYtak0QaIfZrLrvvv~jl6iwz~}^< zXuuX$;e^aUBf!O;wv~h8lmaAXVOk;7)(7Y?n*73yg1}gffhbCzvU53>glr_?jcs(p z0oI*Ogq*uoe}E;6vM^&(mOT0v!QQpLoFQI>3=}jauhHD3#v2(08MMbG0TULc@{^vB zq=l&xJ?7!_SAGVCqE3gZ@Qr6fvdRw50rZpzk?C)V!WT)X`cYOASrqMTBE5w?~1*x!f{p;(&CiwloHtX<`!+N%gpjL<&fnk_W@7H%18@6Zjx&cJ{Ct1w8_+$b$TtFC2@JVibtx z;W7BAxl~Qx=#u$qU9T@?m6>{vsny-VoSt9QaY=yPx}Y~`wz^|zd4r+=tt=rNEMw;) z_pDY>B_zneWc(2U%YS8iY~vVq?2+JPNCW9cCmtgc(*_|JDFbD!3NNrl1S+s_tv0gi z-(mh|%r~GA*1vgMFN(W+dHKhY|}aVJ`(<5&}| zq#0wP4Kp?FM5_odXGI&z)E1_>mZhOgjWFkmmSv7T(JI2rm}nK{Wlpq;dfbUtkzLkA zD{04^Xj#uOC)!9B?_K8@!zIxe6RlFt-lfhhjAxqs6Rnh)f1+jlyc4a&A8VqOB;!rA zl7_QC#zZR#$DC*-(YO<>((!U8T17hcL@VjWnP@`_G12a$b4R;Y--0*lq;y#OY#~sD2{x_)M6ne%9%ts7S0MkXjRO8Hx}2Zk_lk zJuyfC7;KRLy!uUhsOqPdir^@NNHy^lDJ4E5b;PGq1k7=D$eekjcQv|4|TNgLsWM7B`PZX615c7BGE-(f-w3Nl+mXkB}UwR z_;)Ce0HHYgh@>%%U`HR3tdJ^%39@~ze|Tse&IX{Wo-2XNKP-B#;;_KOYUK)*g9nwq z{DmKKY@sCiYac5^U9_vwjY*yD;c=-wCh}H3zlE^JGB%`7F?tYV1lLjYx5-Sr8G@E7 z@ObuOVa;QBDz-VfZ2R;Z9&d2F9oBK9mA8*$Dv0MpbtyFb?@O!{)ikYor zQqcS^Vl0mdFuVeg0Tp8+2_xv>jkknsP6L?6M8W&%${d&QG)55$oSl>P!3DE)g&3h8 zYUIxSaftwx>Pns)Z-&5x6=l(lc!RC>83KbF4HxN{Cm03TLAy5; z7XaK^9usijh0Y?+er{srH+N-RB{wSpHC_NTJ5>?!i9}c?H@O6F^t-xid%TGXFtkl> z#Eh|C)5D|0_{uIknkdiCjorr!{aL>GMT@mrHB`_;aF^5F^S(9QT(iAeXhBO{`q829@6F8 zdh3!bYRoP8U5B|xs}QjU!|e_Fy|K}%ZQ`~E{TygG8wh#XVuDSD%>Q({f`HzeA;Q*9 zPeHJcB-b~%TNVE9h+AH5Aa>xeDi?oPMhH^;D-0K0lvXVI@PQYgK@GNPyNM{iBx8VO zBO(;Y-v}~AvGAnYw5Fn)*5Y3QZ{LE?_AN4lBgNOCsrN=ZTh02GK*vW5SC!;K6dzdM zC>p$})5qO!fffGPAxoK5qD79d!{kq4i3zW9MA3kEu2cmhsQ4<7O8ilb#z4_eDG*W! z#2v#bg+hWsaPyK4kx^3`0Y!45E3vyhq0Qp@V2C?dl-8C%rPl3Q2i=rPYCpTou+a!M z4%zZ6TG6XMqt(cM7M?Pho87_2PD8Jh!(%g_K<2Dqxdpi?(68YpNx80HZY&s}9UY`a z$}&i_bQ2$U`|u_! zmtu0rh!NzL&>dF-6J$$(L8GcblvR#Q#3{06M74n%5Q(*cO4Zs)toF6)Q9PVtO&;-9 zfxtyvUtp3}rY4`bE>1p|uMbt$e&}QJxeR?yguUh-spDdE8QQ4MLSZBl+l`6 z0wrue0x|lMSc*i|tk+a!<8hWfPS}x{BzT7<@32JDOv)xSC0w9I@&vN>DG`~B71#+i z*a=nGVI9H^kC}}g<|%qIUee>sQwq}0QGo&*V!9C@)5YjR{(|isEf^`ZE)7KhK|A-L zn?44a44gG+GLVCz6e#qD-~%v}5M89*tRGH83AY$Tw0FPTZZc&6_^_!QNRMO$JRRrP>3X)Vy52$&?X_M3ium+;VH#+ z8W#PUFXB(&mku0*Ni3)jBJ@U#95R8vJ|6d2w9^~{pyqm`3CfmVVKNx#vo3yAp@4L}NWs zD9FFPKl6n7R~Vvh-EesRh8 zTDGH>V5l1FX?pHsy($Jme=wq1>0sI5CD@h05U%tS@#@rXT3>qV_dx#`=^ulwZhy#V zBjXDjJ0U>(jXS2BVY>c-w=8ss{zVeS-jJr7*dS8hd_t~1X-g?Q`c-M-05zT%BI?W| zOg%M3)#XO0dTNL&_Tnu0dMcsv@vn{;OJg)$At5_FE!J`#o*Bm(#&sk_U73)ho(R!& zN~-bFJ^_rYq<;gf%Ow8#H$HVq1lGUtDbHLr*+zoeSW@6Nq5@u8kWj_nU6s|Wkm(VC)tf6ICBu1)iL@_p^SY)e- zL5wmfBEnvc{MluQ1<_cH67)<2(O?Xs{Vb$7V`?(DWhuZpMGeR4wU%XoxEy6@ZbVAM z*$;xM_cyUNgK=Rc$i{Izp1z-1cQF^)j|)|`ZQ*OhV8Mi>~Omyd`~v(c26><3nXvPuth*#u$t2>S?N`i+Y-# zT|M2bVS~iTZb9VJ?C$2!gxFLl3C55UgqF0QC7>$`z+04BTF)}~X zMWjpkE$^t@#XeeU-iP#f4@8uT8^c zs27^$Zj=*@0w=F}>sIQ{Zp3Lo31^s!Gb9|-=ytP{wJkR%5;0V$-xz#PWzJSrL83ef z7dkh&$WJO9c}an%WI(9_jKmB~uRR9t0?3ff?##^ zIynTpRd~opfA3JeWh#<7wKkRwh^mdv!Tu5D&KqINX6$hL9{vBE$* z8G^tnDjiWg24ZlFWEJ9kvyIaU*w3;$go_CtmBs!t_Vyf)pGgRnaEOSqP*0yZfTA3< z&7+Vi+9Zkbimc2Km+M&UCWu$hL@hSN%e(3)3JCiX8Zc5T34^U&l$TCuXr=?gmJ}Do z`guo>P7eC@N#TLIsBXkoXc1H;pVU(bw|}(W>m9PbyEH@3i4~5`Ap$))`L7Lv{%jwI zgcLs<*~Y&(mB-VDLobFxt=dgYMGYs5!i-sZGO;KU=Oj-tjV3Zt7DS2^aRwK54$(K< z+`{?tz^V^#iMK|LU=r^>wg;1&GBhjR^cftodGd_N*&;IL<6Z9Ba5V7FEY16i)iYHj ztj?~k(Z6eRbERt40V!1~%N2iVZDAo1cxvtR=~BgCU0(L9i?b<+a4;{=E|hPcT`ey! z`GRvI)3v2@OUoCQ{6(lWd#2=<=d)2~&y?q&>f)(VB@y{TWqIk0$ag6bhh{vSS&YrW zP~68+pBM19L3hXN?Z8aOOBHZQ1Mci#4Tq9kIyCh3yRA~Ew%$T`ZJ?g7wMJr+E}XFS z*K(c!rhLx_!x|hi8G1wBti%cuc z4zUVO(PIb{hq_viw39D9o7kt+x>y zMD61WO*=by01K`S?cSh$$flhOjdEwWhS8qUtSn!^)G>F{+(OB( z%+8mWy-c*TrOMpeLaCa7Ia{fg=Ka!*^Y?FO*N0-BOoIkh!>A zDf#oWtFvw#Ig|2qp{75*o!!GNTnbLmJ!Gv2H}FoE7fRj+raw4OlS?xGrOU?nX9E^* zx95qggt1BS21TfKbS+6te1a_)(#C;WNsNZg)?ku6nSEj(^p74c2jB{Fc1mPS6d#!+ z;;Ty6vN19@Jem{_e(bZ$`EWgWua$H3GaLsir=sDH?QT6yv$*Z#(`1O-$)&}W)temY zOBl7}5W9TZU%jyGK)Jb8f!$udx#WPsnD?c1U-j28tU6G5JoCKz?rv?pNdwTZ-J2ZL zv4vFMnp__>TMhqW(7Dv?3?_HF{Y!{5Q4c0hQTlAB0Xv|HTjYU%0id8S@h97Z-ej+j z=TPdyN!;EY?c(qCCu6D%`gnhami^vp`N(2*WoCNn$eHOQbCYvVeBzNg?A>ezog-_V z=I)X0!il4W;?d&Kh1Dt`y}dq}=SLn_fBcc+)YSBoi&KRYM^^EG(cnnA16M8KD?z{O z-9BtWs3d|i6tG7nbGBWe2$^`$uYoP4&X7V#VRwsy?V#{fw1-?uKCDad3Os+%Dx*rsRZEF>IZmMF4D6^ zJ;6+ht8NpiT#rlU%B{^jDW^7OVlL6B>#Z7IO$z(F$Yw0f%BM}HGCDq?GpjcL#Jt+5 zNtvYvFlgHOr44IiT%nE<%Luj$#f5B9PSg-=M)5*&i&N!vx#X_Watlf-FgJE$nZd^Z z7vlm~d8kl!(rS&3HN^zFapeG?_hOCFyWsoVZD(C7b(Ge4$V;3^P!`1b7pl%dXw{vY zzpA{;XW*A!f`D3b3>q&A2Ln|M;}g2F@8F-5bq8u< zw()knik71fZO*P9%ZC^MEn2HsTmraYMB!o!l&z{<#LmKTNl7do7jjYo6?NpUk1L1R z*o`!%@s3YlsEu%rY|MDxG8o5;=pHk46gC4yf_^n$91KPkpG@W0q z9B~XCbT)?+MNq8T@NZ~nM!&jbh$3PDMc}&f-3#tBr=($3QzfOecFi%8|c8;c}G$AwRCnfbt(?vb;it zDMD#eKb3E@9GZ?wGvJl9D(bMGhwH6F)z8ILDW_JrPU5l!JsspB-h})?)2%nRymFIY zDa|cc=H(({NS>x1sN^#Qbe@Ti0i_Hi_Uh~@cqLt__RWr6ho)sKD`(u9NJjWORQ3*h zVJ>;S+MZ~eqBTBx<x1$be0im`huz_Nb3n%#*dawwy_M7D(!#vw`8{}k4>y{J%Dz}{Zems#$$uW{dEPbNuV3SN z*W#Dwy?TAZd$sr_|B~=Oei*|)_3{Z11rz>}@Z(>{@CS7#yzLO`c@o}v1j9f5^Ap}f zE%-Fhr2G#$;rG9e;deXXfB8)efA||FyeW(SXCBY+i_ecT^Wcd4^2K}t^o%?Bq-|f`zYkr2|A38VT{d35j%eVFO4By_F@X%Po zKT`fJzrgUXd)|cib0L)J&%Kl3-}mjV_PhMw8GcuP!o$H^_($@u{tCk%p;n)3`Ykm$& z41dP6C%j*_^q;`2B;{Y%ag8tkX)%OfobYb9=pVPt@cB1Sc#pH-Z-7-K`QLAI!n?zQ zzxgJH-}zrByd?|%wC6DVDX(HHQC@bNqcLtU^hD<9E2`&+pt| z_&+=4e`S;5cRAs&xWw?M{E$n(hoRJ^{9B#yH}@F+t4{rD1BU;zGyfkMG5l61+}~yR zT~7E%Vb!Vf{cczLdm*eU34bZ-_k~vd4PLy+ zPtwmj;eYxPhX13peQm=kmGnpP%Wi)UgVinJH#_Oy4y#?lAK-*nQL7UEnc;-jvC8MS zf0*I7KY7CY1FQeP?ez?QqqF~&f1KeT{27;h@BcKzAM^{Z`SHX5jp1+HcG3>jHUm|&oTU!IAVb@9sW`F!CeghHfVY@g!1_NweMp1+mTb-K6vfB8D4bKKlaxc z{>#XTZJ)gLJq&-X6aLt{8Ge^De?Rvd41X(H;(1H|FTR)IuR{O0*@7>;kKuPZ$LBx% z9fp6%VvYA;Ul8%>P$>fZ>mT z{ob(T|H_{*{5B{2mjB7{Yn}C1{xgO@6C;tm{<+Ub82%0?{M{dA_y?Wk`-YD({4LJ> zANe@Lf9Wi^IpNj&GW^p{_+Nh|!`}$|`Z1RL z@BS)=zt-9R9`@A?e-q08K^A@Y0Sx~wtWO?l!N2N(41ck+eBS&u4F9-O|Jnb{@DDrT zfBs;Gf4~Xfdnm)-?}R_>;S8U`{9=!MUZIq7eD zB*S0nEZ<-GMuxx83IFDAV))Pr|IQ-}zv!&rhg{F_w>#@^=TQuQy%YYwAIXGfw`0^JIqq zk(2(rCmDX16aI|_hCc=U+g^YFRFUDIcg}y0nql~Roa6V89%K01Up3)9&1zr&dYs|6 zp?%xq+bd5n{7a}Gd;h?D3d3id`oHYIFuZc7YyJM!-^%c#PI&ui3?Dl6`^sl9{7ugC z9nCWQ#1Bk(r>y+H;|#<98SrOV@SiR-{4VHsy#;^xIfj4y&93qB#}*iV)H!~hSYr6; zH@NH*Z-wF4Ip@zGeHO!C;9S48s|>%NQ~u-D7{2O+zxO=DAN~`r{f~<`GQ9EJ3GW?N z`MmYn48IGOzTN(w|6GQD7WSEK|9!$|{Kk{u8-kU7`Zx}KBbI$$YN9;2EUC#B#2lp8Mpc^JUhzS44^}%m`2gB!o zWWqZhLV0~~{x*jHDpqn!7W_poV0gu8zkcoQ41eoOUHi+YU&!#4%7pg`i+>MC3fGF% z2Rilp&X+L!3(org`1djVX)l}b&RYC`|A!dW!ti%F?epJw&3#n{dY3_cEIia_o<&}_+wfV-V3bq`{q|3P!SJDT{(0vo8GhUeum3f}PdUe*KmS{Xe-!m+m*4;W48!}*@pJQY z4F8C8eE+?FVEE@@|Je4yH++HNXPx}N|6dsXkFRjeKVS844BvK+|94JYtJ>FsbNzOo zuVDCFUf?=Ey8C_%pLfDX4`BG~zQ=X`^PeBY@D=Qo*!FGpAq;f2dRb`ZqJY=!C!N(G35`x4QKI=wliFg*#mN?>~{@&v~_Le3_VJ_@kfi z+8_ONk>N`i|7lF;KXQD3^l^sY=G1TLB*Q=Cgx~R0hOfTJwg2+nPiOci8WY}2SUCQb z@_*tK!#{QwgNrr3{LN{G|Lk)nykD~Df8&`9eg>OtuQB}L7=IrSiC5+Gg*wAu z=Pdu@8w|h83E$mf_zRum=esX5{7p{ywQYu9f5~;e@X#K^-}n%$kF4^0(~#l46BFL^ ztnzu~9>c#>oA6$1<^O@tXL!q5zsoOR_^rzwo7)9=IZe$VA!^{B68`0JhJ_wxHQ{DV&W z{N#UP_#HP-cz0R)ZLKi;flmHEU19iwvwR=8#_*%g@_X6^hW{)Y7p9Q#k8D4)&tdo~ z#^0BRP;Q_9;4}QSPW$GXI>VpmT>sw{F#L|Lt9)P6WcZt$mJ4Mw>sgyZ(;cNIpOblEWg537Iv+eL;Sakl?Lo8i~L&2_$1 z>M{H&PWW>N48P-LuJ!FRw;6ui*?xX#m*ICf$M+Y1JHwyhte;OkpW#n)w!g=|fZ=~| z8vB1%`MmKD8UA2r|DO6E41d9f%m3>mf6DN;v|Q`UkN+9NAN*gi|7OX*`y&j0`M08f zTJYz7jN#iCCLH@afBqK?{}|T4_W8qezxgXw|LHi#-`z(s{4LJ)+1-y}`2D`iwf_3Z z6Bz!!?|1okUO&n3Ti@c^KYV+E;XmiJuO2tU@cTR4&!yuG|EzQW>Bmnn{Hc$c@UYnw z{*mMJtxse4R2}1Y2<7?fhEoiG`;yB(_{Q5A{w3%7dhUe`f1q>xec6i{{y}H?fB3&L z{Ql1V_pz5U{Gl&(mH(rDkm2`t_K&R}V)zkf`Tq0|GyKs``j5Yc;lK3w3Gee(``vm2 z!(Y4XD!+HXnc)w1?yo%OCmH^2&h^LN-^uVl!TQyn-~Q>X3_s#r-+t)7G5izG{k4z& zEW>A<{t@5!^9=tm%EvyRf5+Pyey5ZFE8oHJ&pGL*e~IB=!ugnee)yuh7=97`^V_WU zJNIsezpm+8Uwy@U82+Sz%Rl(NcQgERdlTN4#s5X`W%x&Lclifh`#y$0!YTjf-_P*R zV1J=u@&CvlGW>DQ^Oqa{nBmtu;ivwB;deXt&p!1DhX0Wh{>o1>{C((u_Ws!9rx^Yi zXZ!t?FED%o`f0xopA3v4hmD^nX`~1@w{>2x%{P!O`$MCxsUH;*BpJDi8+7sSwR{6Ya znc;Uk+vgWn82&}){CAO=m{48PgWWJIcNRdvBvQCtxb3zw&;K40>f_`y6#uJ z_$G#b=nVRoHNSrDISjvu`N1BazTw*#ejUc|i5sUu1|IY9wXZij2cQgDmtFHdF_8x}M%)0hR|MG5z|G~>#>(>Xr zm*Ecv|BqPuebf6xIMyHb`O%HP&+vX?20WblypUw;Q?)0gly*KWv{F&lVMuP-0yJBx>qD4rz#;HD`Ep8gQe zyAH!7?%jAR6?(%=zKKH^-ZSw3HC_#7G#2XuWnoS|FZuOIILjX=@iAXIwRXmzTV7nO z`iLKZ5Hj<`!kZO5=-zD&dQA{!us+(HqnAm2f7suv4skVEJ>9h0mGAm3bvx^L`Wnyb zYzij-MKGbux$tjtF%VVTC7{23 ziid&dRqMchF_LuiWbx76;GHyL*BhTiehmL#CPLjr_(wr=jrR{VWC+=C;Ey^K`AoKS zAz?~T(52*6H^s1D>kRNVr+PVzh>%T4p^M6Y;?`=o%W9%~5rrrF9^G9oC5YKw>*1-V zOH3eT&}HVgCK2En%pQWA223KeLid~DBIe5caCg4D(;+GIwIRv~f0P*9d4By@xM})( zXM*7(BFf?=R*i(NLH`-*!%@b~K{+gAlq>!`2LE5<(amT$zdA`kATVV=q&w38$IV={ z_f>hUaJ^vrt~($A$p3;bZanHeY{Bwz0_&6C<9UA$toz{quyVxvjMN~w2&JNQ#rm(E zxT3jfTsvwnQe|D>K2~Tz7q36#4izzIZoG z8>*iu=;&_tbxw6^cp|ma2&-L|30>8OH=RQa9v`ct%7ylHh4C8iy>IlqK3Y4ggc8Hx z?3y*?H1%V5dfwL|w=`?et0DAondG-5_`Un5JP-RD65cKC_QY$gD|n4|YFRw{Dqct( zcuxmT(|{KYIGB0Q5FF{^`1^oOgLk=zi3g9pcKc9L_V{5?4%vk56Ymcr5C;8`V>(?f zzv)^Bk3MF_O0bDp=afF{Obf|$<$MC=XiE+yRzOdgD+pndjBcWT5JhT{?ev?&z#&aG z4!WR@3bDzeV!A*KB5{(AF0SXLqoKs}q?&Z0{Y%br4Rc538Htl*bk98}nUp4*FkOHD zdzUn-0reKLP);`CgQt;7 z;3_m84aFD{F%&xd|Lna9m|aD+_gy)ii9uut$Pl0j5ayUpLI?pNQztZJA_-xNob+%y z>Ch8>x-%d`2#A1z3m79HV8qBIAOaTw5t(GV$P0)}B8Jg`h)g0fe*gbkdstQHobJtZP`BD`_bSEiW*jNeL!l=m~$)?%8(w14n%j{(zrdPyx2(E6En5-`D9Is%Nk ztrWG7PxA@g##_!MXIPBP@^Zg}@o&b_uEPD@-7h)Ryh!V;xq_w_xS^|{2r{+hRtLzf zXo3M>!4%4&sHO?y7a<9LkOZfNhBu1cMvASkAnJ@H*+MnYhC{g;!i>cpLdMa`!yR}8 zj)-d7k7#H|H>Lq4rm1lmJ8?CwaGD9@nK^y#9V8Gr`Xcenw#C+)LxCVXd7}3vuUK3mk#b|UxMSCg0Mvf zYMLErabiaQA|dk0P4HxM3deam8lXXnANDO09K)%27&Qjb%Q%{*c(SzQ5qN#g=#@6i z=$O;gl56YIcejs(rP+!HiiRy1fN5c%9SeL4S(pw0FRrb|kf{#DS(Q z-hfJ$uk;1*{8GLMh+wcIf`6#N&Myd|4ohCI9dhZNX$fN>)S=*ux@j`p3PvLOFf@vR z?;ZnDI|@-b8ppt_XCTKXjz@4>OVLP12AOyOWRGk}rn!>giq1~N18Bt0$x3&|(Rv0x zAPEDS`7s2-j6*w&=ruOgPiSjcW&~4}- zm}YMpe~~Xkim5*Sl#Ns&2bV98eREec?vM@4|QmcpkbEot0qK(=@16j z#H8JpOM8j}gHP=2Xbx3qw}z%&*ld^1lZe4oo_k;TIy50^{H6PZl;BV^v#U9uL-#j% z6Z#ai4%7Wphyuw|1uC>_MFTSJ-9ANi{ld27zS=y~s?00sLzI5>B!EuC(#*{2!WPJs zUpuF&V^^A<`3x-<+utJ_YFazB#f+N4>V{|nc9dkPEv~`p8U)`1p)1ke6^*9cc5qz6 zm(b9*U~+Tqg8a-*odp>p;b^~R2}C{yHRZ=Q)X%PMX>ZO=!hu3?iD%?##Rh^RRohT6 zb7GH?_297tdanAK#2zIzuP#wEIHKH>Z@4 zYiyJ|>eL2J;G9)lP%0B-JCRnkG>GG?#mtXp@fnd?O<7vTS>~y&lhPPVY0}X?4r&AQ zG>N(++8fY5%B}UuX)EUtWYzS^MHa;))~Q`o+RVXc=@?hSqcZhtWxt4y0xD zFgqav8AmfZ%qHorv96U0Rf-U8>7b!05Yo4zgA&@)@n!1roweHa)mzb`j(@8t-Biua zax0qEIn;Z^RvKz(%cS2 ziztk%7g4G`UfSNdrSR_Z9+La(E29~nQlfDTbVig0dGKEt1FwoR4@UbuerZYaS5#Uw zL20Mw8BZ;{(Pm{#vmnj&`0COOqwhy!NwYoQ@zf=9Ql^r}*Xog0d@l6FC0AtgwT(G0 z>UFkt%i->D;q9&0`qB&FsV8XjVn=9`Y> z!sJvzS|BPWXp&R~X^N zRsM7P$*f|uTeLJ0t8JLkI&ooByOeRw;rha8zG!76*3Jc-8Lg7qNL1%4@t1M5V04@> zq6tlrXoiATjOu)uIQ}A~g_E|7;=&o-Y;ya8T9K&4zZlw9W|A_b5{->%e0CBUS~QyP z-K(+DL`WZ>W{nyGAumSy__S^`FAz(jG(>Jk14oZXB59R9rM;<5(@`T%Ge?UfDNK7x zcQUQK^d-~O(W$A76b#JV=G!oa;f@>J4jVe~mvOXu6nEkpkwg<~Td}n_yN^4D;Ogb}qP7O6zJCL$MI14>aiI*lX?I*@IZbx%U-}U0=*ZZ3MG^!M*swx^eccdSC?b_115}RRGLJduMCTr1W z)l5lSOL3Wur1`MvV^l&-#?jaINYfD7aP3TR_%ayxzF2!uYcpT{#@6}K_nsEAsm8)-SZEWgjN$;qUqA91~ zj;V;gR$6oVkyW*%wy6^xy5#XH@sM~?FzR$*g^8KBfT}NyhMmxfPh;PKMIuQe^`~Jc z?|rax6MtPEr(q{9ATevp)1z9GN&8w^1ZCwGWq_R|PUkPoxa}eTKB$Yi8fhgP^E8*J z(2Y&L5E?=&q*>{Ai!yFYtBLo@Nz_!}&EtK6s#HMVEsaj05|TxgBW6#m$&Rl|M!_mU zvs1pr@I<0go`;5~eur3m0y<*+tT{M*SvIq=LmhYLXnYDU)yTxFA|h0Ye>092s5rHl zD#AK)4wHZ)qve!VsBZOcR=BH6YeL$i;-W#Sjqfc@0F|OuD)z%tDZY}bq)clf&^8qs z8Y4wrY%k(=oz|%e^$ZX6&_-3E9!;o9=)$l7^VLK9+B@0hkOM@9mZ~=LVk0%ctfj|b zw2_}yyL4h(S8M0&ChQa7TE0wzAYk0Dry;9svEZ}nsyjN+%{H<$YBjDFfowJ&OKFoxD_Be+PBmF6 zrneabs!E!~db@~96hMhrrQDc?u~=baN!%@LYdb!hkJcAO<|`sY<5;`lwv=h9ZPEec z#o~3z_bVLwNOEF9eqmczbHjw(5v^VMTmu)&B&ppnsPBwvB9}w+I5xVqK_-k^;n|G) zq9cF`N;(s!Um%OtOE{^SCpu)h-m5JEjeUI>-HY?uRoSL|M>ab0SK?HOe>09o zzm`XGOo@)+wuVAq8Zv+VX@&boKg}}7qCu{0uIy~9oYl4%s}QUYv-R!mUmrWRsiP@B zc5Kb`nmO19KFf7LYmd^^)8|xUXZe)uVb#?$v*V}M%&nHd8Qi$Xz(JVh<%CIYIJ2fRB(CYbCHo)oS1W0Z*d(QaTHM8|jcw;?3 zR4Tus9Qh-rA2xl)k@_giMVg6d8IBWG8{jX`95JWOj3XvUMsv?sNLR8SWac(?bao*Z zHFmX13tlM)&sJg*r&2Rfnztrk(9Ih~o9OHQSm9ZEWj4oUX{-@ zA`Hiq54#V1phTU9?bsZA2@0~uOdrKKR*mxGSUq;E?;w%Zy+Sm6hsngA!lNcg8&A%Y zXB#TI<8)Mo${eqwBJ0XKlVozM+VpS=G_FUwf}2XqK&`6=xGW z+5)UCUtQ6qMp1XDJS>;0+w>qV*^GIyCuvu=hsG_;UBg>ChxZ*64Iz%+lFyb%E z*EE%jKr&_GEd*$+XhiX6z0`#l;AzsNqPfKj%hv=Y5;2aw(`rN?kd_$_>Xj;LG0VY{ zSd%2NXvML21&O+BPSAv+wMTTVdddl=#?WkKHR;pQF615MYbxA1AWx^Uq7BKhVslS_tKbb7d()53=p}T!AKi*R&=2Y0rtH?TCI~M@{C@bfiz4qh*xRg|dCk z?uph{O_QYc1A2TQ9b0$irsG)qni2KmrPC`3tT~RBORIZMmm**Bjh7ch%ch_996p|i z4!<+iNYMQ0{^ceqS55g{iadnoSDHsf?(ga4*4MU5U5CY5>8o=8nP@pk9)(6!F_Ybs z7Jae$I+MM)<3t0^tYS*KJPmP)Np$FYr72d-LYJo_SiO*k(OgQ4trL5t#?D(%(bwdW zXxVk+p5Lz~ibN;bGNciq>DQHbJv|h>_FMRdx&hGOB*$sh<&qXJsOetlhcAC zthEZw$(Au>P+ij9Do~^^i*{$f)^qB_Jqb}2Z{wAhHC7Ut=4p>8Uk$g4nb0&|`(V$Z za|jiGi7uhX$-QaXc0tdf^OzIVJdcNvFMvhI!J>oaZ!hlG<2!D~xG2|w7Golo&g$?X zfvC`WgcfrDTtY~ZreFpaUObu<9P8&O<|Hj1CT($}2?1)h?U zQxnBC&6ONL1H@R`a@#^%JWnxVzjRunAgniOQQ#{Ns+wuK_=Qz z70sv&amF`tBXq8_s~uGpwla1`TV@Uy)wGvmH63L_c}`PQ$IO=}rj_W& zQ9bnLh09Ww6z@50M`9ULC;HRxvE++6Xm?JB&a^arZ!Z(U-a}OB#1@TGWBRXG(T$o> zsfcVFdIa=l9L-oa^-^Qpc1amcYNDj;G)ENE{`F7(8&5qM-PHWTBif}vNfJyHy|kNs zZ!aV4tpaOS|KPBGvH^9|FIN9fYs%;2Wf5)gmQCyDPJl8hEUWglDkjOJy*0g`Z07J( z^jP;=JvvWI)8Pjr>9@8u@4kgKZxpg9 z(6*W8%s)p#?rrS+N+B!nfu_%IKo%=smo2U(s{~y?)+UVB(>M56++sw1vSVI5vb4L- zcIJykUJBY&Nd+2c|3j~$SgNMcRHZ@p<9em9tW+H-QLd9H(nN z_@bkbMeET*tvndu>VKhDeVIH?fa~KuWy&*)3%L=A(Yd$rSU7;wrQuFCnsFlt5~VBfvN}u;GqT3|By$SMyAKSG57g*+~2T~9w_ zi~hY>Pfr5tOd}7XxCXDQ)NB;Ry`r6j*Y$KBRPnW*!+XU|6OBh$bT>yC-MM7XM@v2r zx?qFfL;Oo+igEJ(cpAnbJu4}ZQFXGECuU44S4Yq*R1G{+gEkd_gGrU9 zWn%O~Es<2!Z9D1*))#SMQ-6o=@#R>JByh=*h_6BCk$61GFr*{rk>c5(s{PY3ND{^? zT8XPXh*qaO$YfL0SLJBxwx-g7AJ07*^hMMqaZ9Q`?Xd8ml-J9A(t_7MQA!`rQkhbw zilPnA1X05ySN_&3HGT=uMwJJ%%o{E)<6$q{$52il@G4pz z9Pac$fA=5Ahy(FgY!lkF+E#oq+~MsUl&#uxmKt-Ls_W(lzo4#Jg}SCZ{Ka%t6^Yk# z|MdlRdGR_&GE&QL`#XH$(yR1B`-1I1ow?S|n$~#o;Idw%cN$)ouyYMk2TYI%@i3p2 zc>nCtC$)*0OO9TkSC>R?qD5;G9{IzaW<6_(H^0rOTZ9jbkZjsEjQNiJca0_ zvcj`iAtCTpeTRhK7XM}(Pbs<*FNJAvJd`iJ`*Nf&X&OW@)esY`3 zb{OD}h7u}D+M{9{G;L6Q!jE?xAU#trXvwC`hS#jebC&RBVd)gsnLt15nb|=dVDL1i z$=#)MqNUp=Oj{ft-Gu#0Wke}fW_E={c^9WUVIM^qDx!X4u~k^@EASvFd^S*qs=|E> z+G*oaQ5|JzNDI;&UG5w&*@I_Eal*4?Nla3=XzQt&l?P6ZEK5nr#%i3zh9^@!*{}TA z_>J%+(ZSQJZYwLll87}(TH+EXYa@|!(qYtQh$n+h>E@l3 zP*&Lg)SfmE5~Gc=QklO{UEv-ttrU3V7&d5?p{binL5nm`C*zito+DMFNb~rz?uvB! zRNWM5o^jS)kxrHLP^5Vn8ox;B`EfKhev#Iq$OF^5D~f4kyrQ_XWaICy9U#WV{|OpD zb!t|=Qql7dIKviy>%~LYa9W6bPBjbblG=O47kc=7Nk3hptg7SzY_ws=Pp_!n3vm_&p-W5>eiXjeM|hOAY?(->6kSMYk!|2Vn85g~El2>vpT zrx{*VT-yj}E{usPEOZy0Q8kAX5WgSk#LY{{?ke}^X^3nr_%tOVszqqt2Ls$55PTbg zN&0c5CYhX>JI#(-g`D+|0rEku7a~dVBEj~N81ekYPTYu}p=OVn-MN3F8%de`hG%SZ z_~VZTxGhn4{0)IbYinEQ!j8zqnpP7$vytWhJp^h)AEy>y)mAp(Th`88B^5<2Cy#FI z>P~Doh@$1}Gtf=L4L=5DvvX=-Rk$7-!#ZFjA=`XnbgG4l@-WB8ps|=}YitouMR~5{ z#t?lKT6f`BwCF&!539|$j2$&*?7sW6RdQ}8{AC=Ec)SOqv}h+0I1wL=rzZ6D&GMW_ z*iDre#w=QkFSI*y*~R)%B$Y)i9S?l0h2Wc_t+o!I@n&;NbM;-x_ra==2S4rux%DE~ zl5a~iZdtiC!ahF zvQSk=q^c5f8OH-5i^*tbXD5;2p^)Fg?erO=xaT{XqaM-rBE*v+ne+Y%%4#~aM91rF zBLdfNH&85gy-Wdofg0^N8!DbWH}X7${tG>6(6Dp(@N8>aZ3oUVX=(3*t8;oEo*?-a z=qmhW>6gAbU2EVGlCWN*RSYv&Eo|G05ERz2i-iAU+6Mn$*oM!umo#YSVn-;%0bD}| zx&sgqT9lC7(b>|DVwZ;}HkgTs+kK#zIF<)#l+R+tcL(vU*khpBp%h=|IPBMcO2Og%MHJc08* zWFM+-M0Z}_yuMqWzR7N_yb$VMg3{im(N>9hQwPcy)~tv4ZnG_7I#=SS?Mu_Nfo?E# zP(nTN)xW$_wd~L!vfJU`j5}-kK(P!?St?^!TfFr-c-UtydJY&{L>h^wmJ^=zd2Hl~ zDW-N7xyYi8zDXYSNn=Ek3Q(MF#zZx&`?bJkfap;%p7?o5ff(#92R@{i z@G8KAMDIoTSO7%~Cy$AM#-1mMerldB9nxz2{&vnl8K}I9FxiPUGcfGVO7Kejn{hm7 zlw(Tf2dO6{eB2^vQRQKy>}n-4e27>?vpCNiWp9BZC@u91b(&p0dD!TZC_Fvemq7|= z)!{GWc+x1RPot3eXe_I*oyUxRjF7B?;j=hSdW{zk8O_62+dCBVsE(uZs1w0+M&Gbe zmzU3)R)jR;@vu=^aH5_xb7=bWpiwTqG4nJwwKkZ%r|Hj=M%PCI7;hPWeFUB~%3Ljv z&<=xeotk^});wpFW=y1wLEW#lnELUI(M85jYmG`oB;$C#=!Hl%_Vu#uv~8S)UCOSd zTElA0c*ZEFwnYZ1*VvS6)>=y+jc1JR5&NqSlpQE^PCIKnWc2Y^fYqo*AN?V;Y^caY zRG*UPjouW+m9N-;$2@H`2St3xxP_lPc+@B@Nynbihj5xZc+O~z@$|9|4;f_-A`00Y z6+Dd*PZ;GrCEYtaTKyRDd{K^X7}OLgEiyb@^dInKnO&SOcxOCY^uoxS?X`VpJXf^E z_~|>-_sKIw?}Q(-Sz1bA^9%3u+h$Q4sJ9{n^@v-`|zr$LBDZ zcWdN#^OAOvx=yGC9~r{yb^#pX74ZYYt<6~+n%3f;j0klVWM33&Yiz`C$>~}A9z6>5 zvG}NZu5sZkO4z1`hxY68wb{nnmZoOLWr%p^@#uKbV0NW2?!)Au7%zfLwYYTB@(zfN zDw?4a_soMFBX`yK0<{*C2Lov}22G6^7=g7K1G7+e zM)ep_eP4_p0M$}n9#E?@2#AY3h}LPblSE&uw%AD`trZ-dXbf3&X$_Y+i88I_5;xIy zAc}ybum%-%oI8Yhy3USy;=@{W`TtfL7 zBfM*6aE46c+!grCxTiOE?icvQx(IQLiv)g3tXUxNTO!NifZq~FmIXcw{$!xP%-*4h8ph}c%V(azIYJ${Ibvo z=`*8U4hCbj5hzSOS%Ji!aP_`7=V%bwZx`o&gI|oWZZ2kX8l}BPx4=1yY%zC6Ro%ne zF`gOs5N`Kv{QAGRX*&&%mo$sgO2Z+VahS8KE?P62+fu(D%6rBgf(HBgFKZz%2d71) zpdMigT{&_yuK3_pj1riB#r-`>{LYtP27rZvng+3SZj`4UFCbqT5BbbCw&#Fwr&e_9 zeXj5ATLDtD=KRd``trnRHq6AO(6&^n@s;vL-|_si=&a zW=m8}DNk%pfmmeOD^UdNAi@1YiBpS8M3%-9J=c^a^@{?j)BswdYF#-(Fce_pEozXU znzIsBJN7F_YHwc(YK+CIMAy`^q>d?&5_?>UmT&jq|2^LywIa`|%4WSHJHyEUAB%kcu`~N_hK4Sq}a*MKgJGMMRIbY+q-5P+NMg%)kEb9KHZa`u{rv2FJw2soJX<5M@+5p%6-Zc zJD__pYgRK`zGzEn(X`o<;WlKDoH_ci=o3^UVu8tFhF)5Y16XXC2xkw+%)EMLmYn13PO2d48)} z#QA7A`{u~p9}&sG36YTPN*VX@R2b)roz2(~ zIRtBVTNeU4PJfs7JvH&2S=+%qBit*X;*rA|ILwgaKyen44#BWwWK|BuzM`h%>10*|r{KUiJc^l4^m-OURx#vmKBiOy2mxIlV`}9Tn zdOndEPfk)6bLVuW=dSO>JzK(^TMRt;ni=QiL2`JU_(7m?x8V>dEY z)N@W5GEDEQ@rMaPWZbn;dN;La7dCXr(K`6qp3ikPw9%mvvF~b7&-?IO4ot~+wPfko zUVnV2!y$PNK@#SN>ox61z&o2xpdFhyrfv%pxA@&&T;RgUUMG>=>zjHG0jrmI_Q{)7 z;`Cq<56mn5q@>S{g+8dXqDioKyYu|qcp`{53AP*jGHwiNJkIEsj4=G%S`qyKqTD=S zMfIfMC~sX3vH00MkDnEIATm*)H@flrM=?LwggE%Ofi_6St643}u@x0Ed_X<0NQ$`3 zKPu~I5_xw)A`!d%FmXW+Xlz>Gejhr#lsH5Wzyg`e4;?NxKFFCU)Y30rMW@9NU+!&fn@;@hkIS>-1k7tFX@Ldl3h|vX5`rwDB=uP zw+?s2X>^!*J^}3ulgX?m%jyuBfNURg`uv@X{p|Xb;cgDeKXt>b}NSYEA zzo>*eZG4LMFu;qYJl=u_BN+y$ls-YB`#$VSOvec|ahqMk4>w@8RU@_ludN$zzT=1S zhvT_m?&BLswfG%p=XBJz=Jh~0uKBxzqL*Lbaaa)#z4=WgeeNpZgSv+6GR!>oK2!&< zgJZ9VX{=C0BZkuG>#Uc@;lN%HpQd1CBS$%RJpOQc+xR~24*V)1$hNH@eAKcPb7#9& ze8uEIx!ryf`Z(G!;_YTPH?>!{a@i*-iBpO@!_}?CAI@_{_yeN1#PDgQf=Hblh4vg- zxKqirk-EQxJC_eUc~^z|`7RKN;`1wPdH&xKpJv1<<32gOk6VRbar&l7p<{^jIW&i& zBW9jW+~V5w?9yKFabxk9afe|kd@+9Ueqtv)y&+x*<5cJhN2j^r4lJC17sSx^=(s35 zpH6?P;hLn`CC&dbOK1jb$O6SpCGDY>B=S~R0di}2o}>9!x>OjZ0! zQbEu0*6%c;~vfU-9?GDD9*^0~cJoXLtZ~bL^Om$`4y)WQk!$GPSpFhp+9GT6I z7*W;Ugd-l8;Pbm|J(sCFy6Ul4pjuYw6DfWwg?*se_S&Y7nyHJ1S65fNHHbhdfhr2T z=n0JKYOU>9mW@yJVjVs@I}`fmR4;bN9o-(o{ zqokTiO_Y)C6eVREC?cC9N{Td6goaJh6bfS_H+sEWksP(`i3YK>mZcOqzFU!Iid@^R zh$PHkyA`RWmSJdpOUGp)McTR*SwxW=x)oVQk$1WkX`#r7e%-~TlOp+UMV3(HW{BWJ zpRN{ki{;Zy2dj;N%VPyDFBG`ES>W;i96qb^1nYw7?2ukByi&VM_b$-6Swi!DxMW?BSr!ErlH@XvV zn7U{bbxz-)8=Z}jrW?Bx%0-&C+OQiKZ2*$!CB}%_3()+%j5xep1FD09+qYm5u+griW zeNW@WS;lzVxfsAoVry1SxRbw_JD>O4^1QeHJ>yP8zk$z-yrrj&TFYyZX(cg%+Ks@N z*#t&oYijX=~d5k8Oj+)Q8LxVyurP9G#q$Z$CJ7sE(%mG!PEklOJZan?I z9$C-&br~{9+-MSQR^N*MnQh0~+-=vdLhKpx^(OW82rXn0AgM-L0r;Zg@k^ zzGPe#?EY?!YRtP~H|L_bHpC9?%M7gLO2apzJ7Iq3nZ&KMU=XwYBxX~-QsFom-&4$@ z{Zuy9ci5)Fy&nX%$ANRgUFECfR$FaXA>UBiTNO9V3~}eaDuJHCp`E`9Z(@4^YCu=- zbF>7xXom{7U+{LTOpxSJwl(QiL?B47Ger55n9#o!@nNN^b6wI~D6*t?Um_7N={=sf zL^E;wLy;-glSq4tAh_1+zoNq7sPhT1u>NqdMoSifSwr~dIM5nxRIkJoScyk09$;AM0O=m|i^>tY zvV>5uQT@~M#5O`Fve<(Z*?nGHzGz!_qIRSDZ^{+?T?xS=yU%BDRQ!>Oh}M=6E!e33 zi*f~j)03dtsJQgW^TjI$B z$smR(SnWYXO=6tx`d!?RPTdn=3+4u z&o7toEWS}a*DL9KAZ<3PUyFHY8zbp7PHHRA>1LpbKGZl50-F$%6B(YLx06+ z!Q8<3a8#k=o0a=jxH~ZDxEU_d0904dt46@SOCHuu8f&rMRqgJiK)lQldUDTihgldq z8Jq}@*cX~`SaAnzroc>cTL%}+VI8V5*P+8WR#_Q0b^i)?H$G90hKm{t1npeXRxMj4 z5`|U!;hXr}f(}@WkhOh$f?iWMwN94rU-qI|Tu_$r#i~N`JVgYtE+rcOWS^zjtsy8& zOw%#ETwL4S1zQZ<-7(L{MLsU|@eH7ZS{47eJpOS*{DbzHv5z5A{|KnD7WU8dZqEVJ z1VXYk*Pgg6i(S;&CY%smGqtX&`cN)$?TT56RBluxhxNEfY`BWGTd~nuQB)%e_~mb+ z0QW&q_2}=dZ6i!`Q(b*~J1z0io=VMP-2HG*W`7vQ$Y)#et%BG-&?ro5h1?}pj%H_5 zUGb~0;Ud?c%aG%$m$#^1LLZmGzS++_TnRa@i#=F|92dTDT3nh~CG^RH+HvIwauw|A zG6cD{_I??1Tx>fSUEAb!mWUzmdv+OeT#oyF8FE~ot3;o(r~7ij4%PyDl;aBCEoI1Y zNv{t&hUtC1Tq9dDtYx44Mll?d4g%Ye& z{#_*hw#dKBiYhuDeJxosam$il-{!A5wN1_Ld&#dK^H*HSNAYpTpbL~ZR>3ve9i~=? zu#d;{M;7t?M^(H2=$jyEnqjaA36Xb$$njmO@FsD36TaxJ7jLQeauPyKMn!@0;uPDg zh#XJ#G~xZV)E=LMy=>a>WD_SX*FD_{{Fiu7v%3Jezr!X)OC)`6EPY9L(n}-hKgQC3=}vlC zB)vC!Z4#5Q_>ra{@{7bIesjrd`9}9*@r$`5R{L=G^6{(L2;Do0#y0rTO*G<{b4)D1 zuzUIV^;{jx|Dt>O_yv6!%lEh29axO~WQkwV6o^UukLX@Leo3oi`L*54$FJ$tSpGd< z9yK2hc#wUcO{n;!7#@TUahilEs1TAKBzK3#)x#-Ph<#TpL{-^^xn`JbuXcA?Ntk?s z>A+n5@z97K7Yw;;x2O-gw8=e3pfb-bg&lQlMy1upMpReX&e{dlZbElr`CK#1F;eU_ zPYk8P)7I1hYr`UkUa;df-;CRAMunJWmu|IJ<#%==ni|R7ZLfJ><8hPq;C5M5ML3!* z+gZbI(EFY*Vk055xf8l-(dE?c^S)m98PBgW%@`lWB8xqdF|kN}ElnqL+@O*C1;ivL z;jXR;JwJS*hfgrG=y5dKh(JL@t`jMXH^Mv_-{uMkNqFy}ibzW>`(7;VZ0w3iOW&W1 z`J$Uf$dlJyM0zAzLw8OreQ^)cvMcSmSo+UBNbgJCyT!wWQFcU7Bqp-wt}~WCwFl|_ zsQd0%`q84&xCv}7V_#pK;+xp9LJ|clCP_WLM=?obS}-b1TB}VG_t753Bvm)DLx-Yq zljNMO%kTmwSzGa2?xzC|xSRwRGlOsjFv;*n(P11)KVmdJ zSD%VJ{Vy>Fe9NS~0zJk1e%Tcyp1rD2Qa9wx!3U2Zjiv@E)TO zoJ-IFQ%4R*Q$)7!`39tu&3bHmFI$g_UPv}y+nDRbAc)su{AJwFaeO@wZQv_~b$nQO z(N7xxYmR<%iYflBb~|C08x{t5hD2klQ{$a9g^msbb}qw-*U9+H zxEdVb_GxryIdmpELk3Ye4g%uD1XjcTuSQNIhKpNANA0p~YiPwgWSAo}#~aLZj=N8k#zgez0|i`AuJxTi23% zju?$EKO5Rwvasuo&Qu_Jsudj*tKsKKRr?o<>tb9e8TTNVsev8=(nzgNAV~RfPr)s& z!q(w;GQS|k`{O%h(R<4+XzN&pr*rO1{AJvejTP=S{PI$Fl=K97Z{}X!bswCrapKPMKbhyT-HJ*ZMOTrz2A7zAVh{F8{EuMt?nQi(?-!B)1`xrA+NdZyA z(GQ+b@o&S?G!D-ypV?7uNsEc!e;bY#|V1{N&TpM(kV5-c`-q zg;N)emVu;h-Q^UGI|=o@kaqV|w;#hTZZRDf`cxos`W2kww)Ww~J9c>* zE^6F`>y58~!nXPyxOL!Qj1DXlCQ9+SLlTj|i*Jbwl^OTm(h7Gee#x`{`;e3WzZ`P% z1}Zepnx*FAXCV{#E?IHWV^5mpcYN&0GE#Ev3D>j{GCB6-yTZY-C%P+r)i)~K1mr#D zHjLk*a}ij58iV#WR`79Ln9sQ95cDHx<~(ClTi$W_x`aPw;0NY^alRP#8n}7%RunT% zI2({&j&qNYRya+AU=5H#&WnQ3KAQSp3KzA`wnf^2jPGxQ_}NBag=!HU^sV zj(`6Jzn7>G1AR!0W7-c7wj_=n?c(ssG%hrV!(dTl_ZCm(NMipua2nmoX`o1GHeKQf z&le?e#9AbLOecz96beQmqO`>!i&9TSPe8l|o?TU=Rg@0Dpu@-!sRPdfRKg(+?qwy! z(!GtJ(L?bKyRjJYd>W!#e9&upv`vpcqb0Q_E^3zi8RQ`Ftj`r-$ERQr4Bg95UG1$ z>VQ2LbU8G2VXUMz$1GN?hi=lIW8fCM#m7pZ&l5W(Jrf>*!LRq?Xm}pyr5=g9-0-s0 zBkjJ353M^yx{@FgpW9Q9G>G^-nEE6^qyzF)>X8N!9~!7PcZvHs@21WYAa-}ilYzKI zmJ`bM!6`2ugHsPiiS82BJyZAO2I4U$^@syVL?@^2NdWPnh59r~d<%7{3q|SFo;txr zVs>)sL@9AwnYzJA;&XB8L@{x@Ds_XC#Nw9JiDKe*U+M-YPR(_?CsH@csUz*xM~@Iy z`ER8zX_N3t>WH9vF3N_e8cf2gBWn*1$Z$CFX%%h==7s&*19J({ARWCi)J3R$U`<4- z3`|K?HMimDtZc5MqfJdb%52$492zEP?WlVt%BQ%Gz${EHY}2UoO|kQ6Ojh8~70l5^ zhB(}0WGM}yvu#m`XA@`4%-~#`EGBjq&TICVLQhf4_-`liKl_{tSA}1@;SUGv)nYNW6F>2ZD*iI= z*YMs0n)LDPN!@bTDHC%HXDsVc1l><0vPdtPGvz!-Q-kQ*MRaX;O@-qCmMeS3%@6GZ zpNxC>rV2M=cjrFi-WI%SPQ6l@Og_4ExmTmWc+t(`THjoYX}eT*AooY$Tw@pyO&t#v zM{mATHJ=xIG~f`@)=r+DmE3hp?r+GpbG^g3u2ffUZsMVPZ9GR8N5dJ3fA|uKz7B3x zD0Xc73*wR9ct7qTz~M|yIQP(hIHv4AlCb-&=_}tGN99q!^WS$O=IZKje)SRgT*vqh zlto_mNPyQ7;G0na{udZdrd_R~hLew?N1@?lw(UinIW!BbBFAy%7FQp*6 z&HA}_@vi<@v>^Y5o5BhTaz)VuJF-}UU0f=`UW`486yya(6YNEG?WQ14FOguYN+sCF zL4xJVNU%3n^mDt8#sovr1p9W;1pA@5hLyv+;u_?zQE|G+T8OEoPK-T@B-rQT7v`|V zJtkO?q)84NS}MV0!`VvWkjVP61R|N_7dAA9sotEcL>+dE` zgx$%n6sxV!OgL>E&V04MyAo3`zb~4wuNF<%Pm3n(;gVEA(Ong%Uzo6eh&_rVY;Dnm z{ez!uMH2Q9NtbvHKh0p=8(Or}(m$x{vSrkD7grB(N8nV&x}vS=CGuFIiOOE|@(z=y zEYg}@5PK9!u&wpMgPeGQpBzOJOfynpf>ld86lqO=6(rbJ-S+afM=nFR_!k2l7bMtW zNsU$mV%yhKZXF=TX#;`1Jo&`r(u(5FRQG-SW!y_o3~-$Tox@iF z95)qomS0iVxQ$JUYZLl-MRV1&;*n-QMs2-xEbe=KfTJ0rsKd)$l=VxO*48yGuHqVO z(O6ZBg?LOyS?Q|%3OaJwjE;K*a{P>=FfUcR6AMK#YkL!H^KGTPn6uR5k$P_jGusEF0Wzu%ebR)UfVD6i*L&$Im&}P>d)bvJo69{ ziq2^UXn8Pwvvp0_=p-+-OMg;qJSWNK)VMw^_GbhIedW!i+)rkiQtmJ1Fy#SKZ>)SQ);G}A@aMRgH*hocr~F&tHgrdNypgN- zcw={h$6s=%kdydr;?DN`zbqEQVy6l`?N4IB|0~>P?k0~ncXxZdh5J9`!RlDy2FbDa zo9q$umhL(IDgRcut=y~lwKoP)ykL+`tcxm%x+6W_ zO)QkA;dggA&wmfuESvi8DF+XwyqEN%Qr_Efr)7LqAorc=@i4~|QEvWRB`Vxk`;&Ms=%h+QAWOR z=AF;Sfv>7l|4imMSroh0@KpHUVwl5$hYfRm`W3^+fj={hE!=J}4^_ZL{fof68>VT4 z3nTdo_IYO8pI`OKA_}qRz{}UT&dBy&RZs79^0oP%tF|SzuX-p$nzJLuRF8X`# zFEdy8BK3y9G6#LUVqPBbpd|h(e_g=84frsmiPd+%VK4t=g8Y*?O7c^q21k5?{FFIb z{9g+EVd`0~ipZa9GQ8sO2VyX-tl_yWNm=!O6C-_P_5WI;FY-^)U;Sx|L*>=~?Iiux z|NOxJo0!m1dG-HKET78_KL#GfMhq9jKMkH__yzFw_lP&{_jUIg_yxmnfd}53`hNi4#PDa};f85< zhQA7a%rJLjJY{%1_!+~8f}b-y8~nWCd0=@Tc%%xX zFL%rGeefdlWRdmUYbJc0TMOPaN>A2LzXQL)MnCd@8~l{vtxz}JWB4HOR#AF0{9JIH z-W5o1)_0uYRef6D9lV9lwS#~W=Y|}z8UI&z^!b{d ze12ny&u$l=9}0NRuBkuk&jXQ0yyE(iwh=Awm((v>KXwKDM8JC`he-`kRq`gr81%_E4b9}AObELHIs{&>o<5hwBn(}dd%$*`2Osl+=FRwWv!1N5B#@I@~`?I zle~|pJ-~X14gY-Lzdp&o8h%FdzBK%L&UfI7+pAXN&-S2FeCdCT^q^|CpNrl-UD#fo0DgR=-~OC;xJDpue^wc0`!jV`>d*FPbv9-84=*;%{^31_ z*+2ZmF#Cst=cnPZs*UqHQa%$r-0**Zk1@O&+-Uex@N&az!Iv2RDfo87H-eur%=Ys` z!)!md?vuvnHpq`Ld>440;RnF&h93o=Zus}$3k^RHzSi)|;JXaJ0e;f(JK)z0e+V9! zN#pl9cyGh~QC24#{u1~o!-K#J4Q~ftW0-sQJ~O-rcyKf+!Tft@mmZYZJ1k`J~MnecrpSrSi(}2mG64yrKSeNqeXKUchH_k`!0mzu9s#pJ|Me7ya4(Kd;FP*8afWa8rNf zrH0x5Uy#)I+8(zg^}X`z0q2tE*Y8Z@` z=y|cdWqbN)^1Rw!Zjkh+mG=wy(}0&H{S}peJ?Wp!b2Fm84e!VH^;j_HhaW*4IKFED zzcxaryvZkkPsezKQ6$sS-%ym_aS?Mo_!Vg%=Y+9!)%W)H_Z0R-N^M1fd*hnAS z=OGuT%=USA!)%}TH2j|kfBD>0p6&G`hS^>}W|-~u^M=`89}-PcGribeHydVq-D;Ta z_4Cnqk@9S>*BNGe{mcbveAr&UYnbijY9r6~@?yhmFK0%R@YK)ta*koPm-7v?y=*tk z_VRMWY%i}d%=Ypn!)!0t8)kd?reU_1?;B=&`H5k+m&5t>SM>haUQRO1_HwRawwLn_ zv%OqunC<0BhS^@8X_)QhO2cd~R~g1e6t~v!v*0TXuLIx0kBy@E{uz9$;kUr+PEGy) z4t~Y(C*ZdYSD>yQv?7(?5In^2X5bUor2bojR~p_Ce4b&p_qVT==%GH)`I#pTv%UYs zFz08s{z)qT8MxCh=VvZ3%=wuc40C?w8N-~P`M@yeXEwhg)zA5v9Sn1R=3K*^pSi{` z=Vu-?%=wuQ4G+chZ+fNC4<2lI40spAKpPZ@I2#xD|l2?e(C=QhL7?;`7`jtQT`@x zjlM%;lt0Ow&x-SB+&?@eTBMEpYo~ubem?Cl{^&TL|6c3!s0N=`Hu~JK$mi>teLl9$ z=j)G)=G2tgKRpOL_ISnp#R