From 0542f3aa764cc597df5b4487664f87b5a00ddc2a Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Tue, 18 Feb 2025 20:51:16 -0500 Subject: [PATCH 1/7] Some notes from the rules? --- scripts/node_specific/scripts/test_dash.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index 8b1035f..dcfb1bf 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -34,6 +34,26 @@ def hil(): def test_bspd(hil): # Begin the test # hil.start_test(test_bspd.__name__) +""" +0v: Brake released +5v: Fully pressed + +test_bspd (brake signal plausibility detection) + +BSE (Brake System Encoder) +- T.4.3.4 + - When an analogue signal is used, the BSE sensors will be considered to have failed when they + achieve an open circuit or short circuit condition which generates a signal outside of the + normal operating range, for example <0.5 V or >4.5 V. + +APPS (Accelerator Pedal Position Sensor) +- T.4.2.4: + - Implausibility is defined as a deviation of more than 10% Pedal Travel between the sensors or + other failure as defined in this Section T.4.2. +- T.4.2.5: + - If an Implausibility occurs between the values of the APPSs and persists for more than 100 + msec, the power to the (IC) Electronic Throttle / (EV) Motor(s) must be immediately stopped completely. +""" # Outputs brk1 = hil.aout("Dashboard", "BRK1_RAW") From 1191e1e2b13ada2707cef510f85c76bd007e150a Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Tue, 18 Feb 2025 20:51:25 -0500 Subject: [PATCH 2/7] Cleaning all the tests --- scripts/node_specific/scripts/test_dash.py | 124 ++++++++++----------- 1 file changed, 61 insertions(+), 63 deletions(-) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index dcfb1bf..bd9d735 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -31,9 +31,6 @@ def hil(): # ---------------------------------------------------------------------------- # BRK_SWEEP_DELAY = 0.1 -def test_bspd(hil): - # Begin the test - # hil.start_test(test_bspd.__name__) """ 0v: Brake released 5v: Fully pressed @@ -55,46 +52,49 @@ def test_bspd(hil): msec, the power to the (IC) Electronic Throttle / (EV) Motor(s) must be immediately stopped completely. """ - # Outputs - brk1 = hil.aout("Dashboard", "BRK1_RAW") - brk2 = hil.aout("Dashboard", "BRK2_RAW") - # Inputs +def test_bspd(hil): + # HIL outputs (hil writes) + brk1 = hil.aout("Dashboard", "BRK1_RAW") + brk2 = hil.aout("Dashboard", "BRK2_RAW") + + # HIL inputs (hil reads) brk_fail_tap = hil.mcu_pin("Dashboard", "BRK_FAIL_TAP") brk_stat_tap = hil.mcu_pin("Dashboard", "BRK_STAT_TAP") - # Brake threshold check + # Brakes 1 and 2 are at rest brk1.state = BRK_1_REST_V brk2.state = BRK_2_REST_V - # hil.check(brk_stat_tap.state == 0, "Brake stat starts low") - check.equal(brk_stat_tap.state, 0, "Brake stat starts low") + time.sleep(0.1) + check.equal(brk_stat_tap.state, 0, f"Brakes 1 ({BRK_1_REST_V}) and 2 ({BRK_2_REST_V}) -> rests") + # Brake 1 trips brk1.state = BRK_1_THRESH_V time.sleep(0.1) - # hil.check(brk_stat_tap.state == 1, "Brake stat goes high at brk 1 thresh") - check.equal(brk_stat_tap.state, 1, "Brake stat goes high at brk 1 thresh") + check.equal(brk_stat_tap.state, 1, f"Brake 1 ({BRK_1_THRESH_V}) -> trips") + # Brake 1 resets -> rest brk1.state = BRK_1_REST_V - # hil.check(brk_stat_tap.state == 0, "Brake stat starts low") - check.equal(brk_stat_tap.state, 0, "Brake stat starts low") + time.sleep(0.1) + check.equal(brk_stat_tap.state, 0, f"Brake 1 ({BRK_1_REST_V}) -> rests") + # Brake 2 trips brk2.state = BRK_2_THRESH_V time.sleep(0.1) - # hil.check(brk_stat_tap.state == 1, "Brake stat goes high at brk 2 thresh") - check.equal(brk_stat_tap.state, 1, "Brake stat goes high at brk 2 thresh") + check.equal(brk_stat_tap.state, 1, f"Brake 2 ({BRK_2_THRESH_V}) -> trips") + # Brake 1 high -> still tripped brk1.state = BRK_1_THRESH_V - # hil.check(brk_stat_tap.state == 1, "Brake stat stays high for both brakes") - check.equal(brk_stat_tap.state, 1, "Brake stat stays high for both brakes") - + time.sleep(0.1) + check.equal(brk_stat_tap.state, 1, f"Brakes (1 -> {BRK_1_REST_V}) stay tripped") - # Brake threshold scan + # Reset both brakes brk1.state = BRK_MIN_OUT_V brk2.state = BRK_MIN_OUT_V time.sleep(0.1) - # hil.check(brk_stat_tap.state == 0, "Brake Stat Starts Low Brk 1") - check.equal(brk_stat_tap.state, 0, "Brake Stat Starts Low Brk 1") + check.equal(brk_stat_tap.state, 0, f"Brakes 1 ({BRK_MIN_OUT_V}) and 2 ({BRK_MIN_OUT_V}) -> rests") + # Brake 1 trips at the correct voltage start = BRK_MIN_OUT_V stop = BRK_MAX_OUT_V step = 0.1 @@ -103,97 +103,95 @@ def test_bspd(hil): BRK_SWEEP_DELAY, brk_stat_tap, is_falling=False) print(f"Brake 1 braking threshold: {thresh}") - # hil.check_within(thresh, BRK_1_THRESH_V, 0.2, "Brake 1 trip voltage") - # hil.check(brk_stat_tap.state == 1, "Brake Stat Tripped for Brk 1") check.almost_equal( thresh, BRK_1_THRESH_V, abs=0.2, rel=0.0, - msg="Brake 1 trip voltage" + msg="Brake 1 trips at correct voltage" ) - check.equal(brk_stat_tap.state, 1, "Brake Stat Tripped for Brk 1") + check.equal(brk_stat_tap.state, 1, "Brake 1 tripped") + # Reset both brakes brk1.state = BRK_MIN_OUT_V brk2.state = BRK_MIN_OUT_V - hil.check(brk_stat_tap.state == 0, "Brake Stat Starts Low Brk 2") + time.sleep(0.1) + hil.check(brk_stat_tap.state == 0, f"Brakes 1 ({BRK_MIN_OUT_V}) and 2 ({BRK_MIN_OUT_V}) -> rests") + + # Brake 2 trips at the correct voltage thresh = utils.measure_trip_thresh(brk2, start, stop, step, BRK_SWEEP_DELAY, brk_stat_tap, is_falling=False) print(f"Brake 2 braking threshold: {thresh}") - # hil.check_within(thresh, BRK_2_THRESH_V, 0.2, "Brake 2 trip voltage") - # hil.check(brk_stat_tap.state == 1, "Brake Stat Tripped for Brk 2") check.almost_equal( thresh, BRK_2_THRESH_V, abs=0.2, rel=0.0, - msg="Brake 2 trip voltage" + msg="Brake 2 trips at correct voltage" ) - check.equal(brk_stat_tap.state, 1, "Brake Stat Tripped for Brk 2") + check.equal(brk_stat_tap.state, 1, "Brake 2 tripped") - # Brake Fail scan + + # Brakes at rest brk1.state = BRK_1_REST_V brk2.state = BRK_2_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 1 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 1 Starts 0") + check.equal(brk_fail_tap.state, 0, f"Brakes 1 ({BRK_1_REST_V}) and 2 ({BRK_2_REST_V}) -> no fail") - brk1.state = 0.0 # Force 0 + # Brake 1 forced to 0V (short to GND) + brk1.state = 0.0 time.sleep(0.1) - # hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 1 Short GND") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 1 Short GND") + check.equal(brk_fail_tap.state, 1, "Brake 1 short to GND -> fail") + # Reset brake 1 brk1.state = BRK_1_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 2 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 2 Starts 0") + check.equal(brk_fail_tap.state, 0, "Brake 1 reset -> no fail") - brk2.state = 0.0 # Force 0 + # Brake 2 forced to 0V (short to GND) + brk2.state = 0.0 time.sleep(0.1) - hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 2 Short GND") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 2 Short GND") + check.equal(brk_fail_tap.state, 1, "Brake 2 short to GND -> fail") + # Reset brake 2 brk2.state = BRK_2_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 3 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 3 Starts 0") + check.equal(brk_fail_tap.state, 0, "Brake 2 reset -> no fail") - brk1.state = 5.0 # Short VCC + # Brake 1 forced to 5V (short to VCC) + brk1.state = 5.0 time.sleep(0.1) - # hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 1 Short VCC") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 1 Short VCC") + check.equal(brk_fail_tap.state, 1, "Brake 1 short to VCC -> fail") + # Reset brake 1 brk1.state = BRK_1_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 4 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 4 Starts 0") + check.equal(brk_fail_tap.state, 0, "Brake 1 reset -> no fail") - brk2.state = 5.0 # Short VCC + # Brake 2 forced to 5V (short to VCC) + brk2.state = 5.0 time.sleep(0.1) - # hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 2 Short VCC") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 2 Short VCC") + check.equal(brk_fail_tap.state, 1, "Brake 2 short to VCC -> fail") + # Reset brake 2 brk2.state = BRK_2_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 5 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 5 Starts 0") + check.equal(brk_fail_tap.state, 0, "Brake 2 reset -> no fail") + # Brake 1 Hi-Z brk1.hiZ() time.sleep(0.1) - # hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 1 Hi-Z") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 1 Hi-Z") + check.equal(brk_fail_tap.state, 1, "Brake 1 Hi-Z -> fail") + # Reset brake 1 brk1.state = BRK_1_REST_V time.sleep(0.1) - # hil.check(brk_fail_tap.state == 0, "Brake Fail Check 6 Starts 0") - check.equal(brk_fail_tap.state, 0, "Brake Fail Check 6 Starts 0") + check.equal(brk_fail_tap.state, 0, "Brake 1 reset -> no fail") + # Brake 2 Hi-Z brk2.hiZ() time.sleep(0.1) - # hil.check(brk_fail_tap.state == 1, "Brake Fail Brk 2 Hi-Z") - check.equal(brk_fail_tap.state, 1, "Brake Fail Brk 2 Hi-Z") + check.equal(brk_fail_tap.state, 1, "Brake 2 Hi-Z -> fail") + # Reset brake 2 brk2.state = BRK_2_REST_V - - # End the test - # hil.end_test() # ---------------------------------------------------------------------------- # From c04b82c42d1c534640b05bd69678330bccb931ff Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Tue, 18 Feb 2025 21:35:41 -0500 Subject: [PATCH 3/7] High key confused about what I am supposed to be doing --- scripts/node_specific/scripts/test_dash.py | 33 ++++++++++++++++++++-- 1 file changed, 31 insertions(+), 2 deletions(-) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index bd9d735..bb624c6 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -32,7 +32,7 @@ def hil(): BRK_SWEEP_DELAY = 0.1 """ -0v: Brake released +0v: Released 5v: Fully pressed test_bspd (brake signal plausibility detection) @@ -49,7 +49,14 @@ def hil(): other failure as defined in this Section T.4.2. - T.4.2.5: - If an Implausibility occurs between the values of the APPSs and persists for more than 100 - msec, the power to the (IC) Electronic Throttle / (EV) Motor(s) must be immediately stopped completely. + msec, the power to the (IC) Electronic Throttle / (EV) Motor(s) must be immediately stopped + completely. +- T.4.2.10: + - When an analogue signal is used, the APPS will be considered to have failed when they achieve + an open circuit or short circuit condition which generates a signal outside of the normal + operating range, for example <0.5 V or >4.5 V. + + """ @@ -196,3 +203,25 @@ def test_bspd(hil): # TODO: add throttle checks + +# ---------------------------------------------------------------------------- # +def test_throttle(hil): + # HIL outputs (hil writes) + thrtl1 = hil.aout("Dashboard", "THRTL1_RAW") + thrtl2 = hil.aout("Dashboard", "THRTL2_RAW") + + # HIL inputs (hil reads) + # TODO: CAN?????????? + + + # Test set 1: throttles at rest + # Test set 2: throttle 1 trips + # Test set 3: throttle 2 trips + # Test set 4: throttle 1 and 2 trip + # Test set 5: throttle 1 and 2 trip at the correct voltage + # Test set 6: throttle 1 and 2 at rest + + + # Test throttle high and brakes high +# ---------------------------------------------------------------------------- # + From 9a26340fe40a4bbebb09dd09785b0161fd141938 Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Wed, 19 Feb 2025 21:28:01 -0500 Subject: [PATCH 4/7] Throttle uses DACs for 2025 --- configurations/config_system_hil_attached.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/configurations/config_system_hil_attached.json b/configurations/config_system_hil_attached.json index a32921f..c28c119 100644 --- a/configurations/config_system_hil_attached.json +++ b/configurations/config_system_hil_attached.json @@ -15,8 +15,8 @@ {"board":"Dashboard", "harness_connections":[ {"dut":{"connector":"J1","pin":9}, "hil":{"device":"FrontTester", "port":"DAC1"}}, {"dut":{"connector":"J1","pin":10}, "hil":{"device":"FrontTester", "port":"DAC2"}}, - {"dut":{"connector":"J1","pin":11}, "hil":{"device":"FrontTester", "port":"POT1"}}, - {"dut":{"connector":"J1","pin":12}, "hil":{"device":"FrontTester", "port":"POT2"}} + {"dut":{"connector":"J1","pin":11}, "hil":{"device":"FrontTester", "port":"DAC1", "_": "can't do breaks and throttle at once, not enough DACs"}}, + {"dut":{"connector":"J1","pin":12}, "hil":{"device":"FrontTester", "port":"DAC2"}} ]} ], "hil_devices":[ From 7606e519f8766c90f0b68cfdd220d6dbefc26b9b Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Wed, 19 Feb 2025 21:28:23 -0500 Subject: [PATCH 5/7] Throttle tests (write AO voltage, read MCU pin check if equal) --- scripts/node_specific/scripts/test_dash.py | 70 ++++++++++------------ 1 file changed, 30 insertions(+), 40 deletions(-) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index bb624c6..3ab4b19 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -5,6 +5,7 @@ from hil.hil import HIL import hil.utils as utils import time +import random from scripts.common.constants.rules_constants import * from scripts.common.constants.vehicle_constants import * @@ -31,34 +32,6 @@ def hil(): # ---------------------------------------------------------------------------- # BRK_SWEEP_DELAY = 0.1 -""" -0v: Released -5v: Fully pressed - -test_bspd (brake signal plausibility detection) - -BSE (Brake System Encoder) -- T.4.3.4 - - When an analogue signal is used, the BSE sensors will be considered to have failed when they - achieve an open circuit or short circuit condition which generates a signal outside of the - normal operating range, for example <0.5 V or >4.5 V. - -APPS (Accelerator Pedal Position Sensor) -- T.4.2.4: - - Implausibility is defined as a deviation of more than 10% Pedal Travel between the sensors or - other failure as defined in this Section T.4.2. -- T.4.2.5: - - If an Implausibility occurs between the values of the APPSs and persists for more than 100 - msec, the power to the (IC) Electronic Throttle / (EV) Motor(s) must be immediately stopped - completely. -- T.4.2.10: - - When an analogue signal is used, the APPS will be considered to have failed when they achieve - an open circuit or short circuit condition which generates a signal outside of the normal - operating range, for example <0.5 V or >4.5 V. - - -""" - def test_bspd(hil): # HIL outputs (hil writes) @@ -205,23 +178,40 @@ def test_bspd(hil): # TODO: add throttle checks # ---------------------------------------------------------------------------- # +THROTTLE_VARIANCE = 0.1 + + def test_throttle(hil): # HIL outputs (hil writes) thrtl1 = hil.aout("Dashboard", "THRTL1_RAW") thrtl2 = hil.aout("Dashboard", "THRTL2_RAW") # HIL inputs (hil reads) - # TODO: CAN?????????? - - - # Test set 1: throttles at rest - # Test set 2: throttle 1 trips - # Test set 3: throttle 2 trips - # Test set 4: throttle 1 and 2 trip - # Test set 5: throttle 1 and 2 trip at the correct voltage - # Test set 6: throttle 1 and 2 at rest - - - # Test throttle high and brakes high + thrtl1_flt = hil.mcu_pin("Dashboard", "THRTL1_FLT") + thrtl2_flt = hil.mcu_pin("Dashboard", "THRTL2_FLT") + + # 0-5V throttle sweep with 0.2 + throttle_values = [x / 10.0 for x in range(0, 52, 2)] + random.shuffle(throttle_values) + + # Sweep throttle 1 + for v in throttle_values: + thrtl1.state = v + time.sleep(0.1) + check.almost_equal( + thrtl1_flt.state, v, + abs=THROTTLE_VARIANCE, rel=0.0, + msg=f"Throttle 1: {v}V" + ) + + # Sweep throttle 2 + for v in throttle_values: + thrtl2.state = v + time.sleep(0.1) + check.almost_equal( + thrtl2_flt.state, v, + abs=THROTTLE_VARIANCE, rel=0.0, + msg=f"Throttle 2: {v}V" + ) # ---------------------------------------------------------------------------- # From c671aeaa0d61f1e2e4eac507ddac9fb364c83994 Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Sat, 22 Feb 2025 10:23:55 -0500 Subject: [PATCH 6/7] parameterize for test_throttle --- scripts/node_specific/scripts/test_dash.py | 42 ++++++++++------------ 1 file changed, 18 insertions(+), 24 deletions(-) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index 3ab4b19..eb36dd4 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -175,13 +175,12 @@ def test_bspd(hil): # ---------------------------------------------------------------------------- # -# TODO: add throttle checks - # ---------------------------------------------------------------------------- # THROTTLE_VARIANCE = 0.1 - -def test_throttle(hil): +# 0-5V throttle sweep with 0.2 step +@pytest.mark.parametrize("voltage", [x / 10.0 for x in range(0, 52, 2)]) +def test_throttle(hil, voltage): # HIL outputs (hil writes) thrtl1 = hil.aout("Dashboard", "THRTL1_RAW") thrtl2 = hil.aout("Dashboard", "THRTL2_RAW") @@ -190,28 +189,23 @@ def test_throttle(hil): thrtl1_flt = hil.mcu_pin("Dashboard", "THRTL1_FLT") thrtl2_flt = hil.mcu_pin("Dashboard", "THRTL2_FLT") - # 0-5V throttle sweep with 0.2 throttle_values = [x / 10.0 for x in range(0, 52, 2)] random.shuffle(throttle_values) - # Sweep throttle 1 - for v in throttle_values: - thrtl1.state = v - time.sleep(0.1) - check.almost_equal( - thrtl1_flt.state, v, - abs=THROTTLE_VARIANCE, rel=0.0, - msg=f"Throttle 1: {v}V" - ) - - # Sweep throttle 2 - for v in throttle_values: - thrtl2.state = v - time.sleep(0.1) - check.almost_equal( - thrtl2_flt.state, v, - abs=THROTTLE_VARIANCE, rel=0.0, - msg=f"Throttle 2: {v}V" - ) + thrtl1.state = voltage + time.sleep(0.1) + check.almost_equal( + thrtl1_flt.state, voltage, + abs=THROTTLE_VARIANCE, rel=0.0, + msg=f"Throttle 1: {voltage}V" + ) + + thrtl2.state = voltage + time.sleep(0.1) + check.almost_equal( + thrtl2_flt.state, voltage, + abs=THROTTLE_VARIANCE, rel=0.0, + msg=f"Throttle 2: {voltage}V" + ) # ---------------------------------------------------------------------------- # From 66fdb1d25511d0f6418ea40e51bddeb475182d16 Mon Sep 17 00:00:00 2001 From: Millan Kumar Date: Sat, 22 Feb 2025 15:21:12 -0500 Subject: [PATCH 7/7] Deleting unused code --- scripts/node_specific/scripts/test_dash.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/scripts/node_specific/scripts/test_dash.py b/scripts/node_specific/scripts/test_dash.py index eb36dd4..69183e0 100644 --- a/scripts/node_specific/scripts/test_dash.py +++ b/scripts/node_specific/scripts/test_dash.py @@ -5,7 +5,6 @@ from hil.hil import HIL import hil.utils as utils import time -import random from scripts.common.constants.rules_constants import * from scripts.common.constants.vehicle_constants import * @@ -189,9 +188,6 @@ def test_throttle(hil, voltage): thrtl1_flt = hil.mcu_pin("Dashboard", "THRTL1_FLT") thrtl2_flt = hil.mcu_pin("Dashboard", "THRTL2_FLT") - throttle_values = [x / 10.0 for x in range(0, 52, 2)] - random.shuffle(throttle_values) - thrtl1.state = voltage time.sleep(0.1) check.almost_equal(