mirror of
https://github.com/sunnypilot/sunnypilot.git
synced 2026-02-18 20:03:53 +08:00
remove comma two support (#24248)
* remove comma two support
* cleanup release files
* little more
* more libs
* no more gralloc
* add snpe back
old-commit-hash: 5c48e7bc86
This commit is contained in:
93
Jenkinsfile
vendored
93
Jenkinsfile
vendored
@@ -18,18 +18,6 @@ fi
|
||||
|
||||
ln -snf ${env.TEST_DIR} /data/pythonpath
|
||||
|
||||
if [ -f /EON ]; then
|
||||
# kill all old procs in the openpilot cpuset
|
||||
while read p; do
|
||||
kill "\$p" || true
|
||||
done < /dev/cpuset/app/tasks
|
||||
|
||||
echo \$\$ > /dev/cpuset/app/tasks || true
|
||||
|
||||
mkdir -p /dev/shm
|
||||
chmod 777 /dev/shm
|
||||
fi
|
||||
|
||||
cd ${env.TEST_DIR} || true
|
||||
${cmd}
|
||||
exit 0
|
||||
@@ -62,29 +50,15 @@ pipeline {
|
||||
}
|
||||
|
||||
stages {
|
||||
stage('build releases') {
|
||||
stage('build release3') {
|
||||
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
|
||||
when {
|
||||
branch 'devel-staging'
|
||||
}
|
||||
|
||||
parallel {
|
||||
stage('release2') {
|
||||
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
|
||||
steps {
|
||||
phone_steps("eon-build", [
|
||||
["build release2-staging & dashcam-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
stage('release3') {
|
||||
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
|
||||
steps {
|
||||
phone_steps("tici", [
|
||||
["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"],
|
||||
])
|
||||
}
|
||||
}
|
||||
steps {
|
||||
phone_steps("tici", [
|
||||
["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
@@ -106,41 +80,6 @@ pipeline {
|
||||
stages {
|
||||
stage('parallel tests') {
|
||||
parallel {
|
||||
stage('C2: build') {
|
||||
steps {
|
||||
phone_steps("eon-build", [
|
||||
["build master-ci", "cd $SOURCE_DIR/release && EXTRA_FILES='tools/' ./build_devel.sh"],
|
||||
["build openpilot", "cd selfdrive/manager && ./build.py"],
|
||||
["test manager", "python selfdrive/manager/test/test_manager.py"],
|
||||
["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"],
|
||||
["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
stage('C2: replay') {
|
||||
steps {
|
||||
phone_steps("eon2", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
stage('C2: HW + Unit Tests') {
|
||||
steps {
|
||||
phone_steps("eon", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
["test sounds", "python selfdrive/ui/tests/test_soundd.py"],
|
||||
["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"],
|
||||
["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"],
|
||||
["test encoder", "python selfdrive/loggerd/tests/test_encoder.py"],
|
||||
["test logcatd", "python selfdrive/logcatd/tests/test_logcatd_android.py"],
|
||||
["test updater", "python selfdrive/hardware/eon/test_neos_updater.py"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
stage('Power Consumption Tests') {
|
||||
steps {
|
||||
@@ -162,7 +101,7 @@ pipeline {
|
||||
}
|
||||
*/
|
||||
|
||||
stage('C3: build') {
|
||||
stage('build') {
|
||||
environment {
|
||||
R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}"
|
||||
}
|
||||
@@ -177,7 +116,7 @@ pipeline {
|
||||
}
|
||||
}
|
||||
|
||||
stage('C3: HW + Unit Tests') {
|
||||
stage('HW + Unit Tests') {
|
||||
steps {
|
||||
phone_steps("tici2", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
@@ -188,17 +127,7 @@ pipeline {
|
||||
}
|
||||
}
|
||||
|
||||
stage('C2: camerad') {
|
||||
steps {
|
||||
phone_steps("eon-party", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
["test camerad", "python selfdrive/camerad/test/test_camerad.py"],
|
||||
["test exposure", "python selfdrive/camerad/test/test_exposure.py"],
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
stage('C3: camerad') {
|
||||
stage('camerad') {
|
||||
steps {
|
||||
phone_steps("tici-party", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
@@ -208,7 +137,7 @@ pipeline {
|
||||
}
|
||||
}
|
||||
|
||||
stage('C3: replay') {
|
||||
stage('replay') {
|
||||
steps {
|
||||
phone_steps("tici3", [
|
||||
["build", "cd selfdrive/manager && ./build.py"],
|
||||
@@ -225,7 +154,7 @@ pipeline {
|
||||
branch 'master'
|
||||
}
|
||||
steps {
|
||||
phone_steps("eon-build", [
|
||||
phone_steps("tici-build", [
|
||||
["push devel", "cd $SOURCE_DIR/release && PUSH='master-ci' ./build_devel.sh"],
|
||||
])
|
||||
}
|
||||
|
||||
@@ -41,8 +41,8 @@ Running in a car
|
||||
To use openpilot in a car, you need four things
|
||||
* This software. It's free and available right here.
|
||||
* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported, but has adaptive cruise control and lane keeping assist, it's likely able to run openpilot.
|
||||
* A supported device to run this software. This can be a [comma two](https://comma.ai/shop/products/two), [comma three](https://comma.ai/shop/products/three), or if you like to experiment, a [Ubuntu computer with webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam).
|
||||
* A way to connect to your car. With a comma two or three, you need only a [car harness](https://comma.ai/shop/products/car-harness). With an EON Gold or PC, you also need a [black panda](https://comma.ai/shop/products/panda).
|
||||
* A supported device to run this software: a [comma three](https://comma.ai/shop/products/three), or if you like to experiment, a [Ubuntu computer with webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam).
|
||||
* A way to connect to your car. With a comma three, you need only a [car harness](https://comma.ai/shop/products/car-harness). With a PC, you also need a [black panda](https://comma.ai/shop/products/panda).
|
||||
|
||||
We have detailed instructions for [how to install the device in a car](https://comma.ai/setup).
|
||||
|
||||
|
||||
55
SConstruct
55
SConstruct
@@ -73,14 +73,9 @@ lenv = {
|
||||
|
||||
rpath = lenv["LD_LIBRARY_PATH"].copy()
|
||||
|
||||
if arch == "aarch64" or arch == "larch64":
|
||||
if arch == "larch64":
|
||||
lenv["LD_LIBRARY_PATH"] += ['/data/data/com.termux/files/usr/lib']
|
||||
|
||||
if arch == "aarch64":
|
||||
# android
|
||||
lenv["ANDROID_DATA"] = os.environ['ANDROID_DATA']
|
||||
lenv["ANDROID_ROOT"] = os.environ['ANDROID_ROOT']
|
||||
|
||||
cpppath = [
|
||||
"#third_party/opencl/include",
|
||||
]
|
||||
@@ -92,27 +87,17 @@ if arch == "aarch64" or arch == "larch64":
|
||||
f"#third_party/acados/{arch}/lib",
|
||||
]
|
||||
|
||||
if arch == "larch64":
|
||||
libpath += [
|
||||
"#third_party/snpe/larch64",
|
||||
"#third_party/libyuv/larch64/lib",
|
||||
"/usr/lib/aarch64-linux-gnu"
|
||||
]
|
||||
cpppath += [
|
||||
"#selfdrive/camerad/include",
|
||||
]
|
||||
cflags = ["-DQCOM2", "-mcpu=cortex-a57"]
|
||||
cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"]
|
||||
rpath += ["/usr/local/lib"]
|
||||
else:
|
||||
rpath = []
|
||||
libpath += [
|
||||
"#third_party/snpe/aarch64",
|
||||
"#third_party/libyuv/lib",
|
||||
"/system/vendor/lib64"
|
||||
]
|
||||
cflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"]
|
||||
cxxflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"]
|
||||
libpath += [
|
||||
"#third_party/snpe/larch64",
|
||||
"#third_party/libyuv/larch64/lib",
|
||||
"/usr/lib/aarch64-linux-gnu"
|
||||
]
|
||||
cpppath += [
|
||||
"#selfdrive/camerad/include",
|
||||
]
|
||||
cflags = ["-DQCOM2", "-mcpu=cortex-a57"]
|
||||
cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"]
|
||||
rpath += ["/usr/local/lib"]
|
||||
else:
|
||||
cflags = []
|
||||
cxxflags = []
|
||||
@@ -259,6 +244,7 @@ if os.environ.get('SCONS_PROGRESS'):
|
||||
|
||||
SHARED = False
|
||||
|
||||
# TODO: this can probably be removed
|
||||
def abspath(x):
|
||||
if arch == 'aarch64':
|
||||
pth = os.path.join("/data/pythonpath", x[0].path)
|
||||
@@ -287,9 +273,7 @@ Export('envCython')
|
||||
|
||||
# Qt build environment
|
||||
qt_env = env.Clone()
|
||||
qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning"]
|
||||
if arch != "aarch64":
|
||||
qt_modules += ["DBus"]
|
||||
qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus"]
|
||||
|
||||
qt_libs = []
|
||||
if arch == "Darwin":
|
||||
@@ -304,15 +288,6 @@ if arch == "Darwin":
|
||||
qt_env["LINKFLAGS"] += ["-F" + os.path.join(qt_env['QTDIR'], "lib")]
|
||||
qt_env["FRAMEWORKS"] += [f"Qt{m}" for m in qt_modules] + ["OpenGL"]
|
||||
qt_env.AppendENVPath('PATH', os.path.join(qt_env['QTDIR'], "bin"))
|
||||
elif arch == "aarch64":
|
||||
qt_env['QTDIR'] = "/usr"
|
||||
qt_dirs = [
|
||||
f"/usr/include/qt",
|
||||
]
|
||||
qt_dirs += [f"/usr/include/qt/Qt{m}" for m in qt_modules]
|
||||
|
||||
qt_libs = [f"Qt5{m}" for m in qt_modules]
|
||||
qt_libs += ['EGL', 'GLESv3', 'c++_shared']
|
||||
else:
|
||||
qt_env['QTDIR'] = "/usr"
|
||||
qt_dirs = [
|
||||
@@ -390,7 +365,7 @@ rednose_config = {
|
||||
},
|
||||
}
|
||||
|
||||
if arch not in ["aarch64", "larch64"]:
|
||||
if arch != "larch64":
|
||||
rednose_config['to_build'].update({
|
||||
'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []),
|
||||
'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, []),
|
||||
|
||||
@@ -81,25 +81,12 @@ def _get_fileobject_func(writer, temp_dir):
|
||||
return writer.get_fileobject(dir=temp_dir)
|
||||
return _get_fileobject
|
||||
|
||||
def monkeypatch_os_link():
|
||||
# This is neccesary on EON/C2, where os.link is patched out of python
|
||||
if not hasattr(os, 'link'):
|
||||
from cffi import FFI
|
||||
ffi = FFI()
|
||||
ffi.cdef("int link(const char *oldpath, const char *newpath);")
|
||||
libc = ffi.dlopen(None)
|
||||
|
||||
def link(src, dest):
|
||||
return libc.link(src.encode(), dest.encode())
|
||||
os.link = link
|
||||
|
||||
def atomic_write_on_fs_tmp(path, **kwargs):
|
||||
"""Creates an atomic writer using a temporary file in a temporary directory
|
||||
on the same filesystem as path.
|
||||
"""
|
||||
# TODO(mgraczyk): This use of AtomicWriter relies on implementation details to set the temp
|
||||
# directory.
|
||||
monkeypatch_os_link()
|
||||
writer = AtomicWriter(path, **kwargs)
|
||||
return writer._open(_get_fileobject_func(writer, get_tmpdir_on_same_filesystem(path)))
|
||||
|
||||
@@ -108,6 +95,5 @@ def atomic_write_in_dir(path, **kwargs):
|
||||
"""Creates an atomic writer using a temporary file in the same directory
|
||||
as the destination file.
|
||||
"""
|
||||
monkeypatch_os_link()
|
||||
writer = AtomicWriter(path, **kwargs)
|
||||
return writer._open(_get_fileobject_func(writer, os.path.dirname(path)))
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:2ca3679a8e9a066bccbf8cb27377a40bad65e348d668040adda37c27ff6bad4d
|
||||
size 69
|
||||
@@ -8,96 +8,6 @@ source "$BASEDIR/launch_env.sh"
|
||||
|
||||
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"
|
||||
|
||||
function two_init {
|
||||
|
||||
# set IO scheduler
|
||||
setprop sys.io.scheduler noop
|
||||
for f in /sys/block/*/queue/scheduler; do
|
||||
echo noop > $f
|
||||
done
|
||||
|
||||
# *** shield cores 2-3 ***
|
||||
|
||||
# TODO: should we enable this?
|
||||
# offline cores 2-3 to force recurring timers onto the other cores
|
||||
#echo 0 > /sys/devices/system/cpu/cpu2/online
|
||||
#echo 0 > /sys/devices/system/cpu/cpu3/online
|
||||
#echo 1 > /sys/devices/system/cpu/cpu2/online
|
||||
#echo 1 > /sys/devices/system/cpu/cpu3/online
|
||||
|
||||
# android gets two cores
|
||||
echo 0-1 > /dev/cpuset/background/cpus
|
||||
echo 0-1 > /dev/cpuset/system-background/cpus
|
||||
echo 0-1 > /dev/cpuset/foreground/cpus
|
||||
echo 0-1 > /dev/cpuset/foreground/boost/cpus
|
||||
echo 0-1 > /dev/cpuset/android/cpus
|
||||
|
||||
# openpilot gets all the cores
|
||||
echo 0-3 > /dev/cpuset/app/cpus
|
||||
|
||||
# mask off 2-3 from RPS and XPS - Receive/Transmit Packet Steering
|
||||
echo 3 | tee /sys/class/net/*/queues/*/rps_cpus
|
||||
echo 3 | tee /sys/class/net/*/queues/*/xps_cpus
|
||||
|
||||
# *** set up governors ***
|
||||
|
||||
# +50mW offroad, +500mW onroad for 30% more RAM bandwidth
|
||||
echo "performance" > /sys/class/devfreq/soc:qcom,cpubw/governor
|
||||
echo 1056000 > /sys/class/devfreq/soc:qcom,m4m/max_freq
|
||||
echo "performance" > /sys/class/devfreq/soc:qcom,m4m/governor
|
||||
|
||||
# unclear if these help, but they don't seem to hurt
|
||||
echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu0/governor
|
||||
echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu2/governor
|
||||
|
||||
# GPU
|
||||
echo "performance" > /sys/class/devfreq/b00000.qcom,kgsl-3d0/governor
|
||||
|
||||
# /sys/class/devfreq/soc:qcom,mincpubw is the only one left at "powersave"
|
||||
# it seems to gain nothing but a wasted 500mW
|
||||
|
||||
# *** set up IRQ affinities ***
|
||||
|
||||
# Collect RIL and other possibly long-running I/O interrupts onto CPU 1
|
||||
echo 1 > /proc/irq/78/smp_affinity_list # qcom,smd-modem (LTE radio)
|
||||
echo 1 > /proc/irq/33/smp_affinity_list # ufshcd (flash storage)
|
||||
echo 1 > /proc/irq/35/smp_affinity_list # wifi (wlan_pci)
|
||||
echo 1 > /proc/irq/6/smp_affinity_list # MDSS
|
||||
|
||||
# USB traffic needs realtime handling on cpu 3
|
||||
[ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list
|
||||
|
||||
# GPU and camera get cpu 2
|
||||
CAM_IRQS="177 178 179 180 181 182 183 184 185 186 192"
|
||||
for irq in $CAM_IRQS; do
|
||||
echo 2 > /proc/irq/$irq/smp_affinity_list
|
||||
done
|
||||
echo 2 > /proc/irq/193/smp_affinity_list # GPU
|
||||
|
||||
# give GPU threads RT priority
|
||||
for pid in $(pgrep "kgsl"); do
|
||||
chrt -f -p 52 $pid
|
||||
done
|
||||
|
||||
# the flippening!
|
||||
LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1
|
||||
|
||||
# disable bluetooth
|
||||
service call bluetooth_manager 8
|
||||
|
||||
# wifi scan
|
||||
wpa_cli IFNAME=wlan0 SCAN
|
||||
|
||||
# Check for NEOS update
|
||||
if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then
|
||||
echo "Installing NEOS update"
|
||||
NEOS_PY="$DIR/selfdrive/hardware/eon/neos.py"
|
||||
MANIFEST="$DIR/selfdrive/hardware/eon/neos.json"
|
||||
$NEOS_PY --swap-if-ready $MANIFEST
|
||||
$DIR/selfdrive/hardware/eon/updater $NEOS_PY $MANIFEST
|
||||
fi
|
||||
}
|
||||
|
||||
function tici_init {
|
||||
# wait longer for weston to come up
|
||||
if [ -f "$BASEDIR/prebuilt" ]; then
|
||||
@@ -168,9 +78,7 @@ function launch {
|
||||
export PYTHONPATH="$PWD:$PWD/pyextra"
|
||||
|
||||
# hardware specific init
|
||||
if [ -f /EON ]; then
|
||||
two_init
|
||||
elif [ -f /TICI ]; then
|
||||
if [ -f /TICI ]; then
|
||||
tici_init
|
||||
fi
|
||||
|
||||
|
||||
@@ -6,10 +6,6 @@ export NUMEXPR_NUM_THREADS=1
|
||||
export OPENBLAS_NUM_THREADS=1
|
||||
export VECLIB_MAXIMUM_THREADS=1
|
||||
|
||||
if [ -z "$REQUIRED_NEOS_VERSION" ]; then
|
||||
export REQUIRED_NEOS_VERSION="19.1"
|
||||
fi
|
||||
|
||||
if [ -z "$AGNOS_VERSION" ]; then
|
||||
export AGNOS_VERSION="4"
|
||||
fi
|
||||
|
||||
@@ -13,10 +13,6 @@ if [ -f /TICI ]; then
|
||||
FILES_SRC="release/files_tici"
|
||||
RELEASE_BRANCH=release3-staging
|
||||
DASHCAM_BRANCH=dashcam3-staging
|
||||
elif [ -f /EON ]; then
|
||||
FILES_SRC="release/files_eon"
|
||||
RELEASE_BRANCH=release2-staging
|
||||
DASHCAM_BRANCH=dashcam-staging
|
||||
else
|
||||
exit 0
|
||||
fi
|
||||
|
||||
@@ -65,8 +65,6 @@ release/*
|
||||
|
||||
tools/lib/*
|
||||
|
||||
installer/updater/updater
|
||||
|
||||
selfdrive/version.py
|
||||
|
||||
selfdrive/__init__.py
|
||||
@@ -260,14 +258,6 @@ selfdrive/hardware/__init__.py
|
||||
selfdrive/hardware/base.h
|
||||
selfdrive/hardware/base.py
|
||||
selfdrive/hardware/hw.h
|
||||
selfdrive/hardware/eon/__init__.py
|
||||
selfdrive/hardware/eon/androidd.py
|
||||
selfdrive/hardware/eon/shutdownd.py
|
||||
selfdrive/hardware/eon/hardware.h
|
||||
selfdrive/hardware/eon/hardware.py
|
||||
selfdrive/hardware/eon/neos.py
|
||||
selfdrive/hardware/eon/neos.json
|
||||
selfdrive/hardware/eon/updater
|
||||
selfdrive/hardware/tici/__init__.py
|
||||
selfdrive/hardware/tici/hardware.py
|
||||
selfdrive/hardware/tici/amplifier.py
|
||||
@@ -299,7 +289,6 @@ selfdrive/locationd/models/live_kf.cc
|
||||
selfdrive/locationd/calibrationd.py
|
||||
|
||||
selfdrive/logcatd/SConscript
|
||||
selfdrive/logcatd/logcatd_android.cc
|
||||
selfdrive/logcatd/logcatd_systemd.cc
|
||||
|
||||
selfdrive/proclogd/SConscript
|
||||
@@ -329,7 +318,6 @@ selfdrive/loggerd/xattr_cache.py
|
||||
|
||||
selfdrive/sensord/SConscript
|
||||
selfdrive/sensord/libdiag.h
|
||||
selfdrive/sensord/sensors_qcom.cc
|
||||
selfdrive/sensord/sensors_qcom2.cc
|
||||
selfdrive/sensord/sensors/*.cc
|
||||
selfdrive/sensord/sensors/*.h
|
||||
@@ -363,8 +351,6 @@ selfdrive/ui/qt/offroad/*.h
|
||||
selfdrive/ui/qt/offroad/*.qml
|
||||
selfdrive/ui/qt/widgets/*.cc
|
||||
selfdrive/ui/qt/widgets/*.h
|
||||
selfdrive/ui/qt/spinner_aarch64
|
||||
selfdrive/ui/qt/text_aarch64
|
||||
|
||||
selfdrive/ui/replay/*.cc
|
||||
selfdrive/ui/replay/*.h
|
||||
@@ -376,11 +362,8 @@ selfdrive/camerad/snapshot/*
|
||||
selfdrive/camerad/include/*
|
||||
selfdrive/camerad/cameras/camera_common.h
|
||||
selfdrive/camerad/cameras/camera_common.cc
|
||||
selfdrive/camerad/cameras/camera_qcom.cc
|
||||
selfdrive/camerad/cameras/camera_qcom.h
|
||||
selfdrive/camerad/cameras/camera_replay.cc
|
||||
selfdrive/camerad/cameras/camera_replay.h
|
||||
selfdrive/camerad/cameras/debayer.cl
|
||||
selfdrive/camerad/cameras/sensor_i2c.h
|
||||
selfdrive/camerad/cameras/sensor2_i2c.h
|
||||
|
||||
@@ -456,7 +439,6 @@ selfdrive/assets/training/*
|
||||
|
||||
third_party/SConscript
|
||||
|
||||
third_party/libgralloc/**
|
||||
third_party/linux/**
|
||||
third_party/opencl/**
|
||||
third_party/zlib/*
|
||||
@@ -477,19 +459,12 @@ third_party/libyuv/lib/**
|
||||
third_party/libyuv/larch64/**
|
||||
|
||||
third_party/snpe/include/**
|
||||
third_party/snpe/aarch64**
|
||||
third_party/snpe/larch64**
|
||||
third_party/snpe/dsp**
|
||||
|
||||
third_party/acados/x86_64/**
|
||||
third_party/acados/aarch64/**
|
||||
third_party/acados/larch64/**
|
||||
third_party/acados/include/**
|
||||
|
||||
third_party/android_frameworks_native/**
|
||||
third_party/android_hardware_libhardware/**
|
||||
third_party/android_system_core/**
|
||||
|
||||
scripts/update_now.sh
|
||||
scripts/stop_updater.sh
|
||||
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
README.md
|
||||
@@ -1,3 +1,5 @@
|
||||
third_party/snpe/larch64**
|
||||
third_party/snpe/aarch64-linux-gcc4.9/*
|
||||
third_party/mapbox-gl-native-qt/include/*
|
||||
|
||||
selfdrive/timezoned.py
|
||||
|
||||
@@ -2,10 +2,7 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc',
|
||||
|
||||
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon]
|
||||
|
||||
if arch == "aarch64":
|
||||
libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui']
|
||||
cameras = ['cameras/camera_qcom.cc']
|
||||
elif arch == "larch64":
|
||||
if arch == "larch64":
|
||||
libs += ['atomic']
|
||||
cameras = ['cameras/camera_qcom2.cc']
|
||||
else:
|
||||
|
||||
@@ -18,10 +18,7 @@
|
||||
#include "selfdrive/common/util.h"
|
||||
#include "selfdrive/hardware/hw.h"
|
||||
|
||||
#ifdef QCOM
|
||||
#include "CL/cl_ext_qcom.h"
|
||||
#include "selfdrive/camerad/cameras/camera_qcom.h"
|
||||
#elif QCOM2
|
||||
#if QCOM2
|
||||
#include "CL/cl_ext_qcom.h"
|
||||
#include "selfdrive/camerad/cameras/camera_qcom2.h"
|
||||
#elif WEBCAM
|
||||
@@ -418,17 +415,6 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) {
|
||||
}
|
||||
|
||||
static ExpRect rect = def_rect;
|
||||
// use driver face crop for AE
|
||||
if (Hardware::EON() && sm.updated("driverState")) {
|
||||
if (auto state = sm["driverState"].getDriverState(); state.getFaceProb() > 0.4) {
|
||||
auto face_position = state.getFacePosition();
|
||||
int x = is_rhd ? 0 : frame_width - (0.5 * frame_height);
|
||||
x += (face_position[0] * (is_rhd ? -1.0 : 1.0) + 0.5) * (0.5 * frame_height) + x_offset;
|
||||
int y = (face_position[1] + 0.5) * frame_height + y_offset;
|
||||
rect = {std::max(0, x - 72), std::min(b->rgb_width - 1, x + 72), 2,
|
||||
std::max(0, y - 72), std::min(b->rgb_height - 1, y + 72), 1};
|
||||
}
|
||||
}
|
||||
|
||||
camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip));
|
||||
}
|
||||
@@ -452,7 +438,7 @@ void common_process_driver_camera(MultiCameraState *s, CameraState *c, int cnt)
|
||||
|
||||
void camerad_thread() {
|
||||
cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT);
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0};
|
||||
cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err));
|
||||
#else
|
||||
|
||||
@@ -29,7 +29,7 @@
|
||||
#define CAMERA_ID_MAX 10
|
||||
|
||||
const int UI_BUF_COUNT = 4;
|
||||
const int YUV_BUFFER_COUNT = Hardware::EON() ? 100 : 40;
|
||||
const int YUV_BUFFER_COUNT = 40;
|
||||
|
||||
enum CameraType {
|
||||
RoadCam = 0,
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,106 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <atomic>
|
||||
#include <cstdint>
|
||||
#include <memory>
|
||||
|
||||
#include "cereal/messaging/messaging.h"
|
||||
#include "cereal/visionipc/visionbuf.h"
|
||||
#include "selfdrive/camerad/cameras/camera_common.h"
|
||||
#include "selfdrive/camerad/imgproc/utils.h"
|
||||
#include "selfdrive/camerad/include/msm_cam_sensor.h"
|
||||
#include "selfdrive/camerad/include/msmb_camera.h"
|
||||
#include "selfdrive/camerad/include/msmb_isp.h"
|
||||
#include "selfdrive/camerad/include/msmb_ispif.h"
|
||||
#include "selfdrive/common/mat.h"
|
||||
#include "selfdrive/common/util.h"
|
||||
|
||||
#define FRAME_BUF_COUNT 4
|
||||
#define METADATA_BUF_COUNT 4
|
||||
|
||||
#define NUM_FOCUS 8
|
||||
|
||||
#define LP3_AF_DAC_DOWN 366
|
||||
#define LP3_AF_DAC_UP 634
|
||||
#define LP3_AF_DAC_M 440
|
||||
#define LP3_AF_DAC_3SIG 52
|
||||
|
||||
#define FOCUS_RECOVER_PATIENCE 50 // 2.5 seconds of complete blur
|
||||
#define FOCUS_RECOVER_STEPS 240 // 6 seconds
|
||||
|
||||
typedef struct CameraState CameraState;
|
||||
|
||||
typedef int (*camera_apply_exposure_func)(CameraState *s, int gain, int integ_lines, uint32_t frame_length);
|
||||
|
||||
typedef struct StreamState {
|
||||
struct msm_isp_buf_request buf_request;
|
||||
struct msm_vfe_axi_stream_request_cmd stream_req;
|
||||
struct msm_isp_qbuf_info qbuf_info[FRAME_BUF_COUNT];
|
||||
VisionBuf *bufs;
|
||||
} StreamState;
|
||||
|
||||
typedef struct CameraState {
|
||||
int camera_num;
|
||||
int camera_id;
|
||||
|
||||
int fps;
|
||||
CameraInfo ci;
|
||||
|
||||
unique_fd csid_fd;
|
||||
unique_fd csiphy_fd;
|
||||
unique_fd sensor_fd;
|
||||
unique_fd isp_fd;
|
||||
|
||||
struct msm_vfe_axi_stream_cfg_cmd stream_cfg;
|
||||
|
||||
StreamState ss[3];
|
||||
CameraBuf buf;
|
||||
|
||||
std::mutex frame_info_lock;
|
||||
FrameMetadata frame_metadata[METADATA_BUF_COUNT];
|
||||
int frame_metadata_idx;
|
||||
|
||||
// exposure
|
||||
uint32_t pixel_clock, line_length_pclk;
|
||||
uint32_t frame_length;
|
||||
unsigned int max_gain;
|
||||
float cur_exposure_frac, cur_gain_frac;
|
||||
int cur_gain, cur_integ_lines;
|
||||
|
||||
float measured_grey_fraction;
|
||||
float target_grey_fraction;
|
||||
|
||||
std::atomic<float> digital_gain;
|
||||
camera_apply_exposure_func apply_exposure;
|
||||
|
||||
// rear camera only,used for focusing
|
||||
unique_fd actuator_fd;
|
||||
std::atomic<float> focus_err;
|
||||
std::atomic<float> lens_true_pos;
|
||||
std::atomic<int> self_recover; // af recovery counter, neg is patience, pos is active
|
||||
uint16_t cur_step_pos;
|
||||
uint16_t cur_lens_pos;
|
||||
int16_t focus[NUM_FOCUS];
|
||||
uint8_t confidence[NUM_FOCUS];
|
||||
} CameraState;
|
||||
|
||||
|
||||
typedef struct MultiCameraState {
|
||||
unique_fd ispif_fd;
|
||||
unique_fd msmcfg_fd;
|
||||
unique_fd v4l_fd;
|
||||
uint16_t lapres[(ROI_X_MAX-ROI_X_MIN+1)*(ROI_Y_MAX-ROI_Y_MIN+1)];
|
||||
|
||||
VisionBuf focus_bufs[FRAME_BUF_COUNT];
|
||||
VisionBuf stats_bufs[FRAME_BUF_COUNT];
|
||||
|
||||
CameraState road_cam;
|
||||
CameraState driver_cam;
|
||||
|
||||
SubMaster *sm;
|
||||
PubMaster *pm;
|
||||
LapConv *lap_conv;
|
||||
} MultiCameraState;
|
||||
|
||||
void actuator_move(CameraState *s, uint16_t target);
|
||||
int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, int data_type);
|
||||
@@ -7,11 +7,11 @@
|
||||
#include "selfdrive/hardware/hw.h"
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
if (!Hardware::PC()) {
|
||||
if (Hardware::TICI()) {
|
||||
int ret;
|
||||
ret = util::set_realtime_priority(53);
|
||||
assert(ret == 0);
|
||||
ret = util::set_core_affinity({Hardware::EON() ? 2 : 6});
|
||||
ret = util::set_core_affinity({6});
|
||||
assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores
|
||||
}
|
||||
|
||||
|
||||
@@ -4,11 +4,9 @@ import time
|
||||
import unittest
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from selfdrive.hardware import TICI
|
||||
from selfdrive.test.helpers import with_processes
|
||||
|
||||
# only tests for EON and TICI
|
||||
from selfdrive.hardware import EON, TICI
|
||||
|
||||
TEST_TIMESPAN = 30 # random.randint(60, 180) # seconds
|
||||
SKIP_FRAME_TOLERANCE = 0
|
||||
LAG_FRAME_TOLERANCE = 2 # ms
|
||||
@@ -26,7 +24,7 @@ if TICI:
|
||||
class TestCamerad(unittest.TestCase):
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
if not (EON or TICI):
|
||||
if not TICI:
|
||||
raise unittest.SkipTest
|
||||
|
||||
@with_processes(['camerad'])
|
||||
|
||||
@@ -6,7 +6,7 @@ import numpy as np
|
||||
from selfdrive.test.helpers import with_processes
|
||||
from selfdrive.camerad.snapshot.snapshot import get_snapshots
|
||||
|
||||
from selfdrive.hardware import EON, TICI
|
||||
from selfdrive.hardware import TICI
|
||||
|
||||
TEST_TIME = 45
|
||||
REPEAT = 5
|
||||
@@ -14,7 +14,7 @@ REPEAT = 5
|
||||
class TestCamerad(unittest.TestCase):
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
if not (EON or TICI):
|
||||
if not TICI:
|
||||
raise unittest.SkipTest
|
||||
|
||||
def _numpy_rgb2gray(self, im):
|
||||
|
||||
@@ -21,16 +21,6 @@
|
||||
|
||||
ExitHandler do_exit;
|
||||
|
||||
#ifdef QCOM
|
||||
namespace {
|
||||
int64_t arm_cntpct() {
|
||||
int64_t v;
|
||||
asm volatile("mrs %0, cntpct_el0" : "=r"(v));
|
||||
return v;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
int main() {
|
||||
setpriority(PRIO_PROCESS, 0, -13);
|
||||
PubMaster pm({"clocks"});
|
||||
@@ -65,10 +55,6 @@ int main() {
|
||||
uint64_t monotonic_raw = nanos_monotonic_raw();
|
||||
uint64_t wall_time = nanos_since_epoch();
|
||||
|
||||
#ifdef QCOM
|
||||
uint64_t modem_uptime_v = arm_cntpct() / 19200ULL; // 19.2 mhz clock
|
||||
#endif
|
||||
|
||||
MessageBuilder msg;
|
||||
auto clocks = msg.initEvent().initClocks();
|
||||
|
||||
@@ -76,9 +62,6 @@ int main() {
|
||||
clocks.setMonotonicNanos(monotonic);
|
||||
clocks.setMonotonicRawNanos(monotonic_raw);
|
||||
clocks.setWallTimeNanos(wall_time);
|
||||
#ifdef QCOM
|
||||
clocks.setModemUptimeMillis(modem_uptime_v);
|
||||
#endif
|
||||
|
||||
pm.send("clocks", msg);
|
||||
}
|
||||
|
||||
@@ -22,9 +22,7 @@ files = [
|
||||
'visionimg.cc',
|
||||
]
|
||||
|
||||
if arch == "aarch64":
|
||||
_gpu_libs = ['gui', 'adreno_utils']
|
||||
elif arch == "larch64":
|
||||
if arch == "larch64":
|
||||
_gpu_libs = ["GLESv2"]
|
||||
else:
|
||||
_gpu_libs = ["GL"]
|
||||
|
||||
@@ -32,13 +32,9 @@ namespace tici_dm_crop {
|
||||
const int width = 954;
|
||||
};
|
||||
|
||||
const mat3 fcam_intrinsic_matrix =
|
||||
Hardware::EON() ? (mat3){{910., 0., 1164.0 / 2,
|
||||
0., 910., 874.0 / 2,
|
||||
0., 0., 1.}}
|
||||
: (mat3){{2648.0, 0.0, 1928.0 / 2,
|
||||
0.0, 2648.0, 1208.0 / 2,
|
||||
0.0, 0.0, 1.0}};
|
||||
const mat3 fcam_intrinsic_matrix = (mat3){{2648.0, 0.0, 1928.0 / 2,
|
||||
0.0, 2648.0, 1208.0 / 2,
|
||||
0.0, 0.0, 1.0}};
|
||||
|
||||
// tici ecam focal probably wrong? magnification is not consistent across frame
|
||||
// Need to retrain model before this can be changed
|
||||
@@ -47,7 +43,7 @@ const mat3 ecam_intrinsic_matrix = (mat3){{567.0, 0.0, 1928.0 / 2,
|
||||
0.0, 0.0, 1.0}};
|
||||
|
||||
static inline mat3 get_model_yuv_transform(bool bayer = true) {
|
||||
float db_s = Hardware::EON() ? 0.5 : 1.0; // debayering does a 2x downscale on EON
|
||||
float db_s = 1.0;
|
||||
const mat3 transform = (mat3){{
|
||||
1.0, 0.0, 0.0,
|
||||
0.0, 1.0, 0.0,
|
||||
|
||||
@@ -166,7 +166,6 @@ std::unordered_map<std::string, uint32_t> keys = {
|
||||
{"ApiCache_Owner", PERSISTENT},
|
||||
{"Offroad_BadNvme", CLEAR_ON_MANAGER_START},
|
||||
{"Offroad_CarUnrecognized", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON},
|
||||
{"Offroad_ChargeDisabled", CLEAR_ON_MANAGER_START },
|
||||
{"Offroad_ConnectivityNeeded", CLEAR_ON_MANAGER_START},
|
||||
{"Offroad_ConnectivityNeededPrompt", CLEAR_ON_MANAGER_START},
|
||||
{"Offroad_InvalidTime", CLEAR_ON_MANAGER_START},
|
||||
|
||||
@@ -50,9 +50,7 @@ class SwaglogState : public LogState {
|
||||
ctx_j["dirty"] = !getenv("CLEAN");
|
||||
|
||||
// device type
|
||||
if (Hardware::EON()) {
|
||||
ctx_j["device"] = "eon";
|
||||
} else if (Hardware::TICI()) {
|
||||
if (Hardware::TICI()) {
|
||||
ctx_j["device"] = "tici";
|
||||
} else {
|
||||
ctx_j["device"] = "pc";
|
||||
|
||||
@@ -57,9 +57,7 @@ void recv_log(int thread_cnt, int thread_msg_cnt) {
|
||||
REQUIRE(ctx["version"].string_value() == COMMA_VERSION);
|
||||
|
||||
std::string device = "pc";
|
||||
if (Hardware::EON()) {
|
||||
device = "eon";
|
||||
} else if (Hardware::TICI()) {
|
||||
if (Hardware::TICI()) {
|
||||
device = "tici";
|
||||
}
|
||||
REQUIRE(ctx["device"].string_value() == device);
|
||||
|
||||
@@ -2,54 +2,6 @@
|
||||
|
||||
#include <cassert>
|
||||
|
||||
#ifdef QCOM
|
||||
#include <gralloc_priv.h>
|
||||
#include <system/graphics.h>
|
||||
#include <ui/GraphicBuffer.h>
|
||||
#include <ui/PixelFormat.h>
|
||||
#define GL_GLEXT_PROTOTYPES
|
||||
#include <GLES2/gl2ext.h>
|
||||
using namespace android;
|
||||
|
||||
EGLImageTexture::EGLImageTexture(const VisionBuf *buf) {
|
||||
const int bpp = 3;
|
||||
assert((buf->len % buf->stride) == 0);
|
||||
assert((buf->stride % bpp) == 0);
|
||||
|
||||
const int format = HAL_PIXEL_FORMAT_RGB_888;
|
||||
private_handle = new private_handle_t(buf->fd, buf->len,
|
||||
private_handle_t::PRIV_FLAGS_USES_ION|private_handle_t::PRIV_FLAGS_FRAMEBUFFER,
|
||||
0, format,
|
||||
buf->stride/bpp, buf->len/buf->stride,
|
||||
buf->width, buf->height);
|
||||
|
||||
// GraphicBuffer is ref counted by EGLClientBuffer(ANativeWindowBuffer), no need and not possible to release.
|
||||
GraphicBuffer* gb = new GraphicBuffer(buf->width, buf->height, (PixelFormat)format,
|
||||
GraphicBuffer::USAGE_HW_TEXTURE, buf->stride/bpp, (private_handle_t*)private_handle, false);
|
||||
|
||||
EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY);
|
||||
assert(display != EGL_NO_DISPLAY);
|
||||
|
||||
EGLint img_attrs[] = {EGL_IMAGE_PRESERVED_KHR, EGL_TRUE, EGL_NONE};
|
||||
img_khr = eglCreateImageKHR(display, EGL_NO_CONTEXT,
|
||||
EGL_NATIVE_BUFFER_ANDROID, gb->getNativeBuffer(), img_attrs);
|
||||
assert(img_khr != EGL_NO_IMAGE_KHR);
|
||||
|
||||
glGenTextures(1, &frame_tex);
|
||||
glBindTexture(GL_TEXTURE_2D, frame_tex);
|
||||
glEGLImageTargetTexture2DOES(GL_TEXTURE_2D, img_khr);
|
||||
}
|
||||
|
||||
EGLImageTexture::~EGLImageTexture() {
|
||||
glDeleteTextures(1, &frame_tex);
|
||||
EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY);
|
||||
assert(display != EGL_NO_DISPLAY);
|
||||
eglDestroyImageKHR(display, img_khr);
|
||||
delete (private_handle_t*)private_handle;
|
||||
}
|
||||
|
||||
#else // ifdef QCOM
|
||||
|
||||
EGLImageTexture::EGLImageTexture(const VisionBuf *buf) {
|
||||
glGenTextures(1, &frame_tex);
|
||||
glBindTexture(GL_TEXTURE_2D, frame_tex);
|
||||
@@ -60,4 +12,3 @@ EGLImageTexture::EGLImageTexture(const VisionBuf *buf) {
|
||||
EGLImageTexture::~EGLImageTexture() {
|
||||
glDeleteTextures(1, &frame_tex);
|
||||
}
|
||||
#endif // ifdef QCOM
|
||||
|
||||
@@ -8,20 +8,9 @@
|
||||
#include <GLES3/gl3.h>
|
||||
#endif
|
||||
|
||||
#ifdef QCOM
|
||||
#include <EGL/egl.h>
|
||||
#define EGL_EGLEXT_PROTOTYPES
|
||||
#include <EGL/eglext.h>
|
||||
#undef Status
|
||||
#endif
|
||||
|
||||
class EGLImageTexture {
|
||||
public:
|
||||
EGLImageTexture(const VisionBuf *buf);
|
||||
~EGLImageTexture();
|
||||
GLuint frame_tex = 0;
|
||||
#ifdef QCOM
|
||||
void *private_handle = nullptr;
|
||||
EGLImageKHR img_khr = 0;
|
||||
#endif
|
||||
};
|
||||
|
||||
@@ -26,7 +26,7 @@ from selfdrive.controls.lib.events import Events, ET
|
||||
from selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert
|
||||
from selfdrive.controls.lib.vehicle_model import VehicleModel
|
||||
from selfdrive.locationd.calibrationd import Calibration
|
||||
from selfdrive.hardware import HARDWARE, TICI, EON
|
||||
from selfdrive.hardware import HARDWARE, TICI
|
||||
from selfdrive.manager.process_config import managed_processes
|
||||
|
||||
SOFT_DISABLE_TIME = 3 # seconds
|
||||
@@ -36,9 +36,8 @@ LANE_DEPARTURE_THRESHOLD = 0.1
|
||||
REPLAY = "REPLAY" in os.environ
|
||||
SIMULATION = "SIMULATION" in os.environ
|
||||
NOSENSOR = "NOSENSOR" in os.environ
|
||||
IGNORE_PROCESSES = {"rtshield", "uploader", "deleter", "loggerd", "logmessaged", "tombstoned",
|
||||
"logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad",
|
||||
"statsd", "shutdownd"} | \
|
||||
IGNORE_PROCESSES = {"uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "statsd",
|
||||
"logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \
|
||||
{k for k, v in managed_processes.items() if not v.enabled}
|
||||
|
||||
ThermalStatus = log.DeviceState.ThermalStatus
|
||||
@@ -220,11 +219,7 @@ class Controls:
|
||||
if not self.CP.notCar:
|
||||
self.events.add_from_msg(self.sm['driverMonitoringState'].events)
|
||||
|
||||
# Create events for battery, temperature, disk space, and memory
|
||||
if EON and (self.sm['peripheralState'].pandaType != PandaType.uno) and \
|
||||
self.sm['deviceState'].batteryPercent < 1 and self.sm['deviceState'].chargingError:
|
||||
# at zero percent battery, while discharging, OP should not allowed
|
||||
self.events.add(EventName.lowBattery)
|
||||
# Create events for temperature, disk space, and memory
|
||||
if self.sm['deviceState'].thermalStatus >= ThermalStatus.red:
|
||||
self.events.add(EventName.overheat)
|
||||
if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION:
|
||||
@@ -235,7 +230,7 @@ class Controls:
|
||||
self.events.add(EventName.lowMemory)
|
||||
|
||||
# TODO: enable this once loggerd CPU usage is more reasonable
|
||||
#cpus = list(self.sm['deviceState'].cpuUsagePercent)[:(-1 if EON else None)]
|
||||
#cpus = list(self.sm['deviceState'].cpuUsagePercent)
|
||||
#if max(cpus, default=0) > 95 and not SIMULATION:
|
||||
# self.events.add(EventName.highCpuUsage)
|
||||
|
||||
|
||||
@@ -1,8 +1,4 @@
|
||||
{
|
||||
"Offroad_ChargeDisabled": {
|
||||
"text": "EON charging disabled after car being off for more than 30 hours. Turn ignition on to start charging again.",
|
||||
"severity": 0
|
||||
},
|
||||
"Offroad_TemperatureTooHigh": {
|
||||
"text": "Device temperature too high. System won't start.",
|
||||
"severity": 1
|
||||
|
||||
@@ -3,7 +3,7 @@ from cereal import log
|
||||
from common.filter_simple import FirstOrderFilter
|
||||
from common.numpy_fast import interp
|
||||
from common.realtime import DT_MDL
|
||||
from selfdrive.hardware import EON, TICI
|
||||
from selfdrive.hardware import TICI
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
||||
|
||||
@@ -13,9 +13,7 @@ TRAJECTORY_SIZE = 33
|
||||
# the model knows the difference between TICI and EON
|
||||
# so a path offset is not needed
|
||||
PATH_OFFSET = 0.00
|
||||
if EON:
|
||||
CAMERA_OFFSET = -0.06
|
||||
elif TICI:
|
||||
if TICI:
|
||||
CAMERA_OFFSET = 0.04
|
||||
else:
|
||||
CAMERA_OFFSET = 0.0
|
||||
|
||||
@@ -48,7 +48,6 @@ acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
|
||||
|
||||
source_list = ['lat_mpc.py',
|
||||
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
|
||||
f'{acados_dir}/aarch64/lib/libacados.so',
|
||||
f'{acados_dir}/x86_64/lib/libacados.so',
|
||||
f'{acados_dir}/larch64/lib/libacados.so',
|
||||
f'{acados_templates_dir}/acados_solver.in.c',
|
||||
|
||||
@@ -55,7 +55,6 @@ acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
|
||||
|
||||
source_list = ['long_mpc.py',
|
||||
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
|
||||
f'{acados_dir}/aarch64/lib/libacados.so',
|
||||
f'{acados_dir}/x86_64/lib/libacados.so',
|
||||
f'{acados_dir}/larch64/lib/libacados.so',
|
||||
f'{acados_templates_dir}/acados_solver.in.c',
|
||||
|
||||
@@ -52,7 +52,7 @@ optional arguments:
|
||||
-h, --help show this help message and exit
|
||||
--debug enable ISO-TP/UDS stack debugging output
|
||||
|
||||
This tool is meant to run directly on a vehicle-installed comma two or comma three, with
|
||||
This tool is meant to run directly on a vehicle-installed comma three, with
|
||||
the openpilot/tmux processes stopped. It should also work on a separate PC with a USB-
|
||||
attached comma panda. Vehicle ignition must be on. Recommend engine not be running when
|
||||
making changes. Must turn ignition off and on again for any changes to take effect.
|
||||
|
||||
@@ -4,12 +4,7 @@ set -e
|
||||
PORT=5555
|
||||
|
||||
setprop service.adb.tcp.port $PORT
|
||||
if [ -f /EON ]; then
|
||||
stop adbd
|
||||
start adbd
|
||||
else
|
||||
sudo systemctl start adbd
|
||||
fi
|
||||
sudo systemctl start adbd
|
||||
|
||||
IP=$(echo $SSH_CONNECTION | awk '{ print $3}')
|
||||
echo "then, connect on your computer:"
|
||||
|
||||
@@ -23,7 +23,7 @@ if __name__ == "__main__":
|
||||
desc_text = "Shows Volkswagen EPS software and coding info, and enables or disables Heading Control Assist " + \
|
||||
"(Lane Assist). Useful for enabling HCA on cars without factory Lane Assist that want to use " + \
|
||||
"openpilot integrated at the CAN gateway (J533)."
|
||||
epilog_text = "This tool is meant to run directly on a vehicle-installed comma two or comma three, with the " + \
|
||||
epilog_text = "This tool is meant to run directly on a vehicle-installed comma three, with the " + \
|
||||
"openpilot/tmux processes stopped. It should also work on a separate PC with a USB-attached comma " + \
|
||||
"panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must " + \
|
||||
"turn ignition off and on again for any changes to take effect."
|
||||
|
||||
@@ -2,18 +2,14 @@ import os
|
||||
from typing import cast
|
||||
|
||||
from selfdrive.hardware.base import HardwareBase
|
||||
from selfdrive.hardware.eon.hardware import Android
|
||||
from selfdrive.hardware.tici.hardware import Tici
|
||||
from selfdrive.hardware.pc.hardware import Pc
|
||||
|
||||
EON = os.path.isfile('/EON')
|
||||
TICI = os.path.isfile('/TICI')
|
||||
PC = not (EON or TICI)
|
||||
PC = not TICI
|
||||
|
||||
|
||||
if EON:
|
||||
HARDWARE = cast(HardwareBase, Android())
|
||||
elif TICI:
|
||||
if TICI:
|
||||
HARDWARE = cast(HardwareBase, Tici())
|
||||
else:
|
||||
HARDWARE = cast(HardwareBase, Pc())
|
||||
|
||||
@@ -20,6 +20,5 @@ public:
|
||||
static void set_ssh_enabled(bool enabled) {}
|
||||
|
||||
static bool PC() { return false; }
|
||||
static bool EON() { return false; }
|
||||
static bool TICI() { return false; }
|
||||
};
|
||||
|
||||
@@ -1,91 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import os
|
||||
import time
|
||||
import psutil
|
||||
from typing import Optional
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from common.realtime import set_core_affinity, set_realtime_priority
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
||||
|
||||
MAX_MODEM_CRASHES = 3
|
||||
MODEM_PATH = "/sys/devices/soc/2080000.qcom,mss/subsys5"
|
||||
WATCHED_PROCS = ["zygote", "zygote64", "system_server", "/system/bin/servicemanager", "/system/bin/surfaceflinger"]
|
||||
|
||||
|
||||
def get_modem_crash_count() -> Optional[int]:
|
||||
try:
|
||||
with open(os.path.join(MODEM_PATH, "crash_count")) as f:
|
||||
return int(f.read())
|
||||
except Exception:
|
||||
cloudlog.exception("Error reading modem crash count")
|
||||
return None
|
||||
|
||||
def get_modem_state() -> str:
|
||||
try:
|
||||
with open(os.path.join(MODEM_PATH, "state")) as f:
|
||||
return f.read().strip()
|
||||
except Exception:
|
||||
cloudlog.exception("Error reading modem state")
|
||||
return ""
|
||||
|
||||
def main():
|
||||
set_core_affinity(1)
|
||||
set_realtime_priority(1)
|
||||
|
||||
procs = {}
|
||||
crash_count = 0
|
||||
modem_killed = False
|
||||
modem_state = "ONLINE"
|
||||
androidLog = messaging.sub_sock('androidLog')
|
||||
|
||||
while True:
|
||||
# check critical android services
|
||||
if any(p is None or not p.is_running() for p in procs.values()) or not len(procs):
|
||||
cur = {p: None for p in WATCHED_PROCS}
|
||||
for p in psutil.process_iter(attrs=['cmdline']):
|
||||
cmdline = None if not len(p.info['cmdline']) else p.info['cmdline'][0]
|
||||
if cmdline in WATCHED_PROCS:
|
||||
cur[cmdline] = p
|
||||
|
||||
if len(procs):
|
||||
for p in WATCHED_PROCS:
|
||||
if cur[p] != procs[p]:
|
||||
cloudlog.event("android service pid changed", proc=p, cur=cur[p], prev=procs[p], error=True)
|
||||
procs.update(cur)
|
||||
|
||||
# log caught NetworkPolicy exceptions
|
||||
msgs = messaging.drain_sock(androidLog)
|
||||
for m in msgs:
|
||||
try:
|
||||
if m.androidLog.tag == "NetworkPolicy" and m.androidLog.message.startswith("problem with advise persist threshold"):
|
||||
cloudlog.event("network policy exception caught", androidLog=m.androidLog, error=True)
|
||||
except UnicodeDecodeError:
|
||||
pass
|
||||
|
||||
if os.path.exists(MODEM_PATH):
|
||||
# check modem state
|
||||
state = get_modem_state()
|
||||
if state != modem_state and not modem_killed:
|
||||
cloudlog.event("modem state changed", state=state)
|
||||
modem_state = state
|
||||
|
||||
# check modem crashes
|
||||
cnt = get_modem_crash_count()
|
||||
if cnt is not None:
|
||||
if cnt > crash_count:
|
||||
cloudlog.event("modem crash", count=cnt)
|
||||
crash_count = cnt
|
||||
|
||||
# handle excessive modem crashes
|
||||
if crash_count > MAX_MODEM_CRASHES and not modem_killed:
|
||||
cloudlog.event("killing modem", error=True)
|
||||
with open("/sys/kernel/debug/msm_subsys/modem", "w") as f:
|
||||
f.write("put")
|
||||
modem_killed = True
|
||||
|
||||
time.sleep(1)
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@@ -1,73 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdlib>
|
||||
#include <fstream>
|
||||
|
||||
#include <gui/ISurfaceComposer.h>
|
||||
#include <gui/SurfaceComposerClient.h>
|
||||
#include <hardware/hwcomposer_defs.h>
|
||||
|
||||
#include "selfdrive/common/util.h"
|
||||
#include "selfdrive/hardware/base.h"
|
||||
|
||||
class HardwareEon : public HardwareNone {
|
||||
public:
|
||||
static constexpr float MAX_VOLUME = 1.0;
|
||||
static constexpr float MIN_VOLUME = 0.5;
|
||||
|
||||
static bool EON() { return true; }
|
||||
static std::string get_os_version() {
|
||||
return "NEOS " + util::read_file("/VERSION");
|
||||
};
|
||||
|
||||
static void reboot() { std::system("reboot"); };
|
||||
static void poweroff() { std::system("LD_LIBRARY_PATH= svc power shutdown"); };
|
||||
static void set_brightness(int percent) {
|
||||
std::ofstream brightness_control("/sys/class/leds/lcd-backlight/brightness");
|
||||
if (brightness_control.is_open()) {
|
||||
brightness_control << (int)(percent * (255/100.)) << "\n";
|
||||
brightness_control.close();
|
||||
}
|
||||
};
|
||||
static void set_display_power(bool on) {
|
||||
auto dtoken = android::SurfaceComposerClient::getBuiltInDisplay(android::ISurfaceComposer::eDisplayIdMain);
|
||||
android::SurfaceComposerClient::setDisplayPowerMode(dtoken, on ? HWC_POWER_MODE_NORMAL : HWC_POWER_MODE_OFF);
|
||||
};
|
||||
|
||||
static bool get_ssh_enabled() {
|
||||
return std::system("getprop persist.neos.ssh | grep -qF '1'") == 0;
|
||||
};
|
||||
static void set_ssh_enabled(bool enabled) {
|
||||
std::string cmd = util::string_format("setprop persist.neos.ssh %d", enabled ? 1 : 0);
|
||||
std::system(cmd.c_str());
|
||||
};
|
||||
|
||||
// android only
|
||||
inline static bool launched_activity = false;
|
||||
static void check_activity() {
|
||||
int ret = std::system("dumpsys SurfaceFlinger --list | grep -Fq 'com.android.settings'");
|
||||
launched_activity = ret == 0;
|
||||
}
|
||||
|
||||
static void close_activities() {
|
||||
if(launched_activity) {
|
||||
std::system("pm disable com.android.settings && pm enable com.android.settings");
|
||||
}
|
||||
}
|
||||
|
||||
static void launch_activity(std::string activity, std::string opts = "") {
|
||||
if (!launched_activity) {
|
||||
std::string cmd = "am start -n " + activity + " " + opts +
|
||||
" --ez extra_prefs_show_button_bar true \
|
||||
--es extra_prefs_set_next_text ''";
|
||||
std::system(cmd.c_str());
|
||||
}
|
||||
launched_activity = true;
|
||||
}
|
||||
static void launch_wifi() {
|
||||
launch_activity("com.android.settings/.wifi.WifiPickerActivity", "-a android.net.wifi.PICK_WIFI_NETWORK");
|
||||
}
|
||||
static void launch_tethering() {
|
||||
launch_activity("com.android.settings/.TetherSettings");
|
||||
}
|
||||
};
|
||||
@@ -1,425 +0,0 @@
|
||||
import binascii
|
||||
import itertools
|
||||
import os
|
||||
import re
|
||||
import serial
|
||||
import struct
|
||||
import subprocess
|
||||
from typing import List, Union
|
||||
|
||||
from cereal import log
|
||||
from selfdrive.hardware.base import HardwareBase, ThermalConfig
|
||||
|
||||
try:
|
||||
from common.params import Params
|
||||
except Exception:
|
||||
# openpilot is not built yet
|
||||
Params = None
|
||||
|
||||
NetworkType = log.DeviceState.NetworkType
|
||||
NetworkStrength = log.DeviceState.NetworkStrength
|
||||
|
||||
MODEM_PATH = "/dev/smd11"
|
||||
|
||||
def service_call(call: List[str]) -> Union[bytes, None]:
|
||||
try:
|
||||
ret = subprocess.check_output(["service", "call", *call], encoding='utf8').strip()
|
||||
if 'Parcel' not in ret:
|
||||
return None
|
||||
return parse_service_call_bytes(ret)
|
||||
except subprocess.CalledProcessError:
|
||||
return None
|
||||
|
||||
|
||||
def parse_service_call_unpack(r, fmt) -> Union[bytes, None]:
|
||||
try:
|
||||
return struct.unpack(fmt, r)[0]
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
|
||||
def parse_service_call_string(r: bytes) -> Union[str, None]:
|
||||
try:
|
||||
r = r[8:] # Cut off length field
|
||||
r_str = r.decode('utf_16_be')
|
||||
|
||||
# All pairs of two characters seem to be swapped. Not sure why
|
||||
result = ""
|
||||
for a, b, in itertools.zip_longest(r_str[::2], r_str[1::2], fillvalue='\x00'):
|
||||
result += b + a
|
||||
|
||||
return result.replace('\x00', '')
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
|
||||
def parse_service_call_bytes(ret: str) -> Union[bytes, None]:
|
||||
try:
|
||||
r = b""
|
||||
for hex_part in re.findall(r'[ (]([0-9a-f]{8})', ret):
|
||||
r += binascii.unhexlify(hex_part)
|
||||
return r
|
||||
except Exception:
|
||||
return None
|
||||
|
||||
|
||||
def getprop(key: str) -> Union[str, None]:
|
||||
try:
|
||||
return subprocess.check_output(["getprop", key], encoding='utf8').strip()
|
||||
except subprocess.CalledProcessError:
|
||||
return None
|
||||
|
||||
|
||||
class Android(HardwareBase):
|
||||
def get_os_version(self):
|
||||
with open("/VERSION") as f:
|
||||
return f.read().strip()
|
||||
|
||||
def get_device_type(self):
|
||||
try:
|
||||
if int(Params().get("LastPeripheralPandaType")) == log.PandaState.PandaType.uno:
|
||||
return "two"
|
||||
except Exception:
|
||||
pass
|
||||
return "eon"
|
||||
|
||||
def get_sound_card_online(self):
|
||||
return (os.path.isfile('/proc/asound/card0/state') and
|
||||
open('/proc/asound/card0/state').read().strip() == 'ONLINE')
|
||||
|
||||
def get_imei(self, slot):
|
||||
slot = str(slot)
|
||||
if slot not in ("0", "1"):
|
||||
raise ValueError("SIM slot must be 0 or 1")
|
||||
|
||||
return parse_service_call_string(service_call(["iphonesubinfo", "3", "i32", str(slot)]))
|
||||
|
||||
def get_serial(self):
|
||||
ret = getprop("ro.serialno")
|
||||
if len(ret) == 0:
|
||||
ret = "cccccccc"
|
||||
return ret
|
||||
|
||||
def get_subscriber_info(self):
|
||||
ret = parse_service_call_string(service_call(["iphonesubinfo", "7"]))
|
||||
if ret is None or len(ret) < 8:
|
||||
return ""
|
||||
return ret
|
||||
|
||||
def reboot(self, reason=None):
|
||||
# e.g. reason="recovery" to go into recover mode
|
||||
if reason is None:
|
||||
reason_args = ["null"]
|
||||
else:
|
||||
reason_args = ["s16", reason]
|
||||
|
||||
subprocess.check_output([
|
||||
"service", "call", "power", "16", # IPowerManager.reboot
|
||||
"i32", "0", # no confirmation,
|
||||
*reason_args,
|
||||
"i32", "1" # wait
|
||||
])
|
||||
|
||||
def uninstall(self):
|
||||
with open('/cache/recovery/command', 'w') as f:
|
||||
f.write('--wipe_data\n')
|
||||
# IPowerManager.reboot(confirm=false, reason="recovery", wait=true)
|
||||
self.reboot(reason="recovery")
|
||||
|
||||
def get_sim_info(self):
|
||||
# Used for athena
|
||||
# TODO: build using methods from this class
|
||||
sim_state = getprop("gsm.sim.state").split(",")
|
||||
network_type = getprop("gsm.network.type").split(',')
|
||||
mcc_mnc = getprop("gsm.sim.operator.numeric") or None
|
||||
|
||||
sim_id = parse_service_call_string(service_call(['iphonesubinfo', '11']))
|
||||
cell_data_state = parse_service_call_unpack(service_call(['phone', '46']), ">q")
|
||||
cell_data_connected = (cell_data_state == 2)
|
||||
|
||||
return {
|
||||
'sim_id': sim_id,
|
||||
'mcc_mnc': mcc_mnc,
|
||||
'network_type': network_type,
|
||||
'sim_state': sim_state,
|
||||
'data_connected': cell_data_connected
|
||||
}
|
||||
|
||||
def get_network_info(self):
|
||||
msg = log.DeviceState.NetworkInfo.new_message()
|
||||
msg.state = getprop("gsm.sim.state") or ""
|
||||
msg.technology = getprop("gsm.network.type") or ""
|
||||
msg.operator = getprop("gsm.sim.operator.numeric") or ""
|
||||
|
||||
try:
|
||||
modem = serial.Serial(MODEM_PATH, 115200, timeout=0.1)
|
||||
modem.write(b"AT$QCRSRP?\r")
|
||||
msg.extra = modem.read_until(b"OK\r\n").decode('utf-8')
|
||||
|
||||
rsrp = msg.extra.split("$QCRSRP: ")[1].split("\r")[0].split(",")
|
||||
msg.channel = int(rsrp[1])
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
return msg
|
||||
|
||||
def get_network_type(self):
|
||||
wifi_check = parse_service_call_string(service_call(["connectivity", "2"]))
|
||||
if wifi_check is None:
|
||||
return NetworkType.none
|
||||
elif 'WIFI' in wifi_check:
|
||||
return NetworkType.wifi
|
||||
else:
|
||||
cell_check = parse_service_call_unpack(service_call(['phone', '59']), ">q")
|
||||
# from TelephonyManager.java
|
||||
cell_networks = {
|
||||
0: NetworkType.none,
|
||||
1: NetworkType.cell2G,
|
||||
2: NetworkType.cell2G,
|
||||
3: NetworkType.cell3G,
|
||||
4: NetworkType.cell2G,
|
||||
5: NetworkType.cell3G,
|
||||
6: NetworkType.cell3G,
|
||||
7: NetworkType.cell3G,
|
||||
8: NetworkType.cell3G,
|
||||
9: NetworkType.cell3G,
|
||||
10: NetworkType.cell3G,
|
||||
11: NetworkType.cell2G,
|
||||
12: NetworkType.cell3G,
|
||||
13: NetworkType.cell4G,
|
||||
14: NetworkType.cell4G,
|
||||
15: NetworkType.cell3G,
|
||||
16: NetworkType.cell2G,
|
||||
17: NetworkType.cell3G,
|
||||
18: NetworkType.cell4G,
|
||||
19: NetworkType.cell4G
|
||||
}
|
||||
return cell_networks.get(cell_check, NetworkType.none)
|
||||
|
||||
def get_network_strength(self, network_type):
|
||||
network_strength = NetworkStrength.unknown
|
||||
|
||||
# from SignalStrength.java
|
||||
def get_lte_level(rsrp, rssnr):
|
||||
INT_MAX = 2147483647
|
||||
if rsrp == INT_MAX:
|
||||
lvl_rsrp = NetworkStrength.unknown
|
||||
elif rsrp >= -95:
|
||||
lvl_rsrp = NetworkStrength.great
|
||||
elif rsrp >= -105:
|
||||
lvl_rsrp = NetworkStrength.good
|
||||
elif rsrp >= -115:
|
||||
lvl_rsrp = NetworkStrength.moderate
|
||||
else:
|
||||
lvl_rsrp = NetworkStrength.poor
|
||||
if rssnr == INT_MAX:
|
||||
lvl_rssnr = NetworkStrength.unknown
|
||||
elif rssnr >= 45:
|
||||
lvl_rssnr = NetworkStrength.great
|
||||
elif rssnr >= 10:
|
||||
lvl_rssnr = NetworkStrength.good
|
||||
elif rssnr >= -30:
|
||||
lvl_rssnr = NetworkStrength.moderate
|
||||
else:
|
||||
lvl_rssnr = NetworkStrength.poor
|
||||
return max(lvl_rsrp, lvl_rssnr)
|
||||
|
||||
def get_tdscdma_level(tdscmadbm):
|
||||
lvl = NetworkStrength.unknown
|
||||
if tdscmadbm > -25:
|
||||
lvl = NetworkStrength.unknown
|
||||
elif tdscmadbm >= -49:
|
||||
lvl = NetworkStrength.great
|
||||
elif tdscmadbm >= -73:
|
||||
lvl = NetworkStrength.good
|
||||
elif tdscmadbm >= -97:
|
||||
lvl = NetworkStrength.moderate
|
||||
elif tdscmadbm >= -110:
|
||||
lvl = NetworkStrength.poor
|
||||
return lvl
|
||||
|
||||
def get_gsm_level(asu):
|
||||
if asu <= 2 or asu == 99:
|
||||
lvl = NetworkStrength.unknown
|
||||
elif asu >= 12:
|
||||
lvl = NetworkStrength.great
|
||||
elif asu >= 8:
|
||||
lvl = NetworkStrength.good
|
||||
elif asu >= 5:
|
||||
lvl = NetworkStrength.moderate
|
||||
else:
|
||||
lvl = NetworkStrength.poor
|
||||
return lvl
|
||||
|
||||
def get_evdo_level(evdodbm, evdosnr):
|
||||
lvl_evdodbm = NetworkStrength.unknown
|
||||
lvl_evdosnr = NetworkStrength.unknown
|
||||
if evdodbm >= -65:
|
||||
lvl_evdodbm = NetworkStrength.great
|
||||
elif evdodbm >= -75:
|
||||
lvl_evdodbm = NetworkStrength.good
|
||||
elif evdodbm >= -90:
|
||||
lvl_evdodbm = NetworkStrength.moderate
|
||||
elif evdodbm >= -105:
|
||||
lvl_evdodbm = NetworkStrength.poor
|
||||
if evdosnr >= 7:
|
||||
lvl_evdosnr = NetworkStrength.great
|
||||
elif evdosnr >= 5:
|
||||
lvl_evdosnr = NetworkStrength.good
|
||||
elif evdosnr >= 3:
|
||||
lvl_evdosnr = NetworkStrength.moderate
|
||||
elif evdosnr >= 1:
|
||||
lvl_evdosnr = NetworkStrength.poor
|
||||
return max(lvl_evdodbm, lvl_evdosnr)
|
||||
|
||||
def get_cdma_level(cdmadbm, cdmaecio):
|
||||
lvl_cdmadbm = NetworkStrength.unknown
|
||||
lvl_cdmaecio = NetworkStrength.unknown
|
||||
if cdmadbm >= -75:
|
||||
lvl_cdmadbm = NetworkStrength.great
|
||||
elif cdmadbm >= -85:
|
||||
lvl_cdmadbm = NetworkStrength.good
|
||||
elif cdmadbm >= -95:
|
||||
lvl_cdmadbm = NetworkStrength.moderate
|
||||
elif cdmadbm >= -100:
|
||||
lvl_cdmadbm = NetworkStrength.poor
|
||||
if cdmaecio >= -90:
|
||||
lvl_cdmaecio = NetworkStrength.great
|
||||
elif cdmaecio >= -110:
|
||||
lvl_cdmaecio = NetworkStrength.good
|
||||
elif cdmaecio >= -130:
|
||||
lvl_cdmaecio = NetworkStrength.moderate
|
||||
elif cdmaecio >= -150:
|
||||
lvl_cdmaecio = NetworkStrength.poor
|
||||
return max(lvl_cdmadbm, lvl_cdmaecio)
|
||||
|
||||
if network_type == NetworkType.none:
|
||||
return network_strength
|
||||
if network_type == NetworkType.wifi:
|
||||
out = subprocess.check_output('dumpsys connectivity', shell=True).decode('utf-8')
|
||||
network_strength = NetworkStrength.unknown
|
||||
for line in out.split('\n'):
|
||||
signal_str = "SignalStrength: "
|
||||
if signal_str in line:
|
||||
lvl_idx_start = line.find(signal_str) + len(signal_str)
|
||||
lvl_idx_end = line.find(']', lvl_idx_start)
|
||||
lvl = int(line[lvl_idx_start : lvl_idx_end])
|
||||
if lvl >= -50:
|
||||
network_strength = NetworkStrength.great
|
||||
elif lvl >= -60:
|
||||
network_strength = NetworkStrength.good
|
||||
elif lvl >= -70:
|
||||
network_strength = NetworkStrength.moderate
|
||||
else:
|
||||
network_strength = NetworkStrength.poor
|
||||
return network_strength
|
||||
else:
|
||||
# check cell strength
|
||||
out = subprocess.check_output('dumpsys telephony.registry', shell=True).decode('utf-8')
|
||||
for line in out.split('\n'):
|
||||
if "mSignalStrength" in line:
|
||||
arr = line.split(' ')
|
||||
ns = 0
|
||||
if ("gsm" in arr[14]):
|
||||
rsrp = int(arr[9])
|
||||
rssnr = int(arr[11])
|
||||
ns = get_lte_level(rsrp, rssnr)
|
||||
if ns == NetworkStrength.unknown:
|
||||
tdscmadbm = int(arr[13])
|
||||
ns = get_tdscdma_level(tdscmadbm)
|
||||
if ns == NetworkStrength.unknown:
|
||||
asu = int(arr[1])
|
||||
ns = get_gsm_level(asu)
|
||||
else:
|
||||
cdmadbm = int(arr[3])
|
||||
cdmaecio = int(arr[4])
|
||||
evdodbm = int(arr[5])
|
||||
evdosnr = int(arr[7])
|
||||
lvl_cdma = get_cdma_level(cdmadbm, cdmaecio)
|
||||
lvl_edmo = get_evdo_level(evdodbm, evdosnr)
|
||||
if lvl_edmo == NetworkStrength.unknown:
|
||||
ns = lvl_cdma
|
||||
elif lvl_cdma == NetworkStrength.unknown:
|
||||
ns = lvl_edmo
|
||||
else:
|
||||
ns = min(lvl_cdma, lvl_edmo)
|
||||
network_strength = max(network_strength, ns)
|
||||
|
||||
return network_strength
|
||||
|
||||
def get_battery_capacity(self):
|
||||
return self.read_param_file("/sys/class/power_supply/battery/capacity", int, 100)
|
||||
|
||||
def get_battery_status(self):
|
||||
# This does not correspond with actual charging or not.
|
||||
# If a USB cable is plugged in, it responds with 'Charging', even when charging is disabled
|
||||
return self.read_param_file("/sys/class/power_supply/battery/status", lambda x: x.strip(), '')
|
||||
|
||||
def get_battery_current(self):
|
||||
return self.read_param_file("/sys/class/power_supply/battery/current_now", int)
|
||||
|
||||
def get_battery_voltage(self):
|
||||
return self.read_param_file("/sys/class/power_supply/battery/voltage_now", int)
|
||||
|
||||
def get_battery_charging(self):
|
||||
# This does correspond with actually charging
|
||||
return self.read_param_file("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", True)
|
||||
|
||||
def set_battery_charging(self, on):
|
||||
with open('/sys/class/power_supply/battery/charging_enabled', 'w') as f:
|
||||
f.write(f"{1 if on else 0}\n")
|
||||
|
||||
def get_usb_present(self):
|
||||
return self.read_param_file("/sys/class/power_supply/usb/present", lambda x: bool(int(x)), False)
|
||||
|
||||
def get_current_power_draw(self):
|
||||
if self.get_battery_status() == 'Discharging':
|
||||
# If the battery is discharging, we can use this measurement
|
||||
# On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in
|
||||
return ((self.get_battery_voltage() / 1000000) * (self.get_battery_current() / 1000000))
|
||||
else:
|
||||
# We don't have a good direct way to measure this if it's not "discharging"
|
||||
return None
|
||||
|
||||
def shutdown(self):
|
||||
os.system('LD_LIBRARY_PATH="" svc power shutdown')
|
||||
|
||||
def get_thermal_config(self):
|
||||
# the thermal sensors on the 820 don't have meaningful names
|
||||
return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10),
|
||||
bat=("battery", 1000), ambient=("pa_therm0", 1), pmic=(("pm8994_tz",), 1000))
|
||||
|
||||
def set_screen_brightness(self, percentage):
|
||||
with open("/sys/class/leds/lcd-backlight/brightness", "w") as f:
|
||||
f.write(str(int(percentage * 2.55)))
|
||||
|
||||
def get_screen_brightness(self):
|
||||
try:
|
||||
with open("/sys/class/leds/lcd-backlight/brightness") as f:
|
||||
return int(float(f.read()) / 2.55)
|
||||
except Exception:
|
||||
return 0
|
||||
|
||||
def set_power_save(self, powersave_enabled):
|
||||
pass
|
||||
|
||||
def get_gpu_usage_percent(self):
|
||||
try:
|
||||
used, total = open('/sys/devices/soc/b00000.qcom,kgsl-3d0/kgsl/kgsl-3d0/gpubusy').read().strip().split()
|
||||
perc = 100.0 * int(used) / int(total)
|
||||
return min(max(perc, 0), 100)
|
||||
except Exception:
|
||||
return 0
|
||||
|
||||
def get_modem_temperatures(self):
|
||||
# Not sure if we can get this on the LeEco
|
||||
return []
|
||||
|
||||
def get_nvme_temperatures(self):
|
||||
return []
|
||||
|
||||
def initialize_hardware(self):
|
||||
pass
|
||||
|
||||
def get_networks(self):
|
||||
return None
|
||||
@@ -1,7 +0,0 @@
|
||||
{
|
||||
"ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7.zip",
|
||||
"ota_hash": "50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7",
|
||||
"recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f.img",
|
||||
"recovery_len": 15222060,
|
||||
"recovery_hash": "fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f"
|
||||
}
|
||||
@@ -1,130 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import argparse
|
||||
import hashlib
|
||||
import json
|
||||
import logging
|
||||
import os
|
||||
import requests
|
||||
|
||||
NEOSUPDATE_DIR = "/data/neoupdate"
|
||||
|
||||
RECOVERY_DEV = "/dev/block/bootdevice/by-name/recovery"
|
||||
RECOVERY_COMMAND = "/cache/recovery/command"
|
||||
|
||||
|
||||
def get_fn(url: str):
|
||||
return os.path.join(NEOSUPDATE_DIR, os.path.basename(url))
|
||||
|
||||
|
||||
def download_file(url: str, fn: str, sha256: str, display_name: str, cloudlog=logging) -> None:
|
||||
# check if already downloaded
|
||||
if check_hash(fn, sha256):
|
||||
cloudlog.info(f"{display_name} already cached")
|
||||
return
|
||||
|
||||
try:
|
||||
with open(fn, "ab+") as f:
|
||||
headers = {"Range": f"bytes={f.tell()}-"}
|
||||
r = requests.get(url, stream=True, allow_redirects=True, headers=headers)
|
||||
r.raise_for_status()
|
||||
|
||||
total = int(r.headers['Content-Length'])
|
||||
if 'Content-Range' in r.headers:
|
||||
total = int(r.headers['Content-Range'].split('/')[-1])
|
||||
|
||||
for chunk in r.iter_content(chunk_size=1024 * 1024):
|
||||
f.write(chunk)
|
||||
print(f"Downloading {display_name}: {f.tell() / total * 100}", flush=True)
|
||||
except Exception:
|
||||
cloudlog.error("download error")
|
||||
if os.path.isfile(fn):
|
||||
os.unlink(fn)
|
||||
raise
|
||||
|
||||
if not check_hash(fn, sha256):
|
||||
if os.path.isfile(fn):
|
||||
os.unlink(fn)
|
||||
raise Exception("downloaded update failed hash check")
|
||||
|
||||
|
||||
def check_hash(fn: str, sha256: str, length: int = -1) -> bool:
|
||||
if not os.path.exists(fn):
|
||||
return False
|
||||
|
||||
h = hashlib.sha256()
|
||||
with open(fn, "rb") as f:
|
||||
while f.tell() != length:
|
||||
r = min(max(0, length - f.tell()), 1024 * 1024) if length > 0 else 1024 * 1024
|
||||
dat = f.read(r)
|
||||
if not dat:
|
||||
break
|
||||
h.update(dat)
|
||||
return h.hexdigest().lower() == sha256.lower()
|
||||
|
||||
|
||||
def flash_update(update_fn: str, out_path: str) -> None:
|
||||
with open(update_fn, "rb") as update, open(out_path, "w+b") as out:
|
||||
while True:
|
||||
dat = update.read(8192)
|
||||
if len(dat) == 0:
|
||||
break
|
||||
out.write(dat)
|
||||
|
||||
|
||||
def download_neos_update(manifest_path: str, cloudlog=logging) -> None:
|
||||
with open(manifest_path) as f:
|
||||
m = json.load(f)
|
||||
|
||||
os.makedirs(NEOSUPDATE_DIR, exist_ok=True)
|
||||
|
||||
# handle recovery updates
|
||||
if not check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len']):
|
||||
cloudlog.info("recovery needs update")
|
||||
recovery_fn = os.path.join(NEOSUPDATE_DIR, os.path.basename(m['recovery_url']))
|
||||
download_file(m['recovery_url'], recovery_fn, m['recovery_hash'], "recovery", cloudlog)
|
||||
|
||||
flash_update(recovery_fn, RECOVERY_DEV)
|
||||
assert check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len']), "recovery flash corrupted"
|
||||
cloudlog.info("recovery successfully flashed")
|
||||
|
||||
# download OTA update
|
||||
download_file(m['ota_url'], get_fn(m['ota_url']), m['ota_hash'], "system", cloudlog)
|
||||
|
||||
|
||||
def verify_update_ready(manifest_path: str) -> bool:
|
||||
with open(manifest_path) as f:
|
||||
m = json.load(f)
|
||||
|
||||
ota_downloaded = check_hash(get_fn(m['ota_url']), m['ota_hash'])
|
||||
recovery_flashed = check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len'])
|
||||
return ota_downloaded and recovery_flashed
|
||||
|
||||
|
||||
def perform_ota_update(manifest_path: str) -> None:
|
||||
with open(manifest_path) as f:
|
||||
m = json.load(f)
|
||||
|
||||
# reboot into recovery
|
||||
ota_fn = get_fn(m['ota_url'])
|
||||
with open(RECOVERY_COMMAND, "w") as rf:
|
||||
rf.write(f"--update_package={ota_fn}\n")
|
||||
os.system("service call power 16 i32 0 s16 recovery i32 1")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description="NEOS update utility",
|
||||
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
|
||||
parser.add_argument("--swap", action="store_true", help="Peform update after downloading")
|
||||
parser.add_argument("--swap-if-ready", action="store_true", help="Perform update if already downloaded")
|
||||
parser.add_argument("manifest", help="Manifest json")
|
||||
args = parser.parse_args()
|
||||
|
||||
logging.basicConfig(level=logging.INFO)
|
||||
|
||||
if args.swap_if_ready:
|
||||
if verify_update_ready(args.manifest):
|
||||
perform_ota_update(args.manifest)
|
||||
else:
|
||||
download_neos_update(args.manifest, logging)
|
||||
if args.swap:
|
||||
perform_ota_update(args.manifest)
|
||||
@@ -1,34 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import os
|
||||
import time
|
||||
import datetime
|
||||
|
||||
from common.params import Params
|
||||
from selfdrive.hardware.eon.hardware import getprop
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
||||
def main():
|
||||
prev = b""
|
||||
params = Params()
|
||||
while True:
|
||||
with open("/dev/__properties__", 'rb') as f:
|
||||
cur = f.read()
|
||||
|
||||
if cur != prev:
|
||||
prev = cur
|
||||
|
||||
# 0 for shutdown, 1 for reboot
|
||||
prop = getprop("sys.shutdown.requested")
|
||||
if prop is not None and len(prop) > 0:
|
||||
os.system("pkill -9 loggerd")
|
||||
params.put("LastSystemShutdown", f"'{prop}' {datetime.datetime.now()}")
|
||||
os.sync()
|
||||
|
||||
time.sleep(120)
|
||||
cloudlog.error('shutdown false positive')
|
||||
break
|
||||
|
||||
time.sleep(0.1)
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@@ -1,145 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import hashlib
|
||||
import http.server
|
||||
import json
|
||||
import os
|
||||
import unittest
|
||||
import random
|
||||
import requests
|
||||
import shutil
|
||||
import socketserver
|
||||
import tempfile
|
||||
import multiprocessing
|
||||
from pathlib import Path
|
||||
|
||||
from selfdrive.hardware.eon.neos import RECOVERY_DEV, NEOSUPDATE_DIR, get_fn, download_file, \
|
||||
verify_update_ready, download_neos_update
|
||||
|
||||
EON_DIR = os.path.join(os.path.dirname(os.path.abspath(__file__)))
|
||||
MANIFEST = os.path.join(EON_DIR, "neos.json")
|
||||
|
||||
PORT = 8000
|
||||
|
||||
def server_thread(port):
|
||||
socketserver.TCPServer.allow_reuse_address = True
|
||||
httpd = socketserver.TCPServer(("", port), http.server.SimpleHTTPRequestHandler)
|
||||
httpd.serve_forever()
|
||||
|
||||
|
||||
class TestNeosUpdater(unittest.TestCase):
|
||||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
# generate a fake manifest
|
||||
cls.manifest = {}
|
||||
for i in ('ota', 'recovery'):
|
||||
with tempfile.NamedTemporaryFile(delete=False, dir=os.getcwd()) as f:
|
||||
dat = os.urandom(random.randint(1000, 100000))
|
||||
f.write(dat)
|
||||
cls.manifest[f"{i}_url"] = f"http://localhost:{PORT}/" + os.path.relpath(f.name)
|
||||
cls.manifest[F"{i}_hash"] = hashlib.sha256(dat).hexdigest()
|
||||
if i == "recovery":
|
||||
cls.manifest["recovery_len"] = len(dat)
|
||||
|
||||
with tempfile.NamedTemporaryFile(delete=False, mode='w') as f:
|
||||
f.write(json.dumps(cls.manifest))
|
||||
cls.fake_manifest = f.name
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
os.unlink(cls.fake_manifest)
|
||||
os.unlink(os.path.basename(cls.manifest['ota_url']))
|
||||
os.unlink(os.path.basename(cls.manifest['recovery_url']))
|
||||
|
||||
def setUp(self):
|
||||
# server for update files
|
||||
self.server = multiprocessing.Process(target=server_thread, args=(PORT, ))
|
||||
self.server.start()
|
||||
|
||||
# clean up
|
||||
if os.path.exists(NEOSUPDATE_DIR):
|
||||
shutil.rmtree(NEOSUPDATE_DIR)
|
||||
|
||||
def tearDown(self):
|
||||
self.server.kill()
|
||||
self.server.join(1)
|
||||
|
||||
def _corrupt_recovery(self):
|
||||
with open(RECOVERY_DEV, "wb") as f:
|
||||
f.write(b'\x00'*100)
|
||||
|
||||
def test_manifest(self):
|
||||
with open(MANIFEST) as f:
|
||||
m = json.load(f)
|
||||
|
||||
assert m['ota_hash'] in m['ota_url']
|
||||
assert m['recovery_hash'] in m['recovery_url']
|
||||
assert m['recovery_len'] > 0
|
||||
|
||||
for url in (m['ota_url'], m['recovery_url']):
|
||||
r = requests.head(m['recovery_url'])
|
||||
r.raise_for_status()
|
||||
self.assertEqual(r.headers['Content-Type'], "application/octet-stream")
|
||||
if url == m['recovery_url']:
|
||||
self.assertEqual(int(r.headers['Content-Length']), m['recovery_len'])
|
||||
|
||||
def test_download_hash_check(self):
|
||||
os.makedirs(NEOSUPDATE_DIR, exist_ok=True)
|
||||
Path(get_fn(self.manifest['ota_url'])).touch()
|
||||
with self.assertRaisesRegex(Exception, "failed hash check"):
|
||||
download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']),
|
||||
self.manifest['ota_hash']+'a', "system")
|
||||
|
||||
# should've unlinked after the failed hash check, should succeed now
|
||||
download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']),
|
||||
self.manifest['ota_hash'], "system")
|
||||
|
||||
# TODO: needs an http server that supports Content-Range
|
||||
#def test_download_resume(self):
|
||||
# os.makedirs(NEOSUPDATE_DIR, exist_ok=True)
|
||||
# with open(os.path.basename(self.manifest['ota_url']), "rb") as src, \
|
||||
# open(get_fn(self.manifest['ota_url']), "wb") as dest:
|
||||
# l = dest.write(src.read(8192))
|
||||
# assert l == 8192
|
||||
# download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']),
|
||||
# self.manifest['ota_hash'], "system")
|
||||
|
||||
def test_download_no_internet(self):
|
||||
self.server.kill()
|
||||
os.makedirs(NEOSUPDATE_DIR, exist_ok=True)
|
||||
# fail, no internet
|
||||
with self.assertRaises(requests.exceptions.ConnectionError):
|
||||
download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']),
|
||||
self.manifest['ota_hash'], "system")
|
||||
|
||||
# already cached, ensure we don't hit the server
|
||||
shutil.copyfile(os.path.basename(self.manifest['ota_url']), get_fn(self.manifest['ota_url']))
|
||||
download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']),
|
||||
self.manifest['ota_hash'], "system")
|
||||
|
||||
|
||||
def test_download_update(self):
|
||||
download_neos_update(self.fake_manifest)
|
||||
self.assertTrue(verify_update_ready(self.fake_manifest))
|
||||
|
||||
def test_verify_update(self):
|
||||
# good state
|
||||
download_neos_update(self.fake_manifest)
|
||||
self.assertTrue(verify_update_ready(self.fake_manifest))
|
||||
|
||||
# corrupt recovery
|
||||
self._corrupt_recovery()
|
||||
self.assertFalse(verify_update_ready(self.fake_manifest))
|
||||
|
||||
# back to good state
|
||||
download_neos_update(self.fake_manifest)
|
||||
self.assertTrue(verify_update_ready(self.fake_manifest))
|
||||
|
||||
# corrupt ota
|
||||
self._corrupt_recovery()
|
||||
with open(os.path.join(NEOSUPDATE_DIR, os.path.basename(self.manifest['ota_url'])), "ab") as f:
|
||||
f.write(b'\x00')
|
||||
self.assertFalse(verify_update_ready(self.fake_manifest))
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
@@ -1,4 +0,0 @@
|
||||
#!/usr/bin/bash
|
||||
|
||||
ROOT=$PWD/../../..
|
||||
$ROOT/installer/updater/updater "file://$ROOT/installer/updater/update.json"
|
||||
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:93fa3a75fe891d75c3adc515c65dcd899ace6063e16eaf417d202b6befaba3d1
|
||||
size 3193008
|
||||
@@ -3,10 +3,7 @@
|
||||
#include "selfdrive/hardware/base.h"
|
||||
#include "selfdrive/common/util.h"
|
||||
|
||||
#ifdef QCOM
|
||||
#include "selfdrive/hardware/eon/hardware.h"
|
||||
#define Hardware HardwareEon
|
||||
#elif QCOM2
|
||||
#if QCOM2
|
||||
#include "selfdrive/hardware/tici/hardware.h"
|
||||
#define Hardware HardwareTici
|
||||
#else
|
||||
|
||||
@@ -1,6 +1,3 @@
|
||||
Import('env', 'cereal', 'messaging', 'common', 'arch')
|
||||
Import('env', 'cereal', 'messaging', 'common')
|
||||
|
||||
if arch == "aarch64":
|
||||
env.Program('logcatd', 'logcatd_android.cc', LIBS=[cereal, messaging, common, 'cutils', 'zmq', 'capnp', 'kj'])
|
||||
else:
|
||||
env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, common, 'zmq', 'capnp', 'kj', 'systemd', 'json11'])
|
||||
env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, common, 'zmq', 'capnp', 'kj', 'systemd', 'json11'])
|
||||
|
||||
@@ -1,51 +0,0 @@
|
||||
#include <android/log.h>
|
||||
#include <log/logger.h>
|
||||
#include <log/logprint.h>
|
||||
#include <sys/resource.h>
|
||||
|
||||
#include <csignal>
|
||||
|
||||
#include "cereal/messaging/messaging.h"
|
||||
|
||||
#undef LOG_ID_KERNEL
|
||||
#define LOG_ID_KERNEL 5
|
||||
|
||||
int main() {
|
||||
std::signal(SIGINT, exit);
|
||||
std::signal(SIGTERM, exit);
|
||||
setpriority(PRIO_PROCESS, 0, -15);
|
||||
|
||||
// setup android logging
|
||||
logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0);
|
||||
assert(logger_list);
|
||||
for (auto log_id : {LOG_ID_MAIN, LOG_ID_RADIO, LOG_ID_SYSTEM, LOG_ID_CRASH, (log_id_t)LOG_ID_KERNEL}) {
|
||||
logger *logger = android_logger_open(logger_list, log_id);
|
||||
assert(logger);
|
||||
}
|
||||
|
||||
PubMaster pm({"androidLog"});
|
||||
|
||||
while (true) {
|
||||
log_msg log_msg;
|
||||
int err = android_logger_list_read(logger_list, &log_msg);
|
||||
if (err <= 0) break;
|
||||
|
||||
AndroidLogEntry entry;
|
||||
err = android_log_processLogBuffer(&log_msg.entry_v1, &entry);
|
||||
if (err < 0) continue;
|
||||
|
||||
MessageBuilder msg;
|
||||
auto androidEntry = msg.initEvent().initAndroidLog();
|
||||
androidEntry.setId(log_msg.id());
|
||||
androidEntry.setTs(entry.tv_sec * NS_PER_SEC + entry.tv_nsec);
|
||||
androidEntry.setPriority(entry.priority);
|
||||
androidEntry.setPid(entry.pid);
|
||||
androidEntry.setTid(entry.tid);
|
||||
androidEntry.setTag(entry.tag);
|
||||
androidEntry.setMessage(entry.message);
|
||||
pm.send("androidLog", msg);
|
||||
}
|
||||
|
||||
android_logger_list_free(logger_list);
|
||||
return 0;
|
||||
}
|
||||
@@ -1,45 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import os
|
||||
import random
|
||||
import string
|
||||
import time
|
||||
import unittest
|
||||
import uuid
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from selfdrive.test.helpers import with_processes
|
||||
|
||||
class TestLogcatdAndroid(unittest.TestCase):
|
||||
|
||||
@with_processes(['logcatd'])
|
||||
def test_log(self):
|
||||
sock = messaging.sub_sock("androidLog", conflate=False)
|
||||
|
||||
# make sure sockets are ready
|
||||
time.sleep(1)
|
||||
messaging.drain_sock(sock)
|
||||
|
||||
sent_msgs = {}
|
||||
for _ in range(random.randint(2, 10)):
|
||||
# write some log messages
|
||||
for __ in range(random.randint(5, 50)):
|
||||
tag = uuid.uuid4().hex
|
||||
msg = ''.join(random.choice(string.ascii_letters) for _ in range(random.randrange(2, 50)))
|
||||
sent_msgs[tag] = {'recv_cnt': 0, 'msg': msg}
|
||||
os.system(f"log -t '{tag}' '{msg}'")
|
||||
|
||||
time.sleep(1)
|
||||
msgs = messaging.drain_sock(sock)
|
||||
for m in msgs:
|
||||
self.assertTrue(m.valid)
|
||||
self.assertLess(time.monotonic() - (m.logMonoTime / 1e9), 30)
|
||||
tag = m.androidLog.tag
|
||||
if tag in sent_msgs:
|
||||
sent_msgs[tag]['recv_cnt'] += 1
|
||||
self.assertEqual(m.androidLog.message.strip(), sent_msgs[tag]['msg'])
|
||||
|
||||
for v in sent_msgs.values():
|
||||
self.assertEqual(v['recv_cnt'], 1)
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
@@ -4,19 +4,14 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon')
|
||||
libs = [common, cereal, messaging, visionipc,
|
||||
'zmq', 'capnp', 'kj', 'z',
|
||||
'avformat', 'avcodec', 'swscale', 'avutil',
|
||||
'yuv', 'bz2', 'OpenCL']
|
||||
'yuv', 'bz2', 'OpenCL', 'pthread']
|
||||
|
||||
src = ['logger.cc', 'loggerd.cc']
|
||||
if arch in ["aarch64", "larch64"]:
|
||||
if arch == "larch64":
|
||||
src += ['omx_encoder.cc']
|
||||
libs += ['OmxCore', 'gsl', 'CB'] + gpucommon
|
||||
if arch == "aarch64":
|
||||
libs += ['OmxVenc', 'cutils']
|
||||
else:
|
||||
libs += ['pthread']
|
||||
else:
|
||||
src += ['raw_logger.cc']
|
||||
libs += ['pthread']
|
||||
|
||||
if arch == "Darwin":
|
||||
# fix OpenCL
|
||||
|
||||
@@ -11,8 +11,6 @@ static kj::Array<capnp::word> build_boot_log() {
|
||||
if (Hardware::TICI()) {
|
||||
bootlog_commands.push_back("journalctl");
|
||||
bootlog_commands.push_back("sudo nvme smart-log --output-format=json /dev/nvme0");
|
||||
} else if (Hardware::EON()) {
|
||||
bootlog_commands.push_back("logcat -d");
|
||||
}
|
||||
|
||||
MessageBuilder msg;
|
||||
|
||||
@@ -14,9 +14,6 @@
|
||||
#include <fstream>
|
||||
#include <iostream>
|
||||
#include <streambuf>
|
||||
#ifdef QCOM
|
||||
#include <cutils/properties.h>
|
||||
#endif
|
||||
|
||||
#include "selfdrive/common/params.h"
|
||||
#include "selfdrive/common/swaglog.h"
|
||||
@@ -36,9 +33,7 @@ kj::Array<capnp::word> logger_build_init_data() {
|
||||
MessageBuilder msg;
|
||||
auto init = msg.initEvent().initInitData();
|
||||
|
||||
if (Hardware::EON()) {
|
||||
init.setDeviceType(cereal::InitData::DeviceType::NEO);
|
||||
} else if (Hardware::TICI()) {
|
||||
if (Hardware::TICI()) {
|
||||
init.setDeviceType(cereal::InitData::DeviceType::TICI);
|
||||
} else {
|
||||
init.setDeviceType(cereal::InitData::DeviceType::PC);
|
||||
@@ -61,20 +56,6 @@ kj::Array<capnp::word> logger_build_init_data() {
|
||||
init.setKernelVersion(util::read_file("/proc/version"));
|
||||
init.setOsVersion(util::read_file("/VERSION"));
|
||||
|
||||
#ifdef QCOM
|
||||
{
|
||||
std::vector<std::pair<std::string, std::string> > properties;
|
||||
property_list(append_property, (void*)&properties);
|
||||
|
||||
auto lentries = init.initAndroidProperties().initEntries(properties.size());
|
||||
for (int i=0; i<properties.size(); i++) {
|
||||
auto lentry = lentries[i];
|
||||
lentry.setKey(properties[i].first);
|
||||
lentry.setValue(properties[i].second);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
init.setDirty(!getenv("CLEAN"));
|
||||
|
||||
// log params
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#include "selfdrive/loggerd/encoder.h"
|
||||
#include "selfdrive/loggerd/logger.h"
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
#include "selfdrive/loggerd/omx_encoder.h"
|
||||
#define Encoder OmxEncoder
|
||||
#else
|
||||
@@ -74,12 +74,12 @@ const LogCameraInfo cameras_logged[] = {
|
||||
.type = DriverCam,
|
||||
.stream_type = VISION_STREAM_DRIVER,
|
||||
.filename = "dcamera.hevc",
|
||||
.fps = MAIN_FPS, // on EONs, more compressed this way
|
||||
.fps = MAIN_FPS,
|
||||
.bitrate = DCAM_BITRATE,
|
||||
.is_h265 = true,
|
||||
.downscale = false,
|
||||
.has_qcamera = false,
|
||||
.trigger_rotate = Hardware::TICI(),
|
||||
.trigger_rotate = true,
|
||||
.enable = true,
|
||||
.record = Params().getBool("RecordFront"),
|
||||
},
|
||||
|
||||
@@ -3,9 +3,7 @@
|
||||
#include <sys/resource.h>
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
if (Hardware::EON()) {
|
||||
setpriority(PRIO_PROCESS, 0, -20);
|
||||
} else if (Hardware::TICI()) {
|
||||
if (Hardware::TICI()) {
|
||||
int ret;
|
||||
ret = util::set_core_affinity({0, 1, 2, 3});
|
||||
assert(ret == 0);
|
||||
|
||||
@@ -13,27 +13,19 @@ from tqdm import trange
|
||||
|
||||
from common.params import Params
|
||||
from common.timeout import Timeout
|
||||
from selfdrive.hardware import EON, TICI
|
||||
from selfdrive.hardware import TICI
|
||||
from selfdrive.loggerd.config import ROOT
|
||||
from selfdrive.manager.process_config import managed_processes
|
||||
from tools.lib.logreader import LogReader
|
||||
|
||||
SEGMENT_LENGTH = 2
|
||||
if EON:
|
||||
FULL_SIZE = 1253786 # file size for a 2s segment in bytes
|
||||
CAMERAS = [
|
||||
("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"),
|
||||
("dcamera.hevc", 10, 770920, "driverEncodeIdx"),
|
||||
("qcamera.ts", 20, 77066, None),
|
||||
]
|
||||
else:
|
||||
FULL_SIZE = 2507572
|
||||
CAMERAS = [
|
||||
("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"),
|
||||
("dcamera.hevc", 20, FULL_SIZE, "driverEncodeIdx"),
|
||||
("ecamera.hevc", 20, FULL_SIZE, "wideRoadEncodeIdx"),
|
||||
("qcamera.ts", 20, 77066, None),
|
||||
]
|
||||
FULL_SIZE = 2507572
|
||||
CAMERAS = [
|
||||
("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"),
|
||||
("dcamera.hevc", 20, FULL_SIZE, "driverEncodeIdx"),
|
||||
("ecamera.hevc", 20, FULL_SIZE, "wideRoadEncodeIdx"),
|
||||
("qcamera.ts", 20, 77066, None),
|
||||
]
|
||||
|
||||
# we check frame count, so we don't have to be too strict on size
|
||||
FILE_SIZE_TOLERANCE = 0.5
|
||||
@@ -44,7 +36,7 @@ class TestEncoder(unittest.TestCase):
|
||||
# TODO: all of loggerd should work on PC
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
if not (EON or TICI):
|
||||
if not TICI:
|
||||
raise unittest.SkipTest
|
||||
|
||||
def setUp(self):
|
||||
@@ -93,8 +85,6 @@ class TestEncoder(unittest.TestCase):
|
||||
if not record_front and "dcamera" in camera:
|
||||
continue
|
||||
|
||||
eon_dcam = EON and (camera == 'dcamera.hevc')
|
||||
|
||||
file_path = f"{route_prefix_path}--{i}/{camera}"
|
||||
|
||||
# check file exists
|
||||
@@ -107,7 +97,7 @@ class TestEncoder(unittest.TestCase):
|
||||
cmd = "LD_LIBRARY_PATH=/usr/local/lib " + cmd
|
||||
|
||||
expected_frames = fps * SEGMENT_LENGTH
|
||||
frame_tolerance = 1 if eon_dcam else 0
|
||||
frame_tolerance = 0
|
||||
probe = subprocess.check_output(cmd, shell=True, encoding='utf8')
|
||||
frame_count = int(probe.split('\n')[0].strip())
|
||||
counts.append(frame_count)
|
||||
@@ -140,9 +130,8 @@ class TestEncoder(unittest.TestCase):
|
||||
|
||||
self.assertTrue(all(valid))
|
||||
|
||||
if not eon_dcam:
|
||||
self.assertEqual(expected_frames * i, encode_idxs[0])
|
||||
first_frames.append(frame_idxs[0])
|
||||
self.assertEqual(expected_frames * i, encode_idxs[0])
|
||||
first_frames.append(frame_idxs[0])
|
||||
self.assertEqual(len(set(encode_idxs)), len(encode_idxs))
|
||||
|
||||
self.assertEqual(1, len(set(first_frames)))
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
import os
|
||||
|
||||
from selfdrive.hardware import EON, TICI, PC
|
||||
from selfdrive.hardware import TICI, PC
|
||||
from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess
|
||||
|
||||
WEBCAM = os.getenv("USE_WEBCAM") is not None
|
||||
@@ -16,7 +16,7 @@ procs = [
|
||||
NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]),
|
||||
NativeProcess("navd", "selfdrive/ui/navd", ["./navd"], enabled=(PC or TICI), persistent=True),
|
||||
NativeProcess("proclogd", "selfdrive/proclogd", ["./proclogd"]),
|
||||
NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC, persistent=EON, sigkill=EON),
|
||||
NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC),
|
||||
NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=(not PC or WEBCAM)),
|
||||
NativeProcess("ui", "selfdrive/ui", ["./ui"], persistent=True, watchdog_max_dt=(5 if TICI else None)),
|
||||
NativeProcess("soundd", "selfdrive/ui/soundd", ["./soundd"], persistent=True),
|
||||
@@ -38,11 +38,6 @@ procs = [
|
||||
PythonProcess("uploader", "selfdrive.loggerd.uploader", persistent=True),
|
||||
PythonProcess("statsd", "selfdrive.statsd", persistent=True),
|
||||
|
||||
# EON only
|
||||
PythonProcess("rtshield", "selfdrive.rtshield", enabled=EON),
|
||||
PythonProcess("shutdownd", "selfdrive.hardware.eon.shutdownd", enabled=EON),
|
||||
PythonProcess("androidd", "selfdrive.hardware.eon.androidd", enabled=EON, persistent=True),
|
||||
|
||||
# Experimental
|
||||
PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")),
|
||||
]
|
||||
|
||||
@@ -5,14 +5,14 @@ import time
|
||||
import unittest
|
||||
|
||||
import selfdrive.manager.manager as manager
|
||||
from selfdrive.hardware import EON, TICI, HARDWARE
|
||||
from selfdrive.hardware import TICI, HARDWARE
|
||||
from selfdrive.manager.process import DaemonProcess
|
||||
from selfdrive.manager.process_config import managed_processes
|
||||
|
||||
os.environ['FAKEUPLOAD'] = "1"
|
||||
|
||||
# TODO: make eon fast
|
||||
MAX_STARTUP_TIME = 30 if EON else 15
|
||||
MAX_STARTUP_TIME = 15
|
||||
ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['updated', 'pandad'])]
|
||||
|
||||
|
||||
@@ -50,7 +50,7 @@ class TestManager(unittest.TestCase):
|
||||
self.assertTrue(state.running, f"{p} not running")
|
||||
|
||||
exit_code = managed_processes[p].stop(retry=False)
|
||||
if (TICI and p in ['ui', 'navd']) or (EON and p == 'logcatd'):
|
||||
if (TICI and p in ['ui', 'navd']):
|
||||
# TODO: make Qt UI exit gracefully
|
||||
continue
|
||||
|
||||
|
||||
@@ -31,9 +31,8 @@ thneed_src = [
|
||||
|
||||
use_thneed = not GetOption('no_thneed')
|
||||
|
||||
if arch == "aarch64" or arch == "larch64":
|
||||
libs += ['gsl', 'CB']
|
||||
libs += ['gnustl_shared'] if arch == "aarch64" else ['pthread', 'dl']
|
||||
if arch == "larch64":
|
||||
libs += ['gsl', 'CB', 'pthread', 'dl']
|
||||
|
||||
if use_thneed:
|
||||
common_src += thneed_src
|
||||
@@ -64,7 +63,7 @@ else:
|
||||
common_model = lenv.Object(common_src)
|
||||
|
||||
# build thneed model
|
||||
if use_thneed and arch in ("aarch64", "larch64"):
|
||||
if use_thneed and arch == "larch64":
|
||||
fn = File("#models/supercombo").abspath
|
||||
compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs)
|
||||
cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} {fn}.dlc {fn}_badweights.thneed --binary"
|
||||
|
||||
@@ -3,15 +3,10 @@
|
||||
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
|
||||
cd $DIR
|
||||
|
||||
if [ -d /system ]; then
|
||||
if [ -f /TICI ]; then # QCOM2
|
||||
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
|
||||
else # QCOM
|
||||
export LD_LIBRARY_PATH="/data/pythonpath/third_party/snpe/aarch64/:$LD_LIBRARY_PATH"
|
||||
fi
|
||||
if [ -f /TICI ]; then
|
||||
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
|
||||
export ADSP_LIBRARY_PATH="/data/pythonpath/third_party/snpe/dsp/"
|
||||
else
|
||||
# PC
|
||||
export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH"
|
||||
fi
|
||||
exec ./_dmonitoringmodeld
|
||||
|
||||
@@ -3,14 +3,9 @@
|
||||
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
|
||||
cd $DIR
|
||||
|
||||
if [ -d /system ]; then
|
||||
if [ -f /TICI ]; then # QCOM2
|
||||
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
|
||||
else # QCOM
|
||||
export LD_LIBRARY_PATH="/data/pythonpath/third_party/snpe/aarch64/:$LD_LIBRARY_PATH"
|
||||
fi
|
||||
if [ -f /TICI ]; then
|
||||
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
|
||||
else
|
||||
# PC
|
||||
export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH"
|
||||
fi
|
||||
exec ./_modeld
|
||||
|
||||
@@ -160,11 +160,11 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl
|
||||
}
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
if (!Hardware::PC()) {
|
||||
if (Hardware::TICI()) {
|
||||
int ret;
|
||||
ret = util::set_realtime_priority(54);
|
||||
assert(ret == 0);
|
||||
util::set_core_affinity({Hardware::EON() ? 2 : 7});
|
||||
util::set_core_affinity({7});
|
||||
assert(ret == 0);
|
||||
}
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int
|
||||
output = loutput;
|
||||
output_size = loutput_size;
|
||||
use_extra = luse_extra;
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
if (runtime==USE_GPU_RUNTIME) {
|
||||
Runtime = zdl::DlSystem::Runtime_t::GPU;
|
||||
} else if (runtime==USE_DSP_RUNTIME) {
|
||||
@@ -39,7 +39,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int
|
||||
// create model runner
|
||||
zdl::SNPE::SNPEBuilder snpeBuilder(container.get());
|
||||
while (!snpe) {
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
snpe = snpeBuilder.setOutputLayers({})
|
||||
.setRuntimeProcessor(Runtime)
|
||||
.setUseUserSuppliedBuffers(true)
|
||||
|
||||
@@ -38,7 +38,7 @@ public:
|
||||
private:
|
||||
std::string model_data;
|
||||
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
zdl::DlSystem::Runtime_t Runtime;
|
||||
#endif
|
||||
|
||||
|
||||
@@ -433,7 +433,7 @@ cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, c
|
||||
}
|
||||
|
||||
void *dlsym(void *handle, const char *symbol) {
|
||||
#if defined(QCOM) || defined(QCOM2)
|
||||
#ifdef QCOM2
|
||||
void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen + DLSYM_OFFSET);
|
||||
#else
|
||||
#error "Unsupported platform for thneed"
|
||||
|
||||
@@ -1,22 +1,19 @@
|
||||
Import('env', 'arch', 'common', 'cereal', 'messaging')
|
||||
|
||||
if arch == "aarch64":
|
||||
env.Program('_sensord', 'sensors_qcom.cc', LIBS=['hardware', common, cereal, messaging, 'capnp', 'zmq', 'kj'])
|
||||
else:
|
||||
sensors = [
|
||||
'sensors/file_sensor.cc',
|
||||
'sensors/i2c_sensor.cc',
|
||||
'sensors/light_sensor.cc',
|
||||
'sensors/bmx055_accel.cc',
|
||||
'sensors/bmx055_gyro.cc',
|
||||
'sensors/bmx055_magn.cc',
|
||||
'sensors/bmx055_temp.cc',
|
||||
'sensors/lsm6ds3_accel.cc',
|
||||
'sensors/lsm6ds3_gyro.cc',
|
||||
'sensors/lsm6ds3_temp.cc',
|
||||
'sensors/mmc5603nj_magn.cc',
|
||||
]
|
||||
libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj']
|
||||
if arch == "larch64":
|
||||
libs.append('i2c')
|
||||
env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs)
|
||||
sensors = [
|
||||
'sensors/file_sensor.cc',
|
||||
'sensors/i2c_sensor.cc',
|
||||
'sensors/light_sensor.cc',
|
||||
'sensors/bmx055_accel.cc',
|
||||
'sensors/bmx055_gyro.cc',
|
||||
'sensors/bmx055_magn.cc',
|
||||
'sensors/bmx055_temp.cc',
|
||||
'sensors/lsm6ds3_accel.cc',
|
||||
'sensors/lsm6ds3_gyro.cc',
|
||||
'sensors/lsm6ds3_temp.cc',
|
||||
'sensors/mmc5603nj_magn.cc',
|
||||
]
|
||||
libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj']
|
||||
if arch == "larch64":
|
||||
libs.append('i2c')
|
||||
env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs)
|
||||
|
||||
@@ -1,228 +0,0 @@
|
||||
#include <cutils/log.h>
|
||||
#include <hardware/sensors.h>
|
||||
#include <sys/cdefs.h>
|
||||
#include <sys/resource.h>
|
||||
#include <sys/time.h>
|
||||
#include <sys/types.h>
|
||||
#include <unistd.h>
|
||||
#include <utils/Timers.h>
|
||||
|
||||
#include <cassert>
|
||||
#include <cstdint>
|
||||
#include <cstdio>
|
||||
#include <cstdlib>
|
||||
#include <cstring>
|
||||
#include <map>
|
||||
#include <set>
|
||||
|
||||
#include "cereal/messaging/messaging.h"
|
||||
#include "selfdrive/common/swaglog.h"
|
||||
#include "selfdrive/common/timing.h"
|
||||
#include "selfdrive/common/util.h"
|
||||
|
||||
// ACCELEROMETER_UNCALIBRATED is only in Android O
|
||||
// https://developer.android.com/reference/android/hardware/Sensor.html#STRING_TYPE_ACCELEROMETER_UNCALIBRATED
|
||||
|
||||
#define SENSOR_ACCELEROMETER 1
|
||||
#define SENSOR_MAGNETOMETER 2
|
||||
#define SENSOR_GYRO 4
|
||||
#define SENSOR_MAGNETOMETER_UNCALIBRATED 3
|
||||
#define SENSOR_GYRO_UNCALIBRATED 5
|
||||
#define SENSOR_PROXIMITY 6
|
||||
#define SENSOR_LIGHT 7
|
||||
|
||||
ExitHandler do_exit;
|
||||
volatile sig_atomic_t re_init_sensors = 0;
|
||||
|
||||
namespace {
|
||||
|
||||
void sigpipe_handler(int sig) {
|
||||
LOGE("SIGPIPE received");
|
||||
re_init_sensors = true;
|
||||
}
|
||||
|
||||
void sensor_loop() {
|
||||
LOG("*** sensor loop");
|
||||
|
||||
uint64_t frame = 0;
|
||||
bool low_power_mode = false;
|
||||
|
||||
while (!do_exit) {
|
||||
SubMaster sm({"deviceState"});
|
||||
PubMaster pm({"sensorEvents"});
|
||||
|
||||
struct sensors_poll_device_t* device;
|
||||
struct sensors_module_t* module;
|
||||
|
||||
hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module);
|
||||
sensors_open(&module->common, &device);
|
||||
|
||||
// required
|
||||
struct sensor_t const* list;
|
||||
int count = module->get_sensors_list(module, &list);
|
||||
LOG("%d sensors found", count);
|
||||
|
||||
if (getenv("SENSOR_TEST")) {
|
||||
exit(count);
|
||||
}
|
||||
|
||||
for (int i = 0; i < count; i++) {
|
||||
LOGD("sensor %4d: %4d %60s %d-%ld us", i, list[i].handle, list[i].name, list[i].minDelay, list[i].maxDelay);
|
||||
}
|
||||
|
||||
std::set<int> sensor_types = {
|
||||
SENSOR_TYPE_ACCELEROMETER,
|
||||
SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED,
|
||||
SENSOR_TYPE_MAGNETIC_FIELD,
|
||||
SENSOR_TYPE_GYROSCOPE_UNCALIBRATED,
|
||||
SENSOR_TYPE_GYROSCOPE,
|
||||
SENSOR_TYPE_PROXIMITY,
|
||||
SENSOR_TYPE_LIGHT,
|
||||
};
|
||||
|
||||
std::map<int, int64_t> sensors = {
|
||||
{SENSOR_GYRO_UNCALIBRATED, ms2ns(10)},
|
||||
{SENSOR_MAGNETOMETER_UNCALIBRATED, ms2ns(100)},
|
||||
{SENSOR_ACCELEROMETER, ms2ns(10)},
|
||||
{SENSOR_GYRO, ms2ns(10)},
|
||||
{SENSOR_MAGNETOMETER, ms2ns(100)},
|
||||
{SENSOR_PROXIMITY, ms2ns(100)},
|
||||
{SENSOR_LIGHT, ms2ns(100)}
|
||||
};
|
||||
|
||||
// sensors needed while offroad
|
||||
std::set<int> offroad_sensors = {
|
||||
SENSOR_LIGHT,
|
||||
SENSOR_ACCELEROMETER,
|
||||
SENSOR_GYRO_UNCALIBRATED,
|
||||
};
|
||||
|
||||
// init all the sensors
|
||||
for (auto &s : sensors) {
|
||||
device->activate(device, s.first, 0);
|
||||
device->activate(device, s.first, 1);
|
||||
device->setDelay(device, s.first, s.second);
|
||||
}
|
||||
|
||||
// TODO: why is this 16?
|
||||
static const size_t numEvents = 16;
|
||||
sensors_event_t buffer[numEvents];
|
||||
|
||||
while (!do_exit) {
|
||||
int n = device->poll(device, buffer, numEvents);
|
||||
if (n == 0) continue;
|
||||
if (n < 0) {
|
||||
LOG("sensor_loop poll failed: %d", n);
|
||||
continue;
|
||||
}
|
||||
|
||||
int log_events = 0;
|
||||
for (int i=0; i < n; i++) {
|
||||
if (sensor_types.find(buffer[i].type) != sensor_types.end()) {
|
||||
log_events++;
|
||||
}
|
||||
}
|
||||
|
||||
MessageBuilder msg;
|
||||
auto sensor_events = msg.initEvent().initSensorEvents(log_events);
|
||||
|
||||
int log_i = 0;
|
||||
for (int i = 0; i < n; i++) {
|
||||
|
||||
const sensors_event_t& data = buffer[i];
|
||||
|
||||
if (sensor_types.find(data.type) == sensor_types.end()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
auto log_event = sensor_events[log_i];
|
||||
log_event.setSource(cereal::SensorEventData::SensorSource::ANDROID);
|
||||
log_event.setVersion(data.version);
|
||||
log_event.setSensor(data.sensor);
|
||||
log_event.setType(data.type);
|
||||
log_event.setTimestamp(data.timestamp);
|
||||
|
||||
switch (data.type) {
|
||||
case SENSOR_TYPE_ACCELEROMETER: {
|
||||
auto svec = log_event.initAcceleration();
|
||||
svec.setV(data.acceleration.v);
|
||||
svec.setStatus(data.acceleration.status);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED: {
|
||||
auto svec = log_event.initMagneticUncalibrated();
|
||||
// assuming the uncalib and bias floats are contiguous in memory
|
||||
kj::ArrayPtr<const float> vs(&data.uncalibrated_magnetic.uncalib[0], 6);
|
||||
svec.setV(vs);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_MAGNETIC_FIELD: {
|
||||
auto svec = log_event.initMagnetic();
|
||||
svec.setV(data.magnetic.v);
|
||||
svec.setStatus(data.magnetic.status);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_GYROSCOPE_UNCALIBRATED: {
|
||||
auto svec = log_event.initGyroUncalibrated();
|
||||
// assuming the uncalib and bias floats are contiguous in memory
|
||||
kj::ArrayPtr<const float> vs(&data.uncalibrated_gyro.uncalib[0], 6);
|
||||
svec.setV(vs);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_GYROSCOPE: {
|
||||
auto svec = log_event.initGyro();
|
||||
svec.setV(data.gyro.v);
|
||||
svec.setStatus(data.gyro.status);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_PROXIMITY: {
|
||||
log_event.setProximity(data.distance);
|
||||
break;
|
||||
}
|
||||
case SENSOR_TYPE_LIGHT:
|
||||
log_event.setLight(data.light);
|
||||
break;
|
||||
}
|
||||
|
||||
log_i++;
|
||||
}
|
||||
|
||||
pm.send("sensorEvents", msg);
|
||||
|
||||
if (re_init_sensors) {
|
||||
LOGE("Resetting sensors");
|
||||
re_init_sensors = false;
|
||||
break;
|
||||
}
|
||||
|
||||
// Check whether to go into low power mode at 5Hz
|
||||
if (frame % 20 == 0) {
|
||||
sm.update(0);
|
||||
bool offroad = !sm["deviceState"].getDeviceState().getStarted();
|
||||
if (low_power_mode != offroad) {
|
||||
for (auto &s : sensors) {
|
||||
device->activate(device, s.first, 0);
|
||||
if (!offroad || offroad_sensors.find(s.first) != offroad_sensors.end()) {
|
||||
device->activate(device, s.first, 1);
|
||||
}
|
||||
}
|
||||
low_power_mode = offroad;
|
||||
}
|
||||
}
|
||||
|
||||
frame++;
|
||||
}
|
||||
sensors_close(device);
|
||||
}
|
||||
}
|
||||
|
||||
}// Namespace end
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
setpriority(PRIO_PROCESS, 0, -18);
|
||||
signal(SIGPIPE, (sighandler_t)sigpipe_handler);
|
||||
|
||||
sensor_loop();
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -21,13 +21,8 @@ from selfdrive.version import get_commit
|
||||
from tools.lib.framereader import FrameReader
|
||||
from tools.lib.logreader import LogReader
|
||||
|
||||
TICI_TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"
|
||||
EON_TEST_ROUTE = "303055c0002aefd1|2021-11-22--18-36-32"
|
||||
TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"
|
||||
SEGMENT = 0
|
||||
if TICI:
|
||||
TEST_ROUTE = TICI_TEST_ROUTE
|
||||
else:
|
||||
TEST_ROUTE = EON_TEST_ROUTE
|
||||
|
||||
SEND_EXTRA_INPUTS = bool(os.getenv("SEND_EXTRA_INPUTS", "0"))
|
||||
|
||||
|
||||
@@ -21,44 +21,23 @@ umount /data/safe_staging/merged/ || true
|
||||
sudo umount /data/safe_staging/merged/ || true
|
||||
|
||||
export KEYS_PARAM_PATH="/data/params/d/GithubSshKeys"
|
||||
if [ -f "/EON" ]; then
|
||||
export KEYS_PATH="/data/data/com.termux/files/home/setup_keys"
|
||||
export CONTINUE_PATH="/data/data/com.termux/files/continue.sh"
|
||||
export KEYS_PATH="/usr/comma/setup_keys"
|
||||
export CONTINUE_PATH="/data/continue.sh"
|
||||
|
||||
if ! grep -F "$KEYS_PATH" /usr/etc/ssh/sshd_config; then
|
||||
echo "setting up keys"
|
||||
mount -o rw,remount /system
|
||||
sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /usr/etc/ssh/sshd_config
|
||||
mount -o ro,remount /system
|
||||
fi
|
||||
|
||||
# these can get pretty big
|
||||
rm -rf /data/core
|
||||
rm -rf /data/neoupdate
|
||||
rm -rf /data/safe_staging
|
||||
else
|
||||
export KEYS_PATH="/usr/comma/setup_keys"
|
||||
export CONTINUE_PATH="/data/continue.sh"
|
||||
|
||||
if ! grep -F "$KEYS_PATH" /etc/ssh/sshd_config; then
|
||||
echo "setting up keys"
|
||||
sudo mount -o rw,remount /
|
||||
sudo systemctl enable ssh
|
||||
sudo sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /etc/ssh/sshd_config
|
||||
sudo mount -o ro,remount /
|
||||
fi
|
||||
if ! grep -F "$KEYS_PATH" /etc/ssh/sshd_config; then
|
||||
echo "setting up keys"
|
||||
sudo mount -o rw,remount /
|
||||
sudo systemctl enable ssh
|
||||
sudo sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /etc/ssh/sshd_config
|
||||
sudo mount -o ro,remount /
|
||||
fi
|
||||
|
||||
tee $CONTINUE_PATH << EOF
|
||||
#!/usr/bin/bash
|
||||
|
||||
while true; do
|
||||
if [ -f /EON ]; then
|
||||
setprop persist.neos.ssh 1
|
||||
else
|
||||
if ! sudo systemctl is-active -q ssh; then
|
||||
sudo systemctl start ssh
|
||||
fi
|
||||
if ! sudo systemctl is-active -q ssh; then
|
||||
sudo systemctl start ssh
|
||||
fi
|
||||
sleep 10s
|
||||
done
|
||||
|
||||
@@ -15,26 +15,25 @@ from common.basedir import BASEDIR
|
||||
from common.timeout import Timeout
|
||||
from common.params import Params
|
||||
from selfdrive.controls.lib.events import EVENTS, ET
|
||||
from selfdrive.hardware import EON, TICI
|
||||
from selfdrive.loggerd.config import ROOT
|
||||
from selfdrive.test.helpers import set_params_enabled, release_only
|
||||
from tools.lib.logreader import LogReader
|
||||
|
||||
# Baseline CPU usage by process
|
||||
PROCS = {
|
||||
"selfdrive.controls.controlsd": 55.0,
|
||||
"./loggerd": 45.0,
|
||||
"selfdrive.controls.controlsd": 31.0,
|
||||
"./loggerd": 70.0,
|
||||
"./camerad": 41.0,
|
||||
"./locationd": 9.1,
|
||||
"selfdrive.controls.plannerd": 22.6,
|
||||
"./_ui": 20.0,
|
||||
"selfdrive.locationd.paramsd": 14.0,
|
||||
"./camerad": 9.16,
|
||||
"selfdrive.controls.plannerd": 11.7,
|
||||
"./_ui": 33.0,
|
||||
"selfdrive.locationd.paramsd": 5.0,
|
||||
"./_sensord": 6.17,
|
||||
"selfdrive.controls.radard": 7.0,
|
||||
"selfdrive.controls.radard": 4.5,
|
||||
"./_modeld": 4.48,
|
||||
"./boardd": 3.63,
|
||||
"./_dmonitoringmodeld": 2.67,
|
||||
"selfdrive.thermald.thermald": 5.36,
|
||||
"./_dmonitoringmodeld": 10.0,
|
||||
"selfdrive.thermald.thermald": 3.87,
|
||||
"selfdrive.locationd.calibrationd": 2.0,
|
||||
"./_soundd": 1.0,
|
||||
"selfdrive.monitoring.dmonitoringd": 1.90,
|
||||
@@ -46,26 +45,6 @@ PROCS = {
|
||||
"./logcatd": 0,
|
||||
}
|
||||
|
||||
if EON:
|
||||
PROCS.update({
|
||||
"selfdrive.hardware.eon.androidd": 0.4,
|
||||
"selfdrive.hardware.eon.shutdownd": 0.4,
|
||||
})
|
||||
|
||||
if TICI:
|
||||
PROCS.update({
|
||||
"./loggerd": 70.0,
|
||||
"selfdrive.controls.controlsd": 31.0,
|
||||
"./camerad": 41.0,
|
||||
"./_ui": 33.0,
|
||||
"selfdrive.controls.plannerd": 11.7,
|
||||
"./_dmonitoringmodeld": 10.0,
|
||||
"selfdrive.locationd.paramsd": 5.0,
|
||||
"selfdrive.controls.radard": 4.5,
|
||||
"selfdrive.thermald.thermald": 3.87,
|
||||
})
|
||||
|
||||
|
||||
TIMINGS = {
|
||||
# rtols: max/min, rsd
|
||||
"can": [2.5, 0.35],
|
||||
@@ -82,15 +61,8 @@ TIMINGS = {
|
||||
"modelV2": [2.5, 0.35],
|
||||
"driverState": [2.5, 0.35],
|
||||
"liveLocationKalman": [2.5, 0.35],
|
||||
"wideRoadCameraState": [1.5, 0.35],
|
||||
}
|
||||
if EON:
|
||||
TIMINGS.update({
|
||||
"roadCameraState": [2.5, 0.45],
|
||||
})
|
||||
if TICI:
|
||||
TIMINGS.update({
|
||||
"wideRoadCameraState": [1.5, 0.35],
|
||||
})
|
||||
|
||||
|
||||
def cputime_total(ct):
|
||||
@@ -232,12 +204,10 @@ class TestOnroad(unittest.TestCase):
|
||||
result += "----------------- Model Timing -----------------\n"
|
||||
result += "------------------------------------------------\n"
|
||||
# TODO: this went up when plannerd cpu usage increased, why?
|
||||
cfgs = [("driverState", 0.028, 0.026)]
|
||||
if EON:
|
||||
cfgs += [("modelV2", 0.045, 0.04)]
|
||||
else:
|
||||
cfgs += [("modelV2", 0.038, 0.036), ("driverState", 0.028, 0.026)]
|
||||
|
||||
cfgs = [
|
||||
("modelV2", 0.038, 0.036),
|
||||
("driverState", 0.028, 0.026),
|
||||
]
|
||||
for (s, instant_max, avg_max) in cfgs:
|
||||
ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s]
|
||||
self.assertLess(min(ts), instant_max, f"high '{s}' execution time: {min(ts)}")
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import os
|
||||
from smbus2 import SMBus
|
||||
from abc import ABC, abstractmethod
|
||||
|
||||
from common.realtime import DT_TRML
|
||||
from common.numpy_fast import interp
|
||||
from selfdrive.swaglog import cloudlog
|
||||
@@ -14,69 +12,6 @@ class BaseFanController(ABC):
|
||||
pass
|
||||
|
||||
|
||||
class EonFanController(BaseFanController):
|
||||
# Temp thresholds to control fan speed - high hysteresis
|
||||
TEMP_THRS_H = [50., 65., 80., 10000]
|
||||
# Temp thresholds to control fan speed - low hysteresis
|
||||
TEMP_THRS_L = [42.5, 57.5, 72.5, 10000]
|
||||
# Fan speed options
|
||||
FAN_SPEEDS = [0, 16384, 32768, 65535]
|
||||
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
cloudlog.info("Setting up EON fan handler")
|
||||
|
||||
self.fan_speed = -1
|
||||
self.setup_eon_fan()
|
||||
|
||||
def setup_eon_fan(self) -> None:
|
||||
os.system("echo 2 > /sys/module/dwc3_msm/parameters/otg_switch")
|
||||
|
||||
def set_eon_fan(self, speed: int) -> None:
|
||||
if self.fan_speed != speed:
|
||||
# FIXME: this is such an ugly hack to get the right index
|
||||
val = speed // 16384
|
||||
|
||||
bus = SMBus(7, force=True)
|
||||
try:
|
||||
i = [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10][val]
|
||||
bus.write_i2c_block_data(0x3d, 0, [i])
|
||||
except OSError:
|
||||
# tusb320
|
||||
if val == 0:
|
||||
bus.write_i2c_block_data(0x67, 0xa, [0])
|
||||
else:
|
||||
bus.write_i2c_block_data(0x67, 0xa, [0x20])
|
||||
bus.write_i2c_block_data(0x67, 0x8, [(val - 1) << 6])
|
||||
bus.close()
|
||||
self.fan_speed = speed
|
||||
|
||||
def update(self, max_cpu_temp: float, ignition: bool) -> int:
|
||||
new_speed_h = next(speed for speed, temp_h in zip(self.FAN_SPEEDS, self.TEMP_THRS_H) if temp_h > max_cpu_temp)
|
||||
new_speed_l = next(speed for speed, temp_l in zip(self.FAN_SPEEDS, self.TEMP_THRS_L) if temp_l > max_cpu_temp)
|
||||
|
||||
if new_speed_h > self.fan_speed:
|
||||
self.set_eon_fan(new_speed_h)
|
||||
elif new_speed_l < self.fan_speed:
|
||||
self.set_eon_fan(new_speed_l)
|
||||
|
||||
return self.fan_speed
|
||||
|
||||
|
||||
class UnoFanController(BaseFanController):
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
cloudlog.info("Setting up UNO fan handler")
|
||||
|
||||
def update(self, max_cpu_temp: float, ignition: bool) -> int:
|
||||
new_speed = int(interp(max_cpu_temp, [40.0, 80.0], [0, 80]))
|
||||
|
||||
if not ignition:
|
||||
new_speed = min(30, new_speed)
|
||||
|
||||
return new_speed
|
||||
|
||||
|
||||
class TiciFanController(BaseFanController):
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
|
||||
@@ -1,13 +1,11 @@
|
||||
#!/usr/bin/env python3
|
||||
import unittest
|
||||
from unittest.mock import Mock, MagicMock, patch
|
||||
from unittest.mock import Mock, patch
|
||||
from parameterized import parameterized
|
||||
|
||||
with patch("smbus2.SMBus", new=MagicMock()):
|
||||
from selfdrive.thermald.fan_controller import EonFanController, UnoFanController, TiciFanController
|
||||
from selfdrive.thermald.fan_controller import TiciFanController
|
||||
|
||||
ALL_CONTROLLERS = [(EonFanController, ), (UnoFanController,), (TiciFanController,)]
|
||||
GEN2_CONTROLLERS = [(UnoFanController,), (TiciFanController,)]
|
||||
ALL_CONTROLLERS = [(TiciFanController,)]
|
||||
|
||||
def patched_controller(controller_class):
|
||||
with patch("os.system", new=Mock()):
|
||||
@@ -28,7 +26,7 @@ class TestFanController(unittest.TestCase):
|
||||
self.wind_up(controller)
|
||||
self.assertGreaterEqual(controller.update(max_cpu_temp=100, ignition=True), 70)
|
||||
|
||||
@parameterized.expand(GEN2_CONTROLLERS)
|
||||
@parameterized.expand(ALL_CONTROLLERS)
|
||||
def test_offroad_limits(self, controller_class):
|
||||
controller = patched_controller(controller_class)
|
||||
self.wind_up(controller)
|
||||
@@ -40,7 +38,7 @@ class TestFanController(unittest.TestCase):
|
||||
self.wind_down(controller)
|
||||
self.assertEqual(controller.update(max_cpu_temp=10, ignition=False), 0)
|
||||
|
||||
@parameterized.expand(GEN2_CONTROLLERS)
|
||||
@parameterized.expand(ALL_CONTROLLERS)
|
||||
def test_limited(self, controller_class):
|
||||
controller = patched_controller(controller_class)
|
||||
self.wind_up(controller, ignition=True)
|
||||
|
||||
@@ -17,12 +17,12 @@ from common.filter_simple import FirstOrderFilter
|
||||
from common.params import Params
|
||||
from common.realtime import DT_TRML, sec_since_boot
|
||||
from selfdrive.controls.lib.alertmanager import set_offroad_alert
|
||||
from selfdrive.hardware import EON, HARDWARE, PC, TICI
|
||||
from selfdrive.hardware import HARDWARE, TICI
|
||||
from selfdrive.loggerd.config import get_available_percent
|
||||
from selfdrive.statsd import statlog
|
||||
from selfdrive.swaglog import cloudlog
|
||||
from selfdrive.thermald.power_monitoring import PowerMonitoring
|
||||
from selfdrive.thermald.fan_controller import EonFanController, UnoFanController, TiciFanController
|
||||
from selfdrive.thermald.fan_controller import TiciFanController
|
||||
from selfdrive.version import terms_version, training_version
|
||||
|
||||
ThermalStatus = log.DeviceState.ThermalStatus
|
||||
@@ -174,7 +174,6 @@ def thermald_thread(end_event, hw_queue):
|
||||
started_ts = None
|
||||
started_seen = False
|
||||
thermal_status = ThermalStatus.green
|
||||
usb_power = True
|
||||
|
||||
last_hw_state = HardwareState(
|
||||
network_type=NetworkType.none,
|
||||
@@ -189,7 +188,6 @@ def thermald_thread(end_event, hw_queue):
|
||||
temp_filter = FirstOrderFilter(0., TEMP_TAU, DT_TRML)
|
||||
should_start_prev = False
|
||||
in_car = False
|
||||
is_uno = False
|
||||
engaged_prev = False
|
||||
|
||||
params = Params()
|
||||
@@ -216,18 +214,11 @@ def thermald_thread(end_event, hw_queue):
|
||||
pandaState = pandaStates[0]
|
||||
|
||||
in_car = pandaState.harnessStatus != log.PandaState.HarnessStatus.notConnected
|
||||
usb_power = peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client
|
||||
|
||||
# Setup fan handler on first connect to panda
|
||||
if fan_controller is None and peripheralState.pandaType != log.PandaState.PandaType.unknown:
|
||||
is_uno = peripheralState.pandaType == log.PandaState.PandaType.uno
|
||||
|
||||
if TICI:
|
||||
fan_controller = TiciFanController()
|
||||
elif is_uno or PC:
|
||||
fan_controller = UnoFanController()
|
||||
else:
|
||||
fan_controller = EonFanController()
|
||||
|
||||
try:
|
||||
last_hw_state = hw_queue.get_nowait()
|
||||
@@ -380,9 +371,6 @@ def thermald_thread(end_event, hw_queue):
|
||||
msg.deviceState.thermalStatus = thermal_status
|
||||
pm.send("deviceState", msg)
|
||||
|
||||
if EON and not is_uno:
|
||||
set_offroad_alert_if_changed("Offroad_ChargeDisabled", (not usb_power))
|
||||
|
||||
should_start_prev = should_start
|
||||
startup_conditions_prev = startup_conditions.copy()
|
||||
|
||||
@@ -409,9 +397,6 @@ def thermald_thread(end_event, hw_queue):
|
||||
|
||||
# report to server once every 10 minutes
|
||||
if (count % int(600. / DT_TRML)) == 0:
|
||||
if EON and started_ts is None and msg.deviceState.memoryUsagePercent > 40:
|
||||
cloudlog.event("High offroad memory usage", mem=msg.deviceState.memoryUsagePercent)
|
||||
|
||||
cloudlog.event("STATUS_PACKET",
|
||||
count=count,
|
||||
pandaStates=[strip_deprecated_keys(p.to_dict()) for p in pandaStates],
|
||||
|
||||
@@ -7,9 +7,6 @@ base_libs = [gpucommon, common, messaging, cereal, visionipc, transformations, '
|
||||
|
||||
maps = arch in ['larch64', 'x86_64']
|
||||
|
||||
if arch == 'aarch64':
|
||||
base_libs += ['log', 'utils', 'gui', 'ui', 'CB', 'gsl', 'adreno_utils', 'cutils', 'uuid']
|
||||
|
||||
if maps and arch == 'x86_64':
|
||||
rpath = [Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath]
|
||||
qt_env["RPATH"] += rpath
|
||||
@@ -22,10 +19,7 @@ widgets_src = ["qt/util.cc", "qt/widgets/input.cc", "qt/widgets/drive_stats.cc",
|
||||
"qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc",
|
||||
"qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc",
|
||||
"qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", "qt/api.cc",
|
||||
"qt/request_repeater.cc", "qt/qt_window.cc"]
|
||||
|
||||
if arch != 'aarch64':
|
||||
widgets_src += ["qt/offroad/networking.cc", "qt/offroad/wifiManager.cc"]
|
||||
"qt/request_repeater.cc", "qt/qt_window.cc", "qt/offroad/networking.cc", "qt/offroad/wifiManager.cc"]
|
||||
|
||||
qt_env['CPPDEFINES'] = []
|
||||
if maps:
|
||||
@@ -63,7 +57,7 @@ qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs)
|
||||
|
||||
|
||||
# setup and factory resetter
|
||||
if arch != 'aarch64' and GetOption('extras'):
|
||||
if GetOption('extras'):
|
||||
qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs)
|
||||
qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj],
|
||||
LIBS=qt_libs + ['curl', 'common', 'json11'])
|
||||
@@ -80,8 +74,8 @@ if GetOption('extras'):
|
||||
senv = qt_env.Clone()
|
||||
senv['LINKFLAGS'].append('-Wl,-strip-debug')
|
||||
|
||||
release = "release3" if arch == 'larch64' else "release2"
|
||||
dashcam = "dashcam3" if arch == 'larch64' else "dashcam"
|
||||
release = "release3"
|
||||
dashcam = "dashcam3"
|
||||
installers = [
|
||||
("openpilot", release),
|
||||
("openpilot_test", f"{release}-staging"),
|
||||
|
||||
@@ -25,12 +25,7 @@ const std::string GIT_URL = get_str("https://github.com/commaai/openpilot.git" "
|
||||
const std::string BRANCH_STR = get_str(BRANCH "? ");
|
||||
|
||||
#define GIT_SSH_URL "git@github.com:commaai/openpilot.git"
|
||||
|
||||
#ifdef QCOM
|
||||
#define CONTINUE_PATH "/data/data/com.termux/files/continue.sh"
|
||||
#else
|
||||
#define CONTINUE_PATH "/data/continue.sh"
|
||||
#endif
|
||||
#define CONTINUE_PATH "/data/continue.sh"
|
||||
|
||||
const QString CACHE_PATH = "/data/openpilot.cache";
|
||||
|
||||
@@ -212,12 +207,8 @@ void Installer::cloneFinished(int exitCode, QProcess::ExitStatus exitStatus) {
|
||||
run("chmod +x /data/continue.sh.new");
|
||||
run("mv /data/continue.sh.new " CONTINUE_PATH);
|
||||
|
||||
#ifdef QCOM
|
||||
QTimer::singleShot(100, &QCoreApplication::quit);
|
||||
#else
|
||||
// wait for the installed software's UI to take over
|
||||
QTimer::singleShot(60 * 1000, &QCoreApplication::quit);
|
||||
#endif
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
#include <sys/resource.h>
|
||||
|
||||
#include <QApplication>
|
||||
#include <QSslConfiguration>
|
||||
|
||||
#include "selfdrive/hardware/hw.h"
|
||||
#include "selfdrive/ui/qt/qt_window.h"
|
||||
@@ -14,12 +13,6 @@ int main(int argc, char *argv[]) {
|
||||
qInstallMessageHandler(swagLogMessageHandler);
|
||||
initApp(argc, argv);
|
||||
|
||||
if (Hardware::EON()) {
|
||||
QSslConfiguration ssl = QSslConfiguration::defaultConfiguration();
|
||||
ssl.setCaCertificates(QSslCertificate::fromPath("/usr/etc/tls/cert.pem"));
|
||||
QSslConfiguration::setDefaultConfiguration(ssl);
|
||||
}
|
||||
|
||||
QApplication a(argc, argv);
|
||||
MainWindow w;
|
||||
setMainWindow(&w);
|
||||
|
||||
@@ -6,9 +6,7 @@
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
#ifndef QCOM
|
||||
#include "selfdrive/ui/qt/offroad/networking.h"
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_MAPS
|
||||
#include "selfdrive/ui/qt/maps/map_settings.h"
|
||||
@@ -290,57 +288,8 @@ void SoftwarePanel::updateLabels() {
|
||||
osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed());
|
||||
}
|
||||
|
||||
C2NetworkPanel::C2NetworkPanel(QWidget *parent) : QWidget(parent) {
|
||||
QVBoxLayout *layout = new QVBoxLayout(this);
|
||||
layout->setContentsMargins(50, 0, 50, 0);
|
||||
|
||||
ListWidget *list = new ListWidget();
|
||||
list->setSpacing(30);
|
||||
// wifi + tethering buttons
|
||||
#ifdef QCOM
|
||||
auto wifiBtn = new ButtonControl("Wi-Fi Settings", "OPEN");
|
||||
QObject::connect(wifiBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_wifi(); });
|
||||
list->addItem(wifiBtn);
|
||||
|
||||
auto tetheringBtn = new ButtonControl("Tethering Settings", "OPEN");
|
||||
QObject::connect(tetheringBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_tethering(); });
|
||||
list->addItem(tetheringBtn);
|
||||
#endif
|
||||
ipaddress = new LabelControl("IP Address", "");
|
||||
list->addItem(ipaddress);
|
||||
|
||||
// SSH key management
|
||||
list->addItem(new SshToggle());
|
||||
list->addItem(new SshControl());
|
||||
layout->addWidget(list);
|
||||
layout->addStretch(1);
|
||||
}
|
||||
|
||||
void C2NetworkPanel::showEvent(QShowEvent *event) {
|
||||
ipaddress->setText(getIPAddress());
|
||||
}
|
||||
|
||||
QString C2NetworkPanel::getIPAddress() {
|
||||
std::string result = util::check_output("ifconfig wlan0");
|
||||
if (result.empty()) return "";
|
||||
|
||||
const std::string inetaddrr = "inet addr:";
|
||||
std::string::size_type begin = result.find(inetaddrr);
|
||||
if (begin == std::string::npos) return "";
|
||||
|
||||
begin += inetaddrr.length();
|
||||
std::string::size_type end = result.find(' ', begin);
|
||||
if (end == std::string::npos) return "";
|
||||
|
||||
return result.substr(begin, end - begin).c_str();
|
||||
}
|
||||
|
||||
QWidget *network_panel(QWidget *parent) {
|
||||
#ifdef QCOM
|
||||
return new C2NetworkPanel(parent);
|
||||
#else
|
||||
return new Networking(parent);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SettingsWindow::showEvent(QShowEvent *event) {
|
||||
@@ -457,9 +406,3 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
|
||||
}
|
||||
)");
|
||||
}
|
||||
|
||||
void SettingsWindow::hideEvent(QHideEvent *event) {
|
||||
#ifdef QCOM
|
||||
HardwareEon::close_activities();
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -19,7 +19,6 @@ public:
|
||||
explicit SettingsWindow(QWidget *parent = 0);
|
||||
|
||||
protected:
|
||||
void hideEvent(QHideEvent *event) override;
|
||||
void showEvent(QShowEvent *event) override;
|
||||
|
||||
signals:
|
||||
@@ -76,14 +75,3 @@ private:
|
||||
Params params;
|
||||
QFileSystemWatcher *fs_watch;
|
||||
};
|
||||
|
||||
class C2NetworkPanel: public QWidget {
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit C2NetworkPanel(QWidget* parent = nullptr);
|
||||
|
||||
private:
|
||||
void showEvent(QShowEvent *event) override;
|
||||
QString getIPAddress();
|
||||
LabelControl *ipaddress;
|
||||
};
|
||||
|
||||
@@ -6,10 +6,7 @@
|
||||
#include "selfdrive/ui/qt/util.h"
|
||||
#include "selfdrive/ui/qt/qt_window.h"
|
||||
#include "selfdrive/ui/qt/setup/updater.h"
|
||||
|
||||
#ifndef QCOM
|
||||
#include "selfdrive/ui/qt/offroad/networking.h"
|
||||
#endif
|
||||
|
||||
Updater::Updater(const QString &updater_path, const QString &manifest_path, QWidget *parent)
|
||||
: updater(updater_path), manifest(manifest_path), QStackedWidget(parent) {
|
||||
@@ -43,11 +40,7 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid
|
||||
QPushButton *connect = new QPushButton("Connect to Wi-Fi");
|
||||
connect->setObjectName("navBtn");
|
||||
QObject::connect(connect, &QPushButton::clicked, [=]() {
|
||||
#ifndef QCOM
|
||||
setCurrentWidget(wifi);
|
||||
#else
|
||||
HardwareEon::launch_wifi();
|
||||
#endif
|
||||
});
|
||||
hlayout->addWidget(connect);
|
||||
|
||||
@@ -64,11 +57,9 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid
|
||||
QVBoxLayout *layout = new QVBoxLayout(wifi);
|
||||
layout->setContentsMargins(100, 100, 100, 100);
|
||||
|
||||
#ifndef QCOM
|
||||
Networking *networking = new Networking(this, false);
|
||||
networking->setStyleSheet("Networking { background-color: #292929; border-radius: 13px; }");
|
||||
layout->addWidget(networking, 1);
|
||||
#endif
|
||||
|
||||
QPushButton *back = new QPushButton("Back");
|
||||
back->setObjectName("navBtn");
|
||||
@@ -175,20 +166,6 @@ void Updater::updateFinished(int exitCode, QProcess::ExitStatus exitStatus) {
|
||||
}
|
||||
}
|
||||
|
||||
bool Updater::eventFilter(QObject *obj, QEvent *event) {
|
||||
#ifdef QCOM
|
||||
// filter out touches while in android activity
|
||||
const static QSet<QEvent::Type> filter_events({QEvent::MouseButtonPress, QEvent::MouseMove, QEvent::TouchBegin, QEvent::TouchUpdate, QEvent::TouchEnd});
|
||||
if (HardwareEon::launched_activity && filter_events.contains(event->type())) {
|
||||
HardwareEon::check_activity();
|
||||
if (HardwareEon::launched_activity) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
initApp(argc, argv);
|
||||
QApplication a(argc, argv);
|
||||
|
||||
@@ -19,8 +19,6 @@ private slots:
|
||||
void updateFinished(int exitCode, QProcess::ExitStatus exitStatus);
|
||||
|
||||
private:
|
||||
bool eventFilter(QObject *obj, QEvent *event) override;
|
||||
|
||||
QProcess proc;
|
||||
QString updater, manifest;
|
||||
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:56a3413e09c42849a190031665a2bdabf628a495fd3c8e181c8e863c22a7cd64
|
||||
size 3166352
|
||||
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:8c33f9f4090720b23f3c70cf1fe5b3bda23f31fe17a20f769279bf14dbb1178e
|
||||
size 3214400
|
||||
@@ -102,9 +102,6 @@ void initApp(int argc, char *argv[]) {
|
||||
#endif
|
||||
|
||||
setQtSurfaceFormat();
|
||||
if (Hardware::EON()) {
|
||||
QApplication::setAttribute(Qt::AA_ShareOpenGLContexts);
|
||||
}
|
||||
}
|
||||
|
||||
void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) {
|
||||
|
||||
@@ -38,10 +38,6 @@ const char frame_fragment_shader[] =
|
||||
"out vec4 colorOut;\n"
|
||||
"void main() {\n"
|
||||
" colorOut = texture(uTexture, vTexCoord.xy);\n"
|
||||
#ifdef QCOM
|
||||
" vec3 dz = vec3(0.0627f, 0.0627f, 0.0627f);\n"
|
||||
" colorOut.rgb = ((vec3(1.0f, 1.0f, 1.0f) - dz) * colorOut.rgb / vec3(1.0f, 1.0f, 1.0f)) + dz;\n"
|
||||
#endif
|
||||
"}\n";
|
||||
|
||||
const mat4 device_transform = {{
|
||||
@@ -256,20 +252,18 @@ void CameraViewWidget::vipcThread() {
|
||||
std::unique_ptr<QOffscreenSurface> surface;
|
||||
std::unique_ptr<QOpenGLBuffer> gl_buffer;
|
||||
|
||||
if (!Hardware::EON()) {
|
||||
ctx = std::make_unique<QOpenGLContext>();
|
||||
ctx->setFormat(context()->format());
|
||||
ctx->setShareContext(context());
|
||||
ctx->create();
|
||||
assert(ctx->isValid());
|
||||
ctx = std::make_unique<QOpenGLContext>();
|
||||
ctx->setFormat(context()->format());
|
||||
ctx->setShareContext(context());
|
||||
ctx->create();
|
||||
assert(ctx->isValid());
|
||||
|
||||
surface = std::make_unique<QOffscreenSurface>();
|
||||
surface->setFormat(ctx->format());
|
||||
surface->create();
|
||||
ctx->makeCurrent(surface.get());
|
||||
assert(QOpenGLContext::currentContext() == ctx.get());
|
||||
initializeOpenGLFunctions();
|
||||
}
|
||||
surface = std::make_unique<QOffscreenSurface>();
|
||||
surface->setFormat(ctx->format());
|
||||
surface->create();
|
||||
ctx->makeCurrent(surface.get());
|
||||
assert(QOpenGLContext::currentContext() == ctx.get());
|
||||
initializeOpenGLFunctions();
|
||||
|
||||
while (!QThread::currentThread()->isInterruptionRequested()) {
|
||||
if (!vipc_client || cur_stream_type != stream_type) {
|
||||
@@ -283,13 +277,11 @@ void CameraViewWidget::vipcThread() {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (!Hardware::EON()) {
|
||||
gl_buffer.reset(new QOpenGLBuffer(QOpenGLBuffer::PixelUnpackBuffer));
|
||||
gl_buffer->create();
|
||||
gl_buffer->bind();
|
||||
gl_buffer->setUsagePattern(QOpenGLBuffer::StreamDraw);
|
||||
gl_buffer->allocate(vipc_client->buffers[0].len);
|
||||
}
|
||||
gl_buffer.reset(new QOpenGLBuffer(QOpenGLBuffer::PixelUnpackBuffer));
|
||||
gl_buffer->create();
|
||||
gl_buffer->bind();
|
||||
gl_buffer->setUsagePattern(QOpenGLBuffer::StreamDraw);
|
||||
gl_buffer->allocate(vipc_client->buffers[0].len);
|
||||
|
||||
emit vipcThreadConnected(vipc_client.get());
|
||||
}
|
||||
@@ -297,29 +289,29 @@ void CameraViewWidget::vipcThread() {
|
||||
if (VisionBuf *buf = vipc_client->recv(nullptr, 1000)) {
|
||||
{
|
||||
std::lock_guard lk(lock);
|
||||
if (!Hardware::EON()) {
|
||||
void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly);
|
||||
|
||||
if (texture_buffer == nullptr) {
|
||||
LOGE("gl_buffer->map returned nullptr");
|
||||
continue;
|
||||
}
|
||||
void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly);
|
||||
|
||||
memcpy(texture_buffer, buf->addr, buf->len);
|
||||
gl_buffer->unmap();
|
||||
|
||||
// copy pixels from PBO to texture object
|
||||
glBindTexture(GL_TEXTURE_2D, texture[buf->idx]->frame_tex);
|
||||
glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0);
|
||||
glBindTexture(GL_TEXTURE_2D, 0);
|
||||
assert(glGetError() == GL_NO_ERROR);
|
||||
|
||||
wait_fence.reset(new WaitFence());
|
||||
|
||||
// Ensure the fence is in the GPU command queue, or waiting on it might block
|
||||
// https://www.khronos.org/opengl/wiki/Sync_Object#Flushing_and_contexts
|
||||
glFlush();
|
||||
if (texture_buffer == nullptr) {
|
||||
LOGE("gl_buffer->map returned nullptr");
|
||||
continue;
|
||||
}
|
||||
|
||||
memcpy(texture_buffer, buf->addr, buf->len);
|
||||
gl_buffer->unmap();
|
||||
|
||||
// copy pixels from PBO to texture object
|
||||
glBindTexture(GL_TEXTURE_2D, texture[buf->idx]->frame_tex);
|
||||
glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0);
|
||||
glBindTexture(GL_TEXTURE_2D, 0);
|
||||
assert(glGetError() == GL_NO_ERROR);
|
||||
|
||||
wait_fence.reset(new WaitFence());
|
||||
|
||||
// Ensure the fence is in the GPU command queue, or waiting on it might block
|
||||
// https://www.khronos.org/opengl/wiki/Sync_Object#Flushing_and_contexts
|
||||
glFlush();
|
||||
|
||||
latest_texture_id = buf->idx;
|
||||
}
|
||||
// Schedule update. update() will be invoked on the gui thread.
|
||||
|
||||
@@ -85,15 +85,6 @@ bool MainWindow::eventFilter(QObject *obj, QEvent *event) {
|
||||
|
||||
if (evts.contains(event->type())) {
|
||||
device.resetInteractiveTimout();
|
||||
#ifdef QCOM
|
||||
// filter out touches while in android activity
|
||||
if (HardwareEon::launched_activity) {
|
||||
HardwareEon::check_activity();
|
||||
if (HardwareEon::launched_activity) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
#!/bin/sh
|
||||
|
||||
if [ -f /EON ] && [ ! -f qt/spinner ]; then
|
||||
cp qt/spinner_aarch64 qt/spinner
|
||||
elif [ -f /TICI ] && [ ! -f qt/spinner ]; then
|
||||
if [ -f /TICI ] && [ ! -f qt/spinner ]; then
|
||||
cp qt/spinner_larch64 qt/spinner
|
||||
fi
|
||||
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
#!/bin/sh
|
||||
|
||||
if [ -f /EON ] && [ ! -f qt/text ]; then
|
||||
cp qt/text_aarch64 qt/text
|
||||
elif [ -f /TICI ] && [ ! -f qt/text ]; then
|
||||
if [ -f /TICI ] && [ ! -f qt/text ]; then
|
||||
cp qt/text_larch64 qt/text
|
||||
fi
|
||||
|
||||
|
||||
@@ -166,17 +166,7 @@ static void update_state(UIState *s) {
|
||||
}
|
||||
}
|
||||
}
|
||||
if (!Hardware::TICI() && sm.updated("roadCameraState")) {
|
||||
auto camera_state = sm["roadCameraState"].getRoadCameraState();
|
||||
|
||||
float max_lines = Hardware::EON() ? 5408 : 1904;
|
||||
float max_gain = Hardware::EON() ? 1.0: 10.0;
|
||||
float max_ev = max_lines * max_gain;
|
||||
|
||||
float ev = camera_state.getGain() * float(camera_state.getIntegLines());
|
||||
|
||||
scene.light_sensor = std::clamp<float>(1.0 - (ev / max_ev), 0.0, 1.0);
|
||||
} else if (Hardware::TICI() && sm.updated("wideRoadCameraState")) {
|
||||
if (Hardware::TICI() && sm.updated("wideRoadCameraState")) {
|
||||
auto camera_state = sm["wideRoadCameraState"].getWideRoadCameraState();
|
||||
|
||||
float max_lines = 1618;
|
||||
|
||||
@@ -24,8 +24,8 @@ typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert;
|
||||
|
||||
// TODO: this is also hardcoded in common/transformations/camera.py
|
||||
// TODO: choose based on frame input size
|
||||
const float y_offset = Hardware::EON() ? 0.0 : 150.0;
|
||||
const float ZOOM = Hardware::EON() ? 2138.5 : 2912.8;
|
||||
const float y_offset = 150.0;
|
||||
const float ZOOM = 2912.8;
|
||||
|
||||
struct Alert {
|
||||
QString text1;
|
||||
|
||||
@@ -37,7 +37,7 @@ from typing import List, Tuple, Optional
|
||||
from common.basedir import BASEDIR
|
||||
from common.markdown import parse_markdown
|
||||
from common.params import Params
|
||||
from selfdrive.hardware import EON, TICI, HARDWARE
|
||||
from selfdrive.hardware import TICI, HARDWARE
|
||||
from selfdrive.swaglog import cloudlog
|
||||
from selfdrive.controls.lib.alertmanager import set_offroad_alert
|
||||
from selfdrive.version import is_tested_branch
|
||||
@@ -283,42 +283,6 @@ def handle_agnos_update(wait_helper: WaitTimeHelper) -> None:
|
||||
set_offroad_alert("Offroad_NeosUpdate", False)
|
||||
|
||||
|
||||
def handle_neos_update(wait_helper: WaitTimeHelper) -> None:
|
||||
from selfdrive.hardware.eon.neos import download_neos_update
|
||||
|
||||
cur_neos = HARDWARE.get_os_version()
|
||||
updated_neos = run(["bash", "-c", r"unset REQUIRED_NEOS_VERSION && source launch_env.sh && \
|
||||
echo -n $REQUIRED_NEOS_VERSION"], OVERLAY_MERGED).strip()
|
||||
|
||||
cloudlog.info(f"NEOS version check: {cur_neos} vs {updated_neos}")
|
||||
if cur_neos == updated_neos:
|
||||
return
|
||||
|
||||
cloudlog.info(f"Beginning background download for NEOS {updated_neos}")
|
||||
set_offroad_alert("Offroad_NeosUpdate", True)
|
||||
|
||||
update_manifest = os.path.join(OVERLAY_MERGED, "selfdrive/hardware/eon/neos.json")
|
||||
|
||||
neos_downloaded = False
|
||||
start_time = time.monotonic()
|
||||
# Try to download for one day
|
||||
while not neos_downloaded and not wait_helper.shutdown and \
|
||||
(time.monotonic() - start_time < 60*60*24):
|
||||
wait_helper.ready_event.clear()
|
||||
try:
|
||||
download_neos_update(update_manifest, cloudlog)
|
||||
neos_downloaded = True
|
||||
except Exception:
|
||||
cloudlog.info("NEOS background download failed, retrying")
|
||||
wait_helper.sleep(120)
|
||||
|
||||
# If the download failed, we'll show the alert again when we retry
|
||||
set_offroad_alert("Offroad_NeosUpdate", False)
|
||||
if not neos_downloaded:
|
||||
raise Exception("Failed to download NEOS update")
|
||||
cloudlog.info(f"NEOS background download successful, took {time.monotonic() - start_time} seconds")
|
||||
|
||||
|
||||
def check_git_fetch_result(fetch_txt: str) -> bool:
|
||||
err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n"
|
||||
return len(fetch_txt) > 0 and (fetch_txt != err_msg)
|
||||
@@ -360,9 +324,7 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool:
|
||||
]
|
||||
cloudlog.info("git reset success: %s", '\n'.join(r))
|
||||
|
||||
if EON:
|
||||
handle_neos_update(wait_helper)
|
||||
elif TICI:
|
||||
if TICI:
|
||||
handle_agnos_update(wait_helper)
|
||||
|
||||
# Create the finalized, ready-to-swap update
|
||||
|
||||
@@ -7,7 +7,7 @@ from functools import lru_cache
|
||||
from common.basedir import BASEDIR
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
||||
TESTED_BRANCHES = ['devel', 'release2-staging', 'release3-staging', 'dashcam-staging', 'release2', 'release3', 'dashcam']
|
||||
TESTED_BRANCHES = ['devel', 'release3-staging', 'dashcam3-staging', 'release3', 'dashcam3']
|
||||
|
||||
training_version: bytes = b"0.2.0"
|
||||
terms_version: bytes = b"2"
|
||||
|
||||
3
third_party/acados/aarch64/lib/libacados.so
vendored
3
third_party/acados/aarch64/lib/libacados.so
vendored
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:fa02515dd1229ea78c0354189112f1d5ca777f581803d4344f744e80e3b2aa91
|
||||
size 576129
|
||||
3
third_party/acados/aarch64/lib/libblasfeo.so
vendored
3
third_party/acados/aarch64/lib/libblasfeo.so
vendored
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:ed4929ed8af91c883a28d53e491eca6e970cebc09669a3499db4cd380c937a9a
|
||||
size 1200745
|
||||
3
third_party/acados/aarch64/lib/libhpipm.so
vendored
3
third_party/acados/aarch64/lib/libhpipm.so
vendored
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:d6873d1bf018369aaf13cabe5d870d3154656668b31647df0a1a648b3bb383dc
|
||||
size 1324409
|
||||
@@ -1 +0,0 @@
|
||||
libqpOASES_e.so.3.1
|
||||
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:17841debecba17ce4bb1150820c61f9d965c3cb045f46afc8b20ee286dd42350
|
||||
size 218545
|
||||
3
third_party/acados/aarch64/t_renderer
vendored
3
third_party/acados/aarch64/t_renderer
vendored
@@ -1,3 +0,0 @@
|
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:c3f13c06f967ae8c785c73e716c9e0ce9f4688b55fde0d798d4fa077a1edb0ad
|
||||
size 4498992
|
||||
40
third_party/acados/build.sh
vendored
40
third_party/acados/build.sh
vendored
@@ -7,9 +7,6 @@ BLAS_TARGET="X64_AUTOMATIC"
|
||||
if [ -f /TICI ]; then
|
||||
ARCHNAME="larch64"
|
||||
BLAS_TARGET="ARMV8A_ARM_CORTEX_A57"
|
||||
elif [ -f /EON ]; then
|
||||
ARCHNAME="aarch64"
|
||||
BLAS_TARGET="ARMV8A_ARM_CORTEX_A57"
|
||||
fi
|
||||
|
||||
if [ ! -d acados_repo/ ]; then
|
||||
@@ -40,38 +37,7 @@ rm -rf $DIR/../../pyextra/acados_template
|
||||
cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/../../pyextra
|
||||
#pip3 install -e $DIR/acados/interfaces/acados_template
|
||||
|
||||
# hack to workaround no rpath on android
|
||||
if [ -f /EON ]; then
|
||||
pushd $INSTALL_DIR/lib
|
||||
for lib in $(ls .); do
|
||||
if ! readlink $lib; then
|
||||
patchelf --set-soname $PWD/$lib $lib
|
||||
|
||||
if [ "$lib" = "libacados.so" ]; then
|
||||
for nlib in "libhpipm.so" "libblasfeo.so" "libqpOASES_e.so.3.1"; do
|
||||
patchelf --replace-needed $nlib $PWD/$nlib $lib
|
||||
done
|
||||
fi
|
||||
|
||||
if [ "$lib" = "libhpipm.so" ]; then
|
||||
patchelf --replace-needed libblasfeo.so $PWD/libblasfeo.so $lib
|
||||
fi
|
||||
|
||||
# pad extra byte to workaround bionic linker bug
|
||||
# https://android.googlesource.com/platform/bionic/+/93ce35434ca5af43a7449e289959543f0a2426fa%5E%21/#F0
|
||||
dd if=/dev/zero bs=1 count=1 >> $lib
|
||||
fi
|
||||
done
|
||||
popd
|
||||
|
||||
cd $DIR
|
||||
git checkout $INSTALL_DIR/t_renderer
|
||||
fi
|
||||
|
||||
# build tera
|
||||
# build with commaai/termux-packages for NEOS
|
||||
if [ ! -f /EON ]; then
|
||||
cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/
|
||||
cargo build --verbose --release
|
||||
cp target/release/t_renderer $INSTALL_DIR/
|
||||
fi
|
||||
cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/
|
||||
cargo build --verbose --release
|
||||
cp target/release/t_renderer $INSTALL_DIR/
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
git clone https://github.com/CyanogenMod/android_frameworks_native.git && cd android_frameworks_native
|
||||
git reset --hard b22bca465e55618a949d9cbdea665a1a3a831241
|
||||
cp -r include ~/one/third_party/android_frameworks_native/
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user