From 1bc6f2fa7db49ebd3d29063e2a93234488b88db0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 May 2022 15:58:08 -0700 Subject: [PATCH 01/32] increase cruiseMismatch threshold (#24428) --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 6dff3bb2e1..498218ab46 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -343,7 +343,7 @@ class Controls: # Check for mismatch between openpilot and car's PCM cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 - if self.cruise_mismatch_counter > int(3. / DT_CTRL): + if self.cruise_mismatch_counter > int(6. / DT_CTRL): self.events.add(EventName.cruiseMismatch) # Check for FCW From 1f9907122a9bda9279d73f698addaa0e22796059 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 13:06:13 +0200 Subject: [PATCH 02/32] make debayering consistent at edges (#24437) --- selfdrive/camerad/cameras/real_debayer.cl | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 6452e44ebb..8cb0aeb166 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -104,38 +104,38 @@ __kernel void debayer10(const __global uchar * in, half pv = val_from_10(in, x_global, y_global, black_level); cached[localOffset] = pv; - // don't care - if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { - return; - } - // cache padding int localColOffset = -1; int globalColOffset = -1; // cache padding - if (x_local < 1) { + if (x_global >= 1 && x_local < 1) { localColOffset = x_local; globalColOffset = -1; cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-1, y_global, black_level); - } else if (x_local >= get_local_size(0) - 1) { + } else if (x_global < RGB_WIDTH - 1 && x_local >= get_local_size(0) - 1) { localColOffset = x_local + 2; globalColOffset = 1; cached[localOffset + 1] = val_from_10(in, x_global+1, y_global, black_level); } - if (y_local < 1) { + if (y_global >= 1 && y_local < 1) { cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-1, black_level); if (localColOffset != -1) { cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global-1, black_level); } - } else if (y_local >= get_local_size(1) - 1) { + } else if (y_global < RGB_HEIGHT - 1 && y_local >= get_local_size(1) - 1) { cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+1, black_level); if (localColOffset != -1) { cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global+1, black_level); } } + // don't care + if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { + return; + } + // sync barrier(CLK_LOCAL_MEM_FENCE); From 9da9b773eba344e9e59aeaa8a2c0235aadbd1f44 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 16:05:37 +0200 Subject: [PATCH 03/32] test for comparing debayer results to ref commit (#24420) * test for comparing debayering results to ref commit * fix run on device * print more useful diff * limit to diff output * remove env var * ref * more useful diff * use real local work size * remove pyopencl install * update ref * include rgb_to_yuv * fix diff * get kernel build out of loop Co-authored-by: Comma Device --- .../process_replay/debayer_replay_ref_commit | 1 + selfdrive/test/process_replay/test_debayer.py | 205 ++++++++++++++++++ 2 files changed, 206 insertions(+) create mode 100644 selfdrive/test/process_replay/debayer_replay_ref_commit create mode 100755 selfdrive/test/process_replay/test_debayer.py diff --git a/selfdrive/test/process_replay/debayer_replay_ref_commit b/selfdrive/test/process_replay/debayer_replay_ref_commit new file mode 100644 index 0000000000..44fe33001c --- /dev/null +++ b/selfdrive/test/process_replay/debayer_replay_ref_commit @@ -0,0 +1 @@ +1f9907122a9bda9279d73f698addaa0e22796059 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py new file mode 100755 index 0000000000..17fa9afd63 --- /dev/null +++ b/selfdrive/test/process_replay/test_debayer.py @@ -0,0 +1,205 @@ +#!/usr/bin/env python3 +import os +import sys +import bz2 +import numpy as np + +import pyopencl as cl # install with `PYOPENCL_CL_PRETEND_VERSION=2.0 pip install pyopencl` + +from selfdrive.hardware import PC, TICI +from common.basedir import BASEDIR +from selfdrive.test.openpilotci import BASE_URL, get_url +from selfdrive.version import get_commit +from tools.lib.logreader import LogReader +from tools.lib.filereader import FileReader + +TEST_ROUTE = "8345e3b82948d454|2022-05-04--13-45-33" +SEGMENT = 0 + +FRAME_WIDTH = 1928 +FRAME_HEIGHT = 1208 +FRAME_STRIDE = 2896 + +UV_WIDTH = FRAME_WIDTH // 2 +UV_HEIGHT = FRAME_HEIGHT // 2 +UV_SIZE = UV_WIDTH * UV_HEIGHT + +def get_frame_fn(ref_commit, test_route, tici=True): + return f"{test_route}_debayer{'_tici' if tici else ''}_{ref_commit}.bz2" + +def bzip_frames(frames): + data = bytes() + for y, u, v in frames: + data += y.tobytes() + data += u.tobytes() + data += v.tobytes() + return bz2.compress(data) + +def unbzip_frames(url): + with FileReader(url) as f: + dat = f.read() + + data = bz2.decompress(dat) + + res = [] + for y_start in range(0, len(data), FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2): + u_start = y_start + FRAME_WIDTH * FRAME_HEIGHT + v_start = u_start + UV_SIZE + + y = np.frombuffer(data[y_start: u_start], dtype=np.uint8).reshape((FRAME_HEIGHT, FRAME_WIDTH)) + u = np.frombuffer(data[u_start: v_start], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) + v = np.frombuffer(data[v_start: v_start + UV_SIZE], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) + + res.append((y, u, v)) + + return res + +def init_kernels(): + ctx = cl.create_some_context() + + with open(os.path.join(BASEDIR, 'selfdrive/camerad/cameras/real_debayer.cl')) as f: + build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ + f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DCAM_NUM=0' + if PC: + build_args += ' -DHALF_AS_FLOAT=1' + debayer_prg = cl.Program(ctx, f.read()).build(options=build_args) + + with open(os.path.join(BASEDIR, 'selfdrive/camerad/transforms/rgb_to_yuv.cl')) as f: + build_args = f' -cl-fast-relaxed-math -cl-denorms-are-zero -DWIDTH={FRAME_WIDTH} -DHEIGHT={FRAME_HEIGHT}' + \ + f' -DUV_WIDTH={UV_WIDTH} -DUV_HEIGHT={UV_HEIGHT} -DRGB_STRIDE={FRAME_WIDTH*3}' + \ + f' -DRGB_SIZE={FRAME_WIDTH*FRAME_HEIGHT}' + rgb_to_yuv_prg = cl.Program(ctx, f.read()).build(options=build_args) + + return ctx, debayer_prg, rgb_to_yuv_prg + +def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): + q = cl.CommandQueue(ctx) + + rgb_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT * 3, dtype=np.uint8) + yuv_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2, dtype=np.uint8) + + cam_g = cl.Buffer(ctx, cl.mem_flags.READ_ONLY | cl.mem_flags.COPY_HOST_PTR, hostbuf=data) + rgb_wg = cl.Buffer(ctx, cl.mem_flags.WRITE_ONLY, FRAME_WIDTH * FRAME_HEIGHT * 3) + yuv_g = cl.Buffer(ctx, cl.mem_flags.WRITE_ONLY, FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2) + + local_worksize = (16, 16) if TICI else (8, 8) + local_mem = cl.LocalMemory(648 if TICI else 400) + ev1 = debayer_prg.debayer10(q, (FRAME_WIDTH, FRAME_HEIGHT), local_worksize, cam_g, rgb_wg, local_mem, np.float32(42)) + cl.enqueue_copy(q, rgb_buff, rgb_wg, wait_for=[ev1]).wait() + cl.enqueue_barrier(q) + + rgb_rg = cl.Buffer(ctx, cl.mem_flags.READ_ONLY | cl.mem_flags.COPY_HOST_PTR, hostbuf=rgb_buff) + cl.enqueue_barrier(q) + + ev3 = rgb_to_yuv_prg.rgb_to_yuv(q, (FRAME_WIDTH // 4, FRAME_HEIGHT // 4), None, rgb_rg, yuv_g) + cl.enqueue_barrier(q) + + cl.enqueue_copy(q, yuv_buff, yuv_g, wait_for=[ev3]).wait() + cl.enqueue_barrier(q) + + y = yuv_buff[:FRAME_WIDTH*FRAME_HEIGHT].reshape((FRAME_HEIGHT, FRAME_WIDTH)) + u = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT:FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE].reshape((UV_HEIGHT, UV_WIDTH)) + v = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE:].reshape((UV_HEIGHT, UV_WIDTH)) + + return y, u, v + +def debayer_replay(lr): + ctx, debayer_prg, rgb_to_yuv_prg = init_kernels() + + frames = [] + for m in lr: + if m.which() == 'roadCameraState': + cs = m.roadCameraState + if cs.image: + data = np.frombuffer(cs.image, dtype=np.uint8) + img = debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data) + + frames.append(img) + + return frames + +if __name__ == "__main__": + update = "--update" in sys.argv + replay_dir = os.path.dirname(os.path.abspath(__file__)) + ref_commit_fn = os.path.join(replay_dir, "debayer_replay_ref_commit") + + # load logs + lr = list(LogReader(get_url(TEST_ROUTE, SEGMENT))) + + # run replay + frames = debayer_replay(lr) + + # get diff + failed = False + diff = '' + yuv_i = ['y', 'u', 'v'] + if not update: + with open(ref_commit_fn) as f: + ref_commit = f.read().strip() + frame_fn = get_frame_fn(ref_commit, TEST_ROUTE, tici=TICI) + + try: + cmp_frames = unbzip_frames(BASE_URL + frame_fn) + + if len(frames) != len(cmp_frames): + failed = True + diff += 'amount of frames not equal\n' + + for i, (frame, cmp_frame) in enumerate(zip(frames, cmp_frames)): + for j in range(3): + fr = frame[j] + cmp_f = cmp_frame[j] + if fr.shape != cmp_f.shape: + failed = True + diff += f'frame shapes not equal for ({i}, {yuv_i[j]})\n' + diff += f'{ref_commit}: {cmp_f.shape}\n' + diff += f'HEAD: {fr.shape}\n' + elif not np.array_equal(fr, cmp_f): + failed = True + if np.allclose(fr, cmp_f, atol=1): + diff += f'frames not equal for ({i}, {yuv_i[j]}), but are all close\n' + else: + diff += f'frames not equal for ({i}, {yuv_i[j]})\n' + + frame_diff = np.abs(np.subtract(fr, cmp_f)) + diff_len = len(np.nonzero(frame_diff)[0]) + if diff_len > 1000: + diff += f'different at a large amount of pixels ({diff_len})\n' + else: + diff += 'different at (frame, yuv, pixel, ref, HEAD):\n' + for k in zip(*np.nonzero(frame_diff)): + diff += f'{i}, {yuv_i[j]}, {k}, {cmp_f[k]}, {fr[k]}\n' + + if failed: + print(diff) + with open("debayer_diff.txt", "w") as f: + f.write(diff) + except Exception as e: + print(str(e)) + failed = True + + # upload new refs + if update or failed: + from selfdrive.test.openpilotci import upload_file + + print("Uploading new refs") + + frames_bzip = bzip_frames(frames) + + new_commit = get_commit() + frame_fn = os.path.join(replay_dir, get_frame_fn(new_commit, TEST_ROUTE, tici=TICI)) + with open(frame_fn, "wb") as f2: + f2.write(frames_bzip) + + try: + upload_file(frame_fn, os.path.basename(frame_fn)) + except Exception as e: + print("failed to upload", e) + + if update: + with open(ref_commit_fn, 'w') as f: + f.write(str(new_commit)) + + print("\nNew ref commit: ", new_commit) + + sys.exit(int(failed)) From d8c0cf5d55890cc46aff51f1fe1345e339863000 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 17:38:39 +0200 Subject: [PATCH 04/32] debayering: typedef half as float to run on pc (#24439) * debayering: typedef half as float to run on pc * add casts to literals * define existing half type * remove test code --- selfdrive/camerad/cameras/real_debayer.cl | 31 +++++++++++++---------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 8cb0aeb166..50a7846213 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -1,11 +1,14 @@ +#ifdef HALF_AS_FLOAT +#define half float +#define half3 float3 +#else #pragma OPENCL EXTENSION cl_khr_fp16 : enable +#endif -const __constant half3 color_correction[3] = { - // post wb CCM - (half3)(1.82717181, -0.31231438, 0.07307673), - (half3)(-0.5743977, 1.36858544, -0.53183455), - (half3)(-0.25277411, -0.05627105, 1.45875782), -}; +// post wb CCM +const __constant half3 color_correction_0 = (half3)(1.82717181, -0.31231438, 0.07307673); +const __constant half3 color_correction_1 = (half3)(-0.5743977, 1.36858544, -0.53183455); +const __constant half3 color_correction_2 = (half3)(-0.25277411, -0.05627105, 1.45875782); // tone mapping params const half cpk = 0.75; @@ -25,15 +28,15 @@ half mf(half x, half cp) { } half3 color_correct(half3 rgb) { - half3 ret = (0,0,0); + half3 ret = (half3)(0.0, 0.0, 0.0); half cpx = 0.01; - ret += (half)rgb.x * color_correction[0]; - ret += (half)rgb.y * color_correction[1]; - ret += (half)rgb.z * color_correction[2]; + ret += (half)rgb.x * color_correction_0; + ret += (half)rgb.y * color_correction_1; + ret += (half)rgb.z * color_correction_2; ret.x = mf(ret.x, cpx); ret.y = mf(ret.y, cpx); ret.z = mf(ret.z, cpx); - ret = clamp(0.0h, 255.0h, ret*255.0h); + ret = clamp(0.0, 255.0, ret*255.0); return ret; } @@ -46,7 +49,7 @@ inline half val_from_10(const uchar * source, int gx, int gy, half black_level) half pv = (half)((major + minor)/4); // normalize - pv = max(0.0h, pv - black_level); + pv = max((half)0.0, pv - black_level); pv /= (1024.0f - black_level); // correct vignetting @@ -67,7 +70,7 @@ inline half val_from_10(const uchar * source, int gx, int gy, half black_level) pv = s * pv; } - pv = clamp(0.0h, 1.0h, pv); + pv = clamp((half)0.0, (half)1.0, pv); return pv; } @@ -197,7 +200,7 @@ __kernel void debayer10(const __global uchar * in, } } - rgb = clamp(0.0h, 1.0h, rgb); + rgb = clamp(0.0, 1.0, rgb); rgb = color_correct(rgb); out[out_idx + 0] = (uchar)(rgb.z); From 6efb42613b79d53dbe4f802e1d6357953c6253d1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 5 May 2022 10:21:46 -0700 Subject: [PATCH 05/32] Toyota: Add missing FW versions for RAV4 Hybrid 2022 (#24430) --- selfdrive/car/toyota/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2d9948b9ab..0fa83d56cc 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1337,6 +1337,7 @@ FW_VERSIONS = { b'\x01F15264283100\x00\x00\x00\x00', b'\x01F15264286200\x00\x00\x00\x00', b'\x01F15264286100\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', @@ -1347,6 +1348,7 @@ FW_VERSIONS = { b'\x01896634A62000\x00\x00\x00\x00', b'\x01896634A08000\x00\x00\x00\x00', b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A02001\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R01100\x00\x00\x00\x00', From da74085d561198af0d06422df1758222edcc6d64 Mon Sep 17 00:00:00 2001 From: Brandon Zimmerman Date: Thu, 5 May 2022 13:20:53 -0500 Subject: [PATCH 06/32] Toyota: add missing FW versions for 2022 Lexus ES 300h (#24431) * Add 2022 Lexus ES Hybrid f/w - LEXUS_ESH_TSS2 2022 Lexus ES Hybrid * change carinfo Co-authored-by: Shane Smiskol --- docs/CARS.md | 2 +- selfdrive/car/toyota/values.py | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 14664d480c..8a78afe5cb 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -47,7 +47,7 @@ How We Rate The Cars |Kia|Niro Electric 2019-22|All|||||| |Kia|Telluride 2020|SCC + LKAS|||||| |Lexus|ES 2019-21|All|||||| -|Lexus|ES Hybrid 2019-21|All|||||| +|Lexus|ES Hybrid 2019-22|All|||||| |Lexus|NX 2020|All|||||| |Lexus|RX 2020-22|All|||||| |Lexus|RX Hybrid 2020-21|All|||||| diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0fa83d56cc..0ad2a419cf 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -151,7 +151,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-21"), - CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-21"), + CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22"), CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"), CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19", footnotes=[Footnote.DSU]), CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19", footnotes=[Footnote.DSU]), @@ -1450,22 +1450,26 @@ FW_VERSIONS = { b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + b'\x01896633T38000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152633423\x00\x00\x00\x00\x00\x00', b'F152633680\x00\x00\x00\x00\x00\x00', b'F152633681\x00\x00\x00\x00\x00\x00', + b'F152633F50\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B33252\x00\x00\x00\x00\x00\x00', b'8965B33590\x00\x00\x00\x00\x00\x00', b'8965B33690\x00\x00\x00\x00\x00\x00', + b'8965B33721\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', b'\x018821F3301200\x00\x00\x00\x00', b'\x018821F3301300\x00\x00\x00\x00', b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', @@ -1474,6 +1478,7 @@ FW_VERSIONS = { b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', ], }, CAR.LEXUS_ESH: { From 4beb764aed74cfda7b873d87bb82f3a5117df3e8 Mon Sep 17 00:00:00 2001 From: Left5566 Date: Fri, 6 May 2022 02:59:15 +0800 Subject: [PATCH 07/32] Toyota: add missing Prius TSS2 engine FW (#24438) Prius 2021 DongleID/route c3834a2fe82b632b|2022-05-05--19-39-41 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0ad2a419cf..e3cb0b091b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1765,6 +1765,7 @@ FW_VERSIONS = { CAR.PRIUS_TSS2: { (Ecu.engine, 0x700, None): [ b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', From 66fbce638f1a6a2bc9c08c4a17d5efe47fb91651 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 5 May 2022 19:13:06 -0700 Subject: [PATCH 08/32] uploader: compress rlogs (#24447) --- selfdrive/loggerd/uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index d13026c4b3..50557fffaa 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -261,7 +261,7 @@ def uploader_fn(exit_event): key, fn = d # qlogs and bootlogs need to be compressed before uploading - if key.endswith('qlog') or (key.startswith('boot/') and not key.endswith('.bz2')): + if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): key += ".bz2" success = uploader.upload(key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) From b16e612102558c6b94a0c1b7127596dab6f5b2d0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 5 May 2022 19:42:18 -0700 Subject: [PATCH 09/32] remove eon debug scripts --- scripts/clwaste | Bin 155368 -> 0 bytes scripts/restart_modem.sh | 2 - scripts/throttling.sh | 16 ----- scripts/waste | Bin 8608 -> 0 bytes selfdrive/debug/compare_fingerprints.py | 19 ----- .../debug/internal/core_voltage_sweep.py | 23 ------ .../debug/internal/sensor_test_bootloop.py | 67 ------------------ 7 files changed, 127 deletions(-) delete mode 100755 scripts/clwaste delete mode 100755 scripts/restart_modem.sh delete mode 100755 scripts/throttling.sh delete mode 100755 scripts/waste delete mode 100755 selfdrive/debug/compare_fingerprints.py delete mode 100755 selfdrive/debug/internal/core_voltage_sweep.py delete mode 100755 selfdrive/debug/internal/sensor_test_bootloop.py diff --git a/scripts/clwaste b/scripts/clwaste deleted file mode 100755 index 51770f0e372cbd3bc08867bc329c756aca237973..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 155368 zcmc$H34B!5_5Yh0mPy#j24TtOl0>Q`5J(WpBq2%wF_O4ct&<@H639jpHW3K~+hEW# zfJ@bu04|vkm0D5aQUcf(3vEfU=+7=DL2F{rf@~Qi&i{Mvy>I5un>Psb*Z*(wxq0uN zbI-Zwo_p@O%e(iz)mgJ{F&Yet`ZFnSDHPi|n?o!D(RjB}+$oAhNmb1FKT3&I`T*J+ z!6LBQYqMajUdx#!$dmus!B*#$}iAwR}W9AUKLgv{-0zGlwku$D$&6z zXU>PjBGeHfsP-By!qS`O7MI;rQe3vEuyVq9Le(Pt4q+KW6~eU$zeXrTs7IjR zUW9AdoubUd^+kkD2){sh51|yHAHq!t^vh@e6~&2b4Z^Pw)+5mG9)zDGyhRcG9zY-& zHXyu?unJ)@g7y~#zyO4I5SAlY5cVOwim(RZA%rCeLl8zIL?G-$n1L`5;WdQk5t0#B zBJ4)^EkYf_3kXjj#35`)xF6vSgeHU$2+tv8A>4-WG=ln@hntrX>!tfl>Hb#SPm$s=xbH8;)1`auZ5jZ12on*63s&yN z{TKx8Z;}9H;2JFMhvPa|+|y+$LNwjr_alS_2=^kyBGAvqFUmr3EywkCaZf&C5kfJ- zjRKY{uG&kI08GR61_^l`?(aaTkYGjP{!Ved57)^O{wKIELs*OOuz(lfdW*Opi>no( z0U-*3eyIqLBkZ6Ee!oQMh44d!6$teE8A2mMUy9&Yjqnt^QxpfT&mfc_j6+z8FdZQQ zAspdmggFR%5PpE5{vK3sE^#%XcA8b;rF14(>qgP9sNmngSYwesUNro{29D_jd??`K zU*z$Fg5Uz+F%lnYEA)#+;i)}ne{Z4idT@u4`$%p2;2@swx<-!47YU9*E3{iRNi%)c>EdxPk_VH<1;CM{I&q;Zx!-i6ne`O`ur2}(c_;4 z!Svwdi}m1P0rY&A$hU(UFMd1uMJW{JZJ5OcX%+Af`{?rz3ZUnb0D8!QJZjq(tl8y& z$hYnQhn^A0mjduVF49*}Cx&0B&|6#pJwF}*o(soBcKe~|MAZ5%1f1%k$}j%B0dqC+A*wBEzx(fp!}3XtzAq$mCC`UOw8PBh@B04F_kYufc5kzVVsq5{Zo zfp~iIe<0*+CdZ54a?sQ7xPU)RP9MJ${GxOP;L|%myZ#dV^y-)Td_8$41!(Wn2XOsp z{mk8flb-Jp?MU^{;{)iqM5MQD;RPDYt4(nTcg%xJ-$8>*{2JJQjI9Q7 z`}tVYj!pru$N$j)?JFC62Ez^;1Rud(xjlfKcOyNO_vwv1WwRhS7NA}h1@JS+1K2Z7 z8ujFVN#t8C1|DjCjS65_A2I#(Q}P}_LGXjwv)^L@?D-49|HP9#U7bk3IDj7V1Hh+X z@JISN*ufbz3qIw5Q+sdKwD(^G(8J?`&k13-p9y=&1V3H?`uzdyZL3*d&%FcK z`E}q=?I=1}WGMLG7yv#i0G~-h&d)@J%oBWW1Dxq?KL z`#mZ6)IG;h@q$lBfOhnDfO>g8K>A*oNRpm&zUKV;YBd_sc>0A<&$ou1UR)38up zE^WKG25_pEF*HfUPaTJ>5$UIiaqROPt!xzVYi{R&YhVZTy9xE8XFq=k;J05Be4ZEf zY++m!z(!2$}^@BP8ta6(6L_&8kj z?5#Qg|0UoFN#aZGhK|6HwgF;Og@Q!#Sr~fBGr&q2GNKba6_M1XI%H09{#q5@%ySRX}gq()} zAHrG;H(0fPKM$ZcBG;4u6Tx5WS33bGy$${`&(JLNHa3Fmty=iuj_WyoLIC@mhV;be z#9p2*PqeRL0rYcIfOfr691X?laNurmw9|}J61^l5mIbfQwPo<=I?(G$YWtp>XtSVOuN-~xdm(0tlEMHJ*D@F9y z!s^WO(o$R5ygQZ@E-B0|n@@@66js}c%QDN$stcD_vv^6Nt*Y?0!qVI4E-Wk{P-bPJ zt-3H{$^7|+mEIIH3oFYCOFU@7;g-ts(!3QFg&w%b|L)@IqTKQ&l?8;!DqBnv+*wv? ztB^CwEv)8T(<>Kvlg%l#>fALQE@MT3k?=J*^5!5Y1XzSXPZ(<`?5x#sX0)k;C1U z#ggDioKs?}o?l*B>M1-cEawPzTp3c7p}oqHIk5ca6tWad21YLkylUn`3Kk;UTZ+qy ztBQaTV$Pm6$5ytWP@_>zRIWSDR49ViqhNKLt-_-#A)Jo|hzK(cCJk(6LD`b3>Jn>J zk*%_D9+{5y-rVZsu~ut!QDyluYe`|*g6bk`VP$1`WzNh3VDs*podk5j^5wR<#Y>YY zX;rbcpu|>HWvxc#TZJ z~A*a&vrG-3`s`2xS%jRW4ZKafL-d#S~7TQV!NX?a3os=q< z5JG?=a3P^;upej5F0ZnZA1E!K2Qir5(SDZ~qxdYcps?EN(Y>{zx>CRkpk(WkvclyR zX!nKllnT^8+Mcz5wSQjvq;Xs#w6?-PvZp{DRfVd)Qi~xDhzh4AtDwtaGQJ!oAjRnv z3FetJ!D=n%3W2p%6;@X3=_P9pQFDn!>g+sg-dJl^?gVSj%-nI-5>~9L@m0%g6-W&` zr8-U;FKFfm)_E4xO(v0BJ-(oP37OXH-12c1ORBTbM63&zFSk|{R#ugl*-DD5S6G*h z!qN(q z5i+4ImRH&qup;E;f$WM5*jGi|ZQMK0mZP>jv@%;sAs3#THF*Wd<27fl1YgyO(#|Vk zj8Nw4!phR(GSCs@GIWl-UCb?9P+aEmK&Z`>`6WxLiiFixO@MnVUchXU>$+-UWg#qY zDJp-A_JTQ5&TWeEeFmjw$e&$Ei`Dhru^<%MQekOo!q#)c|I@yT^5);r6V!H2*~ zs+N=%l6xtrSRoNH(-9>q;if}Q7Z%~+K$a=VQRVhfYm-GG3e zdtP}Z_8`o~1_ZR9e7j|Z&|8V9=I-#U|!Ggld%;c=O ztkLFW6Lm@!by9MIlnV3>)mifd`-!3>PMudc-?pTr+RD;;D5s6(l`Xi7T1>4duULYC zLt)Omg~Vqj(kCU${c+O7LO!JNj#Z$=*}2vUyfe;Ph$gxe4#!g*;8NJAfjTHSqb!tl z0xaX+*=fs5OW3%jGAVf(jbE&VRRy++LaI^y+>^(O+sy({JTBVp7+Hf|8s<+oI(0l}pO<(BP^tTF*ec zTUI=;x+o7#J8KR#5nsav3{6VSI%`hSxOr@J%|>um)~SJJ!aSNJluW$4l6o)Xj*3Bj z7Vt?!mg?+;1Zfqv%Bn&P;o%>0a>!SiLG z1dU>|XBCf6PEN_n%Az*MrAp84mX?6lN>9X z%4uyNX)LVJx`<5?1KZsM)j2UEl$;Z*13m{?Qbt_}Z|N9{mRGFEo;7zYb21pK5{?6N zW|EDms?NdCE-MQIJ?>?A^90`4`jf}1PD0KD^<$ljnGExIR*#O=Mv^j@rqw>JQm2kl zpEjH!NAcV$q+p$|*C3NdSMB9B{HIX&uBxCZ zYxe9k4EoEKU|71GX0ByeWU!TZ`n2pE%wyD{Oab^~PD($_IA)^`vf-SlXG4$3YJ-ip zt@CXqRfTLqO}Z9xpy`teF$ISv{Kq>!DxJ^hxGNK#5_D*#c{Zw#8M(Ok45&mhMwwfk zGLO1nP0x$jplVyJ=bbC%k~9wWhGiT!%)+?K(+8?f`7-J(iPstHV$_zSv0QHrvZ0e& zhgEWgB_+cJVUUIyS>d#tz)nbQ*E*e_HD^v%_H4`;)91`d{}Fcus(~h|GfM4I-*M`nJSBSv1%LjZHB4^i%H-AatrcNzIUiRpIR$xqP+K` zhROyYs*9EjG#1LF6${cOnT+)osNF~FT(@$a=3ZT$dKyyFM6Z2hWAziWiK{Xa<^@&7 zqji?%l#u6#|DU-Oj)tu?Tupzb^;$V{|EBhBm@%?ZdMZt>vdiwwWhxfEIceDIb!2k2 zr_dRxYrBZ=AE%2JAv_0)3ZFt*!_HK-1ng+%%xL;8KBiYAaa*iRI#sru`dPxay$2xA0JieG6Tj$xTZ8WW+MUfOMpP#5x z7kEl|^c=YI+!X2{lg3q+FF~QobIO<9K0kRODTnBp?F*Bpy!kk27N(eG1(<)6>U{fE zz%GBBegz$)JdXD|RX&X7?G~Mseg`=X9c1zB+-cT{7*o)yuR4{!0#`4(XYK4zmPE~7 z_;%iz=?)LzI7;y-gLLaZCQeQgV`ATj4q{-8hY;nJE3&S9icSOZ+;U}Bc1EUnIHMTY zACK|pHUyF5v|qprqkHd(74=@_qH<8_IbNk!ul`t-4{=sgd13Ux$iSrFx${(93Z9vhkm<1hQ_4?h!m& zqa7ObD;R(WcA$F@&(G*LOz<#?2jJ>{?Pv{r`K>&CyaqmYI){(dz&ivyRRe!Mo2R#E z;P=nq@aYws)ro0eugfA0JZ3G2tNZ2+h`tRu)OvkdrvY{=!<(h_ z*b3_T9hBhd9;l*p8+m;aAF&mNVTy96pCAhlBkjQEz_zxvMbrO841m7sZGbH%a5?pSN4H8^*X^g5-f{QMV!FNgU z*%JRf5?pRa%@X_$Dg8kSo-4tRNbox)_{S3bE(zW$!S9ja9THq@@nzVP68wHCeYXS` zTh2JPx7YsjrSxVAK39Sdmf#B{_%I1xB*CL4c(DYJm*9&e_*e;EA;D86_+klek>Io^ zO8rfj;44%ht~nBXr3Al6fo|!c*hBu3?i##ypgr0c zbu22{^j9@7+%e#`a~z9*g7|(Z{!hf)rFc8y#zBl1OaCv#W2N|)h-XOguMwXs#lJy( ztrS0p_;x9N0rCA({5!AS}DF1@$FLlLB#h<@rMy_m*Q&?H->ui{|Vx;Qv6ZGGo<+Ah|iVc zn-E_s#h*lcyA*#0@%>W#mx#AZ@$HBk!@T*whGKE5*M=JVT0qjrd$C{te=5rT96-w@dL0i0_x;-yz;E#f_QBf0#G_ zK8VLk@nFO=r1(I@=SuORh_996;fQaS;*p5&m*S%lZ(Q?Z|h-!0mIUs{ntnb?N=n1)C@#hDF4vyMsd8z{*Eaf! z$`_;ZLHWpD$X1$7)?-&=D+5(tTA5;^uSlkgJ)*6sI{zk`>HKx@zm$!C-E(y|-m2!O zmD?6`MRNa1<)g}-9LwZh_dRkqU!~lytNCf=-WGdBayO`aRJkkTnA~@LkKCKCQtowX zept`|ZS7tY|hCL#Yelj3B3HfS>}!|lqEN%nVwX_MJ`4)M<7rMm2Aap7f5Em2BD*R~KPkN6Oe z?K-p%fHpr?u@il@hPG{}lGk9gxYCuibJ|U#lXvV;S}4EYLGO*VKi=bZ8ys%%EgGsc zZATidT;V2V%NfYhX&RRNC1j{GTAIG>tGJ>Jy%w93)<+hFD@|)jra0g7q(P=N&_PUe zs=XDs@{Q`H{3^zvDc94!_*(=%ALU|WP2|I64TWA% zmP{^dKFJDwcbOuRPng1z2fV+24s;BCul}aPWO1!G*36mFr)ExRhSGE!@~$`3N1hlI zmAt|5SR~oY48!`!g*Wy|D7mh00@)6p-{f`lm23&|YP6G9Q>b$a^6FW6D{S}{$GN++ z9OvUKF4(r6+Rg`xax!66y2~7+v?TOW-U#Zk)+P2+j1AjGqclPIepCg{IAL3cmpX%A{gw2Ig+$!PJa#-*x5jnr0KK|vv^9&D9m98ep zmo8hU{-bs1n)~|FtvCAThv!ay`Qf3NkDQmQ?^&>SvXfh&Z?ai!J?0y)j_*#iW8ym& ze2w5s`jy+6O=@QaNK@3u+XijOvj~1l)nx;GpWPfYNg2 zcFe<98XY~gn2SR{`P2{P2;UsX{oOQ_f%HbW&BH$X%de}Cep9vZ-EYi2nMY5%e))}g z)zN2d8k*3aX-6jrx}KF84oXYu%z&E>p)=3ip6*Z#v7;da^JPBsCCKp(WJbLQo>L*s z>qtX&v>q}!AX72Pq?iwNLZ_=lm<)-xLFNw;w)RmLzigs@AT)97Xk~E`>a`PTLQoHn1}j5@(i0B_pCHfGqe-yHh3rD5OZ&3h;@~+xDM$OWBw3nMVf4sneg#32P5GJ6RBUL zv7(|_Tu90 zFy}<@KLZ*UU?%9>#q1{vb`%QwDA0#FUqu=Pd2oKi!7r4JBRxC~N=gXYx(znG&KOo7 zU-LkBtYWUG^(aakj!6a=MsajLx&r z6_s_WX;@bcd}f4c_@Q>Ds|YHq^IezwsgQid?p~{$+JQR%^2?Q*7NT6{zDmn#qq(aH z{X$1yCE08kehBTe-fTj+L$OaanY-$GQyU9$V*Kb#46~#LhbgI1rl78Eu!|@qvMU<= z4nijLBN*oxENM}Ll_tC%!&S6!Vk-Ic+ycdZ9`xitKYRRv?mFl);aBOd{l>6E!D}Aq zPB0*DFxDp+f)7nK^y)G}mTgA!A=1fl&^-a!scddzWLFz}KEZod-U6LuK{wN&qfEzz z1sM+LjQOb|V{m6L9u^j3U=l{vYNH+SJo&kHIGbvWdquIDcZQ(7~Exp z5B?K;Ey+h?wW3(11^1UV4%tcm9p!5^ML1VO&i?_Q8u%OKV5TCzx z4LJ3G7QpYpedEC4^-E$EM^Uii8i9IPhOtAtaoC~h7c)0U8HRVYqb{BtXs+MR_zYuw zUIZPb+ina$l!tU%7>?RdxN|FT9RowzTp75!OE8E zffg5=Kh~t#8w!jq?K^_(VUTkh?#brfLY|GacXfY+wn1}pb*$9}pWvZ=4z#tLwhw3- zzed1z7+bdQFtiwmAMo1|C!Vh}o_BVuytct#HJa}7#M8ms5x2}?h8@zFB&s+1t>=}z z4@4iH8}rbWhtljFScjO7 zG#yxzxD$4uwsSN3`5>Kn5`4N(nogauHTB;zpAU4>gd&aHUfI}_=0lLby4(HKF0@}Q z{xHp_fG+|59Uc5Efu9HbTRQj>niqloe&8!~@;@h-Q6o-Tip{4F2jJZ`i$r`bB?3#sQ%eH%|K<# z1@zgUJgKC#0#5UP>ZjUGBb;O}_zr^W9O|zF>qDpymko8@igLAM91=5cihY(y(`X9o zCj7PoWLv|XZw`UIn!L7!_pIf0U_P$eT1*(?6TNo44{?%n8|&pTrlc@^@91aWq14QY=|2g2k8*x- z9%D855Fgw%9M=k*SsDJQyUO4~d;JyGbZAU)WO!1hi*$GpxS*RqR0)#oh{7C-B3g6-Ou1td3ODsLr>c4DE6Ku=W+@?1yr+R;9bp$G-6vc#^z7 zdQ?fFI&NK%?xM94%GbPRxP5qUz>v2?&AR~kS`qH!dA}y-4Ol1eEN`UoUZ7-Pe)vZBN)DG2If&#_^w3{DtX^R_Ir%J?X6g6jUY+WCbMC&_>bMN=g(IkI%(!>(sW|oN4s8Es7Vtv z$Un_eZJNRUX&%<58RDPjCz><~A^vHe(xeH}N%N#8O?J3HpIw?X2|8)8zs*;NI%%*s z&L>T0n15ccAdS{u#!SSRANKO#D_hmY#;I5D2{r~;4YH9U%SY-NoOj}pOSE_gI( zc;KDQes;TDQ{DufG|P1I88eQ{Ivx4oU6+3Kc39voz(1>zBj|srjp1G8e&v~`BWp<# zmvt0msne0Qe=^610soi|UM=f@0A<}N=z9adNrzt5MbBBT3$2aM61qAI{8Kvg{Y9OA z1^h2`@P`HdbKo(D_p6IBXd~1H{sH`}I{2N!cK-^zQwM)IgVX;J_z?6}TKP{1{BMB| z)xnnt{CmI;2EOB^`yDRK=cwQBj5A>GPf%AY=3E_vFdoC4zXAOv-J4@9Y11)&90a{~ z#-%&VG*-tm#Hj{z*S7E6c^zL^Tok9Y(=pC&#kCcA41x`){Aul#(y8$xHfJ(Bk0D(v z#s)NA=!i>a`H=pn_Ei?Aze;Nfk-=E)rqG;WA=Du$XV4+Ga|%3)(V z8YgyQoIt+CT)eb9VST!*@%l7JXKg=wBi3siag#6}Gql*oVr^E88>0J*aqbKyWiE|j z2|h?krZHJY^c4FoD6?m*i}8G+Bk&2p)B23o9(S^}b3;oE@P7b)VINBx{O$OKLoH3KO~GA;8s8;$#EY|iQtb#2DllOX})PPCb8z=Mrzai4*?NX+C(_Hob=;o3mIQ^KorkQ+q3 z5YLWr23HW~A#JrZ#~JS2LUl9Ft9!#cuw!W+vJG*PgXLKeWT$y@OwlC!1mx3(IPs_@ z9yfV;#0Z+!%piN4X{7U8N{f3+yPVSA;7!~1w!}Y9@PB`jeKgS^PBe>%=6WxUO{Osk znlqE^Lx=`(qIrO5;=D9%P42vWl%s8BMpFZDo-!Rb^D<$sW*~aRiGDWGM|tTDp!d)m z5HvYA+s~W<4dO(TPBbIDG;8*VJnJ)>NJk#}9fE%6&GyfT9&w^iBKim~{kFGwp4%|z zYpoSDp=tJyhz4<@SwS=*UYZy|!|O}XV9xgk(6nZnnTP03$wgiI3asJNC(R2LxT}WcwzfgPz*}Bf31I`_@YrT2TdAoe zc*jdyBb(8WG#ZtOb3n`HkVa*EYu{1H3lYcsahDluNz@OS(WdL*x6OY{u@5&ZO=h#= z+7Eojo^;nfTw^Ro`(vQ_C;A^Z@^P;o<#2xiIWf15037l-gQ!0Ptn=US57=KpJ_YsZ zT#Pv-;Yr4hF2$#hngv?)7tminds|#zd&b` z;^TNfIt8?8nTp+N8r~IyHF_8NMVuwV8sc#0P~b?X?oSn0L+u^i2I!Ugnd6Y@t<&zO z&ShGfT7i3Vh?3HFybtOM^X?tg_CuVnjPkU#BdrJec-nUmc(x%<{O=loGW|`e!`FCQ zy=@TY&!6(O*(Rj#xY=v7Ymi1>lZn~o&Qs^mE3q~}^XSzF61)1fa9)#$7uEo1zWpZg zT9)ow30=`zpW4@@7rXPC?yG=~!gY0Y24y83eQM-7YJyHw9en^C>4x~9!#%A6p|4P?Q5965*&2i6u<9>=ikK|)xdCc~o^8Tlmw>181y-K;qz{il>k&S<`5*XT@s7Gb%=x2_#i{pX_ic0;Hefu57Fa{pYbqo6K){L#l|il_MV=>(6j z5YkXid~Yk1{HV69&7*z!AV0skvEF{E{-gNZ?kA+a@e_OWwTG^!Wtp)2HvL8r*jcM0Yw?Z}>WW%#O&s@G0J|;g|dE*Q4 zwv*f#him1|AM49ITW9SJ<2D}~Z^n9*6Lv<=z4EbcOzV&t#2<45KmI?^@E_+G{j0Bsl1V@~QvAFH9)S$7x?T9uBT>$IZH z7r-8GrxqfjB{3-PTgTec22hcSfwJhLX;x4fM?`(Cew9J2qo+&Vpckv|)H7WzJpal|lIo;<(uwcx)Nyj7jArhM@1S&gf8Ana!2)s7d7FJ(8pPOg}@I;NWg-hHGp{6M;w=VS`s zr|ikcp|jtC_FWQOSdnG(E!A|){8I)5ghPr2HuhTj3$NHn#!x-j#5^)=?LzGNm>%}CS z9k6Y+ckiM5zuHMOjQK6mS^SNHGc_$9!<2fQrn<;Zcl>*^()-2dH&e5UKkL1#Wthq=I~ z=-@Z}i{obkpQMo!GW(6;^yVAt^ZQBQLC^1dVI9+iK(@uojX4s{F}QsMbv0k5AL~zZ zQ|LSz`SeDe5Knf_0_#F_FWaovUdhgwO~P(TCR*$GGOo9S>^A}Osj}huD)kc{dnnc! zuS^x^3P_fouSJ{J*!o+LF_5kA0gi0_H@LolK>mU1PqwiypvTuyE;={Y8D}iLu)qZS z?}c{Ydw%YJAZuE|Nc$O6FK7G+OVj#DOVe4gPxw6MbKT@W(02DBYzOYNsdplL%;Mvw zpFcz8_}sMRna|*B{)M%yFR|32E=K-=6O`@E3fpP-wX0ZNLw zpCt`zpW{1B*N4^u)@G@-h0`gbOsOsnY$`^(_pwq-X*ndvE@Qv{yR^)XEd2NDh*ngXd@6a>(_8>nq zS1!589Wi*4OKRQ$O?^uIGW1&sVrJm6jOnBYeIP^aG^o@BPsPixJJYfLj!TAw( zKNHUY6IS&bkzk1LSF~_pYQjF{ju~_Y1T^VbQ=hTQvMGMb;9N?-5c|z3J^8_eB+!Vo zv#=NbF~f-Dy=yp4w85OX7i9=^euT{Byz#)>J-&ahU^)~tiEW=-eHD1DTap6Z>>5UaK_Ou~_^6caze zE09gx3>xL55PX=fjIkMve%If$E4Z~2FojFOucdLp%>1D zn4IL-NO!1j>{&OxvOQSY?Oxs6LF0(lID`E~ypMvl(F2ity76qI0 z6g%cmZ2xdVjAHME-^oT_KzsJ+%t&Wn#YOW`qFIQx{jDiDF~MLyw0h9`t^)Xs@xYN! zrSmoELulML%z6J;=<9Iqg!V14Jq7Sb1gAX(#lW>9&rFmz5n<1Pd-nu^hcaM9z1wYa zxUq-1{Q%Wvg!4OtvPG2}XElaI1u2VTaXzAZQKrL+vmQ3s??vp1CEM$`-r~9ldl|lB zWp|W#Hl&#NnAR+w4ZVrHhh@^UpQ9O+71Tquy>q{mnu>&P09A zz!)tXXEaRgj0V}y&%jr;H?j}*tid&f`KLfO@;YdUwnjsn06L-%6Lu<|t@!wy9fEeT zL`!xagmL8zK`-0+e%OTUPd5vCn?%p-TF{bT4J7wE(1fCn48m5A9fdk$fum;!yRc3~Hb?bT1Kdc!$)6G|AAOJouv-D6ddJ3qs+>?Y>e-W#a?4P_h&v6&m9w~&;2d@2hLt3o>k(kSL+eUN51=0u-j&PLBR zmjJ(n=_btiw-Z#}Q0D-oDMDGbeTV8FvZF1I6D9@YBa@S!>GkVL-@FKZbP>+J1ouqa zTx;le2y=NmrCE!6EAFxO@BxipCyx1D;(z4?q48WTSRM{WS`q;euw_P3p7R02bHsk>BQ_TgD%Mb6Tdjfbv~` zt;LaG=-YK2&Yk4Lw^CbE$H8bHryOxO$3J8%#>cGPxSphP;!MS!bS z*?)AwuYiWuNt(?{ULDT0nGIp=><;G6_NhV2sSKfpeL`laGrT93|IxdEsrt)J#&LnAvMM`z#m9vHPJ z7i*>s;QKt@zahqbiF8I{J+F_%V;C!L$NM;Fte7p06~p24KE+s(Xo>DP$~WGe9u9uc3h2e;tVmf;||zyIP5OL5PIm-q3gS{ zVS9Xh9F8$f7<3Wg#QOJ^B@d|mPy|~WBwf{@{u)I;G!J=FKjhZwhthzn8ya3;E$W!g zbS#I>2b)3!L*xeNTOK%2kT+Fe8XHS%?HsxR{I-#@67w?1%Ls^+!Kv#7SF6%am#TAe6Iocb}w6n29n`n0y!_;GJ9Rjv0zhmP8Kg*4jsc^}pGEEnt=b5^VC#_GrNJW!RCM?IQq#&+_K`_nYnEly10^ z@(|X>wwl5g1>=1Cv!6VK_fw2;z6@MD>WMvHMf~?2tj|csnq1Sjrjdz1hFz$1Gw}W{ z)JHPFzXO&p!=T@f0E?Dk(C=RW!*j3XX0+1> z(NA3inOM1km9!XkkG>Q5NQ06_^BuZ>aHx_-dpp^ExRMs3-sAjrsCqwINu#kll`R49 zun0o==sgxeC}Tf@$Kf0op4}cq8{=icIU2lUFJ|4%_F~9HGLYV}pL@t^)YDA7SB}O~ z)DD!4nmMzOhWtotCarrK?9-rEocC&KN1S|#!JrIH#ad|fK#UDAm;N=@l&U<>r$f37 zcz#4O@Mm@*UE2`vSvdo3I2&zwI@h^<@kn}Db(p&$Ncy0~7{Q`Ve={?u}H^)B#{0cq%DUN>(`1Kn6Gl5cjnkM8guLOH(#ojrOJp#!41A6Kd~mL7eS zmrqbvKKzx;C(u5t>BIxJ>ZQe63+h~^4bpk;jq{33hMS2V?LHb}%52Uex;Z`WYP? z$CyoP7jm0E_b+PGA7eMcrg3po6&vly@h_~LwHP<HYq`!$NBwmc*M>-o>#?EeL$EfLjWu_y;T<&(SYK~881Rm)0f(Xntbe%% z^+b7GgL7V|pfBR_A#Aelx(vsoH)c9EOqk|){D)bNC!i1VXXyLkm%^MK*Bc#Q-ehu| zn5a0uo@#J}_EEOfV0{z*_>CtaL)~cXNr~m}_iINU5ixk~`naY0_t1?S&mneToZbMP z9$8I$k7nL}^Lxe}hhb-hUqbmHM2Y>VRyG zu4?+@EWa>k6Rz?+nbxtX|BJ=D=&Iht-dNOCDDslmcFkY-z9*jbmq?4})ya=W*9=8n zFgoh9iy$-BY1w+OCysS;ypJt70k(oYFdM=C zzO&%}GVF`$kL~Zna}}}++TZ7({e3s9`}>Sye_v?VHmpZAf`<0@HK_ah@ZPNl!I$M24eGRJ-9^WzDsQn zm`^cZpMthf7mGb#n7`GajB7Awjafc`e01{X;I|cX74ng^{=FIgoorI>dp`V}+8%%I zpso#5+vzx<^jr+kc4(hfBl;S(-H=^ppbQOYH_E=)(c^GWeMp07Gw#pO7oxrc$@z{( z&SE-me2F&o64L)S+SCi+8>mga2%OrcE}~6!9I*8K|7ufvp}$MDskeatZ?>te;QxQw zrdA_=y*8DGItkRKCILrnsui@_Hl^3UQ2U|&={WXb$bD0P);_%Ng1n4=g*{KG!$I7TYTN!Ac)4vq=k14f z`OK&Be385A_E}z+Y-R zyS7}qKiXyH{Sn)T@G_5AZZVYDcTupq!hE&;eZWlp7Piar#Whd)=c?oD(2)j_j1@V7vG3?G@ry+3hNIpJJwY< zVx9LC_TAE%j?SCX!6U=*)znO+pN92Y#l8*C$=fpxcE?ROI~s483|w#E`Zz{G=2pl> zbNh4G<2g9iwDjioN1$_cZcphCBaSiY#+W1h?d`p&%wf){C~wcoSua4^#tT`AQJ15@kcy;Pz$9d?B)*KX^CDN`rWMB>!iZzEC ztT{L#$5yfCkdOXu1j>&yxZst6^@~ibUrclG^%}1Z8n3_E;k;=w@V$ZWaL}I2>$PpX5)H{ zH=w2G<3(6kDTYlfN}lE@#kx*4Y>W10EyNx}zP9ryTiZzxYdg)5i^`jhIS#F-)4bqQ z@WL~-joq-lV`~T4X^#-St42K!@)7XZA2X!rUQ1K)Bumr68>cx+u#QCeVI65Ets^Di z+4!T#V;OkQz zJ7Dv1vF7SG?r7l8G(7!7vCcePop-hsDE2oYFXeL$bR+vMTK|j!%>Q}1;-o#k^iF%K zCwl%Gvret6Fy~#M31@W`?tBgRyspAfSK-dv5vRIp6m``g)zv!SSiNr`USw0ezPPUo zb$$c=l0C9C8+m>=gNEzKcmEqbV?T>`i_71xP}@ldjn`E^qKzbg4{IaWO=IswL>_rm zKjt-7?AI{c4Yd9UUs8*7MMg@abXhRIL;ba&9kX

$AF0$A8gSe_=53Y^hl1-J8YG z#U^1dj2GDg@(eimu~lwzTc^EO>4~-Qb<;iCfT4 zsV~L*k}j)VQhUrsyM(Q?Hi`F#FZzS<1ynDzKk*;ne**SV4Lvejy-rDE^)h&%sJl?- zhe*=~A4YQ)Y9mJwXK94a4JIYsBF64pHW4DGvJ-3$Bvu#O*&y^SA&cMOuFKls?>KOkN6Pn7OYjS*e7Sa)B7Z?;kU?Zlqn z;_DRGqv4iKWUoap8XTS2cShfKxB>CR0m1bPuQNFop?&D>T}nln>cN}N4WM508n8c? z%DY$ewNC?2&oXYomF%YmII{EK;kx=^#jz1^((Ml!KE!zj@Y}I|G#kNvz|i7C``3P} zh4e%FYSs^gzeVVQFHM0Drg!AeMW6pB+RR%B$M9VF{KM(4J;;yF8x2OCn$gxjy39Eo zoq;9aYK2TRUNWy-A>Jb&-n9??8_quBJ1&M(bZ(90*p0CO$$;=!@fb>S^jDC5n`6vB9GzhUDd-*bTXw}JNBkqxqWE1sFz!ZF4|o1$j~!3G1~H=nur zZnQO*F|>Ya@8MlR=rb0gYzg?LPXgN8UZYZ(fHnu)veysY`b@SVsDAu_e)UGs(tb7c zoq4cJjC(?z(J1#+?6#;XJdVu-RG^D9U z+pj}9f+eCoEJXVcrnc`iIO0XWRrDf#FUoh1s`|Z^o5AD4f_Jd@!~fe-4`Sa2_D`Q& zim(g;XW&k*Ksb#yOMc*9Q$PFea|7(ho*7_2|H%ORuwM_br~Q6_ou1L9fo~P|P1^8$ zCcaL&BWkg-*bLoGU)i|FY>31+%%bpJ9qe)IOZ``v^9=ka#kb>I3N$V`DdHR-;iSHe zrN?(g+pw>@!zVu6`5EHd#Jc(8&>7|32AH2kkQNIbZw>BL2Dfm82SU3DcS~vD_yWqe0yfG?q`n}5dy|tm;hM{ZcY(H+q z7$wZvZC19JamGA+oTVvfhb2u}Wy*CZ=85!8iqEj7a31?@>A7=^33DnD?=VFqM#5g` zj60pNd<118os(_Q{?2c4U4yhM;hSuzlbEps?d&@naeeG%NK4<%p#5F%(EH%lR=J2_1{##J$U@V?Yc zPBRBIOonR)*&7P*y^dN_%WcF5`0a=jukT2X+Bw4Kj_lf&NAJ4v@=gcu27EtcFTUH+ zhC2SNfSyf9;;ccG^B8!23;i_!H(~|O_ENgqAxIbHlkTvZ4!CzH9qehFX%61qso>q6 z^xcn0oVyD3IkVsOPqr5h~0{8YRU%pO3`^m#p)*K(c zJ5=0il2_tu8O-E;N#zUNGc~?^w+Py|*O0uvd>>PBYn2rD^#+$m5ASoncEPt5xCd)} z`93UYpIL|V`*;_YtcPVP?h){fllV>_!sK14@&)eRpZM}E60{Hg6nycHE}5@Q#npjt zl*IQ4=Ub@q1#Z%MU%q6oRB!j=e|Vw` z=dtOzXZvxpT@QZ>_#*h!p!J#WDKXKb+l+Cejf3%xOUS0&7Ck!A96Q>A_fnXLC5%=^ zHO?lPNN(mAX`f>pm%Bg7jeC;&MxB=tBKRN|3Py!PD8vS@SQ_? zU!q!G+f5SP$Dlh-?~d+cKSgx7r@VehdATjFv^e$*3i}L4cJ0G^-a8)djdw9XM|i)| z)YXcE>FBt=j&`X!I-swkM&L;|s!n8mWNP(sfXjH0WW+tm7)COFtBz&SwmmT`LD7=I&6s;}_xO|V0e7Gn1{zCHoThhg~k}e)XnKC)ea-zY#s*8=Ji!Lu+ zx=i;p=;AotLZZVx(Y-}^ec`3qcMa*Hub(d37rI&7qOSn#e2xxr=6I% zd>JGk?n%C%k$lI!^0h@vy7)WFbR6&7hP|f{4enK4+(x?i)JvBx({+RH0H?d2=x|ST z)s)xYyfpiwNEc>*UEsa`dVb;yoEvAlDA3o%r@#klBM&0)C9==h!R2%R9rEFx#*MQ` zzK^`}wc$N(L}R1z-sEuDI;Z)DXmC$7)JB3y7e~Ex>7b)_nu0MHjUSyzPkz~gxx`+& zhwrERcj+Ge3*9%-J^C=Zf0ORfPtyIb=^lMC-S47%^!IfC3hrr4LHER;#w~RJ5`**i zgg?*V{C)uHp#ftvN)wEGoQFxIaUI3mkq&YuV*HK$E#7a&tMC4~Se}9R|D>0G*?0Oy z+6T2B`cR)c2kCrE=|zmKQ!ljZ}RG|y?$ICRoHt4Xt7C(SdOG{rh;aCXS2 zPP28=;Ea(^ngpFRPifKw>7;p5lcrPWJ6KO>(ggaRR*+^t{)x?4$1G6nO@G5$8EhgYRol{yzu))gJ%+PvH9!gtr6#p$>j0 zzPCd7^}v6kgD-iP|1GDt0e^!I ze#7rL{zt$k>EOrwp5yNTeu5tU5XWZ&f0qvagutf*f4>fX!(mRJ2E0uVe}vyPc7|bG{y>d_xz{RYRX3daM=r(c>GWKJ+?s9-7NNLiAV*@uSDuoDaRucz+A% zmk>SHU;OB?*5*U6^S#=2pf4nPto!)UkI~TUd{?6y^mh{dX&rj3iTUKO^IeU3pwA-u z^E&kL8v0=W`pW}-3ejT?&rg1QJHsb`oiokTKz}XKW1Z5E9&1vdKcdd*KhXJh_ju5U z5k1yM{pe#g^g7>7xCZpSi5_dRe)L#7^2uLk&q^rh&mz!Tv>!dbm*GQ?H4W`~*IuC2 z&ILoh9=gCpqKu-Q2W_`d#<5_&@Ny1}2 zN5$8n9TR;9@GZof@L1zf@g4Xs4&f&Oe;D{y!eiY>#ZMRbWZ-`f{KtgHT9ArwL^~(? zMBw)We}wQ@A5!sVfsY0LJ>Y3Qn7*^8;)^0UeI)REfNv%|){#{FLHGgUKNNWE{SMv3 z=2cnF5p#K>?g$cI;6B%Cn8>pke1emUSPcDczD&pXAr&scv_431(U^# zSAA^__77Z5T|>WY-uBK%{QR^kr~FJbAKzY(dE@-4pB-HX*%DdVay_!EvgHrd&<8l1 z9!d0gM$GcUen?do&IkK3an4?rFV;t`49?d??`Lp+|62y<>!bT||0&*|V}O64HQs@UV}5^x-g8N39Xo!n zu=gjQyVc0nfSbSh+2r9!L+?*+!#LfMtf&BqfGMqO6c4z`Z=`2P-hR)Zvmd2xdESg z+_QZzbPg2fWPQ%wP8DZwUsKQChIFmL-V>%X`Rpy;A^j|5^PC?LeAwAr>{WXXxYjs) z!xPu_2%*@oarXsxgxnT7b@uYoxm!8S2Rdm2pSv}*yos{voe}JRfzCl0T3!YIkJ#I? z9P8xE5SAh=L8wNkLa0Poj8K74j!=eBiad%Ph z55$$#CC*2kL0uJL9|k*U{eyKPO@dhaV`((+z{UF85wY%fgx39D z0*xE{Svup)_*O;`_JIZC97jK#=fHWGm3XIorpbQr%u90)9^Oz%`|8|PN|SqaABX!U z#pTYW`(6%r6!ynY#QP71TGGyAKNQ~Q$M)Y%$2+mk;>>{?XWVH&RQnG8j)yngu*C^@ z_Me!M(1mYnm{$djFs}+8LHpyP4E?&4r20tO8}$pU|Ipc#VGkK|jprXeO7*4g`Juj< z_VoN2^0R#izzrXSch=+icDEbvw8wkdJ0NRkIP$+9_arOoz7y|`Z$>>Z9~C{!zP-TE z@(FmnS$prER^X4}`yH(AYT5ao#NPvlJ$s4gz`GUipW%BMMkgOXs@R)V++Zc82=#*J z7Do)dZ+VaI@qFUQz0cxo0rn82t;X|vQ`~6mquVtRb#v^QF#GxWQ|v+Jn9<}1dj21K z-vb!cRpxucBy9*;ff69JNQV;Jga(>~KvRo0X+j%pN@Gb|RO}=q1BrwrO(t!yXj4I7 zy0U9fwAiAiExU$@F7BdDSG1|%3YyhmSw$E3g@T$&)TDR&UgOabH01-!*{~oWw84lu>ZT@kG359TcsP+8BCk?yEIQBoqPXH@1G79 zoA)PX^t=L`?nl#m3UTfm+qfRLuRM*kR=iYgZ97?=ule4~u+zW)waB*WkEIgh#VG~|i2pN?^! zFwA}p`D;UbN73G5=EZpblkdLqng09WQEeP;fNjC7ZM&Y!qw4r?AVb;xZdq9maDIE& z-9G-e$bQ)^E9(KH$qtC@=f@%Y0%Xj2N3}TDi1ob!xB}Srk60VwSw?J+L;MZ_XwQMh zXQEd?BR&^lb5>EN@N5MSzx(rR;o+Q$ynea!+#tfUac5aGY|48OV+6}|mdCRc>oDt` zlfM#v(&YcFNByw-Y?S$bA4S=qT@|9P%trbKkuQcn$}rkK!}l|cc|s-b&bsj%)QM-2 zm#^dE`sc4F&(c1f>n5Nb`Ouyc(XNuvk6niI2@|%352PIFIRC33b$s@xze~1yf5-Gb zzj+q?ISZ7}(DR#TBD`dGH~c$mXGHg9Y>SzQ9_dY_K&l>55{nwh&!8cpQK;WjGm2*8*5E= zd%Di5u+!Ut^d5jO5@fEX48oM5FU^g7HnIKG&{nXvWy|e?+%sBkD&-KS-2IFT>uM&h zD#$2bM2~#(tOe%D=|9)v&d+8Y$H4;1bWS&0hU2ac%(s)?j(Gqke}U@Lzr@};@bfc zU$I%I=R)RbAAJ8j%BR62KaZa>vJ zj@66W!AUi!umPhV5q^^Yi_PT-BA@7meS1V_#B; z@qG?t%-YCR49nU`y29)Akm(Aq!&fN0UK@E>;qM;tW1dlgFu%p7(zGglTh{?SCeH`{ zDTFz$K7@Sm`?HU6?uh4Lou7%PU*I=TF~(z#0H3qlFmG6f`9lfj5yiXDtuy{+w;O*m z`(55FkG+Y1KpK>ObB3u057#H1JTH6rt$o?WbJ&AtkBeuw2hW#WJdb(saDCL7o;nYn z-7cQx9z5MHo-7ZZFS>Xpdhm$Po^9usJ@#*|XC#(St{P_H3S)J^a?hXV2z2?7>5yJ?EU7bMx#k!KY}R zwJq&O@M-e!+3FX1D(LU?pl5$s%O`@q)`PxhkEWkH5`KJ*2fhAzO+O3zhzGsw+nPQM z`eYBEsMG_RehT#I9`rpzKMwkp9`t_tj3NI=L67S*26{i}aec->KM1;)&sf=Et$#o0 zw|m5&`aMnG2l|~J^gTk~1Nz+_^nUu3A^u&US9{R6{;Q_%1ij9Kp8W$&-wt|%2fd6w zY0$qF^hZ4Csq{$$eGBLx^`Q43)$~oEKLa|S&G|hq+8fXIYJIDY>(t`6mKMEVzgO0; z_HzB|50Ih!cigh_Y(H}p*&&hrx?5JB?MIXSsmOkD9J1dN*&S}#F{Jq$BKw$Ib_{7| zeW9&BI1bs*iR^l}>=@Ggw<5dREjxxZKO(YsjzhLdWZ&tQ9YdO{MD_-^>=@E~x5)a( zAzLi6Q{A$XX4iUCR9nawSv-|Rwdl zuMXy_J!bKh8eVzSe8zwp2h!;f>$`y}<_xzXtFz?_!rjDG_<-w9cSwJQ3Q z82S+EDd`^teLLt}U!zZnp_dB%L!f^G^m$7D-8Q{@s+MmB{jWj4O36p)$wJ=%`bR;Z zrsVIo>TL#LBG-KTnjG5H#?m5WK^FMtWO&qCT)ciUGg4#wlfg7@;SlUxQa{d zN9!{sw4RBlEqt5AnU2F_%wrkONM#;>@dJF@$&p9aZIf265nN2ztW%tYPP0z&TZUzw z;x`Jf*CtLYybcd3yk4hxH*DU8vgUfne1xCB%zEG{JO^;Bdjfoz_jcO;9M4# zde1$8vA(l6;?I%RQx4pT&GhF;>)D1d$JZk6FWCMZ_`U=13TOLsr1jhiobu;DI#6Et zHmhemcInhy6@tC-`vK`}^4Ur9JKaebGZ5VVvo9J!pei|I5Wa9T&fy^1uFD z`Ec0n=VgyMiTH5XJcm7axbNkhqi`OR%Cph2ueA*J_>RY3rt;wc{T-mwhvRar8()Si z30ER6AFc_w5^&LmrhPc)R9$*b6-nC|+r}{cBoOx;#GQz=Qz!j3csJ$pdz6d2Oz01z z?5_PaI<>zB&a6ZkIoHs-Fo$!t+2tN>pEjzObe#KFsrOEw9F*tRkv^8EIuBpUlWAai zJ_{Pl^P9Nu!nMh@K0tqsf5dv<1@{6sryLo=IV17*0C^@s_kk;WYp;ym2TXp4-ushx zna|8Eee1TaXJr2mX?hA_wf~3j4|H$7hx>n>&i%i+*l)9C`yhKj%UYC0SndB&7VDIz zUw!Ikd;d?Ly>e2^yaF4l_R0M}ANKs_VgC;}?m<2cn7Y28bVc?OtKc8beMzG`0lJ^x zJWcQaL7x4=9e+Um^VmtJ3r`Q3X6VA;{y{m$sIrpo*_9>>|-G)+(Mcn`6eboIw=w;kC>wFx z`+wkZ?*Bc7=Mg)-`>&4d|54^ZWPj;Keq+tC|CivD>xbMkI{{XchpHtRS>`Vj}hjAI$&aP0p*dW|DL$^OXxA7!c|`SCG7j{UzA zvd^Zs_?ue z4%(aIQIWukbO4fXJBqUiaGY*6~9_(fuj{U#6 zc%Gz;vhxViRjg(1q71^6QTu<)k7NJu(RA7W!%c>7OIo|iq=OSu2!oY!!;Er&u$MM z?mszs9`oSg{*#lZ&V%PE7teAJo-P+pmIn{_pPX?`^x)yMxRWQ|{*#j@-u{!5XSc^5 z6`%Q?Jdb(sJmKQ0^Wfq7fK$(M4<4Qw;pEBk;Nh7OPM(P#JUlbP$rJC)2q({2&y2|a zirzoT{yz3+T=QSfult3b0eXuEJ$tW~pAGtlJ?MM>LDSPf|DXrGUiRNoL7(EWzf&gr zXNjO+=Rr^9nG2X7p8H<-@dY0AJwiVVdY%Wp|B#j+2EEvWzE$?uPJzDMgPtw>XU9Qb z;XyBx{j;N>2R!JhvVYbOdeDQuN9YGZ|9}U*|A#vL`$2!$gT7Vv*Y<(#b>>61?5|-T z@bQm%$d|pS_3r}xaSwW`?7!^<{d1t3{WsdX7X2dEA(nGp!DIhz4d~o|tHPc8Z!=NG zl>dcW)?<&wEt@Q|KX%J{?6J6IUxN(e{q8tqe=V}TZrL%U`QJr$w_A1$X=Z(4nx7bl z>^DXB<8Ik8r1>i%yU8s(hBSXcWH*dMwo_#9cgv0;&5w%gU2fSiq`6sS3&$Z_EwZ_8 zSxK{V56xXCD@67hx2&XjG}&b$J8c}YOCZDb=@70KT+O&1z}1AS5m&tZu&A+T9Q$EW z^5fVKi;^G5epr8|BVb1+1vnDWz{jezcF|Og7{je_|itL9u_p{7? z*kRB)-)+R&O*fvc%zlU24|@T0?uV@-9nV{aZuY~T1D*R}0VN;VqcZzpUj?1}VO(Ex z?qQkzu-%|@KkP0gAKAk)`(b}|Snr434!Vh3?}s^fWk2jcpo{xqOO>wJJtyvm!IlH& zdG7ESZE5zy-V6QF`(cr_QSOI1b&tLuc8_gGQ_kEEi<0+P6OZhN-7}(iA&r@D1j= z!H>VI=Ai?l?T4KJ&mf*5%zoH()F;^wQ|~vs_rrdRIGp=o+W;qU4r{;PoYu1yII|!2 zuLyHr1nV1)_nXstHUqD4j{UF?1Lxik`x?@RbyBQ@OzU|szK6lR9Gs;;;NA~w0nY4) ztw*@_BKN~EUsvA~cJ7DKp7Hj>)`7sGw|FelH&?uR`JdyKXp zwh?shhZSQT^;TR(xC(LIg6o~Q-hqoYRB1r_VA<$4rr%$VO4}IQhS?8$FXDFZhnaGT zw;!hLj{PvkJKBDjGhKBaZQr>cR)BPv^0dDXjs39S5g%ti>=n>hp0DxF3+?AKxI6bH ze+9e#C)UP>C(k^0`ucO2GNu1H9)Vx|N>eNDuZ2n4Z`F1$q!>dfuh-64CJjbabJgcnW)X=+ore z1~X#5ZLkkIMqvLDocm7xUV&HPO!wLp{hg{I-*s~Wms<}^g1-g6Gclhq-?QfaA$9)> zWx%r5-%qgP=t-DpZKuv>j82}>58lt=nSLV9RyXf)UJiRCXJyTK7~i0K#CPTT>+!9f zx1v6TADOV5{QJO9Jxs&(7{{503+3y>66Y~~#{jZMH{MySc*LZqTc_vmpr2UtTDsSv3bv>iYWCwIV zg)qN!_Y0iO#d(t%=Zo+?3(BZ+tiJ|(x?1MrltGv>Tn~Q+-z(#M%*Z{p(jnIixszJ% zLzF|9a^F*NMfT0+LWcRike&R{!S;6_zGXoE0)d~!cMH7ApWhH1YxzHiZ<Nz&ek5dQ_}!D9Fuoo75tJS3MGtlV6LhnW*b&mU)V80=_C8PP$=`L2lH zL~O*d#M|aCYdt-^zWaK2;Qe6AWB{ke7rYltAC@B6obwN!9l>$?6zIg4T%as^B#n<# z5A?o8;6LDjcaq5BIw+j3R^cBuJ6t4|`9d_ooEimWOWpM!h z1hCJ|(4&1SruTHPEF3-+kK&yQ`G!X4++DEgGg@XLWe{ea=bY;{mW9Ko;snmuWPNx5 zeK`B8UmidnF_$jHbK^S5@>%8iB(;CL*Q_b+_E?`RMq9x1oz3%@2hXi8o;nX6%o(Hf zEcf6++M;-}Ja}$#@zhO<^|61Ci)Xn9&ng#BmIu#$;Bh`<@;SDQ-x@&M{TS@|MUQU{ zsBaa3{$bF)zEx26xR!qq^k+Tf`#+=U4WR#%2fbe8*Mi;)y0dI1daMt#FLUy|>~X## z{bQXxhdp?*J#4Y(3p%aENXs9+(%PlzH-m0@?6IdlrRj@6Px7D-^Br8+@_Nu$d(hQ8 zwxG`g-Rm9OGQOh=`cgS<136Ft@`xJK#ZdD&yVd%BC~um=y{5pma>`e$`oM!t=5 z^T15mp#R2$-Y@j8f&R*$IWNl3 z0(In*NK0Hl3()@>^tgT&pnn8(`dLKP9}judH6f*p+5!a zm7sq_{2iV{7;A0nUE}5O&(4x>Rir!K7smdsdcU#?cltUUhYa`cdmOS^SVPX5c%wRp zb2Qn171<{pvMS!!u2r(mca7cgeoJJxI%J*kjwbsLBKskStcq8BJ4Q=$m&i7_WyfHv zZ6X_R$U4(JTD+_;v~&45WLreG$RVrp`|0a0Xy+P{&2z{)(>$7;?-AK~4p|lN7|QoH zkxg^Rjy2vJMK;MHtKwa*^E;ZIGe!2*7b0!J8SiMavqbh+4p|lN80?%Pvd0{<&Ui<& z^M6Bzb>px@cC7gw7TJGx$U5U4Ex$h(*)KU{$C}?Ci0n>>tTW!x^838V{>?aK_loR? zjF^=qLY5t_hRyt(IT1J~i_T3Iyr>#ayb4X-wjUzi+nu8*{XdJTlifo2M zcC7imU1X;_WXGD{0+GGUA*^Gui?RZ`JjgtKjk=-*6*&mAR=f)x1 z2btaQKkCNy8C-vl>+f)V5!X&!PviO$F1&Y__Is>}@EO;fv2NB7ti{Uzpwm3Z)@8>& z6IMa~6S(+n9V3tRjyled|K<{nq7?i^)C5qV&$ho7SF#P-}0Ds+QPXD zQStj@_3jvXzf0c3*RKzn`OQSp2D`t616e^4H0 z1H{CScWnH0x+r-MpT7pk@=P!1w=PUy(1o)UqU1e%{_cnDR$O>D8)CS`rYT5nC;W7GZ^y8gjKEwUjx8i*-W7g@ezlu&A!RIS2Zk&*Qus(Auz8Y2wEBb9-`By6%M!n$?quev0qkP6jXA^#<_P<64i4YcSJr zU4e_d+_$5iF0A`p1^%mmuL55R?h|n(yZ9=xt}_*UQ-Qw^d?pQies}8g;~D>Q@bOIj zJHh9qVLfx71)5oRortjW8yEM$26#SK^8@vbi|rq5^yJ;)Ze%$LzrovOFuFDOoZt@6M$DZ z+XrlV&+ABw@&Q9S(B8HURa@KgfjfaaeZYQ-^Zj|AH~fk^o!_{4^s>k|E=s^30$qLM z0(#&N*4crz^vC#(3+xA(^AY$i{7|u+k8p!e&PSMbx(NF*%4W{@>2WsyOVHb4{D(x3 zdY>NW@}C5a@9w>f`v9(K@CTz04$G&VG~cxO@CU+~n5FO$x*fhkx4~y<8GMIIcAsl3 z#yR!3Za95?(T3s6m#eceRhy8x!YF=Zk+$Kn4wQ=e;$9;heii2`oJ=_KU*8Nrj_(J= zoDpA!GvZ1A73j}{{#C4N?#1;FxM+8kF6CDl@f#b|exs4JjIl4u#yJO!s~>UEw~2Lx z``f&;4f3wande-f9BWaA>iZXB`^Qjzs+_d{m_AQoo^LnH)P0_U)1HSt)@3p8(B~;2 zJ>5u;DSz7^5aquH^%ScLwY`}dDbuzuS; z&pMJk^$Snn+>qBkjx=Nby7(3FSHez}xc?D2KfaIAy*V&ai|=E+{_w54Uzx;j6YzXi ze0Krg{KmNr>YEqel{}-(pRvD-f%U10Ckm_?U0DN0ux1-d=yW82!qvyO9=Eu6(|G z1!qCNTk;f@Z>(uK^Ia-D7nASxka2&nMc3KH9=wOUuSV6`#M3^hv)prMogJEIZA(I) zAAx+ktG=!P&SJhU*ZGR~4VT%H-l#m`+0~h+X~J_cd0GOQA$|HL%eH-gKYgj_$2OxU z9cS~=C-Wh+wLjSB0?j;q0`qH;#XI|%+9wmT`zbq5%id2}+b478X`UlZnFQ!k-$N*d z-yCHA0WwI#z}$n-Qw=}NXA+L|P!H%lYl7)`pVDRgDQBMMyX-t?Yf0nmm3po`^Yl}| zb!}cXGUS_~d{p&!4d vtQ1=D_Z+P1D~snDsX7dxM{6fv9iPIQXsw->c*U?d#y< zxgK5U>r^@mCU1KQyf=a8_e$5)k=ASF{Ef}}d=tuJOqu`b>ktQ?3-tLLZ_Rt=8Q+ns z4K34Jd@uUIAFsJ~+adVk?)Kf=+m1M%0{_##RlR7751jOU<_V4$-6tm;`Gv3JiCxtb zj=(2O`;wq9-UB-^p6SpvUL8-0j(PiEmte!b+yEL@oh$#+-@*UY&IevQfSHMzx?zJ9&< zCt2_@P3CuX;Cs-HGu-5Cg@L&PsFNpkJxzjc?cbT!b2ra{mo~lUr8y0G;1Xa;NzVBD*1u z>}YB36xsXTvhptNbjMz+JKje{_Aa-qyh}TpY_rG~jzhLuWOJis_hx;0i7KPf;;j(b zYsMkFOk}6IWo2)9w0M_5W;@!}r*O4k&A1uY1Gt>;1)9EPaH>@?o;Hw;Z;`T{e&U~T zW(4BFbE;aSGVktn$h&%90v+#Mq`h0kA9=5E2y0bpJpyT^>~hl4ZyEVgp z-{e{i=2YrTK#rBv!LjAj;5Xw>9>X&JJgM+{{Mmu<^Y~6F&n)6ted@VLAF0-G4(K(U z-(MFw*Ydx>Gl+6g@A2V259QDI)w9^AdYo$+MjUz#N1to?1;9ver}I6&CxAQgaec1k zzaz|itGSlFhJ*7ifmb+t4F~W40jJh*kPejTHqQAEAblrr=Ne8e&bs3qpK})HdweHQ zUMqo9@9{zQ4uoqlH&M_0n8%oP8$S0B-E7uv%(qFWpH6_h8cUq#TH@I}g!I_Y?V^V| z_#MMm&;~KzeHiyOxYW80%9v$!g`#2I=0I}Hw@m(sZ<(BHEZRMEx&D@kv!2CUuW|B> z)hB1`AM`nxn_<7_JjUg%T(7B4IPx&)FMz%bb+80iF|J#2vCLpctmmsUPS0>%ggD*S zCZ6saXFrh2wHw6ye#Dz3^_+fyZ<9DpIsP8y=q^L9nW=KZx(#i@I{oW;_--l6)V*#K zWiyX{fODUEtcfr!Z%0~8`P=XPq5RJRZ@>2^<KYjNFX7;8DFak-!SVb}SCK5N@6XzO#)?=lSk-}x`0&imAP?AEqC;MIBxXqso* zeD||E&(fsqETv;wPY7wSTtBo`JStlj`e5}V{O)^-%8Kv0^G@r5)~fpI#tj>+>iWR? z+UCI8rX~3dS8b@#;Wbq)b=85EP;*_wy0^bQaA%-7*i>It9SqdewKP?Qs%xzkdDZoc zmo+yxHZOx@Q?P2i)!1ScHPkdW*40=k<@HsewT;ai-tM;=sx}0zb=5)8{P>kL*F6|)_Ty@)Yi#iQiOv*7St*L8xN$>MYbfY%ZKw;iKtv>q>l>@r z``0!HA7~9WRBu%1J4-*9V$~>>0a0los}v6?aikVf0b9xqD=rIaEdPS)`UM-RY8C_= zs@Bv8b!u;It*fu`mo=_K8d8wDOvv9J44M2cFKMyv4%P>&T7v$&)_fpX9Rj_$Ian16 z7B|8MZK2zm8#h#JYzk^QZ3#-H%xi6^39j|uwydJKG?3?yh70^Dz<^%Y5Hu{AEv*}} z{dG0j{-SLE2U<5Y-MTT$51jw{cle9mS6B1?n?WR?X*Z8bb1BdFR4!@rqTM`Ns&00t zy}(O_Xz+~MsEoAR8If8`o=X?^?@~24K)wd z)r4vT59S6?CxB{PyS615$_xZFi+^o>V^zpMALezVZq4#P?5}GG(ZcWWXRZr|0_&O^ zTblxPHJLeC{`r1lw9=Nk4+b?(n@=Y!%YVItM@ii*@v#Ws;mc}h4Uj8UK|N7i3D#PlihQdjAnRruz%tX z5;6W?>mqfJA7Y;#+u&`(Mpa!KJ0^37I3R1?1(AZdDH1G-1Tn~%-ljMbEQth{MS{1X zD82jl&{+DZTp9AlJp{T(mN5@zG8)S$iCpMWGIrF9Vf4=Kn1?gb=Q-w&Wju?M<1vg( zF*$jIS@x)^V=43eQOkTRgHs$6jA5Ah6PUnmJ5jB5EQTo<)i7fjY2p}W3}eQh%`mpP z#?*~nc;#_RO|y zKb|eyFf8JEICEpRUmS#|T7eT9WV3l)FR&TGiMf z_k*HYH)v_XBVx=`VN<9%Tb|eg7_=XjFbxnWGQ%GYl&NY|7Av!UB9x~+=Fy~CC-V}t z5mo5_6}zAUcs@{Xj2&Z~H7Re5H7QTEC0%*)vN8i$g}|TdbF*L~RipA$^D_+p-&L=8 z=Fi+{p3@QVdP;W|M*bKJBi~UN`Od=7g_4)0?~Clh$#)b^{-3|?kI`711i)%~#)N>^ zgSpdu1!FW{fx~0<6J;y@<>vaJH z^r`>?UTXr*BF9kbUJONQJVruHD>xSF{wa6K8!2^ND+;6*+$8th923Yj0n-k17a5GH zO1U^4Mfy!7EHW%3VHeeNO3$lS2w<(8T=fW!P~IXF%8wZJMuRKRPx#;~(ogjW73(K? zgqHE?JzklH5DSV8w_FS?Df8;q`t?3QO{Qb}CJU3cc}>k#>o!#R?aVSo2kL6+q8i1u#=r0aYW> z;fre{f9l@wQhd&5ov}Sc#OrNFnY^+(IVP`COX5~1nZIf__XJk3x+69$7u6B}Pbl|{~v$n*c%W{YYiFQ_M3wj)Y;bK|<^ zstxzmg=$wewl-G>Ei(ZV{|Yy`*9lj{fAJma}8+>j)Z!3*^e{U44jb(f9O|{w>HU-_*c+;)MVNGr8 zk7G-46kCpENAOLxDE&S%~B93BsOdKxxo~Q~vCUal%J#kE0_^>(tO=9nk z`jYR7_l}F$+2L_}$@e6VEAl1Z6B(l4pvU4R-xEF4ad~_Gd4>S8o-GocNCsF>!#@%=c1%8lQ(GrFmvPlHhNTJpis`KZS(O~+V%c6 z{n}Z4YSetlOnUwzW>(&demGbpxGvZn_0|~=8_}yZ4C%ERhK$oL!^$WKTyod_pY~?m zIHpXf2f7kD7X4UBJSvea_krs6(V=f)*+=K#dbX0daT&In-R$(6Tnz9Hl@X*tP&k;L(2Is;aMF5DK=0S`gN6uq|lY zP`{uC=ib2xJb(~~6t=Y1hguc_Z!K60J~FJW!;yn2e$C>4-(BSucq4A*`%_Zznw$#0 zJ;m=|(3I_uWZ2(;6WHuub!}rKPV+O?@Mn_R5~^y(QG^e{huWW$MGZKH&lo9M-tQL; z+Jev*g3}n05x=s23yz;_2?eWa{EcgooEpT^+}O~lSeucc(SEgc zH9@~VB+;)eTo-KdzYi~$Rl$I7_pfMtKeH55uo0atIODK7go7LFH~O1f8{|wqzg-3V zEGnhL6n;xnL|TX3I+#7YpVrhItgcf>L5gUsu9^$#(oa8Q(IxfJkvMm{3`b0IVk@rE z;#Ofey$lpx(~Sn+-CE=jLunHcv)E0;DXhXQ8c_XJYZ@O6DuGBb>mqhFC5MI*v@E|g zDSxQZkH+L@V`8bUWo0+5OJM^%=9AJbO(?##8x_*8kT?fa3A3qExR%1~W*m`8kjIPG zS8enw>V{xTOVzqyid8r@9NzA@$`P(~z)sp52{(z(cHEcV!u-k!qVKpScVW&ocyYG6 zu?Cg&9oMvm)-EWx=9YJ+SWB&UT7JLvj%%!It2Q*g3~7#{=5?rh?aQPC3ves70AnJ4D;oVV zU1dvaQ&VGeXs&;yNt9wOQLhg#i0z&;Z@;bVE>&-}s({TBkQl9XFe$38Nq}0Ui-Pi^ zARI<4NA{}q(J06^oTOWsT8G7=8qj4X;V6nOHBB+arXgK!5{{D5C8sG!filQ)J%jN} zTK$=~FV|*}0mII{$&A52m}}?AMnw!@qas$YQ3bJrwmrav0!95oK+=woHUk3@oHhV( zCie*HtTPbd)0qa&54# zj;{5#ltT>XD%W^P-C5P7g)%wzkSog}wV|phO32TSxVi~L7LI1d0at8@JdHu8P}6W; zbmNAArUgK=qEdNJ11OnQYeP84T4g26nYmU{MZk^=18P)ENZq&hz2DxYukuAD)5_T+aR^=(r!nz5Fefwe?fy!#i-_zx{l8 z0C5aHc|M$u!_ANHJRdH=z5R3N!>e#_`~3NEC+ItH-;4V}+}nUZ_J#A|ZrrV>&xdh# zy48()GSZj23;J9jCgTR z{t4p4z3>>~!~NJ#&xel@|L^C+7W8a64m;qU`g7>VeE|0z)c+sn!-q)!-{-?axYrLt zFYR;Ue7F#I|4Zk?O}LkyJRk1Ez5g`w3&U?81|IjJ|3tjF&;AYK#eEa*1Go?3eg^l{ z|AM}WuruyCxNpL}9rr%m58>YNJJ=WZbGWDD1Ej})e?DA_d-|);%lm7H7x%PtNDuU_ zIuAR6f4~ZdyKvu<5DwRZUW<9a&<>{Xo4wvGdmJ$x{z`b%|IDCxw8^Ymq zl<&}@aJUKgvv-BV1Gp!z4~KJ5&a1YC!)>@1d=hfFr++FO?!|q|cF5y?3iouB|CDDS zk2`<(&XM{he6YOiZYyEaoJl)3EZ3;nSEXL9=ox@nSNymq&qRcdALUDM+4O1A^lZ>- zaGgS(%s?3=PZs*B)VEIg{DjXXe(JLA$)8U7OzPwM!8#4R{3U!)r6z%C;E(a}>f3QX zyp@P@hrH01;=c2<=fk^5FN>wG2HO9``S2bOI@5{oEm$SUXBzIw_^6lq#ia8sJEnX# z&B_OHDflwcb~4dMY`d&>#H;c}{wtm^`JydP;YvrF>ShELZhmbC@-aPZgUPsCaneDX zlxEuS$2klFlb*>`aFY^=^e+4%+k-#_zJX z%0Ke$?>`@|L|>5n34CFfzYFN4okNf-{o(oWFv7_z@nv8Bocd`ujkRcpUEohdAEL^o z#e*L_Oz%?godI7T!d`Y527UX#AYR;)9~M3F(wkH|BWZcM(z_k}O-FS6k#uVNGJX3% z@Awh=B-&||@;nZ{kr&aIc=0jK_|ZPw*~g-f+yuVlJ0zVkdQo0rWBdofUxvQ41L5R= zhkZVss`9ZKe0#um5PXq*p#1@){WgJKc?f+p!fra#g>Uv)Iq0j;Ae?-k#N$;jL8rcc z=sN>`6`$Q6BX%1GeLMR6A@Iht8{^%Dcq=d_sPeyMlz7oD$$u351wX@>iE#3#yzCLF zU*u23Skn#uOxpXvDEh(6d@((>AC2GMDxj|&W7igBHTf0M7q6Z<+S@tkJrqZ82IAcV zy?Zd09YQ$y3)Aoyzo>STs`C%N{#VY2OIXjJ7rvNs()|qclZdf%_NnvX3g-X&!mpI; z{BDQ7@?V?}v(3BP73KGVUITh%9QskvcY$6Lhkh3HA<$VCUi#CJzO$g`#G&Vdp7=|Q zu^x2lJO#RivAK=*xH_IabbDfcwn%&>9{N}gyFkzU!};(&(xdDjU9VPSygP$*A7Z>G zF>SuJk8K}qY&|{&!+V$C8pCli&cLn&%F^4)wy^}ocZKsp`Y$r{aE6ry8 zn4?k^Xn&?>FXmLG;Ey*hQg0df23|iOK8vt7Uu0aSy*7d0+I&8|pZqR+(T3TW zvxP8+D?=iZZ&e0I{i{JI?-hyM0!!k*(3<39)bQp6u`9N&ZZt$E?_ zp+v-AObPtr^(&6?s{(R6L_Tft7oxm|%Wa}cpDJy|80vy-(;LdTx8WIXVB!(Y)s7l=SGoDHS z2g%Q0c;^8mtBAo0{^5@SrfQf#C9Vtx_}hYODXy~w`f%AY;hkS^hobxvAZea{L~kYH z4}k#!`|*cb4-w#>O5D|Nbi0ja@7F)hNKZ}5h8|k0f0kwW3J^%cb&xDvhd(WqOl0niJ8+DZvRK113Qka>PHUi}UNSRHb zNhs+AIOV144nKgs02pZ*0hSXhaVdc*iJG#M0GCE6V-a9MlkF@X7k#xtIYVGC0NS90 z0H=mb&H%nS={qBoG<11BRyDHa5GVscwmzuz)f&o`0Q!)Ah*@PbEh{M#57h+931kCU z1wj3_0ASi`@Wn%q zo0Kg8sGy9%KB1HnI3$!I=5$B^rTVM@+et}-p{cEtKqdf{90Ht2kWx-ywNTOsv;(jc z+97OHNZ}-a3Xal<`-L(ps!!p1~CfxjtScq0;!n#FrIb-8334q5&|VcDI~C3D2W6% z3B@ANDZoM2kX-Ae)p;!Zx6qGXN@3Y~2DJrM4jf_R~~n1vpMh zHkKtRa|jBODg-!2N=N|JyR-pV3O4oI2LL*(Qr7E309bp~?~G7NNJ+#OW^GC~KQ{}W zLQ)Eylv<%IC1sP7vP&ohr1Ux|gF?wC<*bu38yLouL&_H9gPA*Z9r9BMdl4wbJ!!Q7 zH3TwXR#LKYPdX?-KLP(dP1%XLM^d=}snpgcKo=>S0NB>)1;84T2sUdNKsoMH2rSLe zWx5M8Rw;mX9|HUx0+}gL3GD~KN+G|55244E-=W1i5Z?LfqwSXO=Lr>nSxvI3sS;Nw zF7-Quze**glM{5BdJ*sz)Dsj73>4B8h7=Z0zq1GkP0&J$1ckbX*$59P@~F2hM_Q}OL3hgq7RoX^Ty_NI*&O}$eb{13HkU_h)exK z_)E%8TnS7Bfeu`%@)FpAE1?sAM$hAFaHt;x%p>ckRf~&}s~dk!QVhsrIu{K-(u)kUUYHh~TSQVDSKmxepnH>`64>>|MV9%V`h6aXOGQUaXs zk&;MY2LLMSCNL~)76B_sv-Mqua3%mM=q0dJDD4C~0N4t+6?GOZNd3k?2R~ry8I7xc z3>4zpM`#l+W?&bAt+*J!qHISXAD8->dPZQiM(F@$)$>CE44ej_hULdrJ7UjGtzLYHdIrJ1N1pY9lChpApz16hpG)}KJ12_k&X4lv!5BQ4;YR1y-y20nTD#=NksVlnfD=jnbjaAp$Je902DSDVqc--K2C1MLlgy7UdTcx{ltZM92xTW_^3nNGTQ@1?0H`h94`3$%T67mF+@`0kO9`9;P;b~O z(4Ug6gp^tUWJ@N{A(TV{I{`4BLwtT>?@XD41dfVK2Z3aC;;TSWDX0NJHuccf20*2N zY&(Ra9@;pJP<1jX142;`ZKp)$5a#s0G&B}lbrS%U0#djhP1PL)b_rz*fnESq%_jsO zmvdE42`GO7MoPdx(V==10J0^L(g}d7`7q_%D-^XLa}WSkcaSn9lr03#iA*VhY_2ha zE!_{G1As~aDO{aYwkE)(NEIo80RYO@=>X0GK!Ixo$ym`N&<9FVngII=&<}x>UIN(y z>?2Shz+M6+0_-7BE)XHIGtUQ7yRKN#P;^4Kl=5veil1CzL~^9CA|52t_sYL_Epc@np*bzoHa6 zDYZiBrZz4T*fLxfU{(CefOIw@zJl-aUK&_QiE0BmimgrYi>dM9POlhW;^a4mr; zsHL`3PD(1!q^M5FkB}WtsgttWN!cQlQfk}br1S|zcU(@&IVWX`b6uc7)&(-Dt;|W` zDg(qU)!B78DSMrigHFn@P?D+5az6cM%DRB+AeTBRHBL&KlhP%WA$DB*oRs52QJv}; zCna5085AWOfNfE(^)Ww(R0rv#bP7dv#Jil7ekWznNl8ZQptf#mn+?E@r$i{Krr zv^yzWLQ95%gSaPgagD$!0wV$>!iY)f_(KX;LXx;TN1%kjDgkN;vU;2Y<0OSjBh(MtL{RGMc7$C4pfTILz z1UN>ZNr2-7HVMG>)uavqP7&BHzz~5h0fq_e5#S7gy#Vqp`JDp5?zUnc{&01>9{1G* zxFXIj`YdFu9QEEi2IhVI&nQ3oNW10x z&V(8$VTzAoUSVy=MWYW8*n^AJYafBLxX8wdiCW;uA(Ft}1Wid~vikrq#U%ue1IWfb zl|bqQ&BkXui*qWnrIC^epc{Af<06P1DL1Dx4J8$Vq^K150oasMp{V4nc2c%DDZ2nL zbKGJ`=o6ryz$pPZw@TN$nTx70MoT0ltF(NNFN)N+|UNMg&kxoM!TV6y1}rPzs8@n6C){jnPe@ z0{|oKAixJpmNZvh)l8Tr%?`!Kf+D4q6grrYQa}nHqDaXkWv5WGNjWBzWKzxw#ZO8O zj7^y#^w&Nv^HEzlDW=p;k;39;PTBkWSQSeR8%v3)-a-m%64^=#4}=TuNXm09$pFu$7QPM;4U=0`yv; z>O=xu0-@?dm~Hru3*{hzGa}PLAQcm4TXmsKrMHk$Ayes60wJN45a<9v)yV`n7l-L| znf3~h2ujjH0W1QXrIYO(W?V_f1sEYPB*0k$X9eKIEQwW@GQ$Lt0Wfoe0MrT-v%QHx zCMarq7h&rZ_E*T(!J0S%Ad^`B{MdXWrIwU@05)Z{P*nA&+pJBYFEwQpWsj3`R4Ap? zHsqvC!R8xfRFla7U~4OLQn<-yQ#yo_No_lwl!HRi&CE$*5ilM_;U=H0ZK+U_sjb{e zX%mWSnp>TeeNM_DC*_P#R0~do!R>gm0WbxsITt!9wN45PX%owlzY#RaWZbzil$4G? z1TqK|2v9;`l>nTwC2^`owk-s92(XL5K>-E`RH9d5H2d%vmQ*i5FM&1z_7m75Kp%ll z0l2T1#K#pX;KO4QA8`ou6W9YFAAtG|0)S1d96WtmX?Xmq$Gw0+I{;S80mxWe0o0%? zRKGJIQyU+X(dM0d8bt9o{xQY)0@Oka%Y!ph-zEf@7Bvp+63SlK$=55C5P@StX(BKz zKt2IWMu=nVMDqpcCBXF+md73fn*cD@8oHtN`>g|sS8@GSeG7KrY zx0kNJjFcQ16jX0t0)WX$C54Z~w(9M|mP|^wu=TSSJ|q;~+XG;#w~}H>*ROhe`p2l8 zlEN1*Y}GZwrh5A}VdJ*BkMChH)w;I_K-Ju8_YDYzkJP?XBEu(dpM`GRR-F$(Wt)^z z04fCpYK2ltU=skUP9@L<0H)IxHA74?C`tAZL%<$l2-rgmv_ys&0`?F?z#d`6yY!^yBDcw%WfKXH==irkm%B)l~La@Se@UbbSLMfv*4n8(zi%?X< z;NW9Z`kWLFJ~ri?P_n6wgO5$2Qwa^P8WRT}n-X$TIQZC{WKB8l^L zDxeca(p~`h0Mzdk0A$I^=b(^|v7;XMr35$I@of>AK>|BOW*3280Jdr_^mFE* z+{n1Lk3?8C(3ZsI{0;zI)KI;+EmI-Aco(&?OJ{Ow2y_UglE6*?Ob*w7e0@Uk6F4d| zTr2Xid$v{k5h{U90VAyeKn3a-0!bmg0V_T;Hz*0lm0l=2o z1%Sy}t+WBaf9*BN@$al!qsb=vd2j| zDwKYvfU`zh8&|I>qbL~wYzhZ%n^NhdaLge^rGR6PEpyOG;hfs0aP^upYHutJfKB1* zwM{8^Qus(@Q?@!OobTI|Lr%&Wq4Y7Qi5Qjac(MUdMp5XUXH#mO6po8FWtUJ?PJ5jc zu3p>P&N?Yvy(UHV$~gdRZL5T$wDH-^rf{c-GW(foK9t#%0Vm~@lah)7l`^X9^aHSE zxWi^^TkWK9BaW0_#-B0Hp+S@W&4}`EmXHAQd`(~;tx0JjFhYJ@^#siPD2ISQL96B+F6$i}n-O~EQ7Pyv7jTnZp*I{?UPnJxfS&0TS|-pYig z5#YRqIaR8MMZpwMl12oeM^{oJ^inmK<&yXS&BUsoc}Pv9Ha?_g3c(rxz(^H^GYy+! zmOhz4we)FIN-xtg${?!&*c2{(+ScJis!iz=iZT_Q4Q$Fep{UGF!A!%Z6v%``QOcZ@ zkdwk0jV-g+N#UcYO&NAlwj^uAcjBJ3OMtxu4hk?pfcyTqTLmnvO8lXD`%o@wazTK# zI;l-4hX`yDpq~JJ1@ghBesm9DF&1Eiws`bFJ?W9%x{W^U*0*S`rk|2K^Tlf>u!bDd6R^6oU2A{lG!(tYzToP`&L=*q{aJZ42L()g1 z*cEKb;f%nm7HNI235+$^|0}-%vHKfUUVfReoLiH|oAPy2-LR=AZSOZ0adT+6yy()M z7Pw@GzwCOTQy2OBcL80m=YC}L`W=yo4&7c{{C1q4x8j~GfBwRo7Pk5Ga&i~vagC>8jj`WsumCj`IL)!ttb{23SiGF5z&t%C1Gm*XtKuX6EU5BvnQ7h|7Z zrPs2S0iS?U@0IfP3!bk$5kD+=r53bx2zb^1DkV4B3c1p=O9`f1Q!bCLS3L?p$*ORb zJGbd9E4E+yy6{)J_;t5A4Njra`oAsw$zM?cl{)@8q`;|`-^Kp}g`a6vy6QQ13i%Y` zuIE2f__tWS-%=m=(fAa>XMQ#sKSl7vF8mC^AAKU4pB_Byw}*7Y zw~5yXzGJ72QUUsrlHWWx8>(r)>GvCqzAqI1Ox;1*#6^NH__&Qy0n^@h{B1P8Pk|_x zPekKQd*7iuI-6+PwY&bGP#lx3PFK62^O9vvw#t5_3c}WNhu{yo@b?Qo`Ne4d2Lxa1 z!fz4$As7B}!B5c@+m5$K@MSLiHwC}Pg{SW|)4#`+ua^YBmy64eAKiHs|B-0?W$FQX zvUSddPY0g;l__`AU*!RxfT!qMX{Y9S`CWoH?bqPfiJsEObYcee&F=TorC;(3-t>EA zf;XxC9Q2IV@11qo=ik9^VLq1W>Sy#g9^0Sjar`Y-rtY{THI{Wk=}EULUH#`T6@HSH z>FVE1yV(0VTZIak`ft{q4As4) znAq}KuJCWM+Fj*k`v2kQZ51kD`v1ajN8?TZ-*F%sZ~A$&K4_?>eDnX_VD#Pedz&{DP zE=)P@7xS5R(Ho~-bh+Ba&!A_tc9Hhe==9G`VnpfK42rJLZ7Tjr)>c>j-=gqSaaKn( zziuxxtv1)Z=sKl8wq5AOYE$VRDvsfT90 z+)zzDblc&CVwh~@xa?!OnD`XJ^d1~884O!-sJjT=oziNcD`gd zwIWkq<*xEF{afWG-1#--QtGmUDVG`-{#7X#qu*UF-Eqq0xT{>~J3d;w zX#cf$xtwv8i|NPiem0ulluLP>a_P9paw+(3w0_f%#cMCCQ=<7zxtM)Cce%LpdqOcx zwsyMgV9KS}g?}&X$^OddcbCgZoN~#YsQY=7+7DfzT=t(aoH_^E{^?es=rQ@y{m&$; zq&J#hj|)?=10OxU=y}vktJ763|AO>*J$Lsj{9CLYamvL#zWh=p1J7|~CWZQL`nRUH zMW@rAFWnK1H}j>gvS@stQkP=2-x-bnj^Nu?MB`0+bldZU;-73CbJ^LH`&k$MM^f%4 zU+!`*m2&Ybz3_ZMGPs_z$yM$n7by4RuSKWd^pl;gayRYq_2;7bO?#|#mAmODceu*^ zLi37ty?`URvMe(nF1sr_UeoT(ez_4a_IKy&gkqR%jkxk_?4S0>X#MZN#x2{O(eJkZ zjyU%3ciBGxJ)`x9Wv@ratL+~$?sOV^*1FPf?778-e^Tse^tRZ+YzFoKyOL8+PxHTp@bQdUC4h&k}skb2H2Wqd z-ggLpzofHJ^ziKR1niHv_iJ=KvHMx~fd3lg%dC%05yQ0ue+BU7x$=jp~;^2<~Kh?o!f-ft6^v~TIQz-)sW1ZLHT$rB;V%N-i~qfG@E=h46l?Xzw1QzNudj)Iv#-=8 z`Y(fW)}Ldpc9aLaSG?cAIPQgi7m!n+$L+VUDvq8y;F({uPt+&rc`gn=U%5sWVt&7l z!~cgk_-pZw6XP}edZxVS7Y>n_-@V|UYen{9(S51kTHw9-+eE+FPwWu>AH?DRc^v$2 zM2}hD>k~cxG+kbUuJ(Ql@LuV;19;}wtXK2JO#W)(@IR#RcwXD9`QU=2e%l0}*`wh@ zqURq)zuCu^?%SFNM^N_XOJ)DDK-A?aya0~d@;LbW;^1q5XTFSIL8heV=W+O7RrnOk z?1yGZ+(|QN&&d9Grr@Uo&-AzdlSZ5q{R;&j+O6?9!e6BD0yu6f+Qq8Xpq=vvKsN!cmuc%zkvH z==mV8ePvbvh z<{>{3{*wE&{#}yRUkcv%=VYkoF3WlZ<>gg>lHdsLRW5H;c&z73eJ&LJHv&Hu62>pi z*z>kHdfub>Mc8p`7X4Af1URq#I*e&aW?N$UAh)JK+ksn{)B`0oPV%l;LLUzi-X zAn>dwX519>SRaqW|M@uhug1ZjRQMEYMDkT8ai0TzD*jDzwU3Ly z0e%YB6O8>e74L7w(X&1dzE$*_bvAy4hQIFsuhRcn4G-y?bqC(|_phC`*0lm_Bi-G3XgG3+FgmIe?N%B zKPdcWy{=yPe-Vd&!Cdcj-UK|$(X3Y=6+JryZ~O{Mq<&h}&7n2Hb#)C3tF4SSE2Bms z@XhiXAgb2Xg{szBH`G*xs`MXxmVF_<*u9~(?FN3^y5)x2#tp$6*0k2u*W6HD-xRD` ze?v=i^$lR#&>N-d!zbWp#I*(zlsGMZ3}bwCs+T4 zsR?kS5UN^JAIyotb32q^!C~@h?(V$yN5sRR+ri4~(honyajr ztIU_HIiVlsRi@6&RBj&}TZj410#Gnw5yU-9_3@SFpyd|+*u`$M~ ziWQ5MDu^lUNNEJ#Tb5hU5^An%SXZ~UE?A?#6W@XoFUwmLi(k>WydeZ4YsiwCV5q9D z9`fsgp>ljVer;p(hI@m}Ep?3z%gS>X2de7>O@a>8)r_OoG&Y5xtHo3swwf9?kQ%fN zSN(OeUVIC$Z(O%7*lglqWvN-1=TQe@?T>2bF5TSNhKow*=JHU#$ek%ivMxSP>*^cV zRMiL8p!0jEt|nA#a+j-fr<WyBdjU3zU}JZCmQD+iqLAtRhfRbZgnN02tLvV}a_b`uYIJ`nm?F zw6t1KYg!sbxmD8`sA}G@BtOs+s%l0jSMr_}MRzVQmfo(w^l*#N+bt_!8CvpSusYP( zynJO&U}Y8mF5@`4Vu^0F#d*uttYkM@v7CM7;$_Xvjm=;PRJT#C5c2ch z6)Riv19u0TZVIdnR5u5az-1dY+vNmi|;=JGqLH;{_7-B{d+iry9~s0psEYON0iR6guP zm*gyakeqj{4CO9fQ`J&e4Fhq!Skt<8c{Px^)wNa40o2U8Pzw^PQoM{~2jx_L)szfH z5UQ?KDGDvAu5E5?Xj~MyH!nA@Wn)VyxB=zVSiOExL*qj_ID7QWepE7KX(VK zYHn>^izcIUrYx45gY4A=5nzb=J+*cQ>UD?>$Tn&?`BHjR;&yx(Ft1i0T}hca#+b!4A2%Ydk__! zCRw=z^`jhrp}nT6+>xjIn(IPAXQpm!4z>iFA4DlxO`%$pX^m6}JGCorYTHn+VOWMlhjvUhX2#r_4784Tydp2AV~VOcepfZ1W|u18%PoFn%*OJ&r68fO#%cM z&?0Tq5JiEc>~*U2NwLL!fBhTEJ<327E174Id%o2e48k|_jPe)~4Bv{f{bCyDz;B>1rh$<3Jh56=~kI-!f@AJph zvVHn-x%hfX!tYQquD8Wy{mPI z?b>)+?lwysRi7#HS;9B?3!<{SOw_?`&+Rb&!kZ+#DyYF#VR|rk{#yw>K?nu{*{;NC z`s|=!(`(o?F>WV=9I@LJkcOyvnBI@yz#q@>~Moy)lT5bM@dC(b#yic7@Ch z|94BW$&r2Xfm}`2(FCH7<@nqq0@M$~fZjeSaLAyp=jDZq*XAg`+obQdh`nh-6Kb6B z#I4YxCD=~yZ{nIOH?epnG&O$48-XLj#mdi}a87)Yde+b}mfdCZG_Dcau*Aq?Q^Tm1 zk&cQ?NJUhe5}&Oin)34pO#jH5{+IFA29thdLA-9ws2f;jZ1yvw@=%;2Y;$*N4t;Y` zVMYpuL#tI}365*TVg$n$q_E=gukc&Vv#RcmU~@*$;^S6!q@jgP&Iv7I{cP;JP3wOV z^NQ_5@al5Jp}8J@1C)Pe&E!LrHjZdP6H?k`L>zBH z>^i$#ajntA;RioV!dG?K| z@pKS?dOx_k>^5Agxpp%T8`^J- zg77@+v+b6kCqn8Jtj@96rMY!n8f=5)@Enb6rd4887g~4V;2=+t4!ldPcyU*ywIl1w zJApiPOOa&Nmau(rae`gkW(O|51DrA&2ETstX7`K-?i9 z20+K+henT$xr*0SYH9==P>w1LE12LCu$UFf4ZHBObi3qO+o0CKtvp9*xK}dwf zMA}~sY5-Sf<@Iq^R16)b0l=czlYvm-C5$1TVL!uyi`mtBSKTm4svveIo;<2&2_exQ z2nD)SLtzkl=@9BophZzyvmc_JMFoBIWn=PYgU35c`83V)M6(#(sCVj_XRBwtpHWS# zNUb28BV!72K5!1$!_I&1<}d+7^%@qJ7YX}RjaXwuEFcU@QJsa4$E@!|hCNh+4Z&k1VKL#t4=#eGIbAGH ze@}|iXr$*sp3lj-EaPiY6xaww-*u|K+EP6xs$XzY@5dus)>ND4Xo=}57b&U0R&}JV zuS7TNNA_aM|HY4Wl&jsJUy+gW1cF4!H8QqWJV4xydS(htDsDoOGu{YXC&eJ9lb1H< zkdG@KX8;TEJKLu`erGD|5*ZpE(5mPowMtp)&07sc!kw~^AETxes%W>+q89AHR>e-Y zHY!%Q%{*KaHUUC;d52)awrHVQn|5kg@ie&Bk5-`z-xRtb@5L#EV{*8`=1s&xwFwlF zsm2bsy8;YYdp}*!M;1SjENG3=`e-a49!Ow^<)A>r&i4K>U`bk79f=zRcPZW0cOHmhwG59Qe#gqNV{5 zQH4Q5fP`qqPBbd0s|__Ea1j*(@{lW)0E1wCFb090X#BolhuP+79_hHc^lTtR1h}ObeYvp zzyRcU8fCS8?dFPEU11i+V~p;Q@+FXoZ}jgxN)uHXb`i)QG3}DDpk5!v#{Tz~E-RIP z7Vw-P*(hHquw8c4F;R6?&R7?6UKaUM;H+Z8gIfb@Ee#lD50b-~GdrG`k_7Yi0a1lK zS<*t={jJp4vw4XwvV^uCpsY(NZ}by=tyXRa z!|ye-!J|^*yOJTc7{fdHp1E^l&{n4Fm^#=`+jTt{(w7^!FW8KSo1#vKSb14w z$uLWhpC1g<8*_yeSZZz(jG=cJe6{Kvz!(hiIzmby;G3c{ei#hh&&YUZT2E6EEtr+* zj`M7V;R?)!e}+t!kb^D5V7S6}Hblsey>M)fe{-hCVeBz8J)XJup4gxCCj1=t_(^rs zP2Z2GCH;piblKy6{7!GW*Yk6~!e{)%rRlHlQPlFiJ&Z)p(-?Zb5ywCI^6)R!EB*Su zMJ@IHxAL^CRXw7Y_d_UDE zrR>lD4^)#ZR6p942;nLx9YyEY@?U76Baqr(&zWj@qaAIj{j~fV_4w&d(_haaYxzU- z{~LXYe>(qrD+w)sgEsf-kM|uKNq4pX*S5cwpIZ4T-;{10=RfG{&ac0F)$*@scQ5U) z<$uxW_Sg4^YWdHe{%Aifsk7T(e=pmV?&SE~^t1J!pflC!`t^LQmVeR)`+UFu&+Pmo z+pdN7|Fu@wl4zw%OFCQHn}XZFdMgXpbERDA^mFffEaIkb^gRAhp2RWe0sVGC=~uh{ WDe4c+|Ls&p{rhLqU;kCQ_5OdRM!_cl diff --git a/scripts/restart_modem.sh b/scripts/restart_modem.sh deleted file mode 100755 index fac54b32ff..0000000000 --- a/scripts/restart_modem.sh +++ /dev/null @@ -1,2 +0,0 @@ -#!/usr/bin/bash -echo "restart" > /sys/kernel/debug/msm_subsys/modem diff --git a/scripts/throttling.sh b/scripts/throttling.sh deleted file mode 100755 index d100c5f5ab..0000000000 --- a/scripts/throttling.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/data/data/com.termux/files/usr/bin/bash -watch -n1 ' - cat /sys/kernel/debug/clk/pwrcl_clk/measure - cat /sys/kernel/debug/clk/perfcl_clk/measure - cat /sys/devices/system/cpu/cpu*/cpufreq/scaling_cur_freq - cat /sys/class/kgsl/kgsl-3d0/gpuclk - echo - echo -n "CPU0 " ; cat /sys/devices/virtual/thermal/thermal_zone5/temp - echo -n "CPU1 " ; cat /sys/devices/virtual/thermal/thermal_zone7/temp - echo -n "CPU2 " ; cat /sys/devices/virtual/thermal/thermal_zone10/temp - echo -n "CPU3 " ; cat /sys/devices/virtual/thermal/thermal_zone12/temp - echo -n "MEM " ; cat /sys/devices/virtual/thermal/thermal_zone2/temp - echo -n "GPU " ; cat /sys/devices/virtual/thermal/thermal_zone16/temp - echo -n "BAT " ; cat /sys/devices/virtual/thermal/thermal_zone29/temp -' - diff --git a/scripts/waste b/scripts/waste deleted file mode 100755 index e3154ab01f1be61991bcfb2eb99229c5f476b3e5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8608 zcmeHMeQ;FO6+gR=k0gKu3=%4AHhkCwWq0$r8?Cy#m_%r@U`!D^Q(oTgK9U{w%iTpt z`4B~?{LxOcilfu%SgQY!INQlMV*8({tz+%9gM!p)83@45G#d-t){jy9{s0-PlHEf8m)t0P`faO75zLE;4ul;FD( zmckt5XK9#T?$rsF>gl+snrVr^C8VSWRsopk5&<)13yIDaWiyf9c{<7z%5|Rf$X3?^ zop-G$q$foCqil!JBbM}fgkF!(V_GicnR5TAZ}e1(ax;A%%P29`#sc{VKF)-xy|0>t znb3uLRL70_$Nl8-bf){$88zk%M&izBB)&sUH8)b*)Q>0eAvs?>oJvH(Ky#6*YY8Ix z#;K{n)!682_{RF=H#8Nc_{_&gOgH8V6O9GQ(pZwekULYK%J88?{o+RhzQ#+!mU(>` z)g-tXz-~kU)*!pM5Yo8%BKYk^@XjK*S_HQh!Iu`neMN8@=b7x^S_Fq^Bp7m}6A+3f zLObMMHIs?NREVjuw3>mK5=9u&QB_SsG8KtuwnH-0mr|9m9Kv@-1zDyV&% zWGSa32Hdz`95vu#3)fVJ4LI*nRPZ|kF1o78A2;B->lWS@f5RiMQar@jcc-9J}F?EA4q4tKr)5 z_B@Ww@Wy<59xS~t*jH2rMx+CGe=-m9xa|-7FSqAELjChn)zJ7sq!Sa*c>!Jps5*UI zl22n@10`>)$fE2CKad;@jYuU!=O!kWP8^ip`*PF#!7n6Od-b7tgYXYXR9##6$j<%V zXD+TPi;eGDFgU(m%8neAaw7+=_*n3PT#W^~k6vGYvgG4^PhVUQ*|m|ru}c!v@2LLZ z7aJ|}hSo-E#x5X!URqW^B2}#&Mw>2R8#rGBaQqI$Z(jQnVk6S5`W#ZpDyKl*lb8Rd305L%&!UjFy_lWaJB*S zu7H1mKX>?S6XxpzZ7bI2J~->fd}E-i^S)f=xfaYfVLh$6htJ)Gc@OHg<^0$doN5WY zg>|>BXwSi^m4Pm;zEy#fntpv?izeR?cpGJEABQZQY7X2!zV+ntQ?~^+T1v7n=Oqzv+eHz77AEm>Ro#lDj`k0)yHMjK{BeiVJS zcHiEoD=ejd`jr*3ug`%;zAr&H`sqO4+4+jU$Cf31^6QWA>9<0DG1hes}TGrn z?Ol?3U-%RswgLKgUh^&MvHi5R$F`$Zv5lhqF|?sdT5{<;wttDn80ATC6!XuXzHM}# zW6?eOes;u*A00b?b?ljheNFgIe9B-=qoaPi9oDV0>p990(&=}m?Zyq1H^%?d|H%=U z5Q&Yy5l^uOB{SWn!(bPbC0r2={ucHML!!ldJ~D>sG3gfOodcOC=qjJ5{YQ2Pr+lQuHWdYb2kK) zU~|11ayK^D*EM*W++mleA>>j$L6;H?HZ^eRY$V@o)Mtf#KQ-RurEg%o#Fvw~Gm_O7F2OQ+tK^rP`wJgu1f=(5*jl-{(ntF@!m z_h75+ak-p$*ifRiH*^MxR=ZeVMqvp-z6U78CE)d0h|ii_r-k@z;PqLE&jDV?h4@@x z|1QK!fY(JKUJAVa3h^@Fby|qe1NPfOyx2K;0oZvXF(^oI6R@8eU_2)+1oqcLyd2n{ z3-LwJBmBP*Ukto272?y+?NlxS?^aXNv~SFU&nBi2Jy)%f>GOM=z>_9_a0}dJ!s+m8 zG587J4{Z_hcbMdR1a9`9h`?8yG2W zz#Ff|13ahE>3;G{#I1PGQX@VH_Y3)>NN2KNAOGoorQ5#%Tqb|h?VoPXu(0QO{t$_F zkNwAXZvv0W-}LcZ2=|+C-JWvTYQm|Rnfi4SaSQsJ*`Ln{{6q1bC4EYtYwzjn@e1NI z-Q&EZ;qxc&Ig(<2=t_7d`Ogq9$9t|yyVlU;>y{$&s|dHwhol%!z8m;n5&2HU7a8_} z6463flb`Yv#%09G9x&OngX*zP;Vi#f$eZmyK=N2miKvI=pVIItKWF@~s0U2#z9{M` zH`Q|#@x|!R>{t99_zmGWK6}OZaQt>mlZR>P&xp^|-%~~8&m+Fbuz#}smqk71aky5b zo-kT6)4Z4B{xXxF+*$;87Qw+8+!=|6gNckY6H7WnsZ211vBkRJcDJ%!aU@`M*x`bB zc!#XX$?=`BpqkPE5t%?dkx^w4kI0d*8qerZSji}QPK}54OkBY`Noqswjl>-xs=SU~ z_4I0>S0lZeVD)ZnRZeG=R7Q?rFax_3ye=n=-Ka6mW^7=c+l?Vd16nNK_i(`1xnVuX z?H!x^z7Ba)Tib)J-Ez0j-_a^#4f;K(*Q?!G7G8rgs9li?Mi$qfavydws;1;!DJ7Z2 zL72KGos`_%)w&_Dps ztMwm>-NSPGsy62OZ7*Z;3zBima+CMJ0x7sjo|Kxp4i*qN(*3cF5=5Fw>9mh? zc+sq;lHed0ad610yNIJVzSGgCr2D`T?vG;?I?bd&D`Dp{GBTE>)TlxVBA1M2z=4<3 z_)aCX&O4GRmF}ixC6!Y8!C}nPr8VPNhZ2i~u(bp#<17J%&oT1eZzIup5tsB-ILh&W zpmxzq9=;$8;O&(;1d|j@OymMdM^YwaxYm7-E>Av1EOY>zVclL2jS*x&OO_zF)|3 z{Lhrn^`uYV0ki&I#K zgI$P<2H4L8I_W>m{}D6PzKa2-Lcfs;4T)JJ<+(SAfoGA /sys/devices/soc/spm-regulator-10/regulator/regulator.56/99e8000.cpr3-ctrl-vdd/driver/unbind") -os.system("echo 1 > /sys/kernel/debug/regulator/pm8994_s11/enable") - -if len(sys.argv) > 1: - i = int(sys.argv[1]) - os.system("echo %d %d > /sys/kernel/debug/regulator/pm8994_s11/voltage" % (i,i)) - os.system("cat /sys/kernel/debug/regulator/pm8994_s11/voltage") -else: - for i in range(900000, 465000, -10000): - print("setting voltage to",i) - os.system("echo %d %d > /sys/kernel/debug/regulator/pm8994_s11/voltage" % (i,i)) - os.system("cat /sys/kernel/debug/regulator/pm8994_s11/voltage") - time.sleep(1) - diff --git a/selfdrive/debug/internal/sensor_test_bootloop.py b/selfdrive/debug/internal/sensor_test_bootloop.py deleted file mode 100755 index 36eb112e44..0000000000 --- a/selfdrive/debug/internal/sensor_test_bootloop.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/python3 -import sys -import os -import stat -import subprocess -import json -from common.text_window import TextWindow -import time - -# Required for sensord not to bus-error on startup -# commaai/cereal#22 -try: - os.mkdir("/dev/shm") -except FileExistsError: - pass -except PermissionError: - print("WARNING: failed to make /dev/shm") - -try: - with open('/tmp/sensor-test-results.json') as infile: - data = json.load(infile) -except Exception: - data = {'sensor-pass': 0, 'sensor-fail': 0} - -STARTUP_SCRIPT = "/data/data/com.termux/files/continue.sh" -try: - with open(STARTUP_SCRIPT, 'w') as startup_script: - startup_script.write("#!/usr/bin/bash\n\n/data/openpilot/selfdrive/debug/internal/sensor_test_bootloop.py\n") - os.chmod(STARTUP_SCRIPT, stat.S_IRWXU) -except Exception: - print("Failed to install new startup script -- aborting") - sys.exit(-1) - -sensord_env = {**os.environ, 'SENSOR_TEST': '1'} -process = subprocess.run("./sensord", cwd="/data/openpilot/selfdrive/sensord", env=sensord_env) # pylint: disable=subprocess-run-check - -if process.returncode == 40: - text = "Current run: SUCCESS\n" - data['sensor-pass'] += 1 -else: - text = "Current run: FAIL\n" - data['sensor-fail'] += 1 - - timestr = str(int(time.time())) - with open('/tmp/dmesg-' + timestr + '.log', 'w') as dmesg_out: - subprocess.call('dmesg', stdout=dmesg_out, shell=False) - with open("/tmp/logcat-" + timestr + '.log', 'w') as logcat_out: - subprocess.call(['logcat', '-d'], stdout=logcat_out, shell=False) - -text += "Sensor pass history: " + str(data['sensor-pass']) + "\n" -text += "Sensor fail history: " + str(data['sensor-fail']) + "\n" - -print(text) - -with open('/tmp/sensor-test-results.json', 'w') as outfile: - json.dump(data, outfile, indent=4) - -with TextWindow(text) as status: - for _ in range(100): - if status.get_status() == 1: - with open(STARTUP_SCRIPT, 'w') as startup_script: - startup_script.write("#!/usr/bin/bash\n\ncd /data/openpilot\nexec ./launch_openpilot.sh\n") - os.chmod(STARTUP_SCRIPT, stat.S_IRWXU) - break - time.sleep(0.1) - -subprocess.Popen("reboot") From 95fa6b1df86b62d98e14319f5bd5cbb1621214a2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 11:47:14 +0200 Subject: [PATCH 10/32] camerad: get embedded statistics and data by embedding in pixel data (#24353) * camerad: AR0231 read embedded data and statistics * reorder * remove unrelated camera config --- selfdrive/camerad/cameras/camera_common.cc | 6 +- selfdrive/camerad/cameras/camera_common.h | 8 +- selfdrive/camerad/cameras/camera_qcom2.cc | 133 ++++++++++++++++++--- selfdrive/camerad/cameras/camera_qcom2.h | 9 ++ selfdrive/camerad/cameras/camera_replay.cc | 6 +- selfdrive/camerad/cameras/real_debayer.cl | 2 +- selfdrive/camerad/cameras/sensor2_i2c.h | 20 ++-- 7 files changed, 150 insertions(+), 34 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 77b0548873..676e740811 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -36,10 +36,10 @@ public: hdr_ = ci->hdr; snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero " - "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d " + "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d " "-DBAYER_FLIP=%d -DHDR=%d -DCAM_NUM=%d", - ci->frame_width, ci->frame_height, ci->frame_stride, + ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, b->rgb_width, b->rgb_height, b->rgb_stride, ci->bayer_flip, ci->hdr, s->camera_num); const char *cl_file = "cameras/real_debayer.cl"; @@ -81,7 +81,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, frame_buf_count = frame_cnt; // RAW frame - const int frame_size = ci->frame_height * ci->frame_stride; + const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; camera_bufs = std::make_unique(frame_buf_count); camera_bufs_metadata = std::make_unique(frame_buf_count); diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 9c7bf6b034..8c836e0bb8 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -52,11 +52,15 @@ const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; typedef void (*release_cb)(void *cookie, int buf_idx); typedef struct CameraInfo { - int frame_width, frame_height; - int frame_stride; + uint32_t frame_width, frame_height; + uint32_t frame_stride; bool bayer; int bayer_flip; bool hdr; + uint32_t frame_offset = 0; + uint32_t extra_height = 0; + int registers_offset = -1; + int stats_offset = -1; } CameraInfo; typedef struct FrameMetadata { diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index 7120bf9576..ce9b5663d8 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -31,6 +31,9 @@ const size_t FRAME_WIDTH = 1928; const size_t FRAME_HEIGHT = 1208; const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) +const size_t AR0231_REGISTERS_HEIGHT = 2; +const size_t AR0231_STATS_HEIGHT = 2; + const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py CameraInfo cameras_supported[CAMERA_ID_MAX] = { @@ -38,17 +41,24 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { .frame_width = FRAME_WIDTH, .frame_height = FRAME_HEIGHT, .frame_stride = FRAME_STRIDE, + .extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT, + + .registers_offset = 0, + .frame_offset = AR0231_REGISTERS_HEIGHT, + .stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT, + .bayer = true, .bayer_flip = 1, - .hdr = false + .hdr = false, }, [CAMERA_ID_IMX390] = { .frame_width = FRAME_WIDTH, .frame_height = FRAME_HEIGHT, .frame_stride = FRAME_STRIDE, + .bayer = true, .bayer_flip = 1, - .hdr = false + .hdr = false, }, }; @@ -509,10 +519,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b if (io_mem_handle != 0) { io_cfg[0].mem_handle[0] = io_mem_handle; io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, - .plane_stride = FRAME_STRIDE, - .slice_height = FRAME_HEIGHT, + .width = ci.frame_width, + .height = ci.frame_height + ci.extra_height, + .plane_stride = ci.frame_stride, + .slice_height = ci.frame_height + ci.extra_height, .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) .meta_size = 0x0, .meta_offset = 0x0, @@ -682,23 +692,23 @@ void CameraState::camera_open() { .lane_cfg = 0x3210, .vc = 0x0, - .dt = 0x2C, // CSI_RAW12 + .dt = 0x12, // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead .format = CAM_FORMAT_MIPI_RAW_12, .test_pattern = 0x2, // 0x3? .usage_type = 0x0, .left_start = 0, - .left_stop = FRAME_WIDTH - 1, - .left_width = FRAME_WIDTH, + .left_stop = ci.frame_width - 1, + .left_width = ci.frame_width, .right_start = 0, - .right_stop = FRAME_WIDTH - 1, - .right_width = FRAME_WIDTH, + .right_stop = ci.frame_width - 1, + .right_width = ci.frame_width, .line_start = 0, - .line_stop = FRAME_HEIGHT - 1, - .height = FRAME_HEIGHT, + .line_stop = ci.frame_height + ci.extra_height - 1, + .height = ci.frame_height + ci.extra_height, .pixel_clk = 0x0, .batch_size = 0x0, @@ -710,8 +720,8 @@ void CameraState::camera_open() { .data[0] = (struct cam_isp_out_port_info){ .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, .format = CAM_FORMAT_MIPI_RAW_12, - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, + .width = ci.frame_width, + .height = ci.frame_height + ci.extra_height, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }, }; @@ -935,6 +945,70 @@ void cameras_close(MultiCameraState *s) { delete s->pm; } +std::map> CameraState::ar0231_build_register_lut(uint8_t *data) { + // This function builds a lookup table from register address, to a pair of indices in the + // buffer where to read this address. The buffer contains padding bytes, + // as well as markers to indicate the type of the next byte. + // + // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. + // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional + // for contigous ranges. See page 27-29 of the AR0231 Developer guide for more information. + + int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; + auto get_next_idx = [](int cur_idx) { + return (cur_idx % 3 == 1) ? cur_idx + 2 : cur_idx + 1; // Every third byte is padding + }; + + std::map> registers; + for (int register_row = 0; register_row < 2; register_row++) { + uint8_t *registers_raw = data + ci.frame_stride * register_row; + assert(registers_raw[0] == 0x0a); // Start of line + + int value_tag_count = 0; + int first_val_idx = 0; + uint16_t cur_addr = 0; + + for (int i = 1; i <= max_i[register_row]; i = get_next_idx(get_next_idx(i))) { + int val_idx = get_next_idx(i); + + uint8_t tag = registers_raw[i]; + uint16_t val = registers_raw[val_idx]; + + if (tag == 0xAA) { // Register MSB tag + cur_addr = val << 8; + } else if (tag == 0xA5) { // Register LSB tag + cur_addr |= val; + cur_addr -= 2; // Next value tag will increment address again + } else if (tag == 0x5A) { // Value tag + + // First tag + if (value_tag_count % 2 == 0) { + cur_addr += 2; + first_val_idx = val_idx; + } else { + registers[cur_addr] = std::make_pair(first_val_idx + ci.frame_stride * register_row, val_idx + ci.frame_stride * register_row); + } + + value_tag_count++; + } + } + } + return registers; +} + +std::map CameraState::ar0231_parse_registers(uint8_t *data, std::initializer_list addrs) { + if (ar0231_register_lut.empty()) { + ar0231_register_lut = ar0231_build_register_lut(data); + } + + std::map registers; + for (uint16_t addr : addrs) { + auto offset = ar0231_register_lut[addr]; + registers[addr] = ((uint16_t)data[offset.first] << 8) | data[offset.second]; + } + return registers; +} + void CameraState::handle_camera_event(void *evdat) { if (!enabled) return; struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; @@ -1114,6 +1188,25 @@ void camera_autoexposure(CameraState *s, float grey_frac) { s->set_camera_exposure(grey_frac); } +static float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { + // See AR0231 Developer Guide - page 36 + float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); + float t0 = 55.0 - slope * (float)calib2; + return t0 + slope * (float)data_reg; +} + +static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal::FrameData::Builder &framed){ + uint8_t *data = (uint8_t*)c->buf.cur_camera_buf->addr + c->ci.registers_offset; + auto registers = c->ar0231_parse_registers(data, {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}); + + uint32_t frame_id = ((uint32_t)registers[0x2000] << 16) | registers[0x2002]; + framed.setFrameIdSensor(frame_id); + + float temp_0 = ar0231_parse_temp_sensor(registers[0x30c6], registers[0x30c8], registers[0x20b0]); + float temp_1 = ar0231_parse_temp_sensor(registers[0x30ca], registers[0x30cc], registers[0x20b2]); + framed.setTemperaturesC({temp_0, temp_1}); +} + static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; const CameraBuf *b = &c->buf; @@ -1132,10 +1225,12 @@ static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) if (env_send_driver) { framed.setImage(get_frame_image(&c->buf)); } + if (c->camera_id == CAMERA_ID_AR0231) { + ar0231_process_registers(s, c, framed); + } s->pm->send("driverCameraState", msg); } -// called by processing_thread void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { const CameraBuf *b = &c->buf; @@ -1152,6 +1247,11 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { framed.setTransform(b->yuv_transform.v); LOGT(c->buf.cur_frame_data.frame_id, "%s: Transformed", "RoadCamera"); } + + if (c->camera_id == CAMERA_ID_AR0231) { + ar0231_process_registers(s, c, framed); + } + s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); @@ -1221,3 +1321,4 @@ void cameras_run(MultiCameraState *s) { cameras_close(s); } + diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h index a7c64c0665..e0553f000e 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ b/selfdrive/camerad/cameras/camera_qcom2.h @@ -1,6 +1,8 @@ #pragma once #include +#include +#include #include @@ -56,6 +58,8 @@ public: void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, int camera_id, int camera_num, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType rgb_type, VisionStreamType yuv_type, bool enabled); void camera_close(); + std::map ar0231_parse_registers(uint8_t *data, std::initializer_list addrs); + int32_t session_handle; int32_t sensor_dev_handle; int32_t isp_dev_handle; @@ -75,6 +79,7 @@ public: CameraBuf buf; MemoryManager mm; + private: void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); void enqueue_req_multi(int start, int n, bool dp); @@ -84,6 +89,10 @@ private: int sensors_init(); void sensors_poke(int request_id); void sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); + + // Register parsing + std::map> ar0231_register_lut; + std::map> ar0231_build_register_lut(uint8_t *data); }; typedef struct MultiCameraState { diff --git a/selfdrive/camerad/cameras/camera_replay.cc b/selfdrive/camerad/cameras/camera_replay.cc index a9983fe23e..05bdfb9236 100644 --- a/selfdrive/camerad/cameras/camera_replay.cc +++ b/selfdrive/camerad/cameras/camera_replay.cc @@ -30,9 +30,9 @@ void camera_init(VisionIpcServer *v, CameraState *s, int camera_id, unsigned int } CameraInfo ci = { - .frame_width = s->frame->width, - .frame_height = s->frame->height, - .frame_stride = s->frame->width * 3, + .frame_width = (uint32_t)s->frame->width, + .frame_height = (uint32_t)s->frame->height, + .frame_stride = (uint32_t)s->frame->width * 3, }; s->ci = ci; s->camera_num = camera_id; diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 50a7846213..783abaabb4 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -42,7 +42,7 @@ half3 color_correct(half3 rgb) { inline half val_from_10(const uchar * source, int gx, int gy, half black_level) { // parse 12bit - int start = gy * FRAME_STRIDE + (3 * (gx / 2)); + int start = gy * FRAME_STRIDE + (3 * (gx / 2)) + (FRAME_STRIDE * FRAME_OFFSET); int offset = gx % 2; uint major = (uint)source[start + offset] << 4; uint minor = (source[start + 2] >> (4 * offset)) & 0xf; diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index e85223243f..650c17cdfa 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -7,7 +7,7 @@ struct i2c_random_wr_payload init_array_imx390[] = { {0x2008, 0xd0}, {0x2009, 0x07}, {0x200a, 0x00}, // MODE_VMAX = time between frames {0x200C, 0xe4}, {0x200D, 0x0c}, // MODE_HMAX - // crop + // crop {0x3410, 0x88}, {0x3411, 0x7}, // CROP_H_SIZE {0x3418, 0xb8}, {0x3419, 0x4}, // CROP_V_SIZE {0x0078, 1}, {0x03c0, 1}, @@ -67,7 +67,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x30A6, 0x0001}, // Y_ODD_INC_ {0x3402, 0x0788}, // X_OUTPUT_CONTROL {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL - {0x3064, 0x1802}, // SMIA_TEST + {0x3064, 0x1982}, // SMIA_TEST {0x30BA, 0x11F2}, // DIGITAL_CTRL // Enable external trigger and disable GPIO outputs @@ -83,10 +83,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { // Readout Settings {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 - {0x3342, 0x122C}, // MIPI_F1_PDT_EDT - {0x3346, 0x122C}, // MIPI_F2_PDT_EDT - {0x334A, 0x122C}, // MIPI_F3_PDT_EDT - {0x334E, 0x122C}, // MIPI_F4_PDT_EDT + {0x3342, 0x1212}, // MIPI_F1_PDT_EDT + {0x3346, 0x1212}, // MIPI_F2_PDT_EDT + {0x334A, 0x1212}, // MIPI_F3_PDT_EDT + {0x334E, 0x1212}, // MIPI_F4_PDT_EDT {0x3344, 0x0011}, // MIPI_F1_VDT_VC {0x3348, 0x0111}, // MIPI_F2_VDT_VC {0x334C, 0x0211}, // MIPI_F3_VDT_VC @@ -101,6 +101,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x3370, 0x03B1}, // DBLC {0x3044, 0x0400}, // DARK_CONTROL + // Enable temperature sensor + {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG + {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG + // Enable dead pixel correction using // the 1D line correction scheme {0x31E0, 0x0003}, @@ -114,9 +118,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x08CB}, // FINE_INTEGRATION_TIME2 - {0x321E, 0x08CB}, // FINE_INTEGRATION_TIME3 - {0x321E, 0x0894}, // FINE_INTEGRATION_TIME4 + {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? {0x33DA, 0x0000}, // COMPANDING From df8f024e19de2d7a528b5921f73895f2078cf03a Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Fri, 6 May 2022 11:47:58 +0200 Subject: [PATCH 11/32] uploader: size limit for automatic uploading of qlogs/qcams (#24403) * uploader: size limit for automatic uploading of qlogs/qcams * move check to add logging * use constant * mark as uploaded Co-authored-by: Willem Melching --- selfdrive/loggerd/uploader.py | 34 ++++++++++++++++++---------------- 1 file changed, 18 insertions(+), 16 deletions(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 50557fffaa..87988171fb 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -23,6 +23,8 @@ NetworkType = log.DeviceState.NetworkType UPLOAD_ATTR_NAME = 'user.upload' UPLOAD_ATTR_VALUE = b'1' +UPLOAD_QLOG_QCAM_MAX_SIZE = 1e7 # 10 MB + allow_sleep = bool(os.getenv("UPLOADER_SLEEP", "1")) force_wifi = os.getenv("FORCEWIFI") is not None fake_upload = os.getenv("FAKEUPLOAD") is not None @@ -121,11 +123,11 @@ class Uploader(): for name, key, fn in upload_files: if any(f in fn for f in self.immediate_folders): - return (key, fn) + return (name, key, fn) for name, key, fn in upload_files: if name in self.immediate_priority: - return (key, fn) + return (name, key, fn) return None @@ -172,7 +174,7 @@ class Uploader(): return self.last_resp - def upload(self, key, fn, network_type, metered): + def upload(self, name, key, fn, network_type, metered): try: sz = os.path.getsize(fn) except OSError: @@ -182,22 +184,15 @@ class Uploader(): cloudlog.event("upload_start", key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) if sz == 0: - try: - # tag files of 0 size as uploaded - setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) - except OSError: - cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + # tag files of 0 size as uploaded + success = True + elif name in self.immediate_priority and sz > UPLOAD_QLOG_QCAM_MAX_SIZE: + cloudlog.event("uploader_too_large", key=key, fn=fn, sz=sz) success = True else: start_time = time.monotonic() stat = self.normal_upload(key, fn) if stat is not None and stat.status_code in (200, 201, 401, 403, 412): - try: - # tag file as uploaded - setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) - except OSError: - cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) - self.last_filename = fn self.last_time = time.monotonic() - start_time self.last_speed = (sz / 1e6) / self.last_time @@ -207,6 +202,13 @@ class Uploader(): success = False cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) + if success: + # tag file as uploaded + try: + setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) + except OSError: + cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + return success def get_msg(self): @@ -258,13 +260,13 @@ def uploader_fn(exit_event): time.sleep(60 if offroad else 5) continue - key, fn = d + name, key, fn = d # qlogs and bootlogs need to be compressed before uploading if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): key += ".bz2" - success = uploader.upload(key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) + success = uploader.upload(name, key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) if success: backoff = 0.1 elif allow_sleep: From b64fe6e339c8b8b3f5016a9c58b553c91abc5bdf Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 04:41:14 -0700 Subject: [PATCH 12/32] Laikad: the basics for ublox msg processing (#24359) * Add laikad that receives ublox messages and publishes corrected measurements and position fix * types * cleanup * laikad version 1 with uncorrected measurements * push * Fix glonass frequency and delete redundant test * Update after cereal and cleanup * Add test, fix laikad and remove process replay for now * update laika * add hatanaka to packages. Used to decompress orbit data * Fix pip --- Pipfile | 1 + Pipfile.lock | 63 ++++++++++++++++++- laika_repo | 2 +- selfdrive/locationd/laikad.py | 84 +++++++++++++++++++++++++ selfdrive/locationd/test/test_laikad.py | 23 +++++++ 5 files changed, 170 insertions(+), 3 deletions(-) create mode 100755 selfdrive/locationd/laikad.py create mode 100755 selfdrive/locationd/test/test_laikad.py diff --git a/Pipfile b/Pipfile index 473b873077..af3e02f54a 100644 --- a/Pipfile +++ b/Pipfile @@ -82,6 +82,7 @@ tqdm = "*" urllib3 = "*" utm = "*" websocket_client = "*" +hatanaka = "*" [requires] python_version = "3.8" diff --git a/Pipfile.lock b/Pipfile.lock index 4398c37d29..5ee3f2b031 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "918c8cba5c6a0242dc0f6ea74246176a1c54f0a9395feddf35af2189cc813378" + "sha256": "19a7b58f24cd7542ccb9fd386c7716d77fff3c1f87de496f3f42753cf34a5dde" }, "pipfile-spec": 6, "requires": { @@ -281,6 +281,16 @@ "index": "pypi", "version": "==20.1.0" }, + "hatanaka": { + "hashes": [ + "sha256:0e095d35ed4f607eb77ae47ecb310e4c25f5a6267037b703ea258ed03e5c47da", + "sha256:84faa953b4f641a6d3cf8187f1775ba7e7f8d815f7bcd48cfb18553b766cbc41", + "sha256:ccf8be554deee2fc70be52bd2f1d3d4dd370001caa74333bf041933d69a19023", + "sha256:ce1628029c6b50c142a8fc5f15453c4cf2a3fd88a7128075415aeb5c9a2727d0" + ], + "index": "pypi", + "version": "==2.8.0" + }, "hexdump": { "hashes": [ "sha256:d781a43b0c16ace3f9366aade73e8ad3a7bd5137d58f0b45ab2d3f54876f20db" @@ -304,12 +314,20 @@ "markers": "python_version < '3.10'", "version": "==4.11.3" }, + "importlib-resources": { + "hashes": [ + "sha256:b6062987dfc51f0fcb809187cffbd60f35df7acb4589091f154214af6d0d49d3", + "sha256:e447dc01619b1e951286f3929be820029d48c75eb25d265c28b92a16548212b8" + ], + "markers": "python_version >= '3.7'", + "version": "==5.7.1" + }, "isort": { "hashes": [ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", + "markers": "python_version < '4' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -449,6 +467,47 @@ ], "version": "==1.2.1" }, + "ncompress": { + "hashes": [ + "sha256:0349d7de11edd70a7efea9ce9dc67f0e47b5774832dd063f7ae68a9e3e36ea31", + "sha256:070044eab19586a45d1855c3e50e000ce86d6075b122a5ec8cffd480713dffac", + "sha256:13fa26ec8000d786a8079bb265508b5df4b445a4f460481a13549b4bd3c83824", + "sha256:15f10fbfa11345ff0af090e3e6ae13a1fe2b52a2bb39d4f2373c2d6aeac75e5d", + "sha256:2a104803fbe3ab0a96edb14927fa22c8142be838aabe7e938b4a52a4e82db56e", + "sha256:34754041d9bac2d6908ae0d07ba541e4d6d606cca222ddd53f3a57e15f386b0a", + "sha256:34c6496168fd4dbc13f1fc0c0fcbadded1957639956f8cbc6894c39999817e36", + "sha256:3590e66313041721ae81e72ece06b7048c9293321bb30900358638673608e264", + "sha256:393cc3c126b9451fb32fe2bc07773264c90e73afbd37da0df472ac23bfd1a2d5", + "sha256:5336a8831a7e587829ce54e9e27d1fb2e04ddbc7d2d983693e35a3a03ac3ce79", + "sha256:5a2ae8a9170fa1f45df7efa292eb8c437b18c225b63d4adca4f50f9da0e8e0c7", + "sha256:6540556d47670a8fb93878a44d0206bbdc87f32e4c5b57d6fe63691efafbb982", + "sha256:66d991155a1655ccd98e8433c4a7e811d63eb649adb55f47d8f9528a30cc4b7a", + "sha256:736dbae078107742cf6ac7ccc11ae9c5eab77ef2c02aab3ef64802877bb01cab", + "sha256:7608fbda43d04d9f476be2dbf4ef3c96e72d83b9557a48b07fbc9ff3ad29cdd2", + "sha256:78674f246878938387b6f82b10d1aa2192e02544d214541943d12ef1a45e66c6", + "sha256:8322482e72ac2802d1dca1007ec06aa281a4d5cf1cf9f8c75bb51e917382b756", + "sha256:8b9acc46cf36bb998ed215d6e76a94e2bd1e827b9a4cb5362982b7004b5a7620", + "sha256:8eb4a55cbeaeb238a3b412952077be6b3f37b3416cd0211cc22776391ff2fef7", + "sha256:916671d62167191af58d6b4a17b1c09c647e349dcff1fc0b7d764aa64c3773ee", + "sha256:94b3f4e851f5b37e1d4cf2d8da911fa10783a59cba3d7f1f2ae5bd2842558077", + "sha256:9cd040ad73a3b0e917e01cdfba507e10e0bb56849daaac3ac3d86382d4d7ad82", + "sha256:9d89acf209858e7940223cf35324e1b2effec119bb009a41f039e2ea4db22177", + "sha256:9da7c81313aed4b6c6e8020442ed8d03d04bff72947f9380ea1ce2c63ffb8ad1", + "sha256:aaa18a509d9fc173b4b47d53c834e43ced1eda63d2aa7d4613dc59b2f802a31a", + "sha256:ab9fc62baaa55faf8ed8ac67f2c64a7295fec91d7c1f306ac46aa894ca4edf91", + "sha256:af0011bae90e44121f4e4edbff3dccdce7e4c5fc5e354db7eb48410d71f496df", + "sha256:b031e06b42037b181e3514261e1e85a9eae4af990c12b9348a9f22b8042201ff", + "sha256:d11df815d280985dfa660974df11dbe051a1a18dca2f91f9d30fbd6548237b8f", + "sha256:d45ec59a8a3ce00613df0c81e5567854574dbbbf01ecd1a5a0929cd8fb04844d", + "sha256:da216a53db7cd4c0247376f87367dd71df457443567e55310f6d3d23a9aff2f2", + "sha256:e0ebd71990ef7909b6627b5341a2fe1977dcce61dd3760a29e19e3f9e4c6a275", + "sha256:e6f5bf381412e9d3847b76e8b6bd1f84dfadcd3d9c25903c8592facb437909a0", + "sha256:e7bbf10cca1376f4f17ae2c447e33a9d4067525abb0c71d488c9a5ced50552f1", + "sha256:f9ba6ab2aadd6fd90365fdad5219e4dc7bc2459b94f1e900a733dddaf4e9b2e6", + "sha256:fe0a671a2f7dc1ee0438d278ef30ab425a969536100c4352b5cb6bc0b6210818" + ], + "version": "==1.0.0" + }, "nose": { "hashes": [ "sha256:9ff7c6cc443f8c51994b34a667bbcf45afd6d945be7477b52e97516fd17c53ac", diff --git a/laika_repo b/laika_repo index 226adc655e..1fbc6780d5 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 226adc655e1488474468a97ab4a7705aad7e5837 +Subproject commit 1fbc6780d5184efd5ccf4518a01fe947ffbb4ba0 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py new file mode 100755 index 0000000000..28150bfea9 --- /dev/null +++ b/selfdrive/locationd/laikad.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 +from typing import List + +from cereal import log, messaging +from laika import AstroDog +from laika.helpers import UbloxGnssId +from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox + + +def correct_and_pos_fix(processed_measurements: List[GNSSMeasurement], dog: AstroDog): + # pos fix needs more than 5 processed_measurements + pos_fix = calc_pos_fix(processed_measurements) + + if len(pos_fix) == 0: + return [], [] + est_pos = pos_fix[0][:3] + corrected = correct_measurements(processed_measurements, est_pos, dog) + return calc_pos_fix(corrected), corrected + + +def process_ublox_msg(ublox_msg, dog, ublox_mono_time: int): + if ublox_msg.which == 'measurementReport': + report = ublox_msg.measurementReport + if len(report.measurements) == 0: + return None + new_meas = read_raw_ublox(report) + processed_measurements = process_measurements(new_meas, dog) + + corrected = correct_and_pos_fix(processed_measurements, dog) + pos_fix, _ = corrected + # todo send corrected messages instead of processed_measurements. Need fix for when having less than 6 measurements + correct_meas_msgs = [create_measurement_msg(m) for m in processed_measurements] + # pos fix can be an empty list if not enough correct measurements are available + if len(pos_fix) > 0: + corrected_pos = pos_fix[0][:3].tolist() + else: + corrected_pos = [0., 0., 0.] + dat = messaging.new_message('gnssMeasurements') + dat.gnssMeasurements = { + "position": corrected_pos, + "ubloxMonoTime": ublox_mono_time, + "correctedMeasurements": correct_meas_msgs + } + return dat + + +def create_measurement_msg(meas: GNSSMeasurement): + c = log.GnssMeasurements.CorrectedMeasurement.new_message() + ublox_gnss_id = meas.ublox_gnss_id + if ublox_gnss_id is None: + # todo never happens will fix in later pr + ublox_gnss_id = UbloxGnssId.GPS + c.constellationId = ublox_gnss_id.value + c.svId = int(meas.prn[1:]) + c.glonassFrequency = meas.glonass_freq if meas.ublox_gnss_id == UbloxGnssId.GLONASS else 0 + c.pseudorange = float(meas.observables['C1C']) # todo should be observables_final when using corrected measurements + c.pseudorangeStd = float(meas.observables_std['C1C']) + c.pseudorangeRate = float(meas.observables['D1C']) # todo should be observables_final when using corrected measurements + c.pseudorangeRateStd = float(meas.observables_std['D1C']) + c.satPos = meas.sat_pos_final.tolist() + c.satVel = meas.sat_vel.tolist() + return c + + +def main(): + dog = AstroDog() + sm = messaging.SubMaster(['ubloxGnss']) + pm = messaging.PubMaster(['gnssMeasurements']) + + while True: + sm.update() + + # Todo if no internet available use latest ephemeris + if sm.updated['ubloxGnss']: + ublox_msg = sm['ubloxGnss'] + msg = process_ublox_msg(ublox_msg, dog, sm.logMonoTime['ubloxGnss']) + if msg is None: + msg = messaging.new_message('gnssMeasurements') + pm.send('gnssMeasurements', msg) + + + +if __name__ == "__main__": + main() diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py new file mode 100755 index 0000000000..877623f0bd --- /dev/null +++ b/selfdrive/locationd/test/test_laikad.py @@ -0,0 +1,23 @@ +#!/usr/bin/env python3 +import unittest +from datetime import datetime + +from laika.helpers import UbloxGnssId + +from laika.gps_time import GPSTime +from laika.raw_gnss import GNSSMeasurement +from selfdrive.locationd.laikad import create_measurement_msg + + +class TestLaikad(unittest.TestCase): + + def test_create_msg_without_errors(self): + gpstime = GPSTime.from_datetime(datetime.now()) + meas = GNSSMeasurement('G01', gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}, ublox_gnss_id=UbloxGnssId.GPS) + msg = create_measurement_msg(meas) + + self.assertEqual(msg.constellationId, 'gps') + + +if __name__ == "__main__": + unittest.main() From 634f630e08c2ad91701a1f3c80574549fd12170c Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 06:44:09 -0700 Subject: [PATCH 13/32] Bump laika and cereal (#24451) --- cereal | 2 +- laika_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 5935572cee..122dbf70d0 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 5935572cee86f202e2524d5f388f9475f92cd649 +Subproject commit 122dbf70d0fe71f9b7d3bf616b4e35b51c9fb04e diff --git a/laika_repo b/laika_repo index 1fbc6780d5..48a9cb686a 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 1fbc6780d5184efd5ccf4518a01fe947ffbb4ba0 +Subproject commit 48a9cb686ae2d12cd830f17c166a8fb9f79ab292 From e6f9f12d1c9faae8f718306bcd2862278a083351 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 06:44:38 -0700 Subject: [PATCH 14/32] Test gnssUblox message processing (#24404) * Add simple test for processing ublox messages * Add simple test for processing ublox messages * Update selfdrive/locationd/test/test_ublox_processing.py Co-authored-by: Willem Melching * Update * Push laika ref Co-authored-by: Willem Melching --- .../locationd/test/test_ublox_processing.py | 80 +++++++++++++++++++ 1 file changed, 80 insertions(+) create mode 100755 selfdrive/locationd/test/test_ublox_processing.py diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py new file mode 100755 index 0000000000..94fddb9392 --- /dev/null +++ b/selfdrive/locationd/test/test_ublox_processing.py @@ -0,0 +1,80 @@ +import unittest + +import numpy as np + +from laika import AstroDog +from laika.helpers import UbloxGnssId +from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox +from selfdrive.test.openpilotci import get_url +from tools.lib.logreader import LogReader + + +def get_gnss_measurements(log_reader): + gnss_measurements = [] + for msg in log_reader: + if msg.which() == "ubloxGnss": + ublox_msg = msg.ubloxGnss + if ublox_msg.which == 'measurementReport': + report = ublox_msg.measurementReport + if len(report.measurements) > 0: + gnss_measurements.append(read_raw_ublox(report)) + return gnss_measurements + + +class TestUbloxProcessing(unittest.TestCase): + NUM_TEST_PROCESS_MEAS = 10 + + @classmethod + def setUpClass(cls): + lr = LogReader(get_url("4cf7a6ad03080c90|2021-09-29--13-46-36", 0)) + cls.gnss_measurements = get_gnss_measurements(lr) + + def test_read_ublox_raw(self): + count_gps = 0 + count_glonass = 0 + for measurements in self.gnss_measurements: + for m in measurements: + if m.ublox_gnss_id == UbloxGnssId.GPS: + count_gps += 1 + elif m.ublox_gnss_id == UbloxGnssId.GLONASS: + count_glonass += 1 + + self.assertEqual(count_gps, 5036) + self.assertEqual(count_glonass, 3651) + + def test_get_fix(self): + dog = AstroDog() + position_fix_found = 0 + count_processed_measurements = 0 + count_corrected_measurements = 0 + position_fix_found_after_correcting = 0 + + pos_ests = [] + for measurements in self.gnss_measurements[:self.NUM_TEST_PROCESS_MEAS]: + processed_meas = process_measurements(measurements, dog) + count_processed_measurements += len(processed_meas) + pos_fix = calc_pos_fix(processed_meas) + if len(pos_fix) > 0 and all(pos_fix[0] != 0): + position_fix_found += 1 + + corrected_meas = correct_measurements(processed_meas, pos_fix[0][:3], dog) + count_corrected_measurements += len(corrected_meas) + + pos_fix = calc_pos_fix(corrected_meas) + if len(pos_fix) > 0 and all(pos_fix[0] != 0): + pos_ests.append(pos_fix[0]) + position_fix_found_after_correcting += 1 + + mean_fix = np.mean(np.array(pos_ests)[:, :3], axis=0) + np.testing.assert_allclose(mean_fix, [-2452306.662377, -4778343.136806, 3428550.090557], rtol=0, atol=1) + + # Note that can happen that there are less corrected measurements compared to processed when they are invalid. + # However, not for the current segment + self.assertEqual(position_fix_found, self.NUM_TEST_PROCESS_MEAS) + self.assertEqual(position_fix_found_after_correcting, self.NUM_TEST_PROCESS_MEAS) + self.assertEqual(count_processed_measurements, 69) + self.assertEqual(count_corrected_measurements, 69) + + +if __name__ == "__main__": + unittest.main() From 85975e3dd91421ac3fffd03f75428257ce42b5b8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 16:32:44 +0200 Subject: [PATCH 15/32] test_debayer.py some PC fixes (#24449) * test_debayer.py some PC fixes * fix rgb shape --- selfdrive/test/process_replay/.gitignore | 1 + selfdrive/test/process_replay/test_debayer.py | 24 +++++++++++++------ 2 files changed, 18 insertions(+), 7 deletions(-) diff --git a/selfdrive/test/process_replay/.gitignore b/selfdrive/test/process_replay/.gitignore index a35cd58d41..63c37e64e1 100644 --- a/selfdrive/test/process_replay/.gitignore +++ b/selfdrive/test/process_replay/.gitignore @@ -1 +1,2 @@ fakedata/ +debayer_diff.txt diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py index 17fa9afd63..6488184263 100755 --- a/selfdrive/test/process_replay/test_debayer.py +++ b/selfdrive/test/process_replay/test_debayer.py @@ -24,9 +24,11 @@ UV_WIDTH = FRAME_WIDTH // 2 UV_HEIGHT = FRAME_HEIGHT // 2 UV_SIZE = UV_WIDTH * UV_HEIGHT + def get_frame_fn(ref_commit, test_route, tici=True): return f"{test_route}_debayer{'_tici' if tici else ''}_{ref_commit}.bz2" + def bzip_frames(frames): data = bytes() for y, u, v in frames: @@ -35,6 +37,7 @@ def bzip_frames(frames): data += v.tobytes() return bz2.compress(data) + def unbzip_frames(url): with FileReader(url) as f: dat = f.read() @@ -54,14 +57,15 @@ def unbzip_frames(url): return res -def init_kernels(): - ctx = cl.create_some_context() + +def init_kernels(frame_offset=0): + ctx = cl.create_some_context(interactive=False) with open(os.path.join(BASEDIR, 'selfdrive/camerad/cameras/real_debayer.cl')) as f: build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ - f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DCAM_NUM=0' + f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DFRAME_OFFSET={frame_offset} -DCAM_NUM=0' if PC: - build_args += ' -DHALF_AS_FLOAT=1' + build_args += ' -DHALF_AS_FLOAT=1 -cl-std=CL2.0' debayer_prg = cl.Program(ctx, f.read()).build(options=build_args) with open(os.path.join(BASEDIR, 'selfdrive/camerad/transforms/rgb_to_yuv.cl')) as f: @@ -72,7 +76,8 @@ def init_kernels(): return ctx, debayer_prg, rgb_to_yuv_prg -def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): + +def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data, rgb=False): q = cl.CommandQueue(ctx) rgb_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT * 3, dtype=np.uint8) @@ -101,7 +106,11 @@ def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): u = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT:FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE].reshape((UV_HEIGHT, UV_WIDTH)) v = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE:].reshape((UV_HEIGHT, UV_WIDTH)) - return y, u, v + if rgb: + return rgb_buff.reshape((FRAME_HEIGHT, FRAME_WIDTH, 3))[:, :, (2, 1, 0)] + else: + return y, u, v + def debayer_replay(lr): ctx, debayer_prg, rgb_to_yuv_prg = init_kernels() @@ -118,6 +127,7 @@ def debayer_replay(lr): return frames + if __name__ == "__main__": update = "--update" in sys.argv replay_dir = os.path.dirname(os.path.abspath(__file__)) @@ -179,7 +189,7 @@ if __name__ == "__main__": failed = True # upload new refs - if update or failed: + if update or (failed and TICI): from selfdrive.test.openpilotci import upload_file print("Uploading new refs") From 9ef17a877fa0cb4b0d9e7017c152dadbfb94a9aa Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 17:27:54 +0200 Subject: [PATCH 16/32] sanity check on debayer time in CI (#24453) * check debayer time * set actual threshold * also print mean and max --- selfdrive/test/test_onroad.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 830522ec5e..21696645cd 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -181,6 +181,20 @@ class TestOnroad(unittest.TestCase): cpu_ok = check_cpu_usage(proclogs[0], proclogs[-1]) self.assertTrue(cpu_ok) + def test_camera_processing_time(self): + result = "\n" + result += "------------------------------------------------\n" + result += "-------------- Debayer Timing ------------------\n" + result += "------------------------------------------------\n" + + ts = [getattr(getattr(m, m.which()), "processingTime") for m in self.lr if 'CameraState' in m.which()] + self.assertLess(min(ts), 0.025, f"high execution time: {min(ts)}") + result += f"execution time: min {min(ts):.5f}s\n" + result += f"execution time: max {max(ts):.5f}s\n" + result += f"execution time: mean {np.mean(ts):.5f}s\n" + result += "------------------------------------------------\n" + print(result) + def test_mpc_execution_timings(self): result = "\n" result += "------------------------------------------------\n" From 49e10dc773780884f2aab309b7dc2436fe6f473a Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Fri, 6 May 2022 18:27:41 +0200 Subject: [PATCH 17/32] debayering: fill outer image borders (#24441) * debayering: fill outer image borders * correct conditions * try something else * remove global check * update ref Co-authored-by: Comma Device --- selfdrive/camerad/cameras/real_debayer.cl | 28 +++++++++---------- .../process_replay/debayer_replay_ref_commit | 2 +- 2 files changed, 14 insertions(+), 16 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 783abaabb4..6be53c2144 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -111,34 +111,32 @@ __kernel void debayer10(const __global uchar * in, int localColOffset = -1; int globalColOffset = -1; + const int x_global_mod = (x_global == 0 || x_global == RGB_WIDTH - 1) ? -1: 1; + const int y_global_mod = (y_global == 0 || y_global == RGB_HEIGHT - 1) ? -1: 1; + // cache padding - if (x_global >= 1 && x_local < 1) { + if (x_local < 1) { localColOffset = x_local; globalColOffset = -1; - cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-1, y_global, black_level); - } else if (x_global < RGB_WIDTH - 1 && x_local >= get_local_size(0) - 1) { + cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-x_global_mod, y_global, black_level); + } else if (x_local >= get_local_size(0) - 1) { localColOffset = x_local + 2; globalColOffset = 1; - cached[localOffset + 1] = val_from_10(in, x_global+1, y_global, black_level); + cached[localOffset + 1] = val_from_10(in, x_global+x_global_mod, y_global, black_level); } - if (y_global >= 1 && y_local < 1) { - cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-1, black_level); + if (y_local < 1) { + cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-y_global_mod, black_level); if (localColOffset != -1) { - cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global-1, black_level); + cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+(x_global_mod*globalColOffset), y_global-y_global_mod, black_level); } - } else if (y_global < RGB_HEIGHT - 1 && y_local >= get_local_size(1) - 1) { - cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+1, black_level); + } else if (y_local >= get_local_size(1) - 1) { + cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+y_global_mod, black_level); if (localColOffset != -1) { - cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global+1, black_level); + cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+(x_global_mod*globalColOffset), y_global+y_global_mod, black_level); } } - // don't care - if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { - return; - } - // sync barrier(CLK_LOCAL_MEM_FENCE); diff --git a/selfdrive/test/process_replay/debayer_replay_ref_commit b/selfdrive/test/process_replay/debayer_replay_ref_commit index 44fe33001c..2f37c33669 100644 --- a/selfdrive/test/process_replay/debayer_replay_ref_commit +++ b/selfdrive/test/process_replay/debayer_replay_ref_commit @@ -1 +1 @@ -1f9907122a9bda9279d73f698addaa0e22796059 \ No newline at end of file +14f411de8085d1cc9e467592c90bcaf95447a467 \ No newline at end of file From 7bcecbfd0d1b3d5f47e263b86d64012f30944ab5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 11:20:04 -0700 Subject: [PATCH 18/32] cell testing script --- scripts/cell.sh | 5 +++++ 1 file changed, 5 insertions(+) create mode 100755 scripts/cell.sh diff --git a/scripts/cell.sh b/scripts/cell.sh new file mode 100755 index 0000000000..cae701eccc --- /dev/null +++ b/scripts/cell.sh @@ -0,0 +1,5 @@ +#!/usr/bin/bash + +nmcli connection modify --temporary lte ipv4.route-metric 1 +nmcli connection modify --temporary lte ipv6.route-metric 1 +nmcli con up lte From 43912eb2523ea0b36183138cf1c800c63b01bcbb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 13:21:08 -0700 Subject: [PATCH 19/32] update issue template --- .github/ISSUE_TEMPLATE/bug_report.yml | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml index 6bbbbacb70..b1a14076ea 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.yml +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -22,23 +22,11 @@ body: validations: required: true - - type: dropdown - id: hw - attributes: - label: What hardware does this issue affect? - multiple: true - options: - - comma three - - comma two - - EON Gold - validations: - required: true - - type: input id: route attributes: label: Provide a route where the issue occurs - description: Ensure the route is fully uploaded at https://useradmin.comma.ai + description: Ensure the route is fully uploaded at https://useradmin.comma.ai. We cannot look into issues without routes, or at least a Dongle ID. placeholder: 77611a1fac303767|2020-05-11--16-37-07 validations: required: true From f1bae8ca8832fd9a408a60863e735c642c9e6b6d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 13:21:38 -0700 Subject: [PATCH 20/32] remove from car bug too --- .github/ISSUE_TEMPLATE/car_bug_report.yml | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/car_bug_report.yml b/.github/ISSUE_TEMPLATE/car_bug_report.yml index a48f984192..23527c3a43 100644 --- a/.github/ISSUE_TEMPLATE/car_bug_report.yml +++ b/.github/ISSUE_TEMPLATE/car_bug_report.yml @@ -21,18 +21,6 @@ body: validations: required: true - - type: dropdown - id: hw - attributes: - label: What hardware does this issue affect? - multiple: true - options: - - comma three - - comma two - - EON Gold - validations: - required: true - - type: input id: car attributes: From ed3be29bfa975a4cbdb4abf85cda3726f64e3caf Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 6 May 2022 16:31:21 -0700 Subject: [PATCH 21/32] no encoder throttle (#24457) Co-authored-by: Comma Device --- selfdrive/hardware/tici/hardware.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index c626c5f825..1005866d69 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -468,6 +468,10 @@ class Tici(HardwareBase): sudo_write("performance", "/sys/class/devfreq/soc:qcom,memlat-cpu0/governor") sudo_write("performance", "/sys/class/devfreq/soc:qcom,memlat-cpu4/governor") + # *** VIDC (encoder) config *** + sudo_write("N", "/sys/kernel/debug/msm_vidc/clock_scaling") + sudo_write("Y", "/sys/kernel/debug/msm_vidc/disable_thermal_mitigation") + def configure_modem(self): sim_id = self.get_sim_info().get('sim_id', '') From c955e273d40dfd5c07a8505dbaf7b34766eee42f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 6 May 2022 16:56:40 -0700 Subject: [PATCH 22/32] Toyota: fill steerFaultPermanent (#24410) * Toyota: fill steerFaultPermanent * same behavior as before, 0 is also fault (0 is most likely initializing) * think this was just wrong (2 or 10 would mean we think it's a fault) --- selfdrive/car/toyota/carcontroller.py | 3 +-- selfdrive/car/toyota/carstate.py | 7 ++++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 1c01703d7e..33e3fe118e 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -54,8 +54,7 @@ class CarController: apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) self.steer_rate_limited = new_steer != apply_steer - # Cut steering while we're in a known fault state (2s) - if not CC.latActive or CS.steer_state in (9, 25): + if not CC.latActive: apply_steer = 0 apply_steer_req = 0 else: diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 54922ac2de..281d01026f 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -82,7 +82,10 @@ class CarState(CarStateBase): ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale # we could use the override bit from dbc, but it's triggered at too high torque values ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] not in (1, 5) + # steer rate fault, goes to 21 or 25 for 1 frame, then 9 for ~2 seconds + ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in (0, 9, 21, 25) + # 17 is a fault from a prolonged high torque delta between cmd and user + ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] == 17 if self.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 @@ -120,8 +123,6 @@ class CarState(CarStateBase): ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 - # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state - self.steer_state = cp.vl["EPS_STATUS"]["LKA_STATE"] if self.CP.enableBsm: ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) From ac343433a22984109401a9de97eab28220e38e72 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 6 May 2022 21:47:58 -0700 Subject: [PATCH 23/32] sync qcam p frames (#24459) Co-authored-by: Comma Device --- cereal | 2 +- selfdrive/loggerd/v4l_encoder.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 122dbf70d0..c7d3a0acba 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 122dbf70d0fe71f9b7d3bf616b4e35b51c9fb04e +Subproject commit c7d3a0acbae267ef93d30044e1941e060dac9e48 diff --git a/selfdrive/loggerd/v4l_encoder.cc b/selfdrive/loggerd/v4l_encoder.cc index b61bf01019..99653758a0 100644 --- a/selfdrive/loggerd/v4l_encoder.cc +++ b/selfdrive/loggerd/v4l_encoder.cc @@ -286,7 +286,7 @@ V4LEncoder::V4LEncoder( struct v4l2_control ctrls[] = { { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 15}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 14}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, From 29afd53d88f5c98efdac8727f3df1e4679790cde Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 6 May 2022 22:17:21 -0700 Subject: [PATCH 24/32] Latcontrol torque: fix integrator induced ping pong (#24458) * Latcontrol torque: fix integrator induced ping pong * Reset on disengage since unwind resets anywayh * Might be overkill * rm whitespace * update ref --- selfdrive/car/toyota/tunes.py | 2 +- selfdrive/controls/lib/latcontrol_torque.py | 3 ++- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 50b03b85ad..7411c0c543 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -56,7 +56,7 @@ def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=.1): tune.torque.useSteeringAngle = True tune.torque.kp = 1.0 / MAX_LAT_ACCEL tune.torque.kf = 1.0 / MAX_LAT_ACCEL - tune.torque.ki = 0.25 / MAX_LAT_ACCEL + tune.torque.ki = 0.1 / MAX_LAT_ACCEL tune.torque.friction = FRICTION elif name == LatTunes.INDI_PRIUS: tune.init('indi') diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 4e9d559798..a373384254 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -42,7 +42,8 @@ class LatControlTorque(LatControl): if CS.vEgo < MIN_STEER_SPEED or not active: output_torque = 0.0 pid_log.active = False - self.pid.reset() + if not active: + self.pid.reset() else: if self.use_steering_angle: actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5bed2e765c..ac8f59b26b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -70d79fbcc2b9ab0af867a7d6f138b58bcaaa3aa8 \ No newline at end of file +10b766fa845934f0258c52cdf2103d0e1a9496c9 \ No newline at end of file From 75efad52eabf008ad87337b1e5fadadaaf21756c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 01:00:43 -0700 Subject: [PATCH 25/32] Chrysler: add ACC fault signal (#24398) * add accFaulted event for Chrysler * add the signal * no class variables * available when not 1 * revert * bump opendbc to master * if not 0 --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/opendbc b/opendbc index e19ba095c3..919154efe2 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e19ba095c3ee288d629284e24ec7e0deaf645f3f +Subproject commit 919154efe2bd07c4dd124d7e6a11a4afc8685f9d diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 5f83bbde8b..6dcd2cea62 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -53,6 +53,7 @@ class CarState(CarStateBase): ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) + ret.accFaulted = cp.vl["ACC_2"]["ACC_FAULTED"] != 0 ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -93,6 +94,7 @@ class CarState(CarStateBase): ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), ("ACC_STATUS_2", "ACC_2"), + ("ACC_FAULTED", "ACC_2"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), ("CRUISE_STATE", "DASHBOARD"), From ed41b14b55426fe4400e1a87ac7c4e9d4f031b40 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 01:23:19 -0700 Subject: [PATCH 26/32] Chrysler: reduce ACC faults when disengaging on gas (#24445) --- selfdrive/car/chrysler/carcontroller.py | 3 +-- selfdrive/car/chrysler/carstate.py | 3 +++ selfdrive/car/chrysler/chryslercan.py | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index eda00a2ea1..3d6295d77d 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -49,8 +49,7 @@ class CarController: # *** control msgs *** if CC.cruiseControl.cancel: - # TODO: would be better to start from frame_2b3 - can_sends.append(create_wheel_buttons(self.packer, self.frame, cancel=True)) + can_sends.append(create_wheel_buttons(self.packer, CS.button_counter + 1, cancel=True)) # LKAS_HEARTBIT is forwarded by Panda so no need to send it here. # frame is 100Hz (0.01s period) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 6dcd2cea62..8ddf1c8684 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -70,6 +70,7 @@ class CarState(CarStateBase): self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"] self.lkas_car_model = cp_cam.vl["LKAS_HUD"]["CAR_MODEL"] self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"] + self.button_counter = cp.vl["WHEEL_BUTTONS"]["COUNTER"] return ret @@ -104,6 +105,7 @@ class CarState(CarStateBase): ("COUNTER", "EPS_STATUS",), ("TRACTION_OFF", "TRACTION_BUTTON"), ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS"), + ("COUNTER", "WHEEL_BUTTONS"), ] checks = [ @@ -116,6 +118,7 @@ class CarState(CarStateBase): ("ACC_2", 50), ("GEAR", 50), ("ACCEL_GAS_134", 50), + ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), ("SEATBELT_STATUS", 2), diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 33f614d75e..896a6b15da 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -52,6 +52,6 @@ def create_wheel_buttons(packer, frame, cancel=False): # WHEEL_BUTTONS (571) Message sent to cancel ACC. values = { "ACC_CANCEL": cancel, - "COUNTER": frame % 10 # FIXME: this counter is wrong + "COUNTER": frame % 0x10 } return packer.make_can_msg("WHEEL_BUTTONS", 0, values) From ba89faa5f77c76023f49b85888e6d6eb7f2e1a11 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 7 May 2022 15:42:47 +0200 Subject: [PATCH 27/32] uploader: ensure requests.put gets file like object (#24462) --- selfdrive/loggerd/uploader.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 87988171fb..74d45f01c9 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import bz2 +import io import json import os import random @@ -153,10 +154,11 @@ class Uploader(): self.last_resp = FakeResponse() else: with open(fn, "rb") as f: - data = f.read() - if key.endswith('.bz2') and not fn.endswith('.bz2'): - data = bz2.compress(data) + data = bz2.compress(f.read()) + data = io.BytesIO(data) + else: + data = f self.last_resp = requests.put(url, data=data, headers=headers, timeout=10) except Exception as e: From 191fbd4f67e7f878b518effd14411779b9435339 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 21:34:17 -0700 Subject: [PATCH 28/32] Camry TSS2: use torque controller (#24268) * use measurements from harald * update from table * average of hybrid and non-hybrid --- selfdrive/car/toyota/interface.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 433058b3c0..559307ef2d 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -87,7 +87,10 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) + if candidate in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.4, FRICTION=0.05) + else: + set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True From ce0cc1f228edc85e8a9153784dfb5475b8376fb3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 8 May 2022 19:18:03 -0700 Subject: [PATCH 29/32] tici modem restart script --- selfdrive/hardware/tici/restart_modem.sh | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100755 selfdrive/hardware/tici/restart_modem.sh diff --git a/selfdrive/hardware/tici/restart_modem.sh b/selfdrive/hardware/tici/restart_modem.sh new file mode 100755 index 0000000000..14cace6ad0 --- /dev/null +++ b/selfdrive/hardware/tici/restart_modem.sh @@ -0,0 +1,13 @@ +#!/usr/bin/bash + +nmcli connection modify --temporary lte gsm.auto-config yes +nmcli connection modify --temporary lte gsm.home-only yes +nmcli connection modify --temporary lte connection.autoconnect-retries 20 + +# restart modem +sudo systemctl stop ModemManager +/usr/comma/lte/lte.sh stop_blocking +sudo systemctl restart lte + +#sudo systemctl restart ModemManager +sudo ModemManager --debug From f7c2eefad9897830bf7bce290dec1dfc7d97e1d2 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Mon, 9 May 2022 04:05:08 -0700 Subject: [PATCH 30/32] Bump laika (#24454) * Fix after laika repo changes * Update laika --- laika_repo | 2 +- selfdrive/locationd/laikad.py | 10 +++------- selfdrive/locationd/test/test_laikad.py | 4 ++-- selfdrive/locationd/test/test_ublox_processing.py | 6 +++--- 4 files changed, 9 insertions(+), 13 deletions(-) diff --git a/laika_repo b/laika_repo index 48a9cb686a..be1a213a5f 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 48a9cb686ae2d12cd830f17c166a8fb9f79ab292 +Subproject commit be1a213a5ffa3cafe2b4f2d53f6df5d2452ad910 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 28150bfea9..4695fd945b 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -3,7 +3,7 @@ from typing import List from cereal import log, messaging from laika import AstroDog -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox @@ -46,13 +46,9 @@ def process_ublox_msg(ublox_msg, dog, ublox_mono_time: int): def create_measurement_msg(meas: GNSSMeasurement): c = log.GnssMeasurements.CorrectedMeasurement.new_message() - ublox_gnss_id = meas.ublox_gnss_id - if ublox_gnss_id is None: - # todo never happens will fix in later pr - ublox_gnss_id = UbloxGnssId.GPS - c.constellationId = ublox_gnss_id.value + c.constellationId = meas.constellation_id.value c.svId = int(meas.prn[1:]) - c.glonassFrequency = meas.glonass_freq if meas.ublox_gnss_id == UbloxGnssId.GLONASS else 0 + c.glonassFrequency = meas.glonass_freq if meas.constellation_id == ConstellationId.GLONASS else 0 c.pseudorange = float(meas.observables['C1C']) # todo should be observables_final when using corrected measurements c.pseudorangeStd = float(meas.observables_std['C1C']) c.pseudorangeRate = float(meas.observables['D1C']) # todo should be observables_final when using corrected measurements diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 877623f0bd..fdbb46f5aa 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -2,7 +2,7 @@ import unittest from datetime import datetime -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.gps_time import GPSTime from laika.raw_gnss import GNSSMeasurement @@ -13,7 +13,7 @@ class TestLaikad(unittest.TestCase): def test_create_msg_without_errors(self): gpstime = GPSTime.from_datetime(datetime.now()) - meas = GNSSMeasurement('G01', gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}, ublox_gnss_id=UbloxGnssId.GPS) + meas = GNSSMeasurement(ConstellationId.GPS, 1, gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}) msg = create_measurement_msg(meas) self.assertEqual(msg.constellationId, 'gps') diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py index 94fddb9392..427003b24c 100755 --- a/selfdrive/locationd/test/test_ublox_processing.py +++ b/selfdrive/locationd/test/test_ublox_processing.py @@ -3,7 +3,7 @@ import unittest import numpy as np from laika import AstroDog -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -34,9 +34,9 @@ class TestUbloxProcessing(unittest.TestCase): count_glonass = 0 for measurements in self.gnss_measurements: for m in measurements: - if m.ublox_gnss_id == UbloxGnssId.GPS: + if m.constellation_id == ConstellationId.GPS: count_gps += 1 - elif m.ublox_gnss_id == UbloxGnssId.GLONASS: + elif m.constellation_id == ConstellationId.GLONASS: count_glonass += 1 self.assertEqual(count_gps, 5036) From bf269bd883e77bf29e4d9a0a21ef0c4a9eb79c2c Mon Sep 17 00:00:00 2001 From: ntegan1 Date: Mon, 9 May 2022 15:07:19 -0400 Subject: [PATCH 31/32] Tools: allow uncompressed logs (#24471) --- tools/lib/route.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/lib/route.py b/tools/lib/route.py index 8092096a0b..067fccf188 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -8,9 +8,9 @@ from tools.lib.auth_config import get_token from tools.lib.api import CommaApi from tools.lib.helpers import RE -QLOG_FILENAMES = ['qlog.bz2'] +QLOG_FILENAMES = ['qlog', 'qlog.bz2'] QCAMERA_FILENAMES = ['qcamera.ts'] -LOG_FILENAMES = ['rlog.bz2', 'raw_log.bz2'] +LOG_FILENAMES = ['rlog', 'rlog.bz2', 'raw_log.bz2'] CAMERA_FILENAMES = ['fcamera.hevc', 'video.hevc'] DCAMERA_FILENAMES = ['dcamera.hevc'] ECAMERA_FILENAMES = ['ecamera.hevc'] From 6163dd5ca06efe05a7d4645f6b4127847ce133ac Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 May 2022 13:31:55 -0700 Subject: [PATCH 32/32] URLFile: raise exception if remote URL doesn't exist when using cache (#24432) * URLFile returns empty bytes if using cache and remote file doesn't exist * better exception * assert on cached files --- tools/lib/url_file.py | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 8ad2f96b3a..1e94a588f1 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -87,6 +87,7 @@ class URLFile: file_begin = self._pos file_end = self._pos + ll if ll is not None else self.get_length() + assert file_end != -1, f"Remote file is empty or doesn't exist: {self._url}" # We have to align with chunks we store. Position is the begginiing of the latest chunk that starts before or at our file position = (file_begin // CHUNK_SIZE) * CHUNK_SIZE response = b""