openpilot v0.9.6 release
date: 2024-01-12T10:13:37 master commit: ba792d576a49a0899b88a753fa1c52956bedf9e6
This commit is contained in:
16
system/hardware/__init__.py
Normal file
16
system/hardware/__init__.py
Normal file
@@ -0,0 +1,16 @@
|
||||
import os
|
||||
from typing import cast
|
||||
|
||||
from openpilot.system.hardware.base import HardwareBase
|
||||
from openpilot.system.hardware.tici.hardware import Tici
|
||||
from openpilot.system.hardware.pc.hardware import Pc
|
||||
|
||||
TICI = os.path.isfile('/TICI')
|
||||
AGNOS = os.path.isfile('/AGNOS')
|
||||
PC = not TICI
|
||||
|
||||
|
||||
if TICI:
|
||||
HARDWARE = cast(HardwareBase, Tici())
|
||||
else:
|
||||
HARDWARE = cast(HardwareBase, Pc())
|
||||
41
system/hardware/base.h
Normal file
41
system/hardware/base.h
Normal file
@@ -0,0 +1,41 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdlib>
|
||||
#include <fstream>
|
||||
#include <map>
|
||||
#include <string>
|
||||
|
||||
#include "cereal/messaging/messaging.h"
|
||||
|
||||
// no-op base hw class
|
||||
class HardwareNone {
|
||||
public:
|
||||
static constexpr float MAX_VOLUME = 0.7;
|
||||
static constexpr float MIN_VOLUME = 0.2;
|
||||
|
||||
static std::string get_os_version() { return ""; }
|
||||
static std::string get_name() { return ""; }
|
||||
static cereal::InitData::DeviceType get_device_type() { return cereal::InitData::DeviceType::UNKNOWN; }
|
||||
static int get_voltage() { return 0; }
|
||||
static int get_current() { return 0; }
|
||||
|
||||
static std::string get_serial() { return "cccccc"; }
|
||||
|
||||
static std::map<std::string, std::string> get_init_logs() {
|
||||
return {};
|
||||
}
|
||||
|
||||
static void reboot() {}
|
||||
static void poweroff() {}
|
||||
static void set_brightness(int percent) {}
|
||||
static void set_display_power(bool on) {}
|
||||
|
||||
static bool get_ssh_enabled() { return false; }
|
||||
static void set_ssh_enabled(bool enabled) {}
|
||||
|
||||
static void config_cpu_rendering(bool offscreen);
|
||||
|
||||
static bool PC() { return false; }
|
||||
static bool TICI() { return false; }
|
||||
static bool AGNOS() { return false; }
|
||||
};
|
||||
151
system/hardware/base.py
Normal file
151
system/hardware/base.py
Normal file
@@ -0,0 +1,151 @@
|
||||
from abc import abstractmethod, ABC
|
||||
from collections import namedtuple
|
||||
from typing import Dict
|
||||
|
||||
from cereal import log
|
||||
|
||||
ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient', 'pmic'])
|
||||
NetworkType = log.DeviceState.NetworkType
|
||||
|
||||
|
||||
class HardwareBase(ABC):
|
||||
@staticmethod
|
||||
def get_cmdline() -> Dict[str, str]:
|
||||
with open('/proc/cmdline') as f:
|
||||
cmdline = f.read()
|
||||
return {kv[0]: kv[1] for kv in [s.split('=') for s in cmdline.split(' ')] if len(kv) == 2}
|
||||
|
||||
@staticmethod
|
||||
def read_param_file(path, parser, default=0):
|
||||
try:
|
||||
with open(path) as f:
|
||||
return parser(f.read())
|
||||
except Exception:
|
||||
return default
|
||||
|
||||
def booted(self) -> bool:
|
||||
return True
|
||||
|
||||
@abstractmethod
|
||||
def reboot(self, reason=None):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def uninstall(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_os_version(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_device_type(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_sound_card_online(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_imei(self, slot) -> str:
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_serial(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_subscriber_info(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_network_info(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_network_type(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_sim_info(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_network_strength(self, network_type):
|
||||
pass
|
||||
|
||||
def get_network_metered(self, network_type) -> bool:
|
||||
return network_type not in (NetworkType.none, NetworkType.wifi, NetworkType.ethernet)
|
||||
|
||||
@staticmethod
|
||||
def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None:
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_current_power_draw(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_som_power_draw(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def shutdown(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_thermal_config(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def set_screen_brightness(self, percentage):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_screen_brightness(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def set_power_save(self, powersave_enabled):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_gpu_usage_percent(self):
|
||||
pass
|
||||
|
||||
def get_modem_version(self):
|
||||
return None
|
||||
|
||||
def get_modem_nv(self):
|
||||
return None
|
||||
|
||||
@abstractmethod
|
||||
def get_modem_temperatures(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_nvme_temperatures(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def initialize_hardware(self):
|
||||
pass
|
||||
|
||||
def configure_modem(self):
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def get_networks(self):
|
||||
pass
|
||||
|
||||
def has_internal_panda(self) -> bool:
|
||||
return False
|
||||
|
||||
def reset_internal_panda(self):
|
||||
pass
|
||||
|
||||
def recover_internal_panda(self):
|
||||
pass
|
||||
|
||||
def get_modem_data_usage(self):
|
||||
return -1, -1
|
||||
50
system/hardware/hw.h
Normal file
50
system/hardware/hw.h
Normal file
@@ -0,0 +1,50 @@
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
#include "system/hardware/base.h"
|
||||
#include "common/util.h"
|
||||
|
||||
#if QCOM2
|
||||
#include "system/hardware/tici/hardware.h"
|
||||
#define Hardware HardwareTici
|
||||
#else
|
||||
#include "system/hardware/pc/hardware.h"
|
||||
#define Hardware HardwarePC
|
||||
#endif
|
||||
|
||||
namespace Path {
|
||||
inline std::string openpilot_prefix() {
|
||||
return util::getenv("OPENPILOT_PREFIX", "");
|
||||
}
|
||||
|
||||
inline std::string comma_home() {
|
||||
return util::getenv("HOME") + "/.comma" + Path::openpilot_prefix();
|
||||
}
|
||||
|
||||
inline std::string log_root() {
|
||||
if (const char *env = getenv("LOG_ROOT")) {
|
||||
return env;
|
||||
}
|
||||
return Hardware::PC() ? Path::comma_home() + "/media/0/realdata" : "/data/media/0/realdata";
|
||||
}
|
||||
|
||||
inline std::string params() {
|
||||
return Hardware::PC() ? util::getenv("PARAMS_ROOT", Path::comma_home() + "/params") : "/data/params";
|
||||
}
|
||||
|
||||
inline std::string rsa_file() {
|
||||
return Hardware::PC() ? Path::comma_home() + "/persist/comma/id_rsa" : "/persist/comma/id_rsa";
|
||||
}
|
||||
|
||||
inline std::string swaglog_ipc() {
|
||||
return "ipc:///tmp/logmessage" + Path::openpilot_prefix();
|
||||
}
|
||||
|
||||
inline std::string download_cache_root() {
|
||||
if (const char *env = getenv("COMMA_CACHE")) {
|
||||
return env;
|
||||
}
|
||||
return "/tmp/comma_download_cache" + Path::openpilot_prefix() + "/";
|
||||
}
|
||||
} // namespace Path
|
||||
56
system/hardware/hw.py
Normal file
56
system/hardware/hw.py
Normal file
@@ -0,0 +1,56 @@
|
||||
import os
|
||||
from pathlib import Path
|
||||
|
||||
from openpilot.system.hardware import PC
|
||||
|
||||
class Paths:
|
||||
@staticmethod
|
||||
def comma_home() -> str:
|
||||
return os.path.join(str(Path.home()), ".comma" + os.environ.get("OPENPILOT_PREFIX", ""))
|
||||
|
||||
@staticmethod
|
||||
def log_root() -> str:
|
||||
if os.environ.get('LOG_ROOT', False):
|
||||
return os.environ['LOG_ROOT']
|
||||
elif PC:
|
||||
return str(Path(Paths.comma_home()) / "media" / "0" / "realdata")
|
||||
else:
|
||||
return '/data/media/0/realdata/'
|
||||
|
||||
@staticmethod
|
||||
def swaglog_root() -> str:
|
||||
if PC:
|
||||
return os.path.join(Paths.comma_home(), "log")
|
||||
else:
|
||||
return "/data/log/"
|
||||
|
||||
@staticmethod
|
||||
def swaglog_ipc() -> str:
|
||||
return "ipc:///tmp/logmessage" + os.environ.get("OPENPILOT_PREFIX", "")
|
||||
|
||||
@staticmethod
|
||||
def download_cache_root() -> str:
|
||||
if os.environ.get('COMMA_CACHE', False):
|
||||
return os.environ['COMMA_CACHE']
|
||||
return "/tmp/comma_download_cache" + os.environ.get("OPENPILOT_PREFIX", "") + "/"
|
||||
|
||||
@staticmethod
|
||||
def persist_root() -> str:
|
||||
if PC:
|
||||
return os.path.join(Paths.comma_home(), "persist")
|
||||
else:
|
||||
return "/persist/"
|
||||
|
||||
@staticmethod
|
||||
def stats_root() -> str:
|
||||
if PC:
|
||||
return str(Path(Paths.comma_home()) / "stats")
|
||||
else:
|
||||
return "/data/stats/"
|
||||
|
||||
@staticmethod
|
||||
def config_root() -> str:
|
||||
if PC:
|
||||
return Paths.comma_home()
|
||||
else:
|
||||
return "/tmp/.comma"
|
||||
0
system/hardware/pc/__init__.py
Normal file
0
system/hardware/pc/__init__.py
Normal file
23
system/hardware/pc/hardware.h
Normal file
23
system/hardware/pc/hardware.h
Normal file
@@ -0,0 +1,23 @@
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
#include "system/hardware/base.h"
|
||||
|
||||
class HardwarePC : public HardwareNone {
|
||||
public:
|
||||
static std::string get_os_version() { return "openpilot for PC"; }
|
||||
static std::string get_name() { return "pc"; }
|
||||
static cereal::InitData::DeviceType get_device_type() { return cereal::InitData::DeviceType::PC; }
|
||||
static bool PC() { return true; }
|
||||
static bool TICI() { return util::getenv("TICI", 0) == 1; }
|
||||
static bool AGNOS() { return util::getenv("TICI", 0) == 1; }
|
||||
|
||||
static void config_cpu_rendering(bool offscreen) {
|
||||
if (offscreen) {
|
||||
setenv("QT_QPA_PLATFORM", "offscreen", 1);
|
||||
}
|
||||
setenv("__GLX_VENDOR_LIBRARY_NAME", "mesa", 1);
|
||||
setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU
|
||||
}
|
||||
};
|
||||
87
system/hardware/pc/hardware.py
Normal file
87
system/hardware/pc/hardware.py
Normal file
@@ -0,0 +1,87 @@
|
||||
import random
|
||||
|
||||
from cereal import log
|
||||
from openpilot.system.hardware.base import HardwareBase, ThermalConfig
|
||||
|
||||
NetworkType = log.DeviceState.NetworkType
|
||||
NetworkStrength = log.DeviceState.NetworkStrength
|
||||
|
||||
|
||||
class Pc(HardwareBase):
|
||||
def get_os_version(self):
|
||||
return None
|
||||
|
||||
def get_device_type(self):
|
||||
return "pc"
|
||||
|
||||
def get_sound_card_online(self):
|
||||
return True
|
||||
|
||||
def reboot(self, reason=None):
|
||||
print("REBOOT!")
|
||||
|
||||
def uninstall(self):
|
||||
print("uninstall")
|
||||
|
||||
def get_imei(self, slot):
|
||||
return "%015d" % random.randint(0, 1 << 32)
|
||||
|
||||
def get_serial(self):
|
||||
return "cccccccc"
|
||||
|
||||
def get_subscriber_info(self):
|
||||
return ""
|
||||
|
||||
def get_network_info(self):
|
||||
return None
|
||||
|
||||
def get_network_type(self):
|
||||
return NetworkType.wifi
|
||||
|
||||
def get_sim_info(self):
|
||||
return {
|
||||
'sim_id': '',
|
||||
'mcc_mnc': None,
|
||||
'network_type': ["Unknown"],
|
||||
'sim_state': ["ABSENT"],
|
||||
'data_connected': False
|
||||
}
|
||||
|
||||
def get_network_strength(self, network_type):
|
||||
return NetworkStrength.unknown
|
||||
|
||||
def get_current_power_draw(self):
|
||||
return 0
|
||||
|
||||
def get_som_power_draw(self):
|
||||
return 0
|
||||
|
||||
def shutdown(self):
|
||||
print("SHUTDOWN!")
|
||||
|
||||
def get_thermal_config(self):
|
||||
return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), ambient=(None, 1), pmic=((None,), 1))
|
||||
|
||||
def set_screen_brightness(self, percentage):
|
||||
pass
|
||||
|
||||
def get_screen_brightness(self):
|
||||
return 0
|
||||
|
||||
def set_power_save(self, powersave_enabled):
|
||||
pass
|
||||
|
||||
def get_gpu_usage_percent(self):
|
||||
return 0
|
||||
|
||||
def get_modem_temperatures(self):
|
||||
return []
|
||||
|
||||
def get_nvme_temperatures(self):
|
||||
return []
|
||||
|
||||
def initialize_hardware(self):
|
||||
pass
|
||||
|
||||
def get_networks(self):
|
||||
return None
|
||||
0
system/hardware/tici/__init__.py
Normal file
0
system/hardware/tici/__init__.py
Normal file
76
system/hardware/tici/agnos.json
Normal file
76
system/hardware/tici/agnos.json
Normal file
@@ -0,0 +1,76 @@
|
||||
[
|
||||
{
|
||||
"name": "boot",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/boot-fd30f580375279ff4605034ec13711890a2b227205571a087cdc5226a2710275.img.xz",
|
||||
"hash": "fd30f580375279ff4605034ec13711890a2b227205571a087cdc5226a2710275",
|
||||
"hash_raw": "fd30f580375279ff4605034ec13711890a2b227205571a087cdc5226a2710275",
|
||||
"size": 15636480,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "abl",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/abl-bb234733816781b3d09266f91f741436e9bf17e1a7caf468cf7d09ee788cef4a.img.xz",
|
||||
"hash": "bb234733816781b3d09266f91f741436e9bf17e1a7caf468cf7d09ee788cef4a",
|
||||
"hash_raw": "bb234733816781b3d09266f91f741436e9bf17e1a7caf468cf7d09ee788cef4a",
|
||||
"size": 274432,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "xbl",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/xbl-bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5.img.xz",
|
||||
"hash": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5",
|
||||
"hash_raw": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5",
|
||||
"size": 3282672,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "xbl_config",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/xbl_config-19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac.img.xz",
|
||||
"hash": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac",
|
||||
"hash_raw": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac",
|
||||
"size": 98124,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "devcfg",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/devcfg-be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27.img.xz",
|
||||
"hash": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27",
|
||||
"hash_raw": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27",
|
||||
"size": 40336,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "aop",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/aop-5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f.img.xz",
|
||||
"hash": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f",
|
||||
"hash_raw": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f",
|
||||
"size": 184364,
|
||||
"sparse": false,
|
||||
"full_check": true,
|
||||
"has_ab": true
|
||||
},
|
||||
{
|
||||
"name": "system",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/system-e1952bb363688c0f5c0646e39bcdfb45be25b5e2baed37d1ba7801aa1a3a9c98.img.xz",
|
||||
"hash": "3b6cdf9bd881a5e90b21dd02c6faa923b415e32ecae9bfdc96753d4208fb82fe",
|
||||
"hash_raw": "e1952bb363688c0f5c0646e39bcdfb45be25b5e2baed37d1ba7801aa1a3a9c98",
|
||||
"size": 10737418240,
|
||||
"sparse": true,
|
||||
"full_check": false,
|
||||
"has_ab": true,
|
||||
"alt": {
|
||||
"hash": "2fb81e58f4bc6c4e5e71c8e7ac7553f85082c430627d7a5cc54a6bbc82862500",
|
||||
"url": "https://commadist.azureedge.net/agnosupdate/system-skip-chunks-e1952bb363688c0f5c0646e39bcdfb45be25b5e2baed37d1ba7801aa1a3a9c98.img.xz"
|
||||
}
|
||||
}
|
||||
]
|
||||
328
system/hardware/tici/agnos.py
Executable file
328
system/hardware/tici/agnos.py
Executable file
@@ -0,0 +1,328 @@
|
||||
#!/usr/bin/env python3
|
||||
import hashlib
|
||||
import json
|
||||
import lzma
|
||||
import os
|
||||
import struct
|
||||
import subprocess
|
||||
import time
|
||||
from typing import Dict, Generator, List, Tuple, Union
|
||||
|
||||
import requests
|
||||
|
||||
import openpilot.system.hardware.tici.casync as casync
|
||||
|
||||
SPARSE_CHUNK_FMT = struct.Struct('H2xI4x')
|
||||
CAIBX_URL = "https://commadist.azureedge.net/agnosupdate/"
|
||||
|
||||
|
||||
class StreamingDecompressor:
|
||||
def __init__(self, url: str) -> None:
|
||||
self.buf = b""
|
||||
|
||||
self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}, timeout=60) # type: ignore
|
||||
self.it = self.req.iter_content(chunk_size=1024 * 1024)
|
||||
self.decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO)
|
||||
self.eof = False
|
||||
self.sha256 = hashlib.sha256()
|
||||
|
||||
def read(self, length: int) -> bytes:
|
||||
while len(self.buf) < length:
|
||||
self.req.raise_for_status()
|
||||
|
||||
try:
|
||||
compressed = next(self.it)
|
||||
except StopIteration:
|
||||
self.eof = True
|
||||
break
|
||||
out = self.decompressor.decompress(compressed)
|
||||
self.buf += out
|
||||
|
||||
result = self.buf[:length]
|
||||
self.buf = self.buf[length:]
|
||||
|
||||
self.sha256.update(result)
|
||||
return result
|
||||
|
||||
|
||||
def unsparsify(f: StreamingDecompressor) -> Generator[bytes, None, None]:
|
||||
# https://source.android.com/devices/bootloader/images#sparse-format
|
||||
magic = struct.unpack("I", f.read(4))[0]
|
||||
assert(magic == 0xed26ff3a)
|
||||
|
||||
# Version
|
||||
major = struct.unpack("H", f.read(2))[0]
|
||||
minor = struct.unpack("H", f.read(2))[0]
|
||||
assert(major == 1 and minor == 0)
|
||||
|
||||
f.read(2) # file header size
|
||||
f.read(2) # chunk header size
|
||||
|
||||
block_sz = struct.unpack("I", f.read(4))[0]
|
||||
f.read(4) # total blocks
|
||||
num_chunks = struct.unpack("I", f.read(4))[0]
|
||||
f.read(4) # crc checksum
|
||||
|
||||
for _ in range(num_chunks):
|
||||
chunk_type, out_blocks = SPARSE_CHUNK_FMT.unpack(f.read(12))
|
||||
|
||||
if chunk_type == 0xcac1: # Raw
|
||||
# TODO: yield in smaller chunks. Yielding only block_sz is too slow. Largest observed data chunk is 252 MB.
|
||||
yield f.read(out_blocks * block_sz)
|
||||
elif chunk_type == 0xcac2: # Fill
|
||||
filler = f.read(4) * (block_sz // 4)
|
||||
for _ in range(out_blocks):
|
||||
yield filler
|
||||
elif chunk_type == 0xcac3: # Don't care
|
||||
yield b""
|
||||
else:
|
||||
raise Exception("Unhandled sparse chunk type")
|
||||
|
||||
|
||||
# noop wrapper with same API as unsparsify() for non sparse images
|
||||
def noop(f: StreamingDecompressor) -> Generator[bytes, None, None]:
|
||||
while not f.eof:
|
||||
yield f.read(1024 * 1024)
|
||||
|
||||
|
||||
def get_target_slot_number() -> int:
|
||||
current_slot = subprocess.check_output(["abctl", "--boot_slot"], encoding='utf-8').strip()
|
||||
return 1 if current_slot == "_a" else 0
|
||||
|
||||
|
||||
def slot_number_to_suffix(slot_number: int) -> str:
|
||||
assert slot_number in (0, 1)
|
||||
return '_a' if slot_number == 0 else '_b'
|
||||
|
||||
|
||||
def get_partition_path(target_slot_number: int, partition: dict) -> str:
|
||||
path = f"/dev/disk/by-partlabel/{partition['name']}"
|
||||
|
||||
if partition.get('has_ab', True):
|
||||
path += slot_number_to_suffix(target_slot_number)
|
||||
|
||||
return path
|
||||
|
||||
|
||||
def get_raw_hash(path: str, partition_size: int) -> str:
|
||||
raw_hash = hashlib.sha256()
|
||||
pos, chunk_size = 0, 1024 * 1024
|
||||
|
||||
with open(path, 'rb+') as out:
|
||||
while pos < partition_size:
|
||||
n = min(chunk_size, partition_size - pos)
|
||||
raw_hash.update(out.read(n))
|
||||
pos += n
|
||||
|
||||
return raw_hash.hexdigest().lower()
|
||||
|
||||
|
||||
def verify_partition(target_slot_number: int, partition: Dict[str, Union[str, int]], force_full_check: bool = False) -> bool:
|
||||
full_check = partition['full_check'] or force_full_check
|
||||
path = get_partition_path(target_slot_number, partition)
|
||||
|
||||
if not isinstance(partition['size'], int):
|
||||
return False
|
||||
|
||||
partition_size: int = partition['size']
|
||||
|
||||
if not isinstance(partition['hash_raw'], str):
|
||||
return False
|
||||
|
||||
partition_hash: str = partition['hash_raw']
|
||||
|
||||
if full_check:
|
||||
return get_raw_hash(path, partition_size) == partition_hash.lower()
|
||||
else:
|
||||
with open(path, 'rb+') as out:
|
||||
out.seek(partition_size)
|
||||
return out.read(64) == partition_hash.lower().encode()
|
||||
|
||||
|
||||
def clear_partition_hash(target_slot_number: int, partition: dict) -> None:
|
||||
path = get_partition_path(target_slot_number, partition)
|
||||
with open(path, 'wb+') as out:
|
||||
partition_size = partition['size']
|
||||
|
||||
out.seek(partition_size)
|
||||
out.write(b"\x00" * 64)
|
||||
os.sync()
|
||||
|
||||
|
||||
def extract_compressed_image(target_slot_number: int, partition: dict, cloudlog):
|
||||
path = get_partition_path(target_slot_number, partition)
|
||||
downloader = StreamingDecompressor(partition['url'])
|
||||
|
||||
with open(path, 'wb+') as out:
|
||||
# Flash partition
|
||||
last_p = 0
|
||||
raw_hash = hashlib.sha256()
|
||||
f = unsparsify if partition['sparse'] else noop
|
||||
for chunk in f(downloader):
|
||||
raw_hash.update(chunk)
|
||||
out.write(chunk)
|
||||
p = int(out.tell() / partition['size'] * 100)
|
||||
if p != last_p:
|
||||
last_p = p
|
||||
print(f"Installing {partition['name']}: {p}", flush=True)
|
||||
|
||||
if raw_hash.hexdigest().lower() != partition['hash_raw'].lower():
|
||||
raise Exception(f"Raw hash mismatch '{raw_hash.hexdigest().lower()}'")
|
||||
|
||||
if downloader.sha256.hexdigest().lower() != partition['hash'].lower():
|
||||
raise Exception("Uncompressed hash mismatch")
|
||||
|
||||
if out.tell() != partition['size']:
|
||||
raise Exception("Uncompressed size mismatch")
|
||||
|
||||
os.sync()
|
||||
|
||||
|
||||
def extract_casync_image(target_slot_number: int, partition: dict, cloudlog):
|
||||
path = get_partition_path(target_slot_number, partition)
|
||||
seed_path = path[:-1] + ('b' if path[-1] == 'a' else 'a')
|
||||
|
||||
target = casync.parse_caibx(partition['casync_caibx'])
|
||||
|
||||
sources: List[Tuple[str, casync.ChunkReader, casync.ChunkDict]] = []
|
||||
|
||||
# First source is the current partition.
|
||||
try:
|
||||
raw_hash = get_raw_hash(seed_path, partition['size'])
|
||||
caibx_url = f"{CAIBX_URL}{partition['name']}-{raw_hash}.caibx"
|
||||
|
||||
try:
|
||||
cloudlog.info(f"casync fetching {caibx_url}")
|
||||
sources += [('seed', casync.FileChunkReader(seed_path), casync.build_chunk_dict(casync.parse_caibx(caibx_url)))]
|
||||
except requests.RequestException:
|
||||
cloudlog.error(f"casync failed to load {caibx_url}")
|
||||
except Exception:
|
||||
cloudlog.exception("casync failed to hash seed partition")
|
||||
|
||||
# Second source is the target partition, this allows for resuming
|
||||
sources += [('target', casync.FileChunkReader(path), casync.build_chunk_dict(target))]
|
||||
|
||||
# Finally we add the remote source to download any missing chunks
|
||||
sources += [('remote', casync.RemoteChunkReader(partition['casync_store']), casync.build_chunk_dict(target))]
|
||||
|
||||
last_p = 0
|
||||
|
||||
def progress(cur):
|
||||
nonlocal last_p
|
||||
p = int(cur / partition['size'] * 100)
|
||||
if p != last_p:
|
||||
last_p = p
|
||||
print(f"Installing {partition['name']}: {p}", flush=True)
|
||||
|
||||
stats = casync.extract(target, sources, path, progress)
|
||||
cloudlog.error(f'casync done {json.dumps(stats)}')
|
||||
|
||||
os.sync()
|
||||
if not verify_partition(target_slot_number, partition, force_full_check=True):
|
||||
raise Exception(f"Raw hash mismatch '{partition['hash_raw'].lower()}'")
|
||||
|
||||
|
||||
def flash_partition(target_slot_number: int, partition: dict, cloudlog, standalone=False):
|
||||
cloudlog.info(f"Downloading and writing {partition['name']}")
|
||||
|
||||
if verify_partition(target_slot_number, partition):
|
||||
cloudlog.info(f"Already flashed {partition['name']}")
|
||||
return
|
||||
|
||||
# Clear hash before flashing in case we get interrupted
|
||||
full_check = partition['full_check']
|
||||
if not full_check:
|
||||
clear_partition_hash(target_slot_number, partition)
|
||||
|
||||
path = get_partition_path(target_slot_number, partition)
|
||||
|
||||
if ('casync_caibx' in partition) and not standalone:
|
||||
extract_casync_image(target_slot_number, partition, cloudlog)
|
||||
else:
|
||||
extract_compressed_image(target_slot_number, partition, cloudlog)
|
||||
|
||||
# Write hash after successful flash
|
||||
if not full_check:
|
||||
with open(path, 'wb+') as out:
|
||||
out.seek(partition['size'])
|
||||
out.write(partition['hash_raw'].lower().encode())
|
||||
|
||||
|
||||
def swap(manifest_path: str, target_slot_number: int, cloudlog) -> None:
|
||||
update = json.load(open(manifest_path))
|
||||
for partition in update:
|
||||
if not partition.get('full_check', False):
|
||||
clear_partition_hash(target_slot_number, partition)
|
||||
|
||||
while True:
|
||||
out = subprocess.check_output(f"abctl --set_active {target_slot_number}", shell=True, stderr=subprocess.STDOUT, encoding='utf8')
|
||||
if ("No such file or directory" not in out) and ("lun as boot lun" in out):
|
||||
cloudlog.info(f"Swap successful {out}")
|
||||
break
|
||||
else:
|
||||
cloudlog.error(f"Swap failed {out}")
|
||||
|
||||
|
||||
def flash_agnos_update(manifest_path: str, target_slot_number: int, cloudlog, standalone=False) -> None:
|
||||
update = json.load(open(manifest_path))
|
||||
|
||||
cloudlog.info(f"Target slot {target_slot_number}")
|
||||
|
||||
# set target slot as unbootable
|
||||
os.system(f"abctl --set_unbootable {target_slot_number}")
|
||||
|
||||
for partition in update:
|
||||
success = False
|
||||
|
||||
for retries in range(10):
|
||||
try:
|
||||
flash_partition(target_slot_number, partition, cloudlog, standalone)
|
||||
success = True
|
||||
break
|
||||
|
||||
except requests.exceptions.RequestException:
|
||||
cloudlog.exception("Failed")
|
||||
cloudlog.info(f"Failed to download {partition['name']}, retrying ({retries})")
|
||||
time.sleep(10)
|
||||
|
||||
if not success:
|
||||
cloudlog.info(f"Failed to flash {partition['name']}, aborting")
|
||||
raise Exception("Maximum retries exceeded")
|
||||
|
||||
cloudlog.info(f"AGNOS ready on slot {target_slot_number}")
|
||||
|
||||
|
||||
def verify_agnos_update(manifest_path: str, target_slot_number: int) -> bool:
|
||||
update = json.load(open(manifest_path))
|
||||
return all(verify_partition(target_slot_number, partition) for partition in update)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
import argparse
|
||||
import logging
|
||||
|
||||
parser = argparse.ArgumentParser(description="Flash and verify AGNOS update",
|
||||
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
|
||||
|
||||
parser.add_argument("--verify", action="store_true", help="Verify and perform swap if update ready")
|
||||
parser.add_argument("--swap", action="store_true", help="Verify and perform swap, downloads if necessary")
|
||||
parser.add_argument("manifest", help="Manifest json")
|
||||
args = parser.parse_args()
|
||||
|
||||
logging.basicConfig(level=logging.INFO)
|
||||
|
||||
target_slot_number = get_target_slot_number()
|
||||
if args.verify:
|
||||
if verify_agnos_update(args.manifest, target_slot_number):
|
||||
swap(args.manifest, target_slot_number, logging)
|
||||
exit(0)
|
||||
exit(1)
|
||||
elif args.swap:
|
||||
while not verify_agnos_update(args.manifest, target_slot_number):
|
||||
logging.error("Verification failed. Flashing AGNOS")
|
||||
flash_agnos_update(args.manifest, target_slot_number, logging, standalone=True)
|
||||
|
||||
logging.warning(f"Verification succeeded. Swapping to slot {target_slot_number}")
|
||||
swap(args.manifest, target_slot_number, logging)
|
||||
else:
|
||||
flash_agnos_update(args.manifest, target_slot_number, logging, standalone=True)
|
||||
157
system/hardware/tici/amplifier.py
Executable file
157
system/hardware/tici/amplifier.py
Executable file
@@ -0,0 +1,157 @@
|
||||
#!/usr/bin/env python3
|
||||
import time
|
||||
from smbus2 import SMBus
|
||||
from collections import namedtuple
|
||||
from typing import List
|
||||
|
||||
# https://datasheets.maximintegrated.com/en/ds/MAX98089.pdf
|
||||
|
||||
AmpConfig = namedtuple('AmpConfig', ['name', 'value', 'register', 'offset', 'mask'])
|
||||
EQParams = namedtuple('EQParams', ['K', 'k1', 'k2', 'c1', 'c2'])
|
||||
|
||||
def configs_from_eq_params(base, eq_params):
|
||||
return [
|
||||
AmpConfig("K (high)", (eq_params.K >> 8), base, 0, 0xFF),
|
||||
AmpConfig("K (low)", (eq_params.K & 0xFF), base + 1, 0, 0xFF),
|
||||
AmpConfig("k1 (high)", (eq_params.k1 >> 8), base + 2, 0, 0xFF),
|
||||
AmpConfig("k1 (low)", (eq_params.k1 & 0xFF), base + 3, 0, 0xFF),
|
||||
AmpConfig("k2 (high)", (eq_params.k2 >> 8), base + 4, 0, 0xFF),
|
||||
AmpConfig("k2 (low)", (eq_params.k2 & 0xFF), base + 5, 0, 0xFF),
|
||||
AmpConfig("c1 (high)", (eq_params.c1 >> 8), base + 6, 0, 0xFF),
|
||||
AmpConfig("c1 (low)", (eq_params.c1 & 0xFF), base + 7, 0, 0xFF),
|
||||
AmpConfig("c2 (high)", (eq_params.c2 >> 8), base + 8, 0, 0xFF),
|
||||
AmpConfig("c2 (low)", (eq_params.c2 & 0xFF), base + 9, 0, 0xFF),
|
||||
]
|
||||
|
||||
BASE_CONFIG = [
|
||||
AmpConfig("MCLK prescaler", 0b01, 0x10, 4, 0b00110000),
|
||||
AmpConfig("PM: enable speakers", 0b11, 0x4D, 4, 0b00110000),
|
||||
AmpConfig("PM: enable DACs", 0b11, 0x4D, 0, 0b00000011),
|
||||
AmpConfig("Enable PLL1", 0b1, 0x12, 7, 0b10000000),
|
||||
AmpConfig("Enable PLL2", 0b1, 0x1A, 7, 0b10000000),
|
||||
AmpConfig("DAI1: I2S mode", 0b00100, 0x14, 2, 0b01111100),
|
||||
AmpConfig("DAI2: I2S mode", 0b00100, 0x1C, 2, 0b01111100),
|
||||
AmpConfig("DAI1 Passband filtering: music mode", 0b1, 0x18, 7, 0b10000000),
|
||||
AmpConfig("DAI1 voice mode gain (DV1G)", 0b00, 0x2F, 4, 0b00110000),
|
||||
AmpConfig("DAI1 attenuation (DV1)", 0x0, 0x2F, 0, 0b00001111),
|
||||
AmpConfig("DAI2 attenuation (DV2)", 0x0, 0x31, 0, 0b00001111),
|
||||
AmpConfig("DAI2: DC blocking", 0b1, 0x20, 0, 0b00000001),
|
||||
AmpConfig("DAI2: High sample rate", 0b0, 0x20, 3, 0b00001000),
|
||||
AmpConfig("ALC enable", 0b1, 0x43, 7, 0b10000000),
|
||||
AmpConfig("ALC/excursion limiter release time", 0b101, 0x43, 4, 0b01110000),
|
||||
AmpConfig("ALC multiband enable", 0b1, 0x43, 3, 0b00001000),
|
||||
AmpConfig("DAI1 EQ enable", 0b0, 0x49, 0, 0b00000001),
|
||||
AmpConfig("DAI2 EQ clip detection disabled", 0b1, 0x32, 4, 0b00010000),
|
||||
AmpConfig("DAI2 EQ attenuation", 0x5, 0x32, 0, 0b00001111),
|
||||
AmpConfig("Excursion limiter upper corner freq", 0b100, 0x41, 4, 0b01110000),
|
||||
AmpConfig("Excursion limiter lower corner freq", 0b00, 0x41, 0, 0b00000011),
|
||||
AmpConfig("Excursion limiter threshold", 0b000, 0x42, 0, 0b00001111),
|
||||
AmpConfig("Distortion limit (THDCLP)", 0x6, 0x46, 4, 0b11110000),
|
||||
AmpConfig("Distortion limiter release time constant", 0b0, 0x46, 0, 0b00000001),
|
||||
AmpConfig("Right DAC input mixer: DAI1 left", 0b0, 0x22, 3, 0b00001000),
|
||||
AmpConfig("Right DAC input mixer: DAI1 right", 0b0, 0x22, 2, 0b00000100),
|
||||
AmpConfig("Right DAC input mixer: DAI2 left", 0b1, 0x22, 1, 0b00000010),
|
||||
AmpConfig("Right DAC input mixer: DAI2 right", 0b0, 0x22, 0, 0b00000001),
|
||||
AmpConfig("DAI1 audio port selector", 0b10, 0x16, 6, 0b11000000),
|
||||
AmpConfig("DAI2 audio port selector", 0b01, 0x1E, 6, 0b11000000),
|
||||
AmpConfig("Enable left digital microphone", 0b1, 0x48, 5, 0b00100000),
|
||||
AmpConfig("Enable right digital microphone", 0b1, 0x48, 4, 0b00010000),
|
||||
AmpConfig("Enhanced volume smoothing disabled", 0b0, 0x49, 7, 0b10000000),
|
||||
AmpConfig("Volume adjustment smoothing disabled", 0b0, 0x49, 6, 0b01000000),
|
||||
AmpConfig("Zero-crossing detection disabled", 0b0, 0x49, 5, 0b00100000),
|
||||
]
|
||||
|
||||
CONFIGS = {
|
||||
"tici": [
|
||||
AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111),
|
||||
AmpConfig("Right Speaker Mixer Gain", 0b00, 0x2D, 2, 0b00001100),
|
||||
AmpConfig("Right speaker output volume", 0x1c, 0x3E, 0, 0b00011111),
|
||||
AmpConfig("DAI2 EQ enable", 0b1, 0x49, 1, 0b00000010),
|
||||
|
||||
*configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656)),
|
||||
*configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)),
|
||||
*configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42)),
|
||||
*configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807)),
|
||||
*configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B)),
|
||||
],
|
||||
"tizi": [
|
||||
AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111),
|
||||
AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111),
|
||||
AmpConfig("Left Speaker Mixer Gain", 0b00, 0x2D, 0, 0b00000011),
|
||||
AmpConfig("Right Speaker Mixer Gain", 0b00, 0x2D, 2, 0b00001100),
|
||||
AmpConfig("Left speaker output volume", 0x17, 0x3D, 0, 0b00011111),
|
||||
AmpConfig("Right speaker output volume", 0x17, 0x3E, 0, 0b00011111),
|
||||
|
||||
AmpConfig("DAI2 EQ enable", 0b0, 0x49, 1, 0b00000010),
|
||||
AmpConfig("DAI2: DC blocking", 0b0, 0x20, 0, 0b00000001),
|
||||
AmpConfig("ALC enable", 0b0, 0x43, 7, 0b10000000),
|
||||
AmpConfig("DAI2 EQ attenuation", 0x2, 0x32, 0, 0b00001111),
|
||||
AmpConfig("Excursion limiter upper corner freq", 0b001, 0x41, 4, 0b01110000),
|
||||
AmpConfig("Excursion limiter threshold", 0b100, 0x42, 0, 0b00001111),
|
||||
AmpConfig("Distortion limit (THDCLP)", 0x0, 0x46, 4, 0b11110000),
|
||||
AmpConfig("Distortion limiter release time constant", 0b1, 0x46, 0, 0b00000001),
|
||||
AmpConfig("Left DAC input mixer: DAI1 left", 0b0, 0x22, 7, 0b10000000),
|
||||
AmpConfig("Left DAC input mixer: DAI1 right", 0b0, 0x22, 6, 0b01000000),
|
||||
AmpConfig("Left DAC input mixer: DAI2 left", 0b1, 0x22, 5, 0b00100000),
|
||||
AmpConfig("Left DAC input mixer: DAI2 right", 0b0, 0x22, 4, 0b00010000),
|
||||
AmpConfig("Right DAC input mixer: DAI2 left", 0b0, 0x22, 1, 0b00000010),
|
||||
AmpConfig("Right DAC input mixer: DAI2 right", 0b1, 0x22, 0, 0b00000001),
|
||||
AmpConfig("Volume adjustment smoothing disabled", 0b1, 0x49, 6, 0b01000000),
|
||||
],
|
||||
}
|
||||
|
||||
class Amplifier:
|
||||
AMP_I2C_BUS = 0
|
||||
AMP_ADDRESS = 0x10
|
||||
|
||||
def __init__(self, debug=False):
|
||||
self.debug = debug
|
||||
|
||||
def _get_shutdown_config(self, amp_disabled: bool) -> AmpConfig:
|
||||
return AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000)
|
||||
|
||||
def _set_configs(self, configs: List[AmpConfig]) -> None:
|
||||
with SMBus(self.AMP_I2C_BUS) as bus:
|
||||
for config in configs:
|
||||
if self.debug:
|
||||
print(f"Setting \"{config.name}\" to {config.value}:")
|
||||
|
||||
old_value = bus.read_byte_data(self.AMP_ADDRESS, config.register, force=True)
|
||||
new_value = (old_value & (~config.mask)) | ((config.value << config.offset) & config.mask)
|
||||
bus.write_byte_data(self.AMP_ADDRESS, config.register, new_value, force=True)
|
||||
|
||||
if self.debug:
|
||||
print(f" Changed {hex(config.register)}: {hex(old_value)} -> {hex(new_value)}")
|
||||
|
||||
def set_configs(self, configs: List[AmpConfig]) -> bool:
|
||||
# retry in case panda is using the amp
|
||||
tries = 15
|
||||
for i in range(15):
|
||||
try:
|
||||
self._set_configs(configs)
|
||||
return True
|
||||
except OSError:
|
||||
print(f"Failed to set amp config, {tries - i - 1} retries left")
|
||||
time.sleep(0.02)
|
||||
return False
|
||||
|
||||
def set_global_shutdown(self, amp_disabled: bool) -> bool:
|
||||
return self.set_configs([self._get_shutdown_config(amp_disabled), ])
|
||||
|
||||
def initialize_configuration(self, model: str) -> bool:
|
||||
cfgs = [
|
||||
self._get_shutdown_config(True),
|
||||
*BASE_CONFIG,
|
||||
*CONFIGS[model],
|
||||
self._get_shutdown_config(False),
|
||||
]
|
||||
return self.set_configs(cfgs)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
with open("/sys/firmware/devicetree/base/model") as f:
|
||||
model = f.read().strip('\x00')
|
||||
model = model.split('comma ')[-1]
|
||||
|
||||
amp = Amplifier()
|
||||
amp.initialize_configuration(model)
|
||||
208
system/hardware/tici/casync.py
Executable file
208
system/hardware/tici/casync.py
Executable file
@@ -0,0 +1,208 @@
|
||||
#!/usr/bin/env python3
|
||||
import io
|
||||
import lzma
|
||||
import os
|
||||
import struct
|
||||
import sys
|
||||
import time
|
||||
from abc import ABC, abstractmethod
|
||||
from collections import defaultdict, namedtuple
|
||||
from typing import Callable, Dict, List, Optional, Tuple
|
||||
|
||||
import requests
|
||||
from Crypto.Hash import SHA512
|
||||
|
||||
CA_FORMAT_INDEX = 0x96824d9c7b129ff9
|
||||
CA_FORMAT_TABLE = 0xe75b9e112f17417d
|
||||
CA_FORMAT_TABLE_TAIL_MARKER = 0xe75b9e112f17417
|
||||
FLAGS = 0xb000000000000000
|
||||
|
||||
CA_HEADER_LEN = 48
|
||||
CA_TABLE_HEADER_LEN = 16
|
||||
CA_TABLE_ENTRY_LEN = 40
|
||||
CA_TABLE_MIN_LEN = CA_TABLE_HEADER_LEN + CA_TABLE_ENTRY_LEN
|
||||
|
||||
CHUNK_DOWNLOAD_TIMEOUT = 60
|
||||
CHUNK_DOWNLOAD_RETRIES = 3
|
||||
|
||||
CAIBX_DOWNLOAD_TIMEOUT = 120
|
||||
|
||||
Chunk = namedtuple('Chunk', ['sha', 'offset', 'length'])
|
||||
ChunkDict = Dict[bytes, Chunk]
|
||||
|
||||
|
||||
class ChunkReader(ABC):
|
||||
@abstractmethod
|
||||
def read(self, chunk: Chunk) -> bytes:
|
||||
...
|
||||
|
||||
|
||||
class FileChunkReader(ChunkReader):
|
||||
"""Reads chunks from a local file"""
|
||||
def __init__(self, fn: str) -> None:
|
||||
super().__init__()
|
||||
self.f = open(fn, 'rb')
|
||||
|
||||
def __del__(self):
|
||||
self.f.close()
|
||||
|
||||
def read(self, chunk: Chunk) -> bytes:
|
||||
self.f.seek(chunk.offset)
|
||||
return self.f.read(chunk.length)
|
||||
|
||||
|
||||
class RemoteChunkReader(ChunkReader):
|
||||
"""Reads lzma compressed chunks from a remote store"""
|
||||
|
||||
def __init__(self, url: str) -> None:
|
||||
super().__init__()
|
||||
self.url = url
|
||||
self.session = requests.Session()
|
||||
|
||||
def read(self, chunk: Chunk) -> bytes:
|
||||
sha_hex = chunk.sha.hex()
|
||||
url = os.path.join(self.url, sha_hex[:4], sha_hex + ".cacnk")
|
||||
|
||||
if os.path.isfile(url):
|
||||
with open(url, 'rb') as f:
|
||||
contents = f.read()
|
||||
else:
|
||||
for i in range(CHUNK_DOWNLOAD_RETRIES):
|
||||
try:
|
||||
resp = self.session.get(url, timeout=CHUNK_DOWNLOAD_TIMEOUT)
|
||||
break
|
||||
except Exception:
|
||||
if i == CHUNK_DOWNLOAD_RETRIES - 1:
|
||||
raise
|
||||
time.sleep(CHUNK_DOWNLOAD_TIMEOUT)
|
||||
|
||||
resp.raise_for_status()
|
||||
contents = resp.content
|
||||
|
||||
decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO)
|
||||
return decompressor.decompress(contents)
|
||||
|
||||
|
||||
def parse_caibx(caibx_path: str) -> List[Chunk]:
|
||||
"""Parses the chunks from a caibx file. Can handle both local and remote files.
|
||||
Returns a list of chunks with hash, offset and length"""
|
||||
caibx: io.BufferedIOBase
|
||||
if os.path.isfile(caibx_path):
|
||||
caibx = open(caibx_path, 'rb')
|
||||
else:
|
||||
resp = requests.get(caibx_path, timeout=CAIBX_DOWNLOAD_TIMEOUT)
|
||||
resp.raise_for_status()
|
||||
caibx = io.BytesIO(resp.content)
|
||||
|
||||
caibx.seek(0, os.SEEK_END)
|
||||
caibx_len = caibx.tell()
|
||||
caibx.seek(0, os.SEEK_SET)
|
||||
|
||||
# Parse header
|
||||
length, magic, flags, min_size, _, max_size = struct.unpack("<QQQQQQ", caibx.read(CA_HEADER_LEN))
|
||||
assert flags == flags
|
||||
assert length == CA_HEADER_LEN
|
||||
assert magic == CA_FORMAT_INDEX
|
||||
|
||||
# Parse table header
|
||||
length, magic = struct.unpack("<QQ", caibx.read(CA_TABLE_HEADER_LEN))
|
||||
assert magic == CA_FORMAT_TABLE
|
||||
|
||||
# Parse chunks
|
||||
num_chunks = (caibx_len - CA_HEADER_LEN - CA_TABLE_MIN_LEN) // CA_TABLE_ENTRY_LEN
|
||||
chunks = []
|
||||
|
||||
offset = 0
|
||||
for i in range(num_chunks):
|
||||
new_offset = struct.unpack("<Q", caibx.read(8))[0]
|
||||
|
||||
sha = caibx.read(32)
|
||||
length = new_offset - offset
|
||||
|
||||
assert length <= max_size
|
||||
|
||||
# Last chunk can be smaller
|
||||
if i < num_chunks - 1:
|
||||
assert length >= min_size
|
||||
|
||||
chunks.append(Chunk(sha, offset, length))
|
||||
offset = new_offset
|
||||
|
||||
caibx.close()
|
||||
return chunks
|
||||
|
||||
|
||||
def build_chunk_dict(chunks: List[Chunk]) -> ChunkDict:
|
||||
"""Turn a list of chunks into a dict for faster lookups based on hash.
|
||||
Keep first chunk since it's more likely to be already downloaded."""
|
||||
r = {}
|
||||
for c in chunks:
|
||||
if c.sha not in r:
|
||||
r[c.sha] = c
|
||||
return r
|
||||
|
||||
|
||||
def extract(target: List[Chunk],
|
||||
sources: List[Tuple[str, ChunkReader, ChunkDict]],
|
||||
out_path: str,
|
||||
progress: Optional[Callable[[int], None]] = None):
|
||||
stats: Dict[str, int] = defaultdict(int)
|
||||
|
||||
mode = 'rb+' if os.path.exists(out_path) else 'wb'
|
||||
with open(out_path, mode) as out:
|
||||
for cur_chunk in target:
|
||||
|
||||
# Find source for desired chunk
|
||||
for name, chunk_reader, store_chunks in sources:
|
||||
if cur_chunk.sha in store_chunks:
|
||||
bts = chunk_reader.read(store_chunks[cur_chunk.sha])
|
||||
|
||||
# Check length
|
||||
if len(bts) != cur_chunk.length:
|
||||
continue
|
||||
|
||||
# Check hash
|
||||
if SHA512.new(bts, truncate="256").digest() != cur_chunk.sha:
|
||||
continue
|
||||
|
||||
# Write to output
|
||||
out.seek(cur_chunk.offset)
|
||||
out.write(bts)
|
||||
|
||||
stats[name] += cur_chunk.length
|
||||
|
||||
if progress is not None:
|
||||
progress(sum(stats.values()))
|
||||
|
||||
break
|
||||
else:
|
||||
raise RuntimeError("Desired chunk not found in provided stores")
|
||||
|
||||
return stats
|
||||
|
||||
|
||||
def print_stats(stats: Dict[str, int]):
|
||||
total_bytes = sum(stats.values())
|
||||
print(f"Total size: {total_bytes / 1024 / 1024:.2f} MB")
|
||||
for name, total in stats.items():
|
||||
print(f" {name}: {total / 1024 / 1024:.2f} MB ({total / total_bytes * 100:.1f}%)")
|
||||
|
||||
|
||||
def extract_simple(caibx_path, out_path, store_path):
|
||||
# (name, callback, chunks)
|
||||
target = parse_caibx(caibx_path)
|
||||
sources = [
|
||||
# (store_path, RemoteChunkReader(store_path), build_chunk_dict(target)),
|
||||
(store_path, FileChunkReader(store_path), build_chunk_dict(target)),
|
||||
]
|
||||
|
||||
return extract(target, sources, out_path)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
caibx = sys.argv[1]
|
||||
out = sys.argv[2]
|
||||
store = sys.argv[3]
|
||||
|
||||
stats = extract_simple(caibx, out, store)
|
||||
print_stats(stats)
|
||||
30
system/hardware/tici/esim.nmconnection
Normal file
30
system/hardware/tici/esim.nmconnection
Normal file
@@ -0,0 +1,30 @@
|
||||
[connection]
|
||||
id=esim
|
||||
uuid=fff6553c-3284-4707-a6b1-acc021caaafb
|
||||
type=gsm
|
||||
permissions=
|
||||
autoconnect=true
|
||||
autoconnect-retries=100
|
||||
autoconnect-priority=2
|
||||
metered=1
|
||||
|
||||
[gsm]
|
||||
apn=
|
||||
home-only=false
|
||||
auto-config=true
|
||||
sim-id=
|
||||
|
||||
[ipv4]
|
||||
route-metric=1000
|
||||
dns-priority=1000
|
||||
dns-search=
|
||||
method=auto
|
||||
|
||||
[ipv6]
|
||||
ddr-gen-mode=stable-privacy
|
||||
dns-search=
|
||||
route-metric=1000
|
||||
dns-priority=1000
|
||||
method=auto
|
||||
|
||||
[proxy]
|
||||
105
system/hardware/tici/hardware.h
Normal file
105
system/hardware/tici/hardware.h
Normal file
@@ -0,0 +1,105 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdlib>
|
||||
#include <fstream>
|
||||
#include <map>
|
||||
#include <string>
|
||||
|
||||
#include "common/params.h"
|
||||
#include "common/util.h"
|
||||
#include "system/hardware/base.h"
|
||||
|
||||
class HardwareTici : public HardwareNone {
|
||||
public:
|
||||
static constexpr float MAX_VOLUME = 0.9;
|
||||
static constexpr float MIN_VOLUME = 0.1;
|
||||
static bool TICI() { return true; }
|
||||
static bool AGNOS() { return true; }
|
||||
static std::string get_os_version() {
|
||||
return "AGNOS " + util::read_file("/VERSION");
|
||||
}
|
||||
|
||||
static std::string get_name() {
|
||||
std::string devicetree_model = util::read_file("/sys/firmware/devicetree/base/model");
|
||||
return (devicetree_model.find("tizi") != std::string::npos) ? "tizi" : "tici";
|
||||
}
|
||||
|
||||
static cereal::InitData::DeviceType get_device_type() {
|
||||
return (get_name() == "tizi") ? cereal::InitData::DeviceType::TIZI : cereal::InitData::DeviceType::TICI;
|
||||
}
|
||||
|
||||
static int get_voltage() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/in1_input").c_str()); }
|
||||
static int get_current() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/curr1_input").c_str()); }
|
||||
|
||||
static std::string get_serial() {
|
||||
static std::string serial("");
|
||||
if (serial.empty()) {
|
||||
std::ifstream stream("/proc/cmdline");
|
||||
std::string cmdline;
|
||||
std::getline(stream, cmdline);
|
||||
|
||||
auto start = cmdline.find("serialno=");
|
||||
if (start == std::string::npos) {
|
||||
serial = "cccccc";
|
||||
} else {
|
||||
auto end = cmdline.find(" ", start + 9);
|
||||
serial = cmdline.substr(start + 9, end - start - 9);
|
||||
}
|
||||
}
|
||||
return serial;
|
||||
}
|
||||
|
||||
static void reboot() { std::system("sudo reboot"); }
|
||||
static void poweroff() { std::system("sudo poweroff"); }
|
||||
static void set_brightness(int percent) {
|
||||
std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness");
|
||||
|
||||
std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness");
|
||||
if (brightness_control.is_open()) {
|
||||
brightness_control << (int)(percent * (std::stof(max)/100.)) << "\n";
|
||||
brightness_control.close();
|
||||
}
|
||||
}
|
||||
static void set_display_power(bool on) {
|
||||
std::ofstream bl_power_control("/sys/class/backlight/panel0-backlight/bl_power");
|
||||
if (bl_power_control.is_open()) {
|
||||
bl_power_control << (on ? "0" : "4") << "\n";
|
||||
bl_power_control.close();
|
||||
}
|
||||
}
|
||||
|
||||
static std::map<std::string, std::string> get_init_logs() {
|
||||
std::map<std::string, std::string> ret = {
|
||||
{"/BUILD", util::read_file("/BUILD")},
|
||||
{"lsblk", util::check_output("lsblk -o NAME,SIZE,STATE,VENDOR,MODEL,REV,SERIAL")},
|
||||
};
|
||||
|
||||
std::string bs = util::check_output("abctl --boot_slot");
|
||||
ret["boot slot"] = bs.substr(0, bs.find_first_of("\n"));
|
||||
|
||||
std::string temp = util::read_file("/dev/disk/by-partlabel/ssd");
|
||||
temp.erase(temp.find_last_not_of(std::string("\0\r\n", 3))+1);
|
||||
ret["boot temp"] = temp;
|
||||
|
||||
// TODO: log something from system and boot
|
||||
for (std::string part : {"xbl", "abl", "aop", "devcfg", "xbl_config"}) {
|
||||
for (std::string slot : {"a", "b"}) {
|
||||
std::string partition = part + "_" + slot;
|
||||
std::string hash = util::check_output("sha256sum /dev/disk/by-partlabel/" + partition);
|
||||
ret[partition] = hash.substr(0, hash.find_first_of(" "));
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static bool get_ssh_enabled() { return Params().getBool("SshEnabled"); }
|
||||
static void set_ssh_enabled(bool enabled) { Params().putBool("SshEnabled", enabled); }
|
||||
|
||||
static void config_cpu_rendering(bool offscreen) {
|
||||
if (offscreen) {
|
||||
setenv("QT_QPA_PLATFORM", "eglfs", 1); // offscreen doesn't work with EGL/GLES
|
||||
}
|
||||
setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU
|
||||
}
|
||||
};
|
||||
573
system/hardware/tici/hardware.py
Normal file
573
system/hardware/tici/hardware.py
Normal file
@@ -0,0 +1,573 @@
|
||||
import json
|
||||
import math
|
||||
import os
|
||||
import subprocess
|
||||
import time
|
||||
import tempfile
|
||||
from enum import IntEnum
|
||||
from functools import cached_property, lru_cache
|
||||
from pathlib import Path
|
||||
|
||||
from cereal import log
|
||||
from openpilot.common.gpio import gpio_set, gpio_init, get_irqs_for_action
|
||||
from openpilot.system.hardware.base import HardwareBase, ThermalConfig
|
||||
from openpilot.system.hardware.tici import iwlist
|
||||
from openpilot.system.hardware.tici.pins import GPIO
|
||||
from openpilot.system.hardware.tici.amplifier import Amplifier
|
||||
|
||||
NM = 'org.freedesktop.NetworkManager'
|
||||
NM_CON_ACT = NM + '.Connection.Active'
|
||||
NM_DEV = NM + '.Device'
|
||||
NM_DEV_WL = NM + '.Device.Wireless'
|
||||
NM_DEV_STATS = NM + '.Device.Statistics'
|
||||
NM_AP = NM + '.AccessPoint'
|
||||
DBUS_PROPS = 'org.freedesktop.DBus.Properties'
|
||||
|
||||
MM = 'org.freedesktop.ModemManager1'
|
||||
MM_MODEM = MM + ".Modem"
|
||||
MM_MODEM_SIMPLE = MM + ".Modem.Simple"
|
||||
MM_SIM = MM + ".Sim"
|
||||
|
||||
class MM_MODEM_STATE(IntEnum):
|
||||
FAILED = -1
|
||||
UNKNOWN = 0
|
||||
INITIALIZING = 1
|
||||
LOCKED = 2
|
||||
DISABLED = 3
|
||||
DISABLING = 4
|
||||
ENABLING = 5
|
||||
ENABLED = 6
|
||||
SEARCHING = 7
|
||||
REGISTERED = 8
|
||||
DISCONNECTING = 9
|
||||
CONNECTING = 10
|
||||
CONNECTED = 11
|
||||
|
||||
class NMMetered(IntEnum):
|
||||
NM_METERED_UNKNOWN = 0
|
||||
NM_METERED_YES = 1
|
||||
NM_METERED_NO = 2
|
||||
NM_METERED_GUESS_YES = 3
|
||||
NM_METERED_GUESS_NO = 4
|
||||
|
||||
TIMEOUT = 0.1
|
||||
REFRESH_RATE_MS = 1000
|
||||
|
||||
NetworkType = log.DeviceState.NetworkType
|
||||
NetworkStrength = log.DeviceState.NetworkStrength
|
||||
|
||||
# https://developer.gnome.org/ModemManager/unstable/ModemManager-Flags-and-Enumerations.html#MMModemAccessTechnology
|
||||
MM_MODEM_ACCESS_TECHNOLOGY_UMTS = 1 << 5
|
||||
MM_MODEM_ACCESS_TECHNOLOGY_LTE = 1 << 14
|
||||
|
||||
|
||||
def sudo_write(val, path):
|
||||
try:
|
||||
with open(path, 'w') as f:
|
||||
f.write(str(val))
|
||||
except PermissionError:
|
||||
os.system(f"sudo chmod a+w {path}")
|
||||
try:
|
||||
with open(path, 'w') as f:
|
||||
f.write(str(val))
|
||||
except PermissionError:
|
||||
# fallback for debugfs files
|
||||
os.system(f"sudo su -c 'echo {val} > {path}'")
|
||||
|
||||
def sudo_read(path: str) -> str:
|
||||
try:
|
||||
return subprocess.check_output(f"sudo cat {path}", shell=True, encoding='utf8')
|
||||
except Exception:
|
||||
return ""
|
||||
|
||||
def affine_irq(val, action):
|
||||
irqs = get_irqs_for_action(action)
|
||||
if len(irqs) == 0:
|
||||
print(f"No IRQs found for '{action}'")
|
||||
return
|
||||
|
||||
for i in irqs:
|
||||
sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list")
|
||||
|
||||
@lru_cache
|
||||
def get_device_type():
|
||||
# lru_cache and cache can cause memory leaks when used in classes
|
||||
with open("/sys/firmware/devicetree/base/model") as f:
|
||||
model = f.read().strip('\x00')
|
||||
model = model.split('comma ')[-1]
|
||||
# TODO: remove this with AGNOS 7+
|
||||
if model.startswith('Qualcomm'):
|
||||
model = 'tici'
|
||||
return model
|
||||
|
||||
class Tici(HardwareBase):
|
||||
@cached_property
|
||||
def bus(self):
|
||||
import dbus
|
||||
return dbus.SystemBus()
|
||||
|
||||
@cached_property
|
||||
def nm(self):
|
||||
return self.bus.get_object(NM, '/org/freedesktop/NetworkManager')
|
||||
|
||||
@property # this should not be cached, in case the modemmanager restarts
|
||||
def mm(self):
|
||||
return self.bus.get_object(MM, '/org/freedesktop/ModemManager1')
|
||||
|
||||
@cached_property
|
||||
def amplifier(self):
|
||||
return Amplifier()
|
||||
|
||||
def get_os_version(self):
|
||||
with open("/VERSION") as f:
|
||||
return f.read().strip()
|
||||
|
||||
def get_device_type(self):
|
||||
return get_device_type()
|
||||
|
||||
def get_sound_card_online(self):
|
||||
if os.path.isfile('/proc/asound/card0/state'):
|
||||
with open('/proc/asound/card0/state') as f:
|
||||
return f.read().strip() == 'ONLINE'
|
||||
return False
|
||||
|
||||
def reboot(self, reason=None):
|
||||
subprocess.check_output(["sudo", "reboot"])
|
||||
|
||||
def uninstall(self):
|
||||
Path("/data/__system_reset__").touch()
|
||||
os.sync()
|
||||
self.reboot()
|
||||
|
||||
def get_serial(self):
|
||||
return self.get_cmdline()['androidboot.serialno']
|
||||
|
||||
def get_network_type(self):
|
||||
try:
|
||||
primary_connection = self.nm.Get(NM, 'PrimaryConnection', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
primary_connection = self.bus.get_object(NM, primary_connection)
|
||||
primary_type = primary_connection.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
|
||||
if primary_type == '802-3-ethernet':
|
||||
return NetworkType.ethernet
|
||||
elif primary_type == '802-11-wireless':
|
||||
return NetworkType.wifi
|
||||
else:
|
||||
active_connections = self.nm.Get(NM, 'ActiveConnections', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
for conn in active_connections:
|
||||
c = self.bus.get_object(NM, conn)
|
||||
tp = c.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
if tp == 'gsm':
|
||||
modem = self.get_modem()
|
||||
access_t = modem.Get(MM_MODEM, 'AccessTechnologies', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
if access_t >= MM_MODEM_ACCESS_TECHNOLOGY_LTE:
|
||||
return NetworkType.cell4G
|
||||
elif access_t >= MM_MODEM_ACCESS_TECHNOLOGY_UMTS:
|
||||
return NetworkType.cell3G
|
||||
else:
|
||||
return NetworkType.cell2G
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
return NetworkType.none
|
||||
|
||||
def get_modem(self):
|
||||
objects = self.mm.GetManagedObjects(dbus_interface="org.freedesktop.DBus.ObjectManager", timeout=TIMEOUT)
|
||||
modem_path = list(objects.keys())[0]
|
||||
return self.bus.get_object(MM, modem_path)
|
||||
|
||||
def get_wlan(self):
|
||||
wlan_path = self.nm.GetDeviceByIpIface('wlan0', dbus_interface=NM, timeout=TIMEOUT)
|
||||
return self.bus.get_object(NM, wlan_path)
|
||||
|
||||
def get_wwan(self):
|
||||
wwan_path = self.nm.GetDeviceByIpIface('wwan0', dbus_interface=NM, timeout=TIMEOUT)
|
||||
return self.bus.get_object(NM, wwan_path)
|
||||
|
||||
def get_sim_info(self):
|
||||
modem = self.get_modem()
|
||||
sim_path = modem.Get(MM_MODEM, 'Sim', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
|
||||
if sim_path == "/":
|
||||
return {
|
||||
'sim_id': '',
|
||||
'mcc_mnc': None,
|
||||
'network_type': ["Unknown"],
|
||||
'sim_state': ["ABSENT"],
|
||||
'data_connected': False
|
||||
}
|
||||
else:
|
||||
sim = self.bus.get_object(MM, sim_path)
|
||||
return {
|
||||
'sim_id': str(sim.Get(MM_SIM, 'SimIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)),
|
||||
'mcc_mnc': str(sim.Get(MM_SIM, 'OperatorIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)),
|
||||
'network_type': ["Unknown"],
|
||||
'sim_state': ["READY"],
|
||||
'data_connected': modem.Get(MM_MODEM, 'State', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) == MM_MODEM_STATE.CONNECTED,
|
||||
}
|
||||
|
||||
def get_subscriber_info(self):
|
||||
return ""
|
||||
|
||||
def get_imei(self, slot):
|
||||
if slot != 0:
|
||||
return ""
|
||||
|
||||
return str(self.get_modem().Get(MM_MODEM, 'EquipmentIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT))
|
||||
|
||||
def get_network_info(self):
|
||||
try:
|
||||
modem = self.get_modem()
|
||||
info = modem.Command("AT+QNWINFO", math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT)
|
||||
extra = modem.Command('AT+QENG="servingcell"', math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT)
|
||||
state = modem.Get(MM_MODEM, 'State', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
if info and info.startswith('+QNWINFO: '):
|
||||
info = info.replace('+QNWINFO: ', '').replace('"', '').split(',')
|
||||
extra = "" if extra is None else extra.replace('+QENG: "servingcell",', '').replace('"', '')
|
||||
state = "" if state is None else MM_MODEM_STATE(state).name
|
||||
|
||||
if len(info) != 4:
|
||||
return None
|
||||
|
||||
technology, operator, band, channel = info
|
||||
|
||||
return({
|
||||
'technology': technology,
|
||||
'operator': operator,
|
||||
'band': band,
|
||||
'channel': int(channel),
|
||||
'extra': extra,
|
||||
'state': state,
|
||||
})
|
||||
else:
|
||||
return None
|
||||
|
||||
def parse_strength(self, percentage):
|
||||
if percentage < 25:
|
||||
return NetworkStrength.poor
|
||||
elif percentage < 50:
|
||||
return NetworkStrength.moderate
|
||||
elif percentage < 75:
|
||||
return NetworkStrength.good
|
||||
else:
|
||||
return NetworkStrength.great
|
||||
|
||||
def get_network_strength(self, network_type):
|
||||
network_strength = NetworkStrength.unknown
|
||||
|
||||
try:
|
||||
if network_type == NetworkType.none:
|
||||
pass
|
||||
elif network_type == NetworkType.wifi:
|
||||
wlan = self.get_wlan()
|
||||
active_ap_path = wlan.Get(NM_DEV_WL, 'ActiveAccessPoint', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
if active_ap_path != "/":
|
||||
active_ap = self.bus.get_object(NM, active_ap_path)
|
||||
strength = int(active_ap.Get(NM_AP, 'Strength', dbus_interface=DBUS_PROPS, timeout=TIMEOUT))
|
||||
network_strength = self.parse_strength(strength)
|
||||
else: # Cellular
|
||||
modem = self.get_modem()
|
||||
strength = int(modem.Get(MM_MODEM, 'SignalQuality', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)[0])
|
||||
network_strength = self.parse_strength(strength)
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
return network_strength
|
||||
|
||||
def get_network_metered(self, network_type) -> bool:
|
||||
try:
|
||||
primary_connection = self.nm.Get(NM, 'PrimaryConnection', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
primary_connection = self.bus.get_object(NM, primary_connection)
|
||||
primary_devices = primary_connection.Get(NM_CON_ACT, 'Devices', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
|
||||
for dev in primary_devices:
|
||||
dev_obj = self.bus.get_object(NM, str(dev))
|
||||
metered_prop = dev_obj.Get(NM_DEV, 'Metered', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
|
||||
if network_type == NetworkType.wifi:
|
||||
if metered_prop in [NMMetered.NM_METERED_YES, NMMetered.NM_METERED_GUESS_YES]:
|
||||
return True
|
||||
elif network_type in [NetworkType.cell2G, NetworkType.cell3G, NetworkType.cell4G, NetworkType.cell5G]:
|
||||
if metered_prop == NMMetered.NM_METERED_NO:
|
||||
return False
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
return super().get_network_metered(network_type)
|
||||
|
||||
def get_modem_version(self):
|
||||
try:
|
||||
modem = self.get_modem()
|
||||
return modem.Get(MM_MODEM, 'Revision', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
def get_modem_nv(self):
|
||||
timeout = 0.2 # Default timeout is too short
|
||||
files = (
|
||||
'/nv/item_files/modem/mmode/ue_usage_setting',
|
||||
'/nv/item_files/ims/IMS_enable',
|
||||
'/nv/item_files/modem/mmode/sms_only',
|
||||
)
|
||||
try:
|
||||
modem = self.get_modem()
|
||||
return { fn: str(modem.Command(f'AT+QNVFR="{fn}"', math.ceil(timeout), dbus_interface=MM_MODEM, timeout=timeout)) for fn in files}
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
def get_modem_temperatures(self):
|
||||
timeout = 0.2 # Default timeout is too short
|
||||
try:
|
||||
modem = self.get_modem()
|
||||
temps = modem.Command("AT+QTEMP", math.ceil(timeout), dbus_interface=MM_MODEM, timeout=timeout)
|
||||
return list(map(int, temps.split(' ')[1].split(',')))
|
||||
except Exception:
|
||||
return []
|
||||
|
||||
def get_nvme_temperatures(self):
|
||||
ret = []
|
||||
try:
|
||||
out = subprocess.check_output("sudo smartctl -aj /dev/nvme0", shell=True)
|
||||
dat = json.loads(out)
|
||||
ret = list(map(int, dat["nvme_smart_health_information_log"]["temperature_sensors"]))
|
||||
except Exception:
|
||||
pass
|
||||
return ret
|
||||
|
||||
def get_usb_present(self):
|
||||
# Not sure if relevant on tici, but the file exists
|
||||
return self.read_param_file("/sys/class/power_supply/usb/present", lambda x: bool(int(x)), False)
|
||||
|
||||
def get_current_power_draw(self):
|
||||
return (self.read_param_file("/sys/class/hwmon/hwmon1/power1_input", int) / 1e6)
|
||||
|
||||
def get_som_power_draw(self):
|
||||
return (self.read_param_file("/sys/class/power_supply/bms/voltage_now", int) * self.read_param_file("/sys/class/power_supply/bms/current_now", int) / 1e12)
|
||||
|
||||
def shutdown(self):
|
||||
os.system("sudo poweroff")
|
||||
|
||||
def get_thermal_config(self):
|
||||
return ThermalConfig(cpu=(["cpu%d-silver-usr" % i for i in range(4)] +
|
||||
["cpu%d-gold-usr" % i for i in range(4)], 1000),
|
||||
gpu=(("gpu0-usr", "gpu1-usr"), 1000),
|
||||
mem=("ddr-usr", 1000),
|
||||
bat=(None, 1),
|
||||
ambient=("xo-therm-adc", 1000),
|
||||
pmic=(("pm8998_tz", "pm8005_tz"), 1000))
|
||||
|
||||
def set_screen_brightness(self, percentage):
|
||||
try:
|
||||
with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
|
||||
max_brightness = float(f.read().strip())
|
||||
|
||||
val = int(percentage * (max_brightness / 100.))
|
||||
with open("/sys/class/backlight/panel0-backlight/brightness", "w") as f:
|
||||
f.write(str(val))
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
def get_screen_brightness(self):
|
||||
try:
|
||||
with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
|
||||
max_brightness = float(f.read().strip())
|
||||
|
||||
with open("/sys/class/backlight/panel0-backlight/brightness") as f:
|
||||
return int(float(f.read()) / (max_brightness / 100.))
|
||||
except Exception:
|
||||
return 0
|
||||
|
||||
def set_power_save(self, powersave_enabled):
|
||||
# amplifier, 100mW at idle
|
||||
self.amplifier.set_global_shutdown(amp_disabled=powersave_enabled)
|
||||
if not powersave_enabled:
|
||||
self.amplifier.initialize_configuration(self.get_device_type())
|
||||
|
||||
# *** CPU config ***
|
||||
|
||||
# offline big cluster, leave core 4 online for boardd
|
||||
for i in range(5, 8):
|
||||
val = '0' if powersave_enabled else '1'
|
||||
sudo_write(val, f'/sys/devices/system/cpu/cpu{i}/online')
|
||||
|
||||
for n in ('0', '4'):
|
||||
gov = 'ondemand' if powersave_enabled else 'performance'
|
||||
sudo_write(gov, f'/sys/devices/system/cpu/cpufreq/policy{n}/scaling_governor')
|
||||
|
||||
# *** IRQ config ***
|
||||
|
||||
# boardd core
|
||||
affine_irq(4, "spi_geni") # SPI
|
||||
affine_irq(4, "xhci-hcd:usb3") # aux panda USB (or potentially anything else on USB)
|
||||
if "tici" in self.get_device_type():
|
||||
affine_irq(4, "xhci-hcd:usb1") # internal panda USB (also modem)
|
||||
|
||||
# GPU
|
||||
affine_irq(5, "kgsl-3d0")
|
||||
|
||||
# camerad core
|
||||
camera_irqs = ("cci", "cpas_camnoc", "cpas-cdm", "csid", "ife", "csid-lite", "ife-lite")
|
||||
for n in camera_irqs:
|
||||
affine_irq(5, n)
|
||||
|
||||
def get_gpu_usage_percent(self):
|
||||
try:
|
||||
with open('/sys/class/kgsl/kgsl-3d0/gpubusy') as f:
|
||||
used, total = f.read().strip().split()
|
||||
return 100.0 * int(used) / int(total)
|
||||
except Exception:
|
||||
return 0
|
||||
|
||||
def initialize_hardware(self):
|
||||
self.amplifier.initialize_configuration(self.get_device_type())
|
||||
|
||||
# Allow thermald to write engagement status to kmsg
|
||||
os.system("sudo chmod a+w /dev/kmsg")
|
||||
|
||||
# Ensure fan gpio is enabled so fan runs until shutdown, also turned on at boot by the ABL
|
||||
gpio_init(GPIO.SOM_ST_IO, True)
|
||||
gpio_set(GPIO.SOM_ST_IO, 1)
|
||||
|
||||
# *** IRQ config ***
|
||||
|
||||
# mask off big cluster from default affinity
|
||||
sudo_write("f", "/proc/irq/default_smp_affinity")
|
||||
|
||||
# move these off the default core
|
||||
affine_irq(1, "msm_drm") # display
|
||||
affine_irq(1, "msm_vidc") # encoders
|
||||
affine_irq(1, "i2c_geni") # sensors
|
||||
|
||||
# *** GPU config ***
|
||||
# https://github.com/commaai/agnos-kernel-sdm845/blob/master/arch/arm64/boot/dts/qcom/sdm845-gpu.dtsi#L216
|
||||
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel")
|
||||
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/max_pwrlevel")
|
||||
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_bus_on")
|
||||
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_clk_on")
|
||||
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_rail_on")
|
||||
sudo_write("1000", "/sys/class/kgsl/kgsl-3d0/idle_timer")
|
||||
sudo_write("performance", "/sys/class/kgsl/kgsl-3d0/devfreq/governor")
|
||||
sudo_write("710", "/sys/class/kgsl/kgsl-3d0/max_clock_mhz")
|
||||
|
||||
# setup governors
|
||||
sudo_write("performance", "/sys/class/devfreq/soc:qcom,cpubw/governor")
|
||||
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', '')
|
||||
|
||||
# configure modem as data-centric
|
||||
cmds = [
|
||||
'AT+QNVW=5280,0,"0102000000000000"',
|
||||
'AT+QNVFW="/nv/item_files/ims/IMS_enable",00',
|
||||
'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01',
|
||||
]
|
||||
modem = self.get_modem()
|
||||
for cmd in cmds:
|
||||
try:
|
||||
modem.Command(cmd, math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT)
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
# blue prime
|
||||
blue_prime = sim_id.startswith('8901410')
|
||||
initial_apn = "Broadband" if blue_prime else ""
|
||||
os.system(f'mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn={initial_apn}"')
|
||||
|
||||
# eSIM prime
|
||||
if sim_id.startswith('8985235'):
|
||||
dest = "/etc/NetworkManager/system-connections/esim.nmconnection"
|
||||
with open(Path(__file__).parent/'esim.nmconnection') as f, tempfile.NamedTemporaryFile(mode='w') as tf:
|
||||
dat = f.read()
|
||||
dat = dat.replace("sim-id=", f"sim-id={sim_id}")
|
||||
tf.write(dat)
|
||||
tf.flush()
|
||||
|
||||
# needs to be root
|
||||
os.system(f"sudo cp {tf.name} {dest}")
|
||||
os.system(f"sudo nmcli con load {dest}")
|
||||
|
||||
def get_networks(self):
|
||||
r = {}
|
||||
|
||||
wlan = iwlist.scan()
|
||||
if wlan is not None:
|
||||
r['wlan'] = wlan
|
||||
|
||||
lte_info = self.get_network_info()
|
||||
if lte_info is not None:
|
||||
extra = lte_info['extra']
|
||||
|
||||
# <state>,"LTE",<is_tdd>,<mcc>,<mnc>,<cellid>,<pcid>,<earfcn>,<freq_band_ind>,
|
||||
# <ul_bandwidth>,<dl_bandwidth>,<tac>,<rsrp>,<rsrq>,<rssi>,<sinr>,<srxlev>
|
||||
if 'LTE' in extra:
|
||||
extra = extra.split(',')
|
||||
try:
|
||||
r['lte'] = [{
|
||||
"mcc": int(extra[3]),
|
||||
"mnc": int(extra[4]),
|
||||
"cid": int(extra[5], 16),
|
||||
"nmr": [{"pci": int(extra[6]), "earfcn": int(extra[7])}],
|
||||
}]
|
||||
except (ValueError, IndexError):
|
||||
pass
|
||||
|
||||
return r
|
||||
|
||||
def get_modem_data_usage(self):
|
||||
try:
|
||||
wwan = self.get_wwan()
|
||||
|
||||
# Ensure refresh rate is set so values don't go stale
|
||||
refresh_rate = wwan.Get(NM_DEV_STATS, 'RefreshRateMs', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
if refresh_rate != REFRESH_RATE_MS:
|
||||
u = type(refresh_rate)
|
||||
wwan.Set(NM_DEV_STATS, 'RefreshRateMs', u(REFRESH_RATE_MS), dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
|
||||
tx = wwan.Get(NM_DEV_STATS, 'TxBytes', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
rx = wwan.Get(NM_DEV_STATS, 'RxBytes', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)
|
||||
return int(tx), int(rx)
|
||||
except Exception:
|
||||
return -1, -1
|
||||
|
||||
def has_internal_panda(self):
|
||||
return True
|
||||
|
||||
def reset_internal_panda(self):
|
||||
gpio_init(GPIO.STM_RST_N, True)
|
||||
|
||||
gpio_set(GPIO.STM_RST_N, 1)
|
||||
time.sleep(1)
|
||||
gpio_set(GPIO.STM_RST_N, 0)
|
||||
|
||||
def recover_internal_panda(self):
|
||||
gpio_init(GPIO.STM_RST_N, True)
|
||||
gpio_init(GPIO.STM_BOOT0, True)
|
||||
|
||||
gpio_set(GPIO.STM_RST_N, 1)
|
||||
gpio_set(GPIO.STM_BOOT0, 1)
|
||||
time.sleep(0.5)
|
||||
gpio_set(GPIO.STM_RST_N, 0)
|
||||
time.sleep(0.5)
|
||||
gpio_set(GPIO.STM_BOOT0, 0)
|
||||
|
||||
def booted(self):
|
||||
# this normally boots within 8s, but on rare occasions takes 30+s
|
||||
encoder_state = sudo_read("/sys/kernel/debug/msm_vidc/core0/info")
|
||||
if "Core state: 0" in encoder_state and (time.monotonic() < 60*2):
|
||||
return False
|
||||
return True
|
||||
|
||||
if __name__ == "__main__":
|
||||
t = Tici()
|
||||
t.configure_modem()
|
||||
t.initialize_hardware()
|
||||
t.set_power_save(False)
|
||||
35
system/hardware/tici/iwlist.py
Normal file
35
system/hardware/tici/iwlist.py
Normal file
@@ -0,0 +1,35 @@
|
||||
import subprocess
|
||||
|
||||
|
||||
def scan(interface="wlan0"):
|
||||
result = []
|
||||
try:
|
||||
r = subprocess.check_output(["iwlist", interface, "scan"], encoding='utf8')
|
||||
|
||||
mac = None
|
||||
for line in r.split('\n'):
|
||||
if "Address" in line:
|
||||
# Based on the adapter eithere a percentage or dBm is returned
|
||||
# Add previous network in case no dBm signal level was seen
|
||||
if mac is not None:
|
||||
result.append({"mac": mac})
|
||||
mac = None
|
||||
|
||||
mac = line.split(' ')[-1]
|
||||
elif "dBm" in line:
|
||||
try:
|
||||
level = line.split('Signal level=')[1]
|
||||
rss = int(level.split(' ')[0])
|
||||
result.append({"mac": mac, "rss": rss})
|
||||
mac = None
|
||||
except ValueError:
|
||||
continue
|
||||
|
||||
# Add last network if no dBm was found
|
||||
if mac is not None:
|
||||
result.append({"mac": mac})
|
||||
|
||||
return result
|
||||
|
||||
except Exception:
|
||||
return None
|
||||
30
system/hardware/tici/pins.py
Normal file
30
system/hardware/tici/pins.py
Normal file
@@ -0,0 +1,30 @@
|
||||
# TODO: these are also defined in a header
|
||||
|
||||
# GPIO pin definitions
|
||||
class GPIO:
|
||||
# both GPIO_STM_RST_N and GPIO_LTE_RST_N are misnamed, they are high to reset
|
||||
HUB_RST_N = 30
|
||||
UBLOX_RST_N = 32
|
||||
UBLOX_SAFEBOOT_N = 33
|
||||
GNSS_PWR_EN = 34 # SCHEMATIC LABEL: GPIO_UBLOX_PWR_EN
|
||||
STM_RST_N = 124
|
||||
STM_BOOT0 = 134
|
||||
|
||||
SIREN = 42
|
||||
SOM_ST_IO = 49
|
||||
|
||||
LTE_RST_N = 50
|
||||
LTE_PWRKEY = 116
|
||||
LTE_BOOT = 52
|
||||
|
||||
# GPIO_CAM0_DVDD_EN = /sys/kernel/debug/regulator/camera_rear_ldo
|
||||
CAM0_AVDD_EN = 8
|
||||
CAM0_RSTN = 9
|
||||
CAM1_RSTN = 7
|
||||
CAM2_RSTN = 12
|
||||
|
||||
# Sensor interrupts
|
||||
BMX055_ACCEL_INT = 21
|
||||
BMX055_GYRO_INT = 23
|
||||
BMX055_MAGN_INT = 87
|
||||
LSM_INT = 84
|
||||
BIN
system/hardware/tici/updater
Executable file
BIN
system/hardware/tici/updater
Executable file
Binary file not shown.
Reference in New Issue
Block a user