Merge pull request #3 from commaai/master

pulling updated changes
pull/19855/head
newstackdevelopment 5 years ago committed by GitHub
commit 5a25d1e47e
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 1
      .github/workflows/test.yaml
  2. 2
      .gitignore
  3. 44
      Dockerfile.openpilot
  4. 2
      Jenkinsfile
  5. 6
      README.md
  6. 10
      SConstruct
  7. 2
      cereal
  8. 22
      common/numpy_helpers.py
  9. 2
      common/params_pyx.pyx
  10. 12
      installer/updater/update_agnos.json
  11. 2
      laika_repo
  12. 3
      launch_chffrplus.sh
  13. 2
      launch_env.sh
  14. 4
      release/files_common
  15. 2
      selfdrive/athena/athenad.py
  16. 49
      selfdrive/athena/tests/helpers.py
  17. 4
      selfdrive/athena/tests/test_athenad.py
  18. 83
      selfdrive/boardd/tests/replay_many.py
  19. 57
      selfdrive/camerad/cameras/camera_common.cc
  20. 5
      selfdrive/camerad/cameras/camera_common.h
  21. 15
      selfdrive/camerad/cameras/camera_qcom.cc
  22. 37
      selfdrive/camerad/cameras/camera_qcom2.cc
  23. 2
      selfdrive/car/chrysler/values.py
  24. 2
      selfdrive/car/fw_versions.py
  25. 1
      selfdrive/car/honda/values.py
  26. 2
      selfdrive/car/hyundai/carcontroller.py
  27. 9
      selfdrive/car/hyundai/interface.py
  28. 15
      selfdrive/car/hyundai/values.py
  29. 2
      selfdrive/car/toyota/interface.py
  30. 16
      selfdrive/car/toyota/values.py
  31. 8
      selfdrive/common/clutil.h
  32. 8
      selfdrive/common/framebuffer.cc
  33. 8
      selfdrive/common/framebuffer.h
  34. 14
      selfdrive/common/gpio.h
  35. 24
      selfdrive/common/modeldata.h
  36. 15
      selfdrive/common/swaglog.cc
  37. 13
      selfdrive/common/swaglog.h
  38. 6
      selfdrive/common/util.h
  39. 36
      selfdrive/controls/controlsd.py
  40. 3
      selfdrive/controls/lib/drive_helpers.py
  41. 4
      selfdrive/controls/lib/events.py
  42. 94
      selfdrive/controls/lib/lane_planner.py
  43. 1
      selfdrive/controls/lib/lateral_mpc/SConscript
  44. 85
      selfdrive/controls/lib/lateral_mpc/generator.cpp
  45. 76
      selfdrive/controls/lib/lateral_mpc/lateral_mpc.c
  46. 177
      selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h
  47. 274
      selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c
  48. 2
      selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp
  49. 6
      selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp
  50. 2504
      selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c
  51. 21
      selfdrive/controls/lib/lateral_mpc/libmpc_py.py
  52. 109
      selfdrive/controls/lib/pathplanner.py
  53. 2
      selfdrive/controls/lib/planner.py
  54. 6
      selfdrive/controls/plannerd.py
  55. 81
      selfdrive/controls/tests/test_lateral_mpc.py
  56. 92
      selfdrive/debug/internal/can_replay.py
  57. 2
      selfdrive/debug/mpc/live_lateral_mpc.py
  58. 27
      selfdrive/debug/mpc/test_mpc_wobble.py
  59. 1
      selfdrive/debug/profiling/clpeak/.gitignore
  60. 22
      selfdrive/debug/profiling/clpeak/build.sh
  61. BIN
      selfdrive/debug/profiling/clpeak/clpeak3
  62. 13
      selfdrive/debug/profiling/clpeak/run_continuously.patch
  63. 7
      selfdrive/loggerd/SConscript
  64. 37
      selfdrive/loggerd/bootlog.cc
  65. 114
      selfdrive/loggerd/logger.cc
  66. 23
      selfdrive/loggerd/logger.h
  67. 162
      selfdrive/loggerd/loggerd.cc
  68. 127
      selfdrive/loggerd/omx_encoder.cc
  69. 8
      selfdrive/loggerd/omx_encoder.h
  70. 2
      selfdrive/loggerd/tests/test_loggerd.py
  71. 3
      selfdrive/loggerd/uploader.py
  72. 2
      selfdrive/manager.py
  73. 10
      selfdrive/modeld/models/dmonitoring.cc
  74. 11
      selfdrive/modeld/models/driving.cc
  75. 11
      selfdrive/registration.py
  76. 11
      selfdrive/test/longitudinal_maneuvers/plant.py
  77. 1
      selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
  78. 2
      selfdrive/test/process_replay/model_replay_ref_commit
  79. 4
      selfdrive/test/process_replay/process_replay.py
  80. 2
      selfdrive/test/process_replay/ref_commit
  81. 11
      selfdrive/test/process_replay/test_processes.py
  82. 108
      selfdrive/test/test_cpu_usage.py
  83. 112
      selfdrive/test/test_onroad.py
  84. 86
      selfdrive/test/testing_closet_client.py
  85. 3
      selfdrive/thermald/thermald.py
  86. 175
      selfdrive/tombstoned.py
  87. 7
      selfdrive/ui/SConscript
  88. 11
      selfdrive/ui/android/text/Makefile
  89. 11
      selfdrive/ui/android/text/text.cc
  90. 247
      selfdrive/ui/paint.cc
  91. 7
      selfdrive/ui/paint.hpp
  92. 127
      selfdrive/ui/qt/api.cc
  93. 47
      selfdrive/ui/qt/api.hpp
  94. 104
      selfdrive/ui/qt/home.cc
  95. 49
      selfdrive/ui/qt/home.hpp
  96. 862
      selfdrive/ui/qt/widgets/QrCode.cc
  97. 556
      selfdrive/ui/qt/widgets/QrCode.hpp
  98. 147
      selfdrive/ui/qt/widgets/drive_stats.cc
  99. 12
      selfdrive/ui/qt/widgets/drive_stats.hpp
  100. 276
      selfdrive/ui/qt/widgets/setup.cc
  101. Some files were not shown because too many files have changed in this diff Show More

@ -71,7 +71,6 @@ jobs:
/usr/local/Cellar
~/github_brew_cache_entries.txt
key: macos-cache-${{ hashFiles('tools/mac_setup.sh') }}
restore-keys: macos-cache-
- name: Brew link restored dependencies
if: steps.dependency-cache.outputs.cache-hit == 'true'
run: |

2
.gitignore vendored

@ -1,4 +1,5 @@
venv/
.clang-format
.DS_Store
.tags
.ipynb_checkpoints
@ -43,6 +44,7 @@ selfdrive/ui/_ui
selfdrive/test/longitudinal_maneuvers/out
selfdrive/visiond/visiond
selfdrive/loggerd/loggerd
selfdrive/loggerd/bootlog
selfdrive/sensord/_gpsd
selfdrive/sensord/_sensord
selfdrive/camerad/camerad

@ -1,28 +1,32 @@
FROM commaai/openpilot-base:latest
ENV PYTHONUNBUFFERED 1
ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH}
RUN mkdir -p /tmp/openpilot
ENV OPENPILOT_PATH /home/batman/openpilot/
ENV PYTHONPATH ${OPENPILOT_PATH}:${PYTHONPATH}
COPY SConstruct \
.pylintrc \
.pre-commit-config.yaml \
/tmp/openpilot/
RUN mkdir -p ${OPENPILOT_PATH}
WORKDIR ${OPENPILOT_PATH}
COPY ./pyextra /tmp/openpilot/pyextra
COPY ./phonelibs /tmp/openpilot/phonelibs
COPY ./site_scons /tmp/openpilot/site_scons
COPY ./laika /tmp/openpilot/laika
COPY ./laika_repo /tmp/openpilot/laika_repo
COPY ./rednose /tmp/openpilot/rednose
COPY ./tools /tmp/openpilot/tools
COPY ./release /tmp/openpilot/release
COPY ./common /tmp/openpilot/common
COPY ./opendbc /tmp/openpilot/opendbc
COPY ./cereal /tmp/openpilot/cereal
COPY ./panda /tmp/openpilot/panda
COPY ./selfdrive /tmp/openpilot/selfdrive
COPY Pipfile Pipfile.lock $OPENPILOT_PATH
RUN pip install --no-cache-dir pipenv==2020.8.13 && \
pipenv install --system --deploy --dev --clear && \
pip uninstall -y pipenv
COPY SConstruct ${OPENPILOT_PATH}
COPY ./pyextra ${OPENPILOT_PATH}/pyextra
COPY ./phonelibs ${OPENPILOT_PATH}/phonelibs
COPY ./site_scons ${OPENPILOT_PATH}/site_scons
COPY ./laika ${OPENPILOT_PATH}/laika
COPY ./laika_repo ${OPENPILOT_PATH}/laika_repo
COPY ./rednose ${OPENPILOT_PATH}/rednose
COPY ./tools ${OPENPILOT_PATH}/tools
COPY ./release ${OPENPILOT_PATH}/release
COPY ./common ${OPENPILOT_PATH}/common
COPY ./opendbc ${OPENPILOT_PATH}/opendbc
COPY ./cereal ${OPENPILOT_PATH}/cereal
COPY ./panda ${OPENPILOT_PATH}/panda
COPY ./selfdrive ${OPENPILOT_PATH}/selfdrive
WORKDIR /tmp/openpilot
RUN scons -j$(nproc)

2
Jenkinsfile vendored

@ -114,7 +114,7 @@ pipeline {
["build", "SCONS_CACHE=1 scons -j4"],
["test athena", "nosetests -s selfdrive/athena/tests/test_athenad_old.py"],
["test manager", "python selfdrive/test/test_manager.py"],
//["test cpu usage", "cd selfdrive/test/ && ./test_cpu_usage.py"],
["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"],
["build devel", "cd release && CI_PUSH=${env.CI_PUSH} ./build_devel.sh"],
["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"],
["test spinner build", "cd selfdrive/ui/spinner && make clean && make"],

@ -97,7 +97,7 @@ Supported Cars
| Lexus | RX 2020-21 | All | openpilot | 0mph | 0mph |
| Lexus | RX Hybrid 2016-19 | All | Stock<sup>3</sup>| 0mph | 0mph |
| Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph |
| Toyota | Avalon 2016-18 | TSS-P | Stock<sup>3</sup>| 20mph<sup>1</sup> | 0mph |
| Toyota | Avalon 2016-18, 2021 | TSS-P | Stock<sup>3</sup>| 20mph<sup>1</sup> | 0mph |
| Toyota | Camry 2018-20 | All | Stock | 0mph<sup>4</sup> | 0mph |
| Toyota | Camry 2021 | All | openpilot | 0mph | 0mph |
| Toyota | Camry Hybrid 2018-20 | All | Stock | 0mph<sup>4</sup> | 0mph |
@ -151,12 +151,12 @@ Community Maintained Cars and Features
| Hyundai | Ioniq Electric 2020 | SCC + LKAS | Stock | 0mph | 0mph |
| Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph |
| Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph |
| Hyundai | Santa Fe 2019 | All | Stock | 0mph | 0mph |
| Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph |
| Hyundai | Sonata 2019 | SCC + LKAS | Stock | 0mph | 0mph |
| Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph |
| Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph |
| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph |
| Kia | Forte 2018-19 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Forte 2018-19, 2021 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Niro EV 2020 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph |
| Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph |

@ -33,6 +33,12 @@ AddOption('--mpc-generate',
action='store_true',
help='regenerates the mpc sources')
AddOption('--external-sconscript',
action='store',
metavar='FILE',
dest='external_sconscript',
help='add an external SConscript to the build')
real_arch = arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip()
if platform.system() == "Darwin":
arch = "Darwin"
@ -375,3 +381,7 @@ if arch != "Darwin":
if real_arch == "x86_64":
SConscript(['tools/nui/SConscript'])
SConscript(['tools/lib/index_log/SConscript'])
external_sconscript = GetOption('external_sconscript')
if external_sconscript:
SConscript([external_sconscript])

@ -1 +1 @@
Subproject commit 61a3b45ed2597b24be6e9d8920b2cd36609267db
Subproject commit 610fa77bc41ddf58e57f52ef678222a435cb6748

@ -0,0 +1,22 @@
import numpy as np
def deep_interp_np(x, xp, fp, axis=None):
if axis is not None:
fp = fp.swapaxes(0,axis)
x = np.atleast_1d(x)
xp = np.array(xp)
if len(xp) < 2:
return np.repeat(fp, len(x), axis=0)
if min(np.diff(xp)) < 0:
raise RuntimeError('Bad x array for interpolation')
j = np.searchsorted(xp, x) - 1
j = np.clip(j, 0, len(xp)-2)
d = np.divide(x - xp[j], xp[j + 1] - xp[j], out=np.ones_like(x, dtype=np.float64), where=xp[j + 1] - xp[j] != 0)
vals_interp = (fp[j].T*(1 - d)).T + (fp[j + 1].T*d).T
if axis is not None:
vals_interp = vals_interp.swapaxes(0,axis)
if len(vals_interp) == 1:
return vals_interp[0]
else:
return vals_interp

@ -31,9 +31,11 @@ keys = {
b"GitCommit": [TxType.PERSISTENT],
b"GitRemote": [TxType.PERSISTENT],
b"GithubSshKeys": [TxType.PERSISTENT],
b"HardwareSerial": [TxType.PERSISTENT],
b"HasAcceptedTerms": [TxType.PERSISTENT],
b"HasCompletedSetup": [TxType.PERSISTENT],
b"IsDriverViewEnabled": [TxType.CLEAR_ON_MANAGER_START],
b"IMEI": [TxType.PERSISTENT],
b"IsLdwEnabled": [TxType.PERSISTENT],
b"IsMetric": [TxType.PERSISTENT],
b"IsOffroad": [TxType.CLEAR_ON_MANAGER_START],

@ -1,17 +1,17 @@
[
{
"name": "system",
"url": "https://commadist.azureedge.net/agnosupdate-staging/system-1e5748c84d9b48bbe599c88da63e46b7ed1c0f1245486cfbcfb05399bd16dbb6.img.xz",
"hash": "de6afb8651dc011fed8a883bac191e61d4b58e2e1c84c2717816b64f71afd3b1",
"hash_raw": "1e5748c84d9b48bbe599c88da63e46b7ed1c0f1245486cfbcfb05399bd16dbb6",
"url": "https://commadist.azureedge.net/agnosupdate-staging/system-3fa2b899a6ca13faed640de9098ec16f15df816493a8a30b70c3e71cbb7a7a23.img.xz",
"hash": "23d1b6ab6c375f3d32815ed257382f42d779778d892c262e699070816e400d5a",
"hash_raw": "3fa2b899a6ca13faed640de9098ec16f15df816493a8a30b70c3e71cbb7a7a23",
"size": 10737418240,
"sparse": true
},
{
"name": "boot",
"url": "https://commadist.azureedge.net/agnosupdate-staging/boot-21649cb35935a92776155e7bb23e437e7e7eb0500c082df89f59a6d4a4ed639a.img.xz",
"hash": "21649cb35935a92776155e7bb23e437e7e7eb0500c082df89f59a6d4a4ed639a",
"hash_raw": "21649cb35935a92776155e7bb23e437e7e7eb0500c082df89f59a6d4a4ed639a",
"url": "https://commadist.azureedge.net/agnosupdate-staging/boot-52b630e250141dbe89db5bb8f5447f3b20bd75539bdd8e23a80bd2217fe0b86c.img.xz",
"hash": "52b630e250141dbe89db5bb8f5447f3b20bd75539bdd8e23a80bd2217fe0b86c",
"hash_raw": "52b630e250141dbe89db5bb8f5447f3b20bd75539bdd8e23a80bd2217fe0b86c",
"size": 14678016,
"sparse": false
}

@ -1 +1 @@
Subproject commit 4b7947374e31df02587dcdd4c7562a78344e11b3
Subproject commit f8f5788df38cb286e1d136e96fb109f197deee37

@ -4,6 +4,8 @@ if [ -z "$BASEDIR" ]; then
BASEDIR="/data/openpilot"
fi
unset REQUIRED_NEOS_VERSION
unset AGNOS_VERSION
source "$BASEDIR/launch_env.sh"
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"
@ -195,6 +197,7 @@ function launch {
echo "Restarting launch script ${LAUNCHER_LOCATION}"
unset REQUIRED_NEOS_VERSION
unset AGNOS_VERSION
exec "${LAUNCHER_LOCATION}"
else
echo "openpilot backup found, not updating"

@ -11,7 +11,7 @@ if [ -z "$REQUIRED_NEOS_VERSION" ]; then
fi
if [ -z "$AGNOS_VERSION" ]; then
export AGNOS_VERSION="0.1"
export AGNOS_VERSION="0.2"
fi
if [ -z "$PASSIVE" ]; then

@ -307,6 +307,7 @@ selfdrive/loggerd/omx_encoder.h
selfdrive/loggerd/logger.cc
selfdrive/loggerd/logger.h
selfdrive/loggerd/loggerd.cc
selfdrive/loggerd/bootlog.cc
selfdrive/loggerd/raw_logger.cc
selfdrive/loggerd/raw_logger.h
selfdrive/loggerd/include/msm_media_info.h
@ -333,7 +334,6 @@ selfdrive/thermald/power_monitoring.py
selfdrive/test/__init__.py
selfdrive/test/helpers.py
selfdrive/test/setup_device_ci.sh
selfdrive/test/test_cpu_usage.py
selfdrive/test/test_fingerprints.py
selfdrive/test/test_manager.py
@ -349,7 +349,7 @@ selfdrive/ui/android/spinner/spinner.c
selfdrive/ui/android/text/Makefile
selfdrive/ui/android/text/text
selfdrive/ui/android/text/text.c
selfdrive/ui/android/text/text.cc
selfdrive/ui/qt/*.cc
selfdrive/ui/qt/*.hpp

@ -280,6 +280,8 @@ def ws_proxy_send(ws, local_sock, signal_sock, end_event):
cloudlog.exception("athenad.ws_proxy_send.exception")
end_event.set()
signal_sock.close()
def ws_recv(ws, end_event):
while not end_event.is_set():

@ -1,6 +1,4 @@
import http.server
import multiprocessing
import queue
import random
import requests
import socket
@ -8,6 +6,7 @@ import time
from functools import wraps
from multiprocessing import Process
from common.timeout import Timeout
class EchoSocket():
def __init__(self, port):
@ -79,41 +78,27 @@ class HTTPRequestHandler(http.server.SimpleHTTPRequestHandler):
self.end_headers()
def http_server(port_queue, **kwargs):
while 1:
try:
port = random.randrange(40000, 50000)
port_queue.put(port)
http.server.test(**kwargs, port=port)
except OSError as e:
if e.errno == 98:
continue
def with_http_server(func):
@wraps(func)
def inner(*args, **kwargs):
port_queue = multiprocessing.Queue()
host = '127.0.0.1'
p = Process(target=http_server,
args=(port_queue,),
kwargs={
'HandlerClass': HTTPRequestHandler,
'bind': host})
p.start()
start = time.monotonic()
port = None
while 1:
if time.monotonic() - start > 10:
raise Exception('HTTP Server did not start')
try:
port = port_queue.get(timeout=0.1)
requests.put(f'http://{host}:{port}/qlog.bz2', data='')
break
except (requests.exceptions.ConnectionError, queue.Empty):
with Timeout(2, 'HTTP Server did not start'):
p = None
host = '127.0.0.1'
while p is None or p.exitcode is not None:
port = random.randrange(40000, 50000)
p = Process(target=http.server.test,
kwargs={'port': port, 'HandlerClass': HTTPRequestHandler, 'bind': host})
p.start()
time.sleep(0.1)
with Timeout(2):
while True:
try:
requests.put(f'http://{host}:{port}/qlog.bz2', data='')
break
except requests.exceptions.ConnectionError:
time.sleep(0.1)
try:
return func(*args, f'http://{host}:{port}', **kwargs)
finally:

@ -64,10 +64,8 @@ class TestAthenadMethods(unittest.TestCase):
try:
item = athenad.UploadItem(path=fn, url="http://localhost:1238", headers={}, created_at=int(time.time()*1000), id='')
try:
with self.assertRaises(requests.exceptions.ConnectionError):
athenad._do_upload(item)
except requests.exceptions.ConnectionError:
pass
item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='')
resp = athenad._do_upload(item)

@ -1,83 +0,0 @@
#!/usr/bin/env python3
import os
import sys
import time
import signal
import traceback
import usb1
from panda import Panda, PandaDFU
from multiprocessing import Pool
jungle = "JUNGLE" in os.environ
if jungle:
from panda_jungle import PandaJungle # pylint: disable=import-error
import cereal.messaging as messaging
from selfdrive.boardd.boardd import can_capnp_to_can_list
def initializer():
"""Ignore CTRL+C in the worker process.
source: https://stackoverflow.com/a/44869451 """
signal.signal(signal.SIGINT, signal.SIG_IGN)
def send_thread(sender_serial):
global jungle
while True:
try:
if jungle:
sender = PandaJungle(sender_serial)
else:
sender = Panda(sender_serial)
sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
sender.set_can_loopback(False)
can_sock = messaging.sub_sock('can')
while True:
tsc = messaging.recv_one(can_sock)
snd = can_capnp_to_can_list(tsc.can)
snd = list(filter(lambda x: x[-1] <= 2, snd))
try:
sender.can_send_many(snd)
except usb1.USBErrorTimeout:
pass
# Drain panda message buffer
sender.can_recv()
except Exception:
traceback.print_exc()
time.sleep(1)
if __name__ == "__main__":
if jungle:
serials = PandaJungle.list()
else:
serials = Panda.list()
num_senders = len(serials)
if num_senders == 0:
print("No senders found. Exiting")
sys.exit(1)
else:
print("%d senders found. Starting broadcast" % num_senders)
if "FLASH" in os.environ:
for s in PandaDFU.list():
PandaDFU(s).recover()
time.sleep(1)
for s in serials:
Panda(s).recover()
Panda(s).flash()
pool = Pool(num_senders, initializer=initializer)
pool.map_async(send_thread, serials)
while True:
try:
time.sleep(10)
except KeyboardInterrupt:
pool.terminate()
pool.join()
raise

@ -58,7 +58,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s,
frame_buf_count = frame_cnt;
// RAW frame
frame_size = ci->frame_height * ci->frame_stride;
const int frame_size = ci->frame_height * ci->frame_stride;
camera_bufs = std::make_unique<VisionBuf[]>(frame_buf_count);
camera_bufs_metadata = std::make_unique<FrameMetadata[]>(frame_buf_count);
@ -121,14 +121,14 @@ CameraBuf::~CameraBuf() {
}
bool CameraBuf::acquire() {
std::unique_lock<std::mutex> lk(frame_queue_mutex);
bool got_frame = frame_queue_cv.wait_for(lk, std::chrono::milliseconds(1), [this]{ return !frame_queue.empty(); });
if (!got_frame) return false;
{
std::unique_lock<std::mutex> lk(frame_queue_mutex);
bool got_frame = frame_queue_cv.wait_for(lk, std::chrono::milliseconds(1), [this]{ return !frame_queue.empty(); });
if (!got_frame) return false;
cur_buf_idx = frame_queue.front();
frame_queue.pop();
lk.unlock();
cur_buf_idx = frame_queue.front();
frame_queue.pop();
}
const FrameMetadata &frame_data = camera_bufs_metadata[cur_buf_idx];
if (frame_data.frame_id == -1) {
@ -139,7 +139,6 @@ bool CameraBuf::acquire() {
cur_frame_data = frame_data;
cur_rgb_buf = vipc_server->get_buffer(rgb_type);
cur_rgb_idx = cur_rgb_buf->idx;
cl_event debayer_event;
cl_mem camrabuf_cl = camera_bufs[cur_buf_idx].buf_cl;
@ -164,7 +163,6 @@ bool CameraBuf::acquire() {
&debayer_work_size, NULL, 0, 0, &debayer_event));
#endif
} else {
assert(cur_rgb_buf->len >= frame_size);
assert(rgb_stride == camera_state->ci.frame_stride);
CL_CHECK(clEnqueueCopyBuffer(q, camrabuf_cl, cur_rgb_buf->buf_cl, 0, 0,
cur_rgb_buf->len, 0, 0, &debayer_event));
@ -174,8 +172,7 @@ bool CameraBuf::acquire() {
CL_CHECK(clReleaseEvent(debayer_event));
cur_yuv_buf = vipc_server->get_buffer(yuv_type);
cur_yuv_idx = cur_yuv_buf->idx;
yuv_metas[cur_yuv_idx] = frame_data;
yuv_metas[cur_yuv_buf->idx] = frame_data;
rgb_to_yuv_queue(&rgb_to_yuv_state, q, cur_rgb_buf->buf_cl, cur_yuv_buf->buf_cl);
VisionIpcBufExtra extra = {
@ -218,25 +215,25 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr
framed.setGainFrac(frame_data.gain_frac);
}
void fill_frame_image(cereal::FrameData::Builder &framed, uint8_t *dat, int w, int h, int stride) {
if (dat != nullptr) {
int scale = env_scale;
int x_min = env_xmin; int y_min = env_ymin; int x_max = w-1; int y_max = h-1;
if (env_xmax != -1) x_max = env_xmax;
if (env_ymax != -1) y_max = env_ymax;
int new_width = (x_max - x_min + 1) / scale;
int new_height = (y_max - y_min + 1) / scale;
uint8_t *resized_dat = new uint8_t[new_width*new_height*3];
int goff = x_min*3 + y_min*stride;
for (int r=0;r<new_height;r++) {
for (int c=0;c<new_width;c++) {
memcpy(&resized_dat[(r*new_width+c)*3], &dat[goff+r*stride*scale+c*3*scale], 3*sizeof(uint8_t));
}
void fill_frame_image(cereal::FrameData::Builder &framed, const CameraBuf *b) {
assert(b->cur_rgb_buf);
const uint8_t *dat = (const uint8_t *)b->cur_rgb_buf->addr;
int scale = env_scale;
int x_min = env_xmin; int y_min = env_ymin; int x_max = b->rgb_width-1; int y_max = b->rgb_height-1;
if (env_xmax != -1) x_max = env_xmax;
if (env_ymax != -1) y_max = env_ymax;
int new_width = (x_max - x_min + 1) / scale;
int new_height = (y_max - y_min + 1) / scale;
uint8_t *resized_dat = new uint8_t[new_width*new_height*3];
int goff = x_min*3 + y_min*b->rgb_stride;
for (int r=0;r<new_height;r++) {
for (int c=0;c<new_width;c++) {
memcpy(&resized_dat[(r*new_width+c)*3], &dat[goff+r*b->rgb_stride*scale+c*3*scale], 3*sizeof(uint8_t));
}
framed.setImage(kj::arrayPtr((const uint8_t*)resized_dat, new_width*new_height*3));
delete[] resized_dat;
}
framed.setImage(kj::arrayPtr((const uint8_t*)resized_dat, (size_t)new_width*new_height*3));
delete[] resized_dat;
}
static void create_thumbnail(MultiCameraState *s, const CameraBuf *b) {
@ -414,7 +411,7 @@ void common_camera_process_front(SubMaster *sm, PubMaster *pm, CameraState *c, i
framed.setFrameType(cereal::FrameData::FrameType::FRONT);
fill_frame_data(framed, b->cur_frame_data, cnt);
if (env_send_front) {
fill_frame_image(framed, (uint8_t*)b->cur_rgb_buf->addr, b->rgb_width, b->rgb_height, b->rgb_stride);
fill_frame_image(framed, b);
}
pm->send("frontFrame", msg);
}

@ -102,12 +102,10 @@ public:
mat3 yuv_transform;
FrameMetadata yuv_metas[YUV_COUNT];
size_t yuv_buf_size;
VisionStreamType rgb_type, yuv_type;
int rgb_width, rgb_height, rgb_stride;
int cur_yuv_idx, cur_rgb_idx;
FrameMetadata cur_frame_data;
VisionBuf *cur_rgb_buf;
@ -122,7 +120,6 @@ public:
std::unique_ptr<FrameMetadata[]> camera_bufs_metadata;
int frame_buf_count;
int frame_size;
release_cb release_callback;
@ -137,7 +134,7 @@ public:
typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt);
void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, uint32_t cnt);
void fill_frame_image(cereal::FrameData::Builder &framed, uint8_t *dat, int w, int h, int stride);
void fill_frame_image(cereal::FrameData::Builder &framed, const CameraBuf *b);
void set_exposure_target(CameraState *c, const uint8_t *pix_ptr, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip);
std::thread start_process_thread(MultiCameraState *cameras, const char *tname,
CameraState *cs, process_thread_cb callback);

@ -1557,9 +1557,7 @@ static FrameMetadata get_frame_metadata(CameraState *s, uint32_t frame_id) {
};
}
static void* ops_thread(void* arg) {
MultiCameraState *s = (MultiCameraState*)arg;
static void ops_thread(MultiCameraState *s) {
int rear_op_id_last = 0;
int front_op_id_last = 0;
@ -1584,8 +1582,6 @@ static void* ops_thread(void* arg) {
util::sleep_for(50);
}
return NULL;
}
static void update_lapmap(MultiCameraState *s, const CameraBuf *b, const int cnt) {
@ -1662,7 +1658,7 @@ void camera_process_frame(MultiCameraState *s, CameraState *c, int cnt) {
auto framed = msg.initEvent().initFrame();
fill_frame_data(framed, b->cur_frame_data, cnt);
if (env_send_rear) {
fill_frame_image(framed, (uint8_t *)b->cur_rgb_buf->addr, b->rgb_width, b->rgb_height, b->rgb_stride);
fill_frame_image(framed, b);
}
framed.setFocusVal(s->rear.focus);
framed.setFocusConf(s->rear.confidence);
@ -1679,10 +1675,8 @@ void camera_process_frame(MultiCameraState *s, CameraState *c, int cnt) {
}
void cameras_run(MultiCameraState *s) {
pthread_t ops_thread_handle;
int err = pthread_create(&ops_thread_handle, NULL, ops_thread, s);
assert(err == 0);
std::vector<std::thread> threads;
threads.push_back(std::thread(ops_thread, s));
threads.push_back(start_process_thread(s, "processing", &s->rear, camera_process_frame));
threads.push_back(start_process_thread(s, "frontview", &s->front, camera_process_front));
@ -1778,9 +1772,6 @@ void cameras_run(MultiCameraState *s) {
LOG(" ************** STOPPING **************");
err = pthread_join(ops_thread_handle, NULL);
assert(err == 0);
for (auto &t : threads) t.join();
cameras_close(s);

@ -1070,8 +1070,7 @@ void camera_autoexposure(CameraState *s, float grey_frac) {
cam_exp[s->camera_num].store(tmp);
}
static void* ae_thread(void* arg) {
MultiCameraState *s = (MultiCameraState*)arg;
static void ae_thread(MultiCameraState *s) {
CameraState *c_handles[3] = {&s->wide, &s->rear, &s->front};
int op_id_last[3] = {0};
@ -1090,8 +1089,6 @@ static void* ae_thread(void* arg) {
util::sleep_for(50);
}
return NULL;
}
void camera_process_front(MultiCameraState *s, CameraState *c, int cnt) {
@ -1106,7 +1103,7 @@ void camera_process_frame(MultiCameraState *s, CameraState *c, int cnt) {
auto framed = c == &s->rear ? msg.initEvent().initFrame() : msg.initEvent().initWideFrame();
fill_frame_data(framed, b->cur_frame_data, cnt);
if ((c == &s->rear && env_send_rear) || (c == &s->wide && env_send_wide)) {
fill_frame_image(framed, (uint8_t*)b->cur_rgb_buf->addr, b->rgb_width, b->rgb_height, b->rgb_stride);
fill_frame_image(framed, b);
}
if (c == &s->rear) {
framed.setTransform(b->yuv_transform.v);
@ -1114,35 +1111,16 @@ void camera_process_frame(MultiCameraState *s, CameraState *c, int cnt) {
s->pm->send(c == &s->rear ? "frame" : "wideFrame", msg);
if (cnt % 3 == 0) {
int exposure_x;
int exposure_y;
int exposure_width;
int exposure_height;
if (c == &s->rear) {
exposure_x = 96;
exposure_y = 160;
exposure_width = 1734;
exposure_height = 986;
} else { // c == &s->wide
exposure_x = 96;
exposure_y = 250;
exposure_width = 1734;
exposure_height = 524;
}
int skip = 2;
set_exposure_target(c, (const uint8_t *)b->cur_yuv_buf->y, exposure_x, exposure_x + exposure_width, skip, exposure_y, exposure_y + exposure_height, skip);
const auto [x, y, w, h] = (c == &s->wide) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986);
const int skip = 2;
set_exposure_target(c, (const uint8_t *)b->cur_yuv_buf->y, x, x + w, skip, y, y + h, skip);
}
}
void cameras_run(MultiCameraState *s) {
int err;
// start threads
LOG("-- Starting threads");
pthread_t ae_thread_handle;
err = pthread_create(&ae_thread_handle, NULL,
ae_thread, s);
assert(err == 0);
std::vector<std::thread> threads;
threads.push_back(std::thread(ae_thread, s));
threads.push_back(start_process_thread(s, "processing", &s->rear, camera_process_frame));
threads.push_back(start_process_thread(s, "frontview", &s->front, camera_process_front));
threads.push_back(start_process_thread(s, "wideview", &s->wide, camera_process_frame));
@ -1193,9 +1171,6 @@ void cameras_run(MultiCameraState *s) {
LOG(" ************** STOPPING **************");
err = pthread_join(ae_thread_handle, NULL);
assert(err == 0);
for (auto &t : threads) t.join();
cameras_close(s);

@ -33,7 +33,7 @@ class CAR:
FINGERPRINTS = {
CAR.PACIFICA_2017_HYBRID: [
{168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8},
{168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788:3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8},
],
CAR.PACIFICA_2018: [
{55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8},

@ -128,7 +128,7 @@ def match_fw_to_car(fw_versions):
continue
# TODO: on some toyota, the engine can show on two different addresses
if ecu_type == Ecu.engine and candidate in [TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS] and found_version is None:
if ecu_type == Ecu.engine and candidate in [TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS, TOYOTA.AVALON] and found_version is None:
continue
# ignore non essential ecus

@ -453,6 +453,7 @@ FW_VERSIONS = {
b'37805-5AN-CH20\x00\x00',
b'37805-5AN-E630\x00\x00',
b'37805-5AN-L840\x00\x00',
b'37805-5AN-L930\x00\x00',
b'37805-5AN-L940\x00\x00',
b'37805-5AN-LF20\x00\x00',
b'37805-5AN-LH20\x00\x00',

@ -50,7 +50,7 @@ class CarController():
self.steer_rate_limited = new_steer != apply_steer
# disable if steer angle reach 90 deg, otherwise mdps fault in some models
lkas_active = enabled and abs(CS.out.steeringAngle) < 90.
lkas_active = enabled and abs(CS.out.steeringAngle) < CS.CP.maxSteerAngle
# fix for Genesis hard fault at low speed
if CS.out.vEgo < 16.7 and self.car_fingerprint == CAR.HYUNDAI_GENESIS:

@ -27,6 +27,13 @@ class CarInterface(CarInterfaceBase):
ret.steerLimitTimer = 0.4
tire_stiffness_factor = 1.
ret.maxSteerAngle = 90.
eps_modified = False
for fw in car_fw:
if fw.ecu == "eps" and b"," in fw.fwVersion:
eps_modified = True
if candidate == CAR.SANTA_FE:
ret.lateralTuning.pid.kf = 0.00005
ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG
@ -58,6 +65,8 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 13.75 * 1.15
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]]
if eps_modified:
ret.maxSteerAngle = 1000.
elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]:
ret.lateralTuning.pid.kf = 0.00006
ret.mass = 1275. + STD_CARGO_KG

@ -35,7 +35,7 @@ class CAR:
VELOSTER = "HYUNDAI VELOSTER 2019"
# Kia
KIA_FORTE = "KIA FORTE E 2018"
KIA_FORTE = "KIA FORTE E 2018 & GT 2021"
KIA_NIRO_EV = "KIA NIRO EV 2020"
KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016"
KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019"
@ -140,7 +140,7 @@ FINGERPRINTS = {
127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
}],
CAR.KIA_FORTE: [{
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1191: 2, 1225: 8, 1265: 4, 1280: 4, 1287: 4, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1427: 6, 1456: 4, 1470: 8
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
}],
CAR.KIA_OPTIMA_H: [{
68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1236: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8
@ -160,6 +160,17 @@ FINGERPRINTS = {
IGNORED_FINGERPRINTS = [CAR.VELOSTER, CAR.GENESIS_G70, CAR.KONA]
FW_VERSIONS = {
CAR.IONIQ_EV_2020: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819',
],
},
CAR.IONIQ_EV_LTD: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ',

@ -53,7 +53,7 @@ class CarInterface(CarInterfaceBase):
ret.lateralTuning.indi.timeConstantV = [1.0]
ret.lateralTuning.indi.actuatorEffectivenessBP = [0.]
ret.lateralTuning.indi.actuatorEffectivenessV = [1.0]
ret.steerActuatorDelay = 0.5
ret.steerActuatorDelay = 0.3
elif candidate in [CAR.RAV4, CAR.RAV4H]:
stop_and_go = True if (candidate in CAR.RAV4H) else False

@ -298,23 +298,34 @@ IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2, CAR.LEXUS_RXH_TSS2
FW_VERSIONS = {
CAR.AVALON: {
(Ecu.esp, 0x7b0, None): [b'F152607060\x00\x00\x00\x00\x00\x00'],
(Ecu.esp, 0x7b0, None): [
b'F152607110\x00\x00\x00\x00\x00\x00',
b'F152607180\x00\x00\x00\x00\x00\x00',
],
(Ecu.dsu, 0x791, None): [
b'881510705200\x00\x00\x00\x00',
b'881510701300\x00\x00\x00\x00',
b'881510703200\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B41090\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [b'8965B41051\x00\x00\x00\x00\x00\x00'],
(Ecu.engine, 0x7e0, None): [
b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
b'\x01896630738000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'8821F4702000\x00\x00\x00\x00',
b'8821F4702100\x00\x00\x00\x00',
b'8821F4702300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
b'8646F0701100\x00\x00\x00\x00',
b'8646F0703000\x00\x00\x00\x00',
b'8646F0702100\x00\x00\x00\x00',
],
},
CAR.CAMRY: {
@ -685,6 +696,7 @@ FW_VERSIONS = {
b'F152612691\x00\x00\x00\x00\x00\x00',
b'F152612692\x00\x00\x00\x00\x00\x00',
b'F152612700\x00\x00\x00\x00\x00\x00',
b'F152612790\x00\x00\x00\x00\x00\x00',
b'F152612800\x00\x00\x00\x00\x00\x00',
b'F152612840\x00\x00\x00\x00\x00\x00',
b'F152612A10\x00\x00\x00\x00\x00\x00',

@ -10,10 +10,6 @@
#include <CL/cl.h>
#endif
#ifdef __cplusplus
extern "C" {
#endif
#define CL_CHECK(_expr) \
do { \
assert(CL_SUCCESS == _expr); \
@ -30,7 +26,3 @@ extern "C" {
cl_device_id cl_get_device_id(cl_device_type device_type);
cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args);
const char* cl_get_error_string(int err);
#ifdef __cplusplus
}
#endif

@ -32,22 +32,22 @@ struct FramebufferState {
EGLContext context;
};
extern "C" void framebuffer_swap(FramebufferState *s) {
void framebuffer_swap(FramebufferState *s) {
eglSwapBuffers(s->display, s->surface);
assert(glGetError() == GL_NO_ERROR);
}
extern "C" bool set_brightness(int brightness) {
bool set_brightness(int brightness) {
char bright[64];
snprintf(bright, sizeof(bright), "%d", brightness);
return 0 == write_file("/sys/class/leds/lcd-backlight/brightness", bright, strlen(bright));
}
extern "C" void framebuffer_set_power(FramebufferState *s, int mode) {
void framebuffer_set_power(FramebufferState *s, int mode) {
SurfaceComposerClient::setDisplayPowerMode(s->dtoken, mode);
}
extern "C" FramebufferState* framebuffer_init(
FramebufferState* framebuffer_init(
const char* name, int32_t layer, int alpha,
int *out_w, int *out_h) {
status_t status;

@ -1,9 +1,5 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
typedef struct FramebufferState FramebufferState;
FramebufferState* framebuffer_init(
@ -39,7 +35,3 @@ enum {
* functionality. */
HWC_POWER_MODE_DOZE_SUSPEND = 3,
};
#ifdef __cplusplus
}
#endif

@ -1,5 +1,4 @@
#ifndef GPIO_H
#define GPIO_H
#pragma once
#include <stdbool.h>
@ -20,16 +19,5 @@
#define GPIO_STM_BOOT0 0
#endif
#ifdef __cplusplus
extern "C" {
#endif
int gpio_init(int pin_nr, bool output);
int gpio_set(int pin_nr, bool high);
#ifdef __cplusplus
} // extern "C"
#endif
#endif

@ -1,10 +1,18 @@
#pragma once
const int TRAJECTORY_SIZE = 33;
const float MIN_DRAW_DISTANCE = 10.0;
const float MAX_DRAW_DISTANCE = 100.0;
constexpr int MODEL_PATH_DISTANCE = 192;
constexpr int TRAJECTORY_SIZE = 33;
constexpr float MIN_DRAW_DISTANCE = 10.0;
constexpr float MAX_DRAW_DISTANCE = 100.0;
constexpr int POLYFIT_DEGREE = 4;
constexpr int SPEED_PERCENTILES = 10;
constexpr int DESIRE_PRED_SIZE = 32;
constexpr int OTHER_META_SIZE = 4;
const double T_IDXS[TRAJECTORY_SIZE] = {0. , 0.00976562, 0.0390625 , 0.08789062, 0.15625 ,
0.24414062, 0.3515625 , 0.47851562, 0.625 , 0.79101562,
0.9765625 , 1.18164062, 1.40625 , 1.65039062, 1.9140625 ,
2.19726562, 2.5 , 2.82226562, 3.1640625 , 3.52539062,
3.90625 , 4.30664062, 4.7265625 , 5.16601562, 5.625 ,
6.10351562, 6.6015625 , 7.11914062, 7.65625 , 8.21289062,
8.7890625 , 9.38476562, 10.};
const double X_IDXS[TRAJECTORY_SIZE] = { 0. , 0.1875, 0.75 , 1.6875, 3. , 4.6875,
6.75 , 9.1875, 12. , 15.1875, 18.75 , 22.6875,
27. , 31.6875, 36.75 , 42.1875, 48. , 54.1875,
60.75 , 67.6875, 75. , 82.6875, 90.75 , 99.1875,
108. , 117.1875, 126.75 , 136.6875, 147. , 157.6875,
168.75 , 180.1875, 192.};

@ -6,7 +6,7 @@
#include <string.h>
#include <assert.h>
#include <pthread.h>
#include <mutex>
#include <zmq.h>
#include "json11.hpp"
@ -17,7 +17,7 @@
#include "swaglog.h"
typedef struct LogState {
pthread_mutex_t lock;
std::mutex lock;
bool inited;
json11::Json::object ctx_j;
void *zctx;
@ -25,9 +25,7 @@ typedef struct LogState {
int print_level;
} LogState;
static LogState s = {
.lock = PTHREAD_MUTEX_INITIALIZER,
};
static LogState s = {};
static void cloudlog_bind_locked(const char* k, const char* v) {
s.ctx_j[k] = v;
@ -65,7 +63,7 @@ static void cloudlog_init() {
void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func,
const char* fmt, ...) {
pthread_mutex_lock(&s.lock);
std::lock_guard lk(s.lock);
cloudlog_init();
char* msg_buf = NULL;
@ -75,7 +73,6 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func
va_end(args);
if (!msg_buf) {
pthread_mutex_unlock(&s.lock);
return;
}
@ -101,12 +98,10 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func
zmq_send(s.sock, &levelnum_c, 1, ZMQ_NOBLOCK | ZMQ_SNDMORE);
zmq_send(s.sock, log_s.c_str(), log_s.length(), ZMQ_NOBLOCK);
pthread_mutex_unlock(&s.lock);
}
void cloudlog_bind(const char* k, const char* v) {
pthread_mutex_lock(&s.lock);
std::lock_guard lk(s.lock);
cloudlog_init();
cloudlog_bind_locked(k, v);
pthread_mutex_unlock(&s.lock);
}

@ -1,5 +1,4 @@
#ifndef SWAGLOG_H
#define SWAGLOG_H
#pragma once
#include "selfdrive/common/timing.h"
@ -9,19 +8,11 @@
#define CLOUDLOG_ERROR 40
#define CLOUDLOG_CRITICAL 50
#ifdef __cplusplus
extern "C" {
#endif
void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func,
const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/;
void cloudlog_bind(const char* k, const char* v);
#ifdef __cplusplus
}
#endif
#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \
__func__, \
fmt, ## __VA_ARGS__)
@ -64,5 +55,3 @@ void cloudlog_bind(const char* k, const char* v);
#define LOG_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_INFO, fmt, ## __VA_ARGS__)
#define LOGW_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_WARNING, fmt, ## __VA_ARGS__)
#define LOGE_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_ERROR, fmt, ## __VA_ARGS__)
#endif

@ -96,6 +96,12 @@ inline std::string getenv_default(const char* env_var, const char * suffix, cons
inline void sleep_for(const int milliseconds) {
std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds));
}
inline bool file_exists(const std::string& fn) {
std::ifstream f(fn);
return f.good();
}
}
class ExitHandler {

@ -52,8 +52,10 @@ class Controls:
self.sm = sm
if self.sm is None:
self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', 'frontFrame',
'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman'])
ignore = ['ubloxRaw', 'frontFrame'] if SIMULATION else None
self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', 'ubloxRaw',
'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman',
'frame', 'frontFrame'], ignore_alive=ignore)
self.can_sock = can_sock
if can_sock is None:
@ -198,7 +200,7 @@ class Controls:
if self.can_rcv_error or (not CS.canValid and self.sm.frame > 5 / DT_CTRL):
self.events.add(EventName.canError)
if (self.sm['health'].safetyModel != self.CP.safetyModel and self.sm.frame > 2 / DT_CTRL) or \
self.mismatch_counter >= 200:
self.mismatch_counter >= 200:
self.events.add(EventName.controlsMismatch)
if not self.sm.alive['plan'] and self.sm.alive['pathPlan']:
# only plan not being received: radar not communicating
@ -210,10 +212,6 @@ class Controls:
if not self.sm['liveLocationKalman'].sensorsOK and not NOSENSOR:
if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs
self.events.add(EventName.sensorDataInvalid)
if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000):
# Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes
if not (SIMULATION or NOSENSOR): # TODO: send GPS in carla
self.events.add(EventName.noGps)
if not self.sm['pathPlan'].paramsValid:
self.events.add(EventName.vehicleModelInvalid)
if not self.sm['liveLocationKalman'].posenetOK:
@ -228,11 +226,19 @@ class Controls:
self.events.add(EventName.relayMalfunction)
if self.sm['plan'].fcw:
self.events.add(EventName.fcw)
if not self.sm.alive['frontFrame'] and (self.sm.frame > 5 / DT_CTRL) and not SIMULATION:
self.events.add(EventName.cameraMalfunction)
if self.sm['model'].frameDropPerc > 20 and not SIMULATION:
self.events.add(EventName.modeldLagging)
# TODO: fix simulator
if not SIMULATION:
if not NOSENSOR:
if not self.sm.alive['ubloxRaw'] and (self.sm.frame > 10. / DT_CTRL):
self.events.add(EventName.gpsMalfunction)
elif not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000):
# Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes
self.events.add(EventName.noGps)
if not self.sm.all_alive(['frame', 'frontFrame']) and (self.sm.frame > 5 / DT_CTRL):
self.events.add(EventName.cameraMalfunction)
if self.sm['model'].frameDropPerc > 20:
self.events.add(EventName.modeldLagging)
# Only allow engagement with brake pressed when stopped behind another stopped car
if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \
@ -388,8 +394,8 @@ class Controls:
if (lac_log.saturated and not CS.steeringPressed) or \
(self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT):
# Check if we deviated from the path
left_deviation = actuators.steer > 0 and path_plan.dPoly[3] > 0.1
right_deviation = actuators.steer < 0 and path_plan.dPoly[3] < -0.1
left_deviation = actuators.steer > 0 and path_plan.dPathPoints[0] < -0.1
right_deviation = actuators.steer < 0 and path_plan.dPathPoints[0] > 0.1
if left_deviation or right_deviation:
self.events.add(EventName.steerSaturated)
@ -431,8 +437,8 @@ class Controls:
if len(meta.desirePrediction) and ldw_allowed:
l_lane_change_prob = meta.desirePrediction[Desire.laneChangeLeft - 1]
r_lane_change_prob = meta.desirePrediction[Desire.laneChangeRight - 1]
l_lane_close = left_lane_visible and (self.sm['pathPlan'].lPoly[3] < (1.08 - CAMERA_OFFSET))
r_lane_close = right_lane_visible and (self.sm['pathPlan'].rPoly[3] > -(1.08 + CAMERA_OFFSET))
l_lane_close = left_lane_visible and (self.sm['model'].leftLane.poly[3] < (1.08 - CAMERA_OFFSET))
r_lane_close = right_lane_visible and (self.sm['model'].rightLane.poly[3] > -(1.08 + CAMERA_OFFSET))
CC.hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close)
CC.hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close)

@ -7,11 +7,12 @@ V_CRUISE_MAX = 144
V_CRUISE_MIN = 8
V_CRUISE_DELTA = 8
V_CRUISE_ENABLE_MIN = 40
MPC_N = 16
CAR_ROTATION_RADIUS = 1.5
class MPC_COST_LAT:
PATH = 1.0
LANE = 3.0
HEADING = 1.0
STEER_RATE = 1.0

@ -468,6 +468,10 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo
ET.PERMANENT: NormalPermanentAlert("Camera Malfunction", "Contact Support"),
},
EventName.gpsMalfunction: {
ET.PERMANENT: NormalPermanentAlert("GPS Malfunction", "Contact Support"),
},
# ********** events that affect controls state transitions **********
EventName.pcmEnable: {

@ -3,103 +3,81 @@ import numpy as np
from cereal import log
CAMERA_OFFSET = 0.06 # m from center car to camera
TRAJECTORY_SIZE = 33
def compute_path_pinv(length=50):
deg = 3
x = np.arange(length*1.0)
X = np.vstack(tuple(x**n for n in range(deg, -1, -1))).T
pinv = np.linalg.pinv(X)
return pinv
def model_polyfit(points, path_pinv):
return np.dot(path_pinv, [float(x) for x in points])
def eval_poly(poly, x):
return poly[3] + poly[2]*x + poly[1]*x**2 + poly[0]*x**3
class LanePlanner:
def __init__(self):
self.l_poly = [0., 0., 0., 0.]
self.r_poly = [0., 0., 0., 0.]
self.p_poly = [0., 0., 0., 0.]
self.d_poly = [0., 0., 0., 0.]
self.ll_t = np.zeros((TRAJECTORY_SIZE,))
self.ll_x = np.zeros((TRAJECTORY_SIZE,))
self.lll_y = np.zeros((TRAJECTORY_SIZE,))
self.rll_y = np.zeros((TRAJECTORY_SIZE,))
self.lane_width_estimate = 3.7
self.lane_width_certainty = 1.0
self.lane_width = 3.7
self.l_prob = 0.
self.r_prob = 0.
self.lll_prob = 0.
self.rll_prob = 0.
self.d_prob = 0.
self.l_std = 0.
self.r_std = 0.
self.lll_std = 0.
self.rll_std = 0.
self.l_lane_change_prob = 0.
self.r_lane_change_prob = 0.
self._path_pinv = compute_path_pinv()
self.x_points = np.arange(50)
def parse_model(self, md):
if len(md.leftLane.poly):
self.l_poly = np.array(md.leftLane.poly)
self.l_std = float(md.leftLane.std)
self.r_poly = np.array(md.rightLane.poly)
self.r_std = float(md.rightLane.std)
self.p_poly = np.array(md.path.poly)
else:
self.l_poly = model_polyfit(md.leftLane.points, self._path_pinv) # left line
self.r_poly = model_polyfit(md.rightLane.points, self._path_pinv) # right line
self.p_poly = model_polyfit(md.path.points, self._path_pinv) # predicted path
self.l_prob = md.leftLane.prob # left line prob
self.r_prob = md.rightLane.prob # right line prob
if len(md.laneLines) == 4 and len(md.laneLines[0].t) == TRAJECTORY_SIZE:
self.ll_t = (np.array(md.laneLines[1].t) + np.array(md.laneLines[2].t))/2
# left and right ll x is the same
self.ll_x = md.laneLines[1].x
# only offset left and right lane lines; offsetting path does not make sense
self.lll_y = np.array(md.laneLines[1].y) - CAMERA_OFFSET
self.rll_y = np.array(md.laneLines[2].y) - CAMERA_OFFSET
self.lll_prob = md.laneLineProbs[1]
self.rll_prob = md.laneLineProbs[2]
self.lll_std = md.laneLineStds[1]
self.rll_std = md.laneLineStds[2]
if len(md.meta.desireState):
self.l_lane_change_prob = md.meta.desireState[log.PathPlan.Desire.laneChangeLeft]
self.r_lane_change_prob = md.meta.desireState[log.PathPlan.Desire.laneChangeRight]
def update_d_poly(self, v_ego):
# only offset left and right lane lines; offsetting p_poly does not make sense
self.l_poly[3] += CAMERA_OFFSET
self.r_poly[3] += CAMERA_OFFSET
def get_d_path(self, v_ego, path_t, path_xyz):
# Reduce reliance on lanelines that are too far apart or
# will be in a few seconds
l_prob, r_prob = self.l_prob, self.r_prob
width_poly = self.l_poly - self.r_poly
l_prob, r_prob = self.lll_prob, self.rll_prob
width_pts = self.rll_y - self.lll_y
prob_mods = []
for t_check in [0.0, 1.5, 3.0]:
width_at_t = eval_poly(width_poly, t_check * (v_ego + 7))
width_at_t = interp(t_check * (v_ego + 7), self.ll_x, width_pts)
prob_mods.append(interp(width_at_t, [4.0, 5.0], [1.0, 0.0]))
mod = min(prob_mods)
l_prob *= mod
r_prob *= mod
# Reduce reliance on uncertain lanelines
l_std_mod = interp(self.l_std, [.15, .3], [1.0, 0.0])
r_std_mod = interp(self.r_std, [.15, .3], [1.0, 0.0])
l_std_mod = interp(self.lll_std, [.15, .3], [1.0, 0.0])
r_std_mod = interp(self.rll_std, [.15, .3], [1.0, 0.0])
l_prob *= l_std_mod
r_prob *= r_std_mod
# Find current lanewidth
self.lane_width_certainty += 0.05 * (l_prob * r_prob - self.lane_width_certainty)
current_lane_width = abs(self.l_poly[3] - self.r_poly[3])
current_lane_width = abs(self.rll_y[0] - self.lll_y[0])
self.lane_width_estimate += 0.005 * (current_lane_width - self.lane_width_estimate)
speed_lane_width = interp(v_ego, [0., 31.], [2.8, 3.5])
self.lane_width = self.lane_width_certainty * self.lane_width_estimate + \
(1 - self.lane_width_certainty) * speed_lane_width
clipped_lane_width = min(4.0, self.lane_width)
path_from_left_lane = self.l_poly.copy()
path_from_left_lane[3] -= clipped_lane_width / 2.0
path_from_right_lane = self.r_poly.copy()
path_from_right_lane[3] += clipped_lane_width / 2.0
lr_prob = l_prob + r_prob - l_prob * r_prob
d_poly_lane = (l_prob * path_from_left_lane + r_prob * path_from_right_lane) / (l_prob + r_prob + 0.0001)
self.d_poly = lr_prob * d_poly_lane + (1.0 - lr_prob) * self.p_poly.copy()
path_from_left_lane = self.lll_y + clipped_lane_width / 2.0
path_from_right_lane = self.rll_y - clipped_lane_width / 2.0
self.d_prob = l_prob + r_prob - l_prob * r_prob
lane_path_y = (l_prob * path_from_left_lane + r_prob * path_from_right_lane) / (l_prob + r_prob + 0.0001)
lane_path_y_interp = np.interp(path_t, self.ll_t, lane_path_y)
path_xyz[:,1] = self.d_prob * lane_path_y_interp + (1.0 - self.d_prob) * path_xyz[:,1]
return path_xyz

@ -1,6 +1,7 @@
Import('env', 'arch')
cpp_path = [
"#selfdrive",
"#phonelibs/acado/include",
"#phonelibs/acado/include/acado",
"#phonelibs/qpoases/INCLUDE",

@ -1,10 +1,10 @@
#include <acado_code_generation.hpp>
#include "common/modeldata.h"
#define PI 3.1415926536
#define deg2rad(d) (d/180.0*PI)
const int controlHorizon = 50;
const int N_steps = 16;
using namespace std;
int main( )
@ -17,54 +17,34 @@ int main( )
DifferentialState xx; // x position
DifferentialState yy; // y position
DifferentialState psi; // vehicle heading
DifferentialState delta;
DifferentialState tire_angle;
OnlineData curvature_factor;
OnlineData v_ref; // m/s
OnlineData l_poly_r0, l_poly_r1, l_poly_r2, l_poly_r3;
OnlineData r_poly_r0, r_poly_r1, r_poly_r2, r_poly_r3;
OnlineData d_poly_r0, d_poly_r1, d_poly_r2, d_poly_r3;
OnlineData l_prob, r_prob;
OnlineData lane_width;
OnlineData v_ego;
OnlineData rotation_radius;
Control t;
Control tire_angle_rate;
// Equations of motion
f << dot(xx) == v_ref * cos(psi);
f << dot(yy) == v_ref * sin(psi);
f << dot(psi) == v_ref * delta * curvature_factor;
f << dot(delta) == t;
auto lr_prob = l_prob + r_prob - l_prob * r_prob;
auto poly_l = l_poly_r0*(xx*xx*xx) + l_poly_r1*(xx*xx) + l_poly_r2*xx + l_poly_r3;
auto poly_r = r_poly_r0*(xx*xx*xx) + r_poly_r1*(xx*xx) + r_poly_r2*xx + r_poly_r3;
auto poly_d = d_poly_r0*(xx*xx*xx) + d_poly_r1*(xx*xx) + d_poly_r2*xx + d_poly_r3;
auto angle_d = atan(3*d_poly_r0*xx*xx + 2*d_poly_r1*xx + d_poly_r2);
// When the lane is not visible, use an estimate of its position
auto weighted_left_lane = l_prob * poly_l + (1 - l_prob) * (poly_d + lane_width/2.0);
auto weighted_right_lane = r_prob * poly_r + (1 - r_prob) * (poly_d - lane_width/2.0);
auto c_left_lane = exp(-(weighted_left_lane - yy));
auto c_right_lane = exp(weighted_right_lane - yy);
f << dot(xx) == v_ego * cos(psi) - rotation_radius * sin(psi) * (v_ego * tire_angle *curvature_factor);
f << dot(yy) == v_ego * sin(psi) + rotation_radius * cos(psi) * (v_ego * tire_angle *curvature_factor);
f << dot(psi) == v_ego * tire_angle * curvature_factor;
f << dot(tire_angle) == tire_angle_rate;
// Running cost
Function h;
// Distance errors
h << poly_d - yy;
h << lr_prob * c_left_lane;
h << lr_prob * c_right_lane;
h << yy;
// Heading error
h << (v_ref + 1.0 ) * (angle_d - psi);
h << (v_ego + 1.0 ) * psi;
// Angular rate error
h << (v_ref + 1.0 ) * t;
h << (v_ego + 1.0 ) * tire_angle_rate;
BMatrix Q(5,5); Q.setAll(true);
BMatrix Q(3,3); Q.setAll(true);
// Q(0,0) = 1.0;
// Q(1,1) = 1.0;
// Q(2,2) = 1.0;
@ -75,34 +55,21 @@ int main( )
Function hN;
// Distance errors
hN << poly_d - yy;
hN << l_prob * c_left_lane;
hN << r_prob * c_right_lane;
hN << yy;
// Heading errors
hN << (2.0 * v_ref + 1.0 ) * (angle_d - psi);
hN << (2.0 * v_ego + 1.0 ) * psi;
BMatrix QN(4,4); QN.setAll(true);
BMatrix QN(2,2); QN.setAll(true);
// QN(0,0) = 1.0;
// QN(1,1) = 1.0;
// QN(2,2) = 1.0;
// QN(3,3) = 1.0;
// Non uniform time grid
// First 5 timesteps are 0.05, after that it's 0.15
DMatrix numSteps(20, 1);
for (int i = 0; i < 5; i++){
numSteps(i) = 1;
}
for (int i = 5; i < 20; i++){
numSteps(i) = 3;
}
// Setup Optimal Control Problem
const double tStart = 0.0;
const double tEnd = 2.5;
OCP ocp( tStart, tEnd, numSteps);
double T_IDXS_ARR[N_steps + 1];
memcpy(T_IDXS_ARR, T_IDXS, (N_steps + 1) * sizeof(double));
Grid times(N_steps + 1, T_IDXS_ARR);
OCP ocp(times);
ocp.subjectTo(f);
ocp.minimizeLSQ(Q, h);
@ -111,15 +78,15 @@ int main( )
// car can't go backward to avoid "circles"
ocp.subjectTo( deg2rad(-90) <= psi <= deg2rad(90));
// more than absolute max steer angle
ocp.subjectTo( deg2rad(-50) <= delta <= deg2rad(50));
ocp.setNOD(17);
ocp.subjectTo( deg2rad(-50) <= tire_angle <= deg2rad(50));
ocp.setNOD(3);
OCPexport mpc(ocp);
mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON );
mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING );
mpc.set( INTEGRATOR_TYPE, INT_RK4 );
mpc.set( NUM_INTEGRATOR_STEPS, 1 * controlHorizon);
mpc.set( MAX_NUM_QP_ITERATIONS, 500);
mpc.set( NUM_INTEGRATOR_STEPS, 2500);
mpc.set( MAX_NUM_QP_ITERATIONS, 1000);
mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES);
mpc.set( SPARSE_QP_SOLUTION, CONDENSING );

@ -1,6 +1,6 @@
#include "acado_common.h"
#include "acado_auxiliary_functions.h"
#include "common/modeldata.h"
#include <stdio.h>
#define NX ACADO_NX /* Number of differential state variables. */
@ -17,48 +17,40 @@ ACADOvariables acadoVariables;
ACADOworkspace acadoWorkspace;
typedef struct {
double x, y, psi, delta, t;
double x, y, psi, tire_angle, tire_angle_rate;
} state_t;
typedef struct {
double x[N+1];
double y[N+1];
double psi[N+1];
double delta[N+1];
double rate[N];
double tire_angle[N+1];
double tire_angle_rate[N];
double cost;
} log_t;
void init_weights(double pathCost, double laneCost, double headingCost, double steerRateCost){
void init_weights(double pathCost, double headingCost, double steerRateCost){
int i;
const int STEP_MULTIPLIER = 3;
const int STEP_MULTIPLIER = 3.0;
for (i = 0; i < N; i++) {
int f = 1;
if (i > 4){
f = STEP_MULTIPLIER;
}
double f = 20 * (T_IDXS[i+1] - T_IDXS[i]);
// Setup diagonal entries
acadoVariables.W[NY*NY*i + (NY+1)*0] = pathCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*1] = laneCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*2] = laneCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*3] = headingCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*4] = steerRateCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*1] = headingCost * f;
acadoVariables.W[NY*NY*i + (NY+1)*2] = steerRateCost * f;
}
acadoVariables.WN[(NYN+1)*0] = pathCost * STEP_MULTIPLIER;
acadoVariables.WN[(NYN+1)*1] = laneCost * STEP_MULTIPLIER;
acadoVariables.WN[(NYN+1)*2] = laneCost * STEP_MULTIPLIER;
acadoVariables.WN[(NYN+1)*3] = headingCost * STEP_MULTIPLIER;
acadoVariables.WN[(NYN+1)*1] = headingCost * STEP_MULTIPLIER;
}
void init(double pathCost, double laneCost, double headingCost, double steerRateCost){
void init(double pathCost, double headingCost, double steerRateCost){
acado_initializeSolver();
int i;
/* Initialize the states and controls. */
for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0;
for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.1;
for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.0;
/* Initialize the measurements/reference. */
for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0;
@ -67,45 +59,31 @@ void init(double pathCost, double laneCost, double headingCost, double steerRate
/* MPC: initialize the current state feedback. */
for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0;
init_weights(pathCost, laneCost, headingCost, steerRateCost);
init_weights(pathCost, headingCost, steerRateCost);
}
int run_mpc(state_t * x0, log_t * solution,
double l_poly[4], double r_poly[4], double d_poly[4],
double l_prob, double r_prob, double curvature_factor, double v_ref, double lane_width){
int run_mpc(state_t * x0, log_t * solution, double v_ego,
double curvature_factor, double rotation_radius, double target_y[N+1], double target_psi[N+1]){
int i;
for (i = 0; i <= NOD * N; i+= NOD){
acadoVariables.od[i] = curvature_factor;
acadoVariables.od[i+1] = v_ref;
acadoVariables.od[i+2] = l_poly[0];
acadoVariables.od[i+3] = l_poly[1];
acadoVariables.od[i+4] = l_poly[2];
acadoVariables.od[i+5] = l_poly[3];
acadoVariables.od[i+6] = r_poly[0];
acadoVariables.od[i+7] = r_poly[1];
acadoVariables.od[i+8] = r_poly[2];
acadoVariables.od[i+9] = r_poly[3];
acadoVariables.od[i+10] = d_poly[0];
acadoVariables.od[i+11] = d_poly[1];
acadoVariables.od[i+12] = d_poly[2];
acadoVariables.od[i+13] = d_poly[3];
acadoVariables.od[i+14] = l_prob;
acadoVariables.od[i+15] = r_prob;
acadoVariables.od[i+16] = lane_width;
acadoVariables.od[i+1] = v_ego;
acadoVariables.od[i+2] = rotation_radius;
}
for (i = 0; i < N; i+= 1){
acadoVariables.y[NY*i + 0] = target_y[i];
acadoVariables.y[NY*i + 1] = (v_ego + 1.0) * target_psi[i];
acadoVariables.y[NY*i + 2] = 0.0;
}
acadoVariables.yN[0] = target_y[N];
acadoVariables.yN[1] = (2.0 * v_ego + 1.0) * target_psi[N];
acadoVariables.x0[0] = x0->x;
acadoVariables.x0[1] = x0->y;
acadoVariables.x0[2] = x0->psi;
acadoVariables.x0[3] = x0->delta;
acadoVariables.x0[3] = x0->tire_angle;
acado_preparationStep();
@ -118,9 +96,9 @@ int run_mpc(state_t * x0, log_t * solution,
solution->x[i] = acadoVariables.x[i*NX];
solution->y[i] = acadoVariables.x[i*NX+1];
solution->psi[i] = acadoVariables.x[i*NX+2];
solution->delta[i] = acadoVariables.x[i*NX+3];
solution->tire_angle[i] = acadoVariables.x[i*NX+3];
if (i < N){
solution->rate[i] = acadoVariables.u[i];
solution->tire_angle_rate[i] = acadoVariables.u[i];
}
}
solution->cost = acado_getObjective();

@ -62,9 +62,9 @@ extern "C"
/** Indicator for fixed initial state. */
#define ACADO_INITIAL_STATE_FIXED 1
/** Number of control/estimation intervals. */
#define ACADO_N 20
#define ACADO_N 16
/** Number of online data values. */
#define ACADO_NOD 17
#define ACADO_NOD 3
/** Number of path constraints. */
#define ACADO_NPAC 0
/** Number of control variables. */
@ -76,11 +76,11 @@ extern "C"
/** Number of differential derivative variables. */
#define ACADO_NXD 0
/** Number of references/measurements per node on the first N nodes. */
#define ACADO_NY 5
#define ACADO_NY 3
/** Number of references/measurements on the last (N + 1)st node. */
#define ACADO_NYN 4
#define ACADO_NYN 2
/** Total number of QP optimization variables. */
#define ACADO_QP_NV 24
#define ACADO_QP_NV 20
/** Number of Runge-Kutta stages per integration step. */
#define ACADO_RK_NSTAGES 4
/** Providing interface for arrival cost. */
@ -102,41 +102,41 @@ extern "C"
typedef struct ACADOvariables_
{
int dummy;
/** Matrix of size: 21 x 4 (row major format)
/** Matrix of size: 17 x 4 (row major format)
*
* Matrix containing 21 differential variable vectors.
* Matrix containing 17 differential variable vectors.
*/
real_t x[ 84 ];
real_t x[ 68 ];
/** Column vector of size: 20
/** Column vector of size: 16
*
* Matrix containing 20 control variable vectors.
* Matrix containing 16 control variable vectors.
*/
real_t u[ 20 ];
real_t u[ 16 ];
/** Matrix of size: 21 x 17 (row major format)
/** Matrix of size: 17 x 3 (row major format)
*
* Matrix containing 21 online data vectors.
* Matrix containing 17 online data vectors.
*/
real_t od[ 357 ];
real_t od[ 51 ];
/** Column vector of size: 100
/** Column vector of size: 48
*
* Matrix containing 20 reference/measurement vectors of size 5 for first 20 nodes.
* Matrix containing 16 reference/measurement vectors of size 3 for first 16 nodes.
*/
real_t y[ 100 ];
real_t y[ 48 ];
/** Column vector of size: 4
/** Column vector of size: 2
*
* Reference/measurement vector for the 21. node.
* Reference/measurement vector for the 17. node.
*/
real_t yN[ 4 ];
real_t yN[ 2 ];
/** Matrix of size: 100 x 5 (row major format) */
real_t W[ 500 ];
/** Matrix of size: 48 x 3 (row major format) */
real_t W[ 144 ];
/** Matrix of size: 4 x 4 (row major format) */
real_t WN[ 16 ];
/** Matrix of size: 2 x 2 (row major format) */
real_t WN[ 4 ];
/** Column vector of size: 4
*
@ -155,64 +155,61 @@ real_t x0[ 4 ];
*/
typedef struct ACADOworkspace_
{
/** Column vector of size: 14 */
real_t rhs_aux[ 14 ];
/** Column vector of size: 28 */
real_t rhs_aux[ 28 ];
real_t rk_ttt;
/** Row vector of size: 42 */
real_t rk_xxx[ 42 ];
/** Row vector of size: 28 */
real_t rk_xxx[ 28 ];
/** Matrix of size: 4 x 24 (row major format) */
real_t rk_kkk[ 96 ];
/** Row vector of size: 42 */
real_t state[ 42 ];
/** Row vector of size: 28 */
real_t state[ 28 ];
/** Column vector of size: 80 */
real_t d[ 80 ];
/** Column vector of size: 100 */
real_t Dy[ 100 ];
/** Column vector of size: 64 */
real_t d[ 64 ];
/** Column vector of size: 4 */
real_t DyN[ 4 ];
/** Column vector of size: 48 */
real_t Dy[ 48 ];
/** Matrix of size: 80 x 4 (row major format) */
real_t evGx[ 320 ];
/** Column vector of size: 2 */
real_t DyN[ 2 ];
/** Column vector of size: 80 */
real_t evGu[ 80 ];
/** Matrix of size: 64 x 4 (row major format) */
real_t evGx[ 256 ];
/** Column vector of size: 11 */
real_t objAuxVar[ 11 ];
/** Column vector of size: 64 */
real_t evGu[ 64 ];
/** Row vector of size: 22 */
real_t objValueIn[ 22 ];
/** Row vector of size: 8 */
real_t objValueIn[ 8 ];
/** Row vector of size: 30 */
real_t objValueOut[ 30 ];
/** Row vector of size: 18 */
real_t objValueOut[ 18 ];
/** Matrix of size: 80 x 4 (row major format) */
real_t Q1[ 320 ];
/** Matrix of size: 64 x 4 (row major format) */
real_t Q1[ 256 ];
/** Matrix of size: 80 x 5 (row major format) */
real_t Q2[ 400 ];
/** Matrix of size: 64 x 3 (row major format) */
real_t Q2[ 192 ];
/** Column vector of size: 20 */
real_t R1[ 20 ];
/** Column vector of size: 16 */
real_t R1[ 16 ];
/** Matrix of size: 20 x 5 (row major format) */
real_t R2[ 100 ];
/** Matrix of size: 16 x 3 (row major format) */
real_t R2[ 48 ];
/** Column vector of size: 80 */
real_t S1[ 80 ];
/** Column vector of size: 64 */
real_t S1[ 64 ];
/** Matrix of size: 4 x 4 (row major format) */
real_t QN1[ 16 ];
/** Matrix of size: 4 x 4 (row major format) */
real_t QN2[ 16 ];
/** Matrix of size: 4 x 2 (row major format) */
real_t QN2[ 8 ];
/** Column vector of size: 4 */
real_t Dx0[ 4 ];
@ -220,50 +217,50 @@ real_t Dx0[ 4 ];
/** Matrix of size: 4 x 4 (row major format) */
real_t T[ 16 ];
/** Column vector of size: 840 */
real_t E[ 840 ];
/** Column vector of size: 544 */
real_t E[ 544 ];
/** Column vector of size: 840 */
real_t QE[ 840 ];
/** Column vector of size: 544 */
real_t QE[ 544 ];
/** Matrix of size: 80 x 4 (row major format) */
real_t QGx[ 320 ];
/** Matrix of size: 64 x 4 (row major format) */
real_t QGx[ 256 ];
/** Column vector of size: 80 */
real_t Qd[ 80 ];
/** Column vector of size: 64 */
real_t Qd[ 64 ];
/** Column vector of size: 84 */
real_t QDy[ 84 ];
/** Column vector of size: 68 */
real_t QDy[ 68 ];
/** Matrix of size: 20 x 4 (row major format) */
real_t H10[ 80 ];
/** Matrix of size: 16 x 4 (row major format) */
real_t H10[ 64 ];
/** Matrix of size: 24 x 24 (row major format) */
real_t H[ 576 ];
/** Matrix of size: 20 x 20 (row major format) */
real_t H[ 400 ];
/** Matrix of size: 40 x 24 (row major format) */
real_t A[ 960 ];
/** Matrix of size: 32 x 20 (row major format) */
real_t A[ 640 ];
/** Column vector of size: 24 */
real_t g[ 24 ];
/** Column vector of size: 20 */
real_t g[ 20 ];
/** Column vector of size: 24 */
real_t lb[ 24 ];
/** Column vector of size: 20 */
real_t lb[ 20 ];
/** Column vector of size: 24 */
real_t ub[ 24 ];
/** Column vector of size: 20 */
real_t ub[ 20 ];
/** Column vector of size: 40 */
real_t lbA[ 40 ];
/** Column vector of size: 32 */
real_t lbA[ 32 ];
/** Column vector of size: 40 */
real_t ubA[ 40 ];
/** Column vector of size: 32 */
real_t ubA[ 32 ];
/** Column vector of size: 24 */
real_t x[ 24 ];
/** Column vector of size: 20 */
real_t x[ 20 ];
/** Column vector of size: 64 */
real_t y[ 64 ];
/** Column vector of size: 52 */
real_t y[ 52 ];
} ACADOworkspace;
@ -314,7 +311,7 @@ void acado_initializeNodesByForwardSimulation( );
/** Shift differential variables vector by one interval.
*
* \param strategy Shifting strategy: 1. Initialize node 21 with xEnd. 2. Initialize node 21 by forward simulation.
* \param strategy Shifting strategy: 1. Initialize node 17 with xEnd. 2. Initialize node 17 by forward simulation.
* \param xEnd Value for the x vector on the last node. If =0 the old value is used.
* \param uEnd Value for the u vector on the second to last node. If =0 the old value is used.
*/

@ -25,38 +25,52 @@ void acado_rhs_forw(const real_t* in, real_t* out)
const real_t* xd = in;
const real_t* u = in + 24;
const real_t* od = in + 25;
/* Vector of auxiliary variables; number of elements: 14. */
/* Vector of auxiliary variables; number of elements: 28. */
real_t* a = acadoWorkspace.rhs_aux;
/* Compute intermediate quantities: */
a[0] = (cos(xd[2]));
a[1] = (sin(xd[2]));
a[2] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2])));
a[3] = (xd[12]*a[2]);
a[4] = (xd[13]*a[2]);
a[5] = (xd[14]*a[2]);
a[6] = (xd[15]*a[2]);
a[7] = (cos(xd[2]));
a[8] = (xd[12]*a[7]);
a[9] = (xd[13]*a[7]);
a[10] = (xd[14]*a[7]);
a[11] = (xd[15]*a[7]);
a[12] = (xd[22]*a[2]);
a[13] = (xd[22]*a[7]);
a[2] = (sin(xd[2]));
a[3] = (cos(xd[2]));
a[4] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2])));
a[5] = (xd[12]*a[4]);
a[6] = (cos(xd[2]));
a[7] = (xd[12]*a[6]);
a[8] = (xd[13]*a[4]);
a[9] = (xd[13]*a[6]);
a[10] = (xd[14]*a[4]);
a[11] = (xd[14]*a[6]);
a[12] = (xd[15]*a[4]);
a[13] = (xd[15]*a[6]);
a[14] = (cos(xd[2]));
a[15] = (xd[12]*a[14]);
a[16] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2])));
a[17] = (xd[12]*a[16]);
a[18] = (xd[13]*a[14]);
a[19] = (xd[13]*a[16]);
a[20] = (xd[14]*a[14]);
a[21] = (xd[14]*a[16]);
a[22] = (xd[15]*a[14]);
a[23] = (xd[15]*a[16]);
a[24] = (xd[22]*a[4]);
a[25] = (xd[22]*a[6]);
a[26] = (xd[22]*a[14]);
a[27] = (xd[22]*a[16]);
/* Compute outputs: */
out[0] = (od[1]*a[0]);
out[1] = (od[1]*a[1]);
out[0] = ((od[1]*a[0])-((od[2]*a[1])*((od[1]*xd[3])*od[0])));
out[1] = ((od[1]*a[2])+((od[2]*a[3])*((od[1]*xd[3])*od[0])));
out[2] = ((od[1]*xd[3])*od[0]);
out[3] = u[0];
out[4] = (od[1]*a[3]);
out[5] = (od[1]*a[4]);
out[6] = (od[1]*a[5]);
out[7] = (od[1]*a[6]);
out[8] = (od[1]*a[8]);
out[9] = (od[1]*a[9]);
out[10] = (od[1]*a[10]);
out[11] = (od[1]*a[11]);
out[4] = ((od[1]*a[5])-(((od[2]*a[7])*((od[1]*xd[3])*od[0]))+((od[2]*a[1])*((od[1]*xd[16])*od[0]))));
out[5] = ((od[1]*a[8])-(((od[2]*a[9])*((od[1]*xd[3])*od[0]))+((od[2]*a[1])*((od[1]*xd[17])*od[0]))));
out[6] = ((od[1]*a[10])-(((od[2]*a[11])*((od[1]*xd[3])*od[0]))+((od[2]*a[1])*((od[1]*xd[18])*od[0]))));
out[7] = ((od[1]*a[12])-(((od[2]*a[13])*((od[1]*xd[3])*od[0]))+((od[2]*a[1])*((od[1]*xd[19])*od[0]))));
out[8] = ((od[1]*a[15])+(((od[2]*a[17])*((od[1]*xd[3])*od[0]))+((od[2]*a[3])*((od[1]*xd[16])*od[0]))));
out[9] = ((od[1]*a[18])+(((od[2]*a[19])*((od[1]*xd[3])*od[0]))+((od[2]*a[3])*((od[1]*xd[17])*od[0]))));
out[10] = ((od[1]*a[20])+(((od[2]*a[21])*((od[1]*xd[3])*od[0]))+((od[2]*a[3])*((od[1]*xd[18])*od[0]))));
out[11] = ((od[1]*a[22])+(((od[2]*a[23])*((od[1]*xd[3])*od[0]))+((od[2]*a[3])*((od[1]*xd[19])*od[0]))));
out[12] = ((od[1]*xd[16])*od[0]);
out[13] = ((od[1]*xd[17])*od[0]);
out[14] = ((od[1]*xd[18])*od[0]);
@ -65,19 +79,19 @@ out[16] = (real_t)(0.0000000000000000e+00);
out[17] = (real_t)(0.0000000000000000e+00);
out[18] = (real_t)(0.0000000000000000e+00);
out[19] = (real_t)(0.0000000000000000e+00);
out[20] = (od[1]*a[12]);
out[21] = (od[1]*a[13]);
out[20] = ((od[1]*a[24])-(((od[2]*a[25])*((od[1]*xd[3])*od[0]))+((od[2]*a[1])*((od[1]*xd[23])*od[0]))));
out[21] = ((od[1]*a[26])+(((od[2]*a[27])*((od[1]*xd[3])*od[0]))+((od[2]*a[3])*((od[1]*xd[23])*od[0]))));
out[22] = ((od[1]*xd[23])*od[0]);
out[23] = (real_t)(1.0000000000000000e+00);
}
/* Fixed step size:0.05 */
/* Fixed step size:0.001 */
int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index )
{
int error;
int run1;
int numSteps[20] = {1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3};
int numSteps[16] = {10, 29, 49, 68, 88, 107, 127, 146, 166, 186, 205, 225, 244, 264, 283, 303};
int numInts = numSteps[rk_index];
acadoWorkspace.rk_ttt = 0.0000000000000000e+00;
rk_eta[4] = 1.0000000000000000e+00;
@ -104,20 +118,6 @@ acadoWorkspace.rk_xxx[24] = rk_eta[24];
acadoWorkspace.rk_xxx[25] = rk_eta[25];
acadoWorkspace.rk_xxx[26] = rk_eta[26];
acadoWorkspace.rk_xxx[27] = rk_eta[27];
acadoWorkspace.rk_xxx[28] = rk_eta[28];
acadoWorkspace.rk_xxx[29] = rk_eta[29];
acadoWorkspace.rk_xxx[30] = rk_eta[30];
acadoWorkspace.rk_xxx[31] = rk_eta[31];
acadoWorkspace.rk_xxx[32] = rk_eta[32];
acadoWorkspace.rk_xxx[33] = rk_eta[33];
acadoWorkspace.rk_xxx[34] = rk_eta[34];
acadoWorkspace.rk_xxx[35] = rk_eta[35];
acadoWorkspace.rk_xxx[36] = rk_eta[36];
acadoWorkspace.rk_xxx[37] = rk_eta[37];
acadoWorkspace.rk_xxx[38] = rk_eta[38];
acadoWorkspace.rk_xxx[39] = rk_eta[39];
acadoWorkspace.rk_xxx[40] = rk_eta[40];
acadoWorkspace.rk_xxx[41] = rk_eta[41];
for (run1 = 0; run1 < 1; ++run1)
{
@ -147,105 +147,105 @@ acadoWorkspace.rk_xxx[21] = + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + rk_eta[23];
acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk );
acadoWorkspace.rk_xxx[0] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[0] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[1] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[2] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[3] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[4] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[5] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[6] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[7] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[8] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[9] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[10] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[11] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[12] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[13] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[14] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[15] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[16] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[17] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[18] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[19] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[20] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[21] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[22] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[23] + rk_eta[23];
acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[0] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[1] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[2] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[3] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[4] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[5] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[6] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[7] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[8] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[9] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[10] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[11] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[12] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[13] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[14] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[15] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[16] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[17] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[18] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[19] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[20] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[21] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[22] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[23] + rk_eta[23];
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) );
acadoWorkspace.rk_xxx[0] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[24] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[25] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[26] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[27] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[28] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[29] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[30] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[31] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[32] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[33] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[34] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[35] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[36] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[37] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[38] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[39] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[40] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[41] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[42] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[43] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[44] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[45] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[46] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[47] + rk_eta[23];
acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[24] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[25] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[26] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[27] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[28] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[29] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[30] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[31] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[32] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[33] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[34] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[35] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[36] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[37] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[38] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[39] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[40] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[41] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[42] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[43] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[44] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[45] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[46] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[47] + rk_eta[23];
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) );
acadoWorkspace.rk_xxx[0] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[48] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[49] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[50] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[51] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[52] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[53] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[54] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[55] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[56] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[57] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[58] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[59] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[60] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[61] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[62] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[63] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[64] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[65] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[66] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[67] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[68] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[69] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[70] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[71] + rk_eta[23];
acadoWorkspace.rk_xxx[0] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[48] + rk_eta[0];
acadoWorkspace.rk_xxx[1] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[49] + rk_eta[1];
acadoWorkspace.rk_xxx[2] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[50] + rk_eta[2];
acadoWorkspace.rk_xxx[3] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[51] + rk_eta[3];
acadoWorkspace.rk_xxx[4] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[52] + rk_eta[4];
acadoWorkspace.rk_xxx[5] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[53] + rk_eta[5];
acadoWorkspace.rk_xxx[6] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[54] + rk_eta[6];
acadoWorkspace.rk_xxx[7] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[55] + rk_eta[7];
acadoWorkspace.rk_xxx[8] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[56] + rk_eta[8];
acadoWorkspace.rk_xxx[9] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[57] + rk_eta[9];
acadoWorkspace.rk_xxx[10] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[58] + rk_eta[10];
acadoWorkspace.rk_xxx[11] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[59] + rk_eta[11];
acadoWorkspace.rk_xxx[12] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[60] + rk_eta[12];
acadoWorkspace.rk_xxx[13] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[61] + rk_eta[13];
acadoWorkspace.rk_xxx[14] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[62] + rk_eta[14];
acadoWorkspace.rk_xxx[15] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[63] + rk_eta[15];
acadoWorkspace.rk_xxx[16] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[64] + rk_eta[16];
acadoWorkspace.rk_xxx[17] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[65] + rk_eta[17];
acadoWorkspace.rk_xxx[18] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[66] + rk_eta[18];
acadoWorkspace.rk_xxx[19] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[67] + rk_eta[19];
acadoWorkspace.rk_xxx[20] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[68] + rk_eta[20];
acadoWorkspace.rk_xxx[21] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[69] + rk_eta[21];
acadoWorkspace.rk_xxx[22] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[70] + rk_eta[22];
acadoWorkspace.rk_xxx[23] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[71] + rk_eta[23];
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) );
rk_eta[0] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[0] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[24] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[48] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[72];
rk_eta[1] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[1] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[25] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[49] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[73];
rk_eta[2] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[2] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[26] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[50] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[74];
rk_eta[3] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[3] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[27] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[51] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[75];
rk_eta[4] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[4] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[28] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[52] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[76];
rk_eta[5] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[5] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[29] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[53] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[77];
rk_eta[6] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[6] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[30] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[54] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[78];
rk_eta[7] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[7] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[31] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[55] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[79];
rk_eta[8] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[8] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[32] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[56] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[80];
rk_eta[9] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[9] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[33] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[57] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[81];
rk_eta[10] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[10] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[34] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[58] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[82];
rk_eta[11] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[11] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[35] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[59] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[83];
rk_eta[12] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[12] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[36] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[60] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[84];
rk_eta[13] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[13] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[37] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[61] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[85];
rk_eta[14] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[14] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[38] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[62] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[86];
rk_eta[15] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[15] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[39] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[63] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[87];
rk_eta[16] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[16] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[40] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[64] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[88];
rk_eta[17] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[17] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[41] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[65] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[89];
rk_eta[18] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[18] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[42] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[66] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[90];
rk_eta[19] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[19] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[43] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[67] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[91];
rk_eta[20] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[20] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[44] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[68] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[92];
rk_eta[21] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[21] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[45] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[69] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[93];
rk_eta[22] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[22] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[46] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[70] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[94];
rk_eta[23] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[23] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[47] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[71] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[95];
rk_eta[0] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[0] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[24] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[48] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[72];
rk_eta[1] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[1] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[25] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[49] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[73];
rk_eta[2] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[2] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[26] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[50] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[74];
rk_eta[3] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[3] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[27] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[51] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[75];
rk_eta[4] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[4] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[28] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[52] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[76];
rk_eta[5] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[5] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[29] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[53] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[77];
rk_eta[6] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[6] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[30] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[54] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[78];
rk_eta[7] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[7] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[31] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[55] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[79];
rk_eta[8] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[8] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[32] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[56] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[80];
rk_eta[9] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[9] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[33] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[57] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[81];
rk_eta[10] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[10] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[34] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[58] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[82];
rk_eta[11] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[11] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[35] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[59] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[83];
rk_eta[12] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[12] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[36] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[60] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[84];
rk_eta[13] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[13] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[37] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[61] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[85];
rk_eta[14] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[14] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[38] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[62] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[86];
rk_eta[15] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[15] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[39] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[63] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[87];
rk_eta[16] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[16] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[40] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[64] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[88];
rk_eta[17] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[17] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[41] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[65] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[89];
rk_eta[18] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[18] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[42] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[66] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[90];
rk_eta[19] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[19] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[43] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[67] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[91];
rk_eta[20] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[20] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[44] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[68] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[92];
rk_eta[21] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[21] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[45] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[69] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[93];
rk_eta[22] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[22] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[46] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[70] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[94];
rk_eta[23] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[23] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[47] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[71] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[95];
acadoWorkspace.rk_ttt += 1.0000000000000000e+00;
}
}

@ -40,7 +40,7 @@ int acado_solve( void )
{
acado_nWSR = QPOASES_NWSRMAX;
QProblem qp(24, 40);
QProblem qp(20, 32);
returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR, acadoWorkspace.y);

@ -37,11 +37,11 @@
*/
/** Maximum number of optimization variables. */
#define QPOASES_NVMAX 24
#define QPOASES_NVMAX 20
/** Maximum number of constraints. */
#define QPOASES_NCMAX 40
#define QPOASES_NCMAX 32
/** Maximum number of working set recalculations. */
#define QPOASES_NWSRMAX 500
#define QPOASES_NWSRMAX 1000
/** Print level for qpOASES. */
#define QPOASES_PRINTLEVEL PL_NONE
/** The value of EPS */

@ -9,23 +9,24 @@ libmpc_fn = os.path.join(mpc_dir, "libmpc"+suffix())
ffi = FFI()
ffi.cdef("""
typedef struct {
double x, y, psi, delta, t;
double x, y, psi, tire_angle, tire_angle_rate;
} state_t;
int N = 16;
typedef struct {
double x[21];
double y[21];
double psi[21];
double delta[21];
double rate[20];
double x[N+1];
double y[N+1];
double psi[N+1];
double tire_angle[N+1];
double tire_angle_rate[N];
double cost;
} log_t;
void init(double pathCost, double laneCost, double headingCost, double steerRateCost);
void init_weights(double pathCost, double laneCost, double headingCost, double steerRateCost);
void init(double pathCost, double headingCost, double steerRateCost);
void init_weights(double pathCost, double headingCost, double steerRateCost);
int run_mpc(state_t * x0, log_t * solution,
double l_poly[4], double r_poly[4], double d_poly[4],
double l_prob, double r_prob, double curvature_factor, double v_ref, double lane_width);
double v_ego, double curvature_factor, double rotation_radius,
double target_y[N+1], double target_psi[N+1]);
""")
libmpc = ffi.dlopen(libmpc_fn)

@ -1,10 +1,12 @@
import os
import math
import numpy as np
from common.realtime import sec_since_boot, DT_MDL
from common.numpy_fast import interp
from selfdrive.swaglog import cloudlog
from selfdrive.controls.lib.lateral_mpc import libmpc_py
from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT
from selfdrive.controls.lib.lane_planner import LanePlanner
from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT, MPC_N, CAR_ROTATION_RADIUS
from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE
from selfdrive.config import Conversions as CV
from common.params import Params
import cereal.messaging as messaging
@ -40,13 +42,6 @@ DESIRES = {
}
def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio, delay):
states[0].x = v_ego * delay
states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * delay
states[0].y = states[0].x * math.sin(states[0].psi / 2)
return states
class PathPlanner():
def __init__(self, CP):
self.LP = LanePlanner()
@ -63,40 +58,46 @@ class PathPlanner():
self.lane_change_ll_prob = 1.0
self.prev_one_blinker = False
self.path_xyz = np.zeros((TRAJECTORY_SIZE,3))
self.plan_yaw = np.zeros((TRAJECTORY_SIZE,))
self.t_idxs = np.arange(TRAJECTORY_SIZE)
def setup_mpc(self):
self.libmpc = libmpc_py.libmpc
self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, self.steer_rate_cost)
self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, self.steer_rate_cost)
self.mpc_solution = libmpc_py.ffi.new("log_t *")
self.cur_state = libmpc_py.ffi.new("state_t *")
self.cur_state[0].x = 0.0
self.cur_state[0].y = 0.0
self.cur_state[0].psi = 0.0
self.cur_state[0].delta = 0.0
self.cur_state[0].tire_angle = 0.0
self.angle_steers_des = 0.0
self.angle_steers_des_mpc = 0.0
self.angle_steers_des_prev = 0.0
self.angle_steers_des_time = 0.0
def update(self, sm, pm, CP, VM):
v_ego = sm['carState'].vEgo
angle_steers = sm['carState'].steeringAngle
active = sm['controlsState'].active
steering_wheel_angle_offset_deg = sm['liveParameters'].angleOffset
steering_wheel_angle_deg = sm['carState'].steeringAngle
measured_tire_angle = -math.radians(steering_wheel_angle_deg - steering_wheel_angle_offset_deg) / VM.sR
angle_offset = sm['liveParameters'].angleOffset
# Run MPC
self.angle_steers_des_prev = self.angle_steers_des_mpc
# Update vehicle model
x = max(sm['liveParameters'].stiffnessFactor, 0.1)
sr = max(sm['liveParameters'].steerRatio, 0.1)
VM.update_params(x, sr)
curvature_factor = VM.curvature_factor(v_ego)
self.LP.parse_model(sm['model'])
md = sm['modelV2']
self.LP.parse_model(sm['modelV2'])
if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE:
self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z])
self.t_idxs = np.array(md.position.t)
self.plan_yaw = list(md.orientation.z)
# Lane change logic
one_blinker = sm['carState'].leftBlinker != sm['carState'].rightBlinker
@ -161,36 +162,50 @@ class PathPlanner():
# Turn off lanes during lane change
if desire == log.PathPlan.Desire.laneChangeRight or desire == log.PathPlan.Desire.laneChangeLeft:
self.LP.l_prob *= self.lane_change_ll_prob
self.LP.r_prob *= self.lane_change_ll_prob
self.LP.update_d_poly(v_ego)
# account for actuation delay
self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers - angle_offset, curvature_factor, VM.sR, CP.steerActuatorDelay)
self.LP.lll_prob *= self.lane_change_ll_prob
self.LP.rll_prob *= self.lane_change_ll_prob
d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz)
y_pts = np.interp(v_ego * self.t_idxs[:MPC_N+1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:,1])
heading_pts = np.interp(v_ego * self.t_idxs[:MPC_N+1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw)
v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed
assert len(y_pts) == MPC_N + 1
assert len(heading_pts) == MPC_N + 1
self.libmpc.run_mpc(self.cur_state, self.mpc_solution,
list(self.LP.l_poly), list(self.LP.r_poly), list(self.LP.d_poly),
self.LP.l_prob, self.LP.r_prob, curvature_factor, v_ego_mpc, self.LP.lane_width)
float(v_ego_mpc),
curvature_factor,
CAR_ROTATION_RADIUS,
list(y_pts),
list(heading_pts))
# init state for next
self.cur_state.x = 0.0
self.cur_state.y = 0.0
self.cur_state.psi = 0.0
self.cur_state.tire_angle = interp(DT_MDL, self.t_idxs[:MPC_N+1], self.mpc_solution.tire_angle)
# TODO this needs more thought, use .2s extra for now to estimate other delays
delay = CP.steerActuatorDelay + .2
next_tire_angle = interp(DT_MDL + delay, self.t_idxs[:MPC_N+1], self.mpc_solution.tire_angle)
next_tire_angle_rate = interp(delay, self.t_idxs[:MPC_N], self.mpc_solution.tire_angle_rate)
# reset to current steer angle if not active or overriding
if active:
delta_desired = self.mpc_solution[0].delta[1]
rate_desired = math.degrees(self.mpc_solution[0].rate[0] * VM.sR)
tire_angle_desired = next_tire_angle
desired_tire_angle_rate = next_tire_angle_rate
else:
delta_desired = math.radians(angle_steers - angle_offset) / VM.sR
rate_desired = 0.0
self.cur_state[0].delta = delta_desired
tire_angle_desired = measured_tire_angle
desired_tire_angle_rate = 0.0
self.angle_steers_des_mpc = float(math.degrees(delta_desired * VM.sR) + angle_offset)
# negative sign, controls uses different convention
self.desired_steering_wheel_angle_deg = -float(math.degrees(tire_angle_desired * VM.sR)) + steering_wheel_angle_offset_deg
self.desired_steering_wheel_angle_rate_deg = -float(math.degrees(desired_tire_angle_rate * VM.sR))
# Check for infeasable MPC solution
mpc_nans = any(math.isnan(x) for x in self.mpc_solution[0].delta)
mpc_nans = any(math.isnan(x) for x in self.mpc_solution.tire_angle)
t = sec_since_boot()
if mpc_nans:
self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, CP.steerRateCost)
self.cur_state[0].delta = math.radians(angle_steers - angle_offset) / VM.sR
self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, CP.steerRateCost)
self.cur_state.tire_angle = measured_tire_angle
if t > self.last_cloudlog_t + 5.0:
self.last_cloudlog_t = t
@ -201,18 +216,16 @@ class PathPlanner():
else:
self.solution_invalid_cnt = 0
plan_solution_valid = self.solution_invalid_cnt < 2
plan_send = messaging.new_message('pathPlan')
plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'liveParameters', 'model'])
plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'liveParameters', 'modelV2'])
plan_send.pathPlan.laneWidth = float(self.LP.lane_width)
plan_send.pathPlan.dPoly = [float(x) for x in self.LP.d_poly]
plan_send.pathPlan.lPoly = [float(x) for x in self.LP.l_poly]
plan_send.pathPlan.lProb = float(self.LP.l_prob)
plan_send.pathPlan.rPoly = [float(x) for x in self.LP.r_poly]
plan_send.pathPlan.rProb = float(self.LP.r_prob)
plan_send.pathPlan.angleSteers = float(self.angle_steers_des_mpc)
plan_send.pathPlan.rateSteers = float(rate_desired)
plan_send.pathPlan.dPathPoints = [float(x) for x in y_pts]
plan_send.pathPlan.lProb = float(self.LP.lll_prob)
plan_send.pathPlan.rProb = float(self.LP.rll_prob)
plan_send.pathPlan.dProb = float(self.LP.d_prob)
plan_send.pathPlan.angleSteers = float(self.desired_steering_wheel_angle_deg)
plan_send.pathPlan.rateSteers = float(self.desired_steering_wheel_angle_rate_deg)
plan_send.pathPlan.angleOffset = float(sm['liveParameters'].angleOffsetAverage)
plan_send.pathPlan.mpcSolutionValid = bool(plan_solution_valid)
plan_send.pathPlan.paramsValid = bool(sm['liveParameters'].valid)
@ -228,6 +241,6 @@ class PathPlanner():
dat.liveMpc.x = list(self.mpc_solution[0].x)
dat.liveMpc.y = list(self.mpc_solution[0].y)
dat.liveMpc.psi = list(self.mpc_solution[0].psi)
dat.liveMpc.delta = list(self.mpc_solution[0].delta)
dat.liveMpc.tire_angle = list(self.mpc_solution[0].tire_angle)
dat.liveMpc.cost = self.mpc_solution[0].cost
pm.send('liveMpc', dat)

@ -186,7 +186,7 @@ class Planner():
plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'radarState'])
plan_send.plan.mdMonoTime = sm.logMonoTime['model']
plan_send.plan.mdMonoTime = sm.logMonoTime['modelV2']
plan_send.plan.radarStateMonoTime = sm.logMonoTime['radarState']
# longitudal plan

@ -23,8 +23,8 @@ def plannerd_thread(sm=None, pm=None):
VM = VehicleModel(CP)
if sm is None:
sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'model', 'liveParameters'],
poll=['radarState', 'model'])
sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'modelV2', 'liveParameters'],
poll=['radarState', 'modelV2'])
if pm is None:
pm = messaging.PubMaster(['plan', 'liveLongitudinalMpc', 'pathPlan', 'liveMpc'])
@ -37,7 +37,7 @@ def plannerd_thread(sm=None, pm=None):
while True:
sm.update()
if sm.updated['model']:
if sm.updated['modelV2']:
PP.update(sm, pm, CP, VM)
if sm.updated['radarState']:
PL.update(sm, pm, CP, VM, PP)

@ -3,74 +3,62 @@ import numpy as np
from selfdrive.car.honda.interface import CarInterface
from selfdrive.controls.lib.lateral_mpc import libmpc_py
from selfdrive.controls.lib.vehicle_model import VehicleModel
from selfdrive.controls.lib.drive_helpers import MPC_N, CAR_ROTATION_RADIUS
def run_mpc(v_ref=30., x_init=0., y_init=0., psi_init=0., delta_init=0.,
l_prob=1., r_prob=1., p_prob=1.,
poly_l=np.array([0., 0., 0., 1.8]), poly_r=np.array([0., 0., 0., -1.8]), poly_p=np.array([0., 0., 0., 0.]),
def run_mpc(v_ref=30., x_init=0., y_init=0., psi_init=0., tire_angle_init=0.,
lane_width=3.6, poly_shift=0.):
libmpc = libmpc_py.libmpc
libmpc.init(1.0, 3.0, 1.0, 1.0)
libmpc.init(1.0, 1.0, 1.0)
mpc_solution = libmpc_py.ffi.new("log_t *")
p_l = poly_l.copy()
p_l[3] += poly_shift
p_r = poly_r.copy()
p_r[3] += poly_shift
p_p = poly_p.copy()
p_p[3] += poly_shift
d_poly = p_p
y_pts = poly_shift * np.ones(MPC_N + 1)
heading_pts = np.zeros(MPC_N + 1)
CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING")
VM = VehicleModel(CP)
curvature_factor = VM.curvature_factor(v_ref)
l_poly = libmpc_py.ffi.new("double[4]", list(map(float, p_l)))
r_poly = libmpc_py.ffi.new("double[4]", list(map(float, p_r)))
d_poly = libmpc_py.ffi.new("double[4]", list(map(float, d_poly)))
cur_state = libmpc_py.ffi.new("state_t *")
cur_state[0].x = x_init
cur_state[0].y = y_init
cur_state[0].psi = psi_init
cur_state[0].delta = delta_init
cur_state.x = x_init
cur_state.y = y_init
cur_state.psi = psi_init
cur_state.tire_angle = tire_angle_init
# converge in no more than 20 iterations
for _ in range(20):
libmpc.run_mpc(cur_state, mpc_solution, l_poly, r_poly, d_poly, l_prob, r_prob,
curvature_factor, v_ref, lane_width)
libmpc.run_mpc(cur_state, mpc_solution, v_ref,
curvature_factor, CAR_ROTATION_RADIUS,
list(y_pts), list(heading_pts))
return mpc_solution
class TestLateralMpc(unittest.TestCase):
def _assert_null(self, sol, delta=1e-6):
def _assert_null(self, sol, tire_angle=1e-6):
for i in range(len(sol[0].y)):
self.assertAlmostEqual(sol[0].y[i], 0., delta=delta)
self.assertAlmostEqual(sol[0].psi[i], 0., delta=delta)
self.assertAlmostEqual(sol[0].delta[i], 0., delta=delta)
self.assertAlmostEqual(sol[0].y[i], 0., delta=tire_angle)
self.assertAlmostEqual(sol[0].psi[i], 0., delta=tire_angle)
self.assertAlmostEqual(sol[0].tire_angle[i], 0., delta=tire_angle)
def _assert_simmetry(self, sol, delta=1e-6):
def _assert_simmetry(self, sol, tire_angle=1e-6):
for i in range(len(sol[0][0].y)):
self.assertAlmostEqual(sol[0][0].y[i], -sol[1][0].y[i], delta=delta)
self.assertAlmostEqual(sol[0][0].psi[i], -sol[1][0].psi[i], delta=delta)
self.assertAlmostEqual(sol[0][0].delta[i], -sol[1][0].delta[i], delta=delta)
self.assertAlmostEqual(sol[0][0].x[i], sol[1][0].x[i], delta=delta)
self.assertAlmostEqual(sol[0][0].y[i], -sol[1][0].y[i], delta=tire_angle)
self.assertAlmostEqual(sol[0][0].psi[i], -sol[1][0].psi[i], delta=tire_angle)
self.assertAlmostEqual(sol[0][0].tire_angle[i], -sol[1][0].tire_angle[i], delta=tire_angle)
self.assertAlmostEqual(sol[0][0].x[i], sol[1][0].x[i], delta=tire_angle)
def _assert_identity(self, sol, ignore_y=False, delta=1e-6):
def _assert_identity(self, sol, ignore_y=False, tire_angle=1e-6):
for i in range(len(sol[0][0].y)):
self.assertAlmostEqual(sol[0][0].psi[i], sol[1][0].psi[i], delta=delta)
self.assertAlmostEqual(sol[0][0].delta[i], sol[1][0].delta[i], delta=delta)
self.assertAlmostEqual(sol[0][0].x[i], sol[1][0].x[i], delta=delta)
self.assertAlmostEqual(sol[0][0].psi[i], sol[1][0].psi[i], delta=tire_angle)
self.assertAlmostEqual(sol[0][0].tire_angle[i], sol[1][0].tire_angle[i], delta=tire_angle)
self.assertAlmostEqual(sol[0][0].x[i], sol[1][0].x[i], delta=tire_angle)
if not ignore_y:
self.assertAlmostEqual(sol[0][0].y[i], sol[1][0].y[i], delta=delta)
self.assertAlmostEqual(sol[0][0].y[i], sol[1][0].y[i], delta=tire_angle)
def test_straight(self):
sol = run_mpc()
@ -88,10 +76,10 @@ class TestLateralMpc(unittest.TestCase):
sol.append(run_mpc(poly_shift=poly_shift))
self._assert_simmetry(sol)
def test_delta_symmetry(self):
def test_tire_angle_symmetry(self):
sol = []
for delta_init in [-0.1, 0.1]:
sol.append(run_mpc(delta_init=delta_init))
for tire_angle_init in [-0.1, 0.1]:
sol.append(run_mpc(tire_angle_init=tire_angle_init))
self._assert_simmetry(sol)
def test_psi_symmetry(self):
@ -100,21 +88,14 @@ class TestLateralMpc(unittest.TestCase):
sol.append(run_mpc(psi_init=psi_init))
self._assert_simmetry(sol)
def test_prob_symmetry(self):
sol = []
lane_width = 3.
for r_prob in [0., 1.]:
sol.append(run_mpc(r_prob=r_prob, l_prob=1.-r_prob, lane_width=lane_width))
self._assert_simmetry(sol)
def test_y_shift_vs_poly_shift(self):
shift = 1.
sol = []
sol.append(run_mpc(y_init=shift))
sol.append(run_mpc(poly_shift=-shift))
# need larger delta than standard, otherwise it false triggers.
# need larger tire_angle than standard, otherwise it false triggers.
# this is acceptable because the 2 cases are very different from the optimizer standpoint
self._assert_identity(sol, ignore_y=True, delta=1e-5)
self._assert_identity(sol, ignore_y=True, tire_angle=1e-5)
def test_no_overshoot(self):
y_init = 1.

@ -0,0 +1,92 @@
#!/usr/bin/env python3
import os
import time
from multiprocessing import Process
from tqdm import tqdm
os.environ['TESTING_CLOSET'] = '1'
os.environ['FILEREADER_CACHE'] = '1'
from common.realtime import config_realtime_process, Ratekeeper
from selfdrive.boardd.boardd import can_capnp_to_can_list
from selfdrive.pandad import set_panda_power
from tools.lib.logreader import LogReader
from panda import Panda
try:
from panda_jungle import PandaJungle # pylint: disable=import-error
except Exception:
PandaJungle = None # type: ignore
ROUTE = "77611a1fac303767/2020-03-24--09-50-38"
NUM_SEGS = 2 # route has 82 segments available
print("Loading log...")
CAN_MSGS = []
for i in tqdm(list(range(1, NUM_SEGS+1))):
log_url = f"https://commadataci.blob.core.windows.net/openpilotci/{ROUTE}/{i}/rlog.bz2"
lr = LogReader(log_url)
CAN_MSGS += [can_capnp_to_can_list(m.can) for m in lr if m.which() == 'can']
def send_thread(sender, core):
config_realtime_process(core, 55)
if "Jungle" in str(type(sender)):
for i in [0, 1, 2, 3, 0xFFFF]:
sender.can_clear(i)
sender.set_ignition(False)
time.sleep(5)
sender.set_ignition(True)
sender.set_panda_power(True)
else:
sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
sender.set_can_loopback(False)
log_idx = 0
rk = Ratekeeper(100)
while True:
snd = CAN_MSGS[log_idx]
log_idx = (log_idx + 1) % len(CAN_MSGS)
snd = list(filter(lambda x: x[-1] <= 2, snd))
sender.can_send_many(snd)
# Drain panda message buffer
sender.can_recv()
rk.keep_time()
def connect():
serials = {}
while True:
# look for new devices
for p in [Panda, PandaJungle]:
if p is None:
continue
for s in p.list():
if s not in serials:
print("starting send thread for", s)
serials[s] = Process(target=send_thread, args=(p(s), 3))
serials[s].start()
# try to join all send procs
cur_serials = serials.copy()
for s, p in cur_serials.items():
p.join(0.01)
if p.exitcode is not None:
del serials[s]
time.sleep(1)
if __name__ == "__main__":
set_panda_power(False)
time.sleep(1)
if "FLASH" in os.environ and PandaJungle is not None:
for s in PandaJungle.list():
PandaJungle(s).flash()
while True:
try:
connect()
except Exception:
pass

@ -75,7 +75,7 @@ def mpc_vwr_thread(addr="127.0.0.1"):
r_path_y = np.polyval(l_poly, path_x)
if pp is not None:
p_path_y = np.polyval(pp.pathPlan.dPoly, path_x)
p_path_y = np.polyval(pp.pathPlan.dPolyDEPRECATED, path_x)
lineP.set_xdata(p_path_y)
lineP.set_ydata(path_x)

@ -2,11 +2,11 @@
# type: ignore
import matplotlib.pyplot as plt
from selfdrive.controls.lib.lateral_mpc import libmpc_py
from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT
from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT, MPC_N, CAR_ROTATION_RADIUS
import math
libmpc = libmpc_py.libmpc
libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, 1.)
libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, 1.)
cur_state = libmpc_py.ffi.new("state_t *")
cur_state[0].x = 0.0
@ -24,30 +24,15 @@ times = []
curvature_factor = 0.3
v_ref = 1.0 * 20.12 # 45 mph
LANE_WIDTH = 3.7
p = [0.0, 0.0, 0.0, 0.0]
p_l = p[:]
p_l[3] += LANE_WIDTH / 2.0
p_r = p[:]
p_r[3] -= LANE_WIDTH / 2.0
l_poly = libmpc_py.ffi.new("double[4]", p_l)
r_poly = libmpc_py.ffi.new("double[4]", p_r)
p_poly = libmpc_py.ffi.new("double[4]", p)
l_prob = 1.0
r_prob = 1.0
p_prob = 1.0
for i in range(1):
cur_state[0].delta = math.radians(510. / 13.)
libmpc.run_mpc(cur_state, mpc_solution, l_poly, r_poly, p_poly, l_prob, r_prob,
curvature_factor, v_ref, LANE_WIDTH)
libmpc.run_mpc(cur_state, mpc_solution, [0,0,0,v_ref],
curvature_factor, CAR_ROTATION_RADIUS,
[0.0]*MPC_N, [0.0]*MPC_N)
timesi = []
ct = 0
for i in range(21):
for i in range(MPC_N + 1):
timesi.append(ct)
if i <= 4:
ct += 0.05

@ -0,0 +1,22 @@
#!/usr/bin/bash
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
cd $DIR
if [ ! -d "$DIR/clpeak" ]; then
git clone https://github.com/krrishnarraj/clpeak.git
cd clpeak
git fetch
git checkout ec2d3e70e1abc7738b81f9277c7af79d89b2133b
git reset --hard origin/master
git submodule update --init --recursive --remote
git apply ../run_continuously.patch
fi
cd clpeak
mkdir build || true
cd build
cmake ..
cmake --build .

@ -0,0 +1,13 @@
diff --git a/src/clpeak.cpp b/src/clpeak.cpp
index 8cb192b..b6fe6f5 100644
--- a/src/clpeak.cpp
+++ b/src/clpeak.cpp
@@ -47,7 +47,7 @@ int clPeak::runAll()
log->xmlOpenTag("clpeak");
log->xmlAppendAttribs("os", OS_NAME);
- for (size_t p = 0; p < platforms.size(); p++)
+ for (size_t p = 0; p < platforms.size(); (p+1 % platforms.size()))
{
if (forcePlatform && (p != specifiedPlatform))
continue;

@ -1,7 +1,9 @@
Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon')
src = ['loggerd.cc', 'logger.cc']
libs = ['zmq', 'capnp', 'kj', 'z',
logger_lib = env.Library('logger', ["logger.cc"])
src = ['loggerd.cc']
libs = [logger_lib, 'zmq', 'capnp', 'kj', 'z',
'avformat', 'avcodec', 'swscale', 'avutil',
'yuv', 'bz2', 'OpenCL', common, cereal, messaging, visionipc]
@ -22,3 +24,4 @@ if arch == "Darwin":
env['FRAMEWORKS'] = ['OpenCL']
env.Program(src, LIBS=libs)
env.Program('bootlog.cc', LIBS=libs)

@ -0,0 +1,37 @@
#include <assert.h>
#include <string>
#include "common/swaglog.h"
#include "common/util.h"
#include "logger.h"
#include "messaging.hpp"
int main(int argc, char** argv) {
LoggerState logger;
logger_init(&logger, "bootlog", false);
char segment_path[4096];
int err = logger_next(&logger, LOG_ROOT.c_str(), segment_path, sizeof(segment_path), nullptr);
assert(err == 0);
LOGW("bootlog to %s", segment_path);
MessageBuilder msg;
auto boot = msg.initEvent().initBoot();
boot.setWallTimeNanos(nanos_since_epoch());
std::string lastKmsg = util::read_file("/sys/fs/pstore/console-ramoops");
boot.setLastKmsg(capnp::Data::Reader((const kj::byte*)lastKmsg.data(), lastKmsg.size()));
std::string lastPmsg = util::read_file("/sys/fs/pstore/pmsg-ramoops-0");
boot.setLastPmsg(capnp::Data::Reader((const kj::byte*)lastPmsg.data(), lastPmsg.size()));
std::string launchLog = util::read_file("/tmp/launch_log");
boot.setLaunchLog(capnp::Text::Reader(launchLog.data(), launchLog.size()));
auto bytes = msg.toBytes();
logger_log(&logger, bytes.begin(), bytes.size(), false);
logger_close(&logger);
return 0;
}

@ -12,12 +12,99 @@
#include <pthread.h>
#include <bzlib.h>
#include <iostream>
#include <fstream>
#include <streambuf>
#ifdef QCOM
#include <cutils/properties.h>
#endif
#include "messaging.hpp"
#include "common/swaglog.h"
#include "common/params.h"
#include "common/util.h"
#include "common/version.h"
#include "logger.h"
void append_property(const char* key, const char* value, void *cookie) {
std::vector<std::pair<std::string, std::string> > *properties =
(std::vector<std::pair<std::string, std::string> > *)cookie;
properties->push_back(std::make_pair(std::string(key), std::string(value)));
}
void log_init_data(LoggerState *s) {
MessageBuilder msg;
auto init = msg.initEvent().initInitData();
if (util::file_exists("/EON")) {
init.setDeviceType(cereal::InitData::DeviceType::NEO);
} else if (util::file_exists("/TICI")) {
init.setDeviceType(cereal::InitData::DeviceType::TICI);
} else {
init.setDeviceType(cereal::InitData::DeviceType::PC);
}
init.setVersion(capnp::Text::Reader(COMMA_VERSION));
std::ifstream cmdline_stream("/proc/cmdline");
std::vector<std::string> kernel_args;
std::string buf;
while (cmdline_stream >> buf) {
kernel_args.push_back(buf);
}
auto lkernel_args = init.initKernelArgs(kernel_args.size());
for (int i=0; i<kernel_args.size(); i++) {
lkernel_args.set(i, kernel_args[i]);
}
init.setKernelVersion(util::read_file("/proc/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
const char* dongle_id = getenv("DONGLE_ID");
if (dongle_id) {
init.setDongleId(std::string(dongle_id));
}
init.setDirty(!getenv("CLEAN"));
// log params
Params params = Params();
init.setGitCommit(params.get("GitCommit"));
init.setGitBranch(params.get("GitBranch"));
init.setGitRemote(params.get("GitRemote"));
init.setPassive(params.read_db_bool("Passive"));
{
std::map<std::string, std::string> params_map;
params.read_db_all(&params_map);
auto lparams = init.initParams().initEntries(params_map.size());
int i = 0;
for (auto& kv : params_map) {
auto lentry = lparams[i];
lentry.setKey(kv.first);
lentry.setValue(kv.second);
i++;
}
}
auto bytes = msg.toBytes();
logger_log(s, bytes.begin(), bytes.size(), s->has_qlog);
}
static void log_sentinel(LoggerState *s, cereal::Sentinel::SentinelType type) {
MessageBuilder msg;
auto sen = msg.initEvent().initSentinel();
@ -43,15 +130,9 @@ static int mkpath(char* file_path) {
return 0;
}
void logger_init(LoggerState *s, const char* log_name, const uint8_t* init_data, size_t init_data_len, bool has_qlog) {
void logger_init(LoggerState *s, const char* log_name, bool has_qlog) {
memset(s, 0, sizeof(*s));
if (init_data) {
s->init_data = (uint8_t*)malloc(init_data_len);
assert(s->init_data);
memcpy(s->init_data, init_data, init_data_len);
s->init_data_len = init_data_len;
}
umask(0);
pthread_mutex_init(&s->lock, NULL);
@ -110,20 +191,10 @@ static LoggerHandle* logger_open(LoggerState *s, const char* root_path) {
h->bz_qlog = BZ2_bzWriteOpen(&bzerror, h->qlog_file, 9, 0, 30);
if (bzerror != BZ_OK) goto fail;
}
if (s->init_data) {
BZ2_bzWrite(&bzerror, h->bz_file, s->init_data, s->init_data_len);
if (bzerror != BZ_OK) goto fail;
if (s->has_qlog) {
// init data goes in the qlog too
BZ2_bzWrite(&bzerror, h->bz_qlog, s->init_data, s->init_data_len);
if (bzerror != BZ_OK) goto fail;
}
}
pthread_mutex_init(&h->lock, NULL);
h->refcnt++;
log_init_data(s);
return h;
fail:
LOGE("logger failed to open files");
@ -203,7 +274,6 @@ void logger_close(LoggerState *s) {
log_sentinel(s, cereal::Sentinel::SentinelType::END_OF_ROUTE);
pthread_mutex_lock(&s->lock);
free(s->init_data);
if (s->cur_handle) {
lh_close(s->cur_handle);
}

@ -1,13 +1,16 @@
#ifndef LOGGER_H
#define LOGGER_H
#pragma once
#include <stdio.h>
#include <stdint.h>
#include <pthread.h>
#include <bzlib.h>
#include <kj/array.h>
#include <capnp/serialize.h>
#ifdef __cplusplus
extern "C" {
#if defined(QCOM) || defined(QCOM2)
const std::string LOG_ROOT = "/data/media/0/realdata";
#else
const std::string LOG_ROOT = util::getenv_default("HOME", "/.comma/media/0/realdata", "/data/media/0/realdata");
#endif
#define LOGGER_MAX_HANDLES 16
@ -28,10 +31,6 @@ typedef struct LoggerHandle {
typedef struct LoggerState {
pthread_mutex_t lock;
uint8_t* init_data;
size_t init_data_len;
int part;
char route_name[64];
char log_name[64];
@ -41,7 +40,7 @@ typedef struct LoggerState {
LoggerHandle* cur_handle;
} LoggerState;
void logger_init(LoggerState *s, const char* log_name, const uint8_t* init_data, size_t init_data_len, bool has_qlog);
void logger_init(LoggerState *s, const char* log_name, bool has_qlog);
int logger_next(LoggerState *s, const char* root_path,
char* out_segment_path, size_t out_segment_path_len,
int* out_part);
@ -51,9 +50,3 @@ void logger_log(LoggerState *s, uint8_t* data, size_t data_size, bool in_qlog);
void lh_log(LoggerHandle* h, uint8_t* data, size_t data_size, bool in_qlog);
void lh_close(LoggerHandle* h);
#ifdef __cplusplus
}
#endif
#endif

@ -10,9 +10,7 @@
#include <sys/resource.h>
#include <string>
#include <iostream>
#include <fstream>
#include <streambuf>
#include <thread>
#include <mutex>
#include <condition_variable>
@ -20,11 +18,6 @@
#include <random>
#include <ftw.h>
#ifdef QCOM
#include <cutils/properties.h>
#endif
#include "common/version.h"
#include "common/timing.h"
#include "common/params.h"
#include "common/swaglog.h"
@ -107,11 +100,6 @@ LogCameraInfo cameras_logged[LOG_CAMERA_ID_MAX] = {
namespace {
constexpr int SEGMENT_LENGTH = 60;
#if defined(QCOM) || defined(QCOM2)
std::string LOG_ROOT = "/data/media/0/realdata";
#else
std::string LOG_ROOT = util::getenv_default("HOME", "/.comma/media/0/realdata", "/data/media/0/realdata");
#endif
double randrange(double a, double b) __attribute__((unused));
double randrange(double a, double b) {
@ -123,11 +111,6 @@ double randrange(double a, double b) {
ExitHandler do_exit;
static bool file_exists(const std::string& fn) {
std::ifstream f(fn);
return f.good();
}
class RotateState {
public:
SubSocket* fpkt_sock;
@ -328,82 +311,6 @@ void encoder_thread(int cam_idx) {
}
void append_property(const char* key, const char* value, void *cookie) {
std::vector<std::pair<std::string, std::string> > *properties =
(std::vector<std::pair<std::string, std::string> > *)cookie;
properties->push_back(std::make_pair(std::string(key), std::string(value)));
}
kj::Array<capnp::word> gen_init_data() {
MessageBuilder msg;
auto init = msg.initEvent().initInitData();
if (file_exists("/EON")) {
init.setDeviceType(cereal::InitData::DeviceType::NEO);
} else if (file_exists("/TICI")) {
init.setDeviceType(cereal::InitData::DeviceType::TICI);
} else {
init.setDeviceType(cereal::InitData::DeviceType::PC);
}
init.setVersion(capnp::Text::Reader(COMMA_VERSION));
std::ifstream cmdline_stream("/proc/cmdline");
std::vector<std::string> kernel_args;
std::string buf;
while (cmdline_stream >> buf) {
kernel_args.push_back(buf);
}
auto lkernel_args = init.initKernelArgs(kernel_args.size());
for (int i=0; i<kernel_args.size(); i++) {
lkernel_args.set(i, kernel_args[i]);
}
init.setKernelVersion(util::read_file("/proc/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
const char* dongle_id = getenv("DONGLE_ID");
if (dongle_id) {
init.setDongleId(std::string(dongle_id));
}
init.setDirty(!getenv("CLEAN"));
// log params
Params params = Params();
init.setGitCommit(params.get("GitCommit"));
init.setGitBranch(params.get("GitBranch"));
init.setGitRemote(params.get("GitRemote"));
init.setPassive(params.read_db_bool("Passive"));
{
std::map<std::string, std::string> params_map;
params.read_db_all(&params_map);
auto lparams = init.initParams().initEntries(params_map.size());
int i = 0;
for (auto& kv : params_map) {
auto lentry = lparams[i];
lentry.setKey(kv.first);
lentry.setValue(kv.second);
i++;
}
}
return capnp::messageToFlatArray(msg);
}
static int clear_locks_fn(const char* fpath, const struct stat *sb, int tyupeflag) {
const char* dot = strrchr(fpath, '.');
if (dot && strcmp(dot, ".lock") == 0) {
@ -416,60 +323,15 @@ static void clear_locks() {
ftw(LOG_ROOT.c_str(), clear_locks_fn, 16);
}
static void bootlog() {
int err;
{
auto words = gen_init_data();
auto bytes = words.asBytes();
logger_init(&s.logger, "bootlog", bytes.begin(), bytes.size(), false);
}
err = logger_next(&s.logger, LOG_ROOT.c_str(), s.segment_path, sizeof(s.segment_path), &s.rotate_segment);
assert(err == 0);
LOGW("bootlog to %s", s.segment_path);
{
MessageBuilder msg;
auto boot = msg.initEvent().initBoot();
boot.setWallTimeNanos(nanos_since_epoch());
std::string lastKmsg = util::read_file("/sys/fs/pstore/console-ramoops");
boot.setLastKmsg(capnp::Data::Reader((const kj::byte*)lastKmsg.data(), lastKmsg.size()));
std::string lastPmsg = util::read_file("/sys/fs/pstore/pmsg-ramoops-0");
boot.setLastPmsg(capnp::Data::Reader((const kj::byte*)lastPmsg.data(), lastPmsg.size()));
std::string launchLog = util::read_file("/tmp/launch_log");
boot.setLaunchLog(capnp::Text::Reader(launchLog.data(), launchLog.size()));
auto bytes = msg.toBytes();
logger_log(&s.logger, bytes.begin(), bytes.size(), false);
}
logger_close(&s.logger);
}
int main(int argc, char** argv) {
setpriority(PRIO_PROCESS, 0, -12);
if (argc > 1 && strcmp(argv[1], "--bootlog") == 0) {
bootlog();
return 0;
}
int segment_length = SEGMENT_LENGTH;
if (getenv("LOGGERD_TEST")) {
segment_length = atoi(getenv("LOGGERD_SEGMENT_LENGTH"));
}
bool record_front = true;
#ifndef QCOM2
record_front = Params().read_db_bool("RecordFront");
#endif
clear_locks();
// setup messaging
@ -500,11 +362,7 @@ int main(int argc, char** argv) {
}
// init logger
{
auto words = gen_init_data();
auto bytes = words.asBytes();
logger_init(&s.logger, "rlog", bytes.begin(), bytes.size(), true);
}
logger_init(&s.logger, "rlog", true);
// init encoders
pthread_mutex_init(&s.rotate_lock, NULL);
@ -515,6 +373,7 @@ int main(int argc, char** argv) {
s.rotate_state[LOG_CAMERA_ID_FCAMERA].enabled = true;
#if defined(QCOM) || defined(QCOM2)
bool record_front = Params().read_db_bool("RecordFront");
if (record_front) {
encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_DCAMERA));
s.rotate_state[LOG_CAMERA_ID_DCAMERA].enabled = true;
@ -555,7 +414,10 @@ int main(int argc, char** argv) {
}
bytes_count += msg->getSize();
msg_count++;
if ((++msg_count % 1000) == 0) {
double ts = seconds_since_boot();
LOGD("%lu messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count * 1.0 / (ts - start_ts), bytes_count * 0.001 / (ts - start_ts));
}
}
if (last_msg) {
@ -622,20 +484,12 @@ int main(int argc, char** argv) {
int err = logger_next(&s.logger, LOG_ROOT.c_str(), s.segment_path, sizeof(s.segment_path), &s.rotate_segment);
assert(err == 0);
if (s.logger.part == 0) {
LOGW("logging to %s", s.segment_path);
}
LOGW("rotated to %s", s.segment_path);
LOGW((s.logger.part == 0) ? "logging to %s" : "rotated to %s", s.segment_path);
// rotate encoders
for (auto &r : s.rotate_state) r.rotate();
pthread_mutex_unlock(&s.rotate_lock);
}
if ((msg_count % 1000) == 0) {
double ts = seconds_since_boot();
LOGD("%lu messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count*1.0/(ts-start_ts), bytes_count*0.001/(ts-start_ts));
}
}
LOGW("closing encoders");

@ -23,6 +23,11 @@
#include "omx_encoder.h"
// Check the OMX error code and assert if an error occurred.
#define OMX_CHECK(_expr) \
do { \
assert(OMX_ErrorNone == _expr); \
} while (0)
// ***** OMX callback functions *****
@ -159,8 +164,6 @@ static const char* omx_color_fomat_name(uint32_t format) {
// ***** encoder functions *****
OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int bitrate, bool h265, bool downscale) {
int err;
this->filename = filename;
this->width = width;
this->height = height;
@ -182,7 +185,7 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
}
auto component = (OMX_STRING)(h265 ? "OMX.qcom.video.encoder.hevc" : "OMX.qcom.video.encoder.avc");
err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks);
int err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks);
if (err != OMX_ErrorNone) {
LOGE("error getting codec: %x", err);
}
@ -194,9 +197,7 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
OMX_PARAM_PORTDEFINITIONTYPE in_port = {0};
in_port.nSize = sizeof(in_port);
in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN;
err = OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR) &in_port);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
in_port.format.video.nFrameWidth = this->width;
in_port.format.video.nFrameHeight = this->height;
@ -209,24 +210,16 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
// in_port.format.video.eColorFormat = OMX_COLOR_FormatYUV420SemiPlanar;
in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m;
err = OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR) &in_port);
assert(err == OMX_ErrorNone);
err = OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR) &in_port);
assert(err == OMX_ErrorNone);
this->num_in_bufs = in_port.nBufferCountActual;
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
this->in_buf_headers.resize(in_port.nBufferCountActual);
// setup output port
OMX_PARAM_PORTDEFINITIONTYPE out_port = {0};
out_port.nSize = sizeof(out_port);
out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
err = OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR)&out_port);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port));
out_port.format.video.nFrameWidth = this->width;
out_port.format.video.nFrameHeight = this->height;
out_port.format.video.xFramerate = 0;
@ -238,28 +231,19 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
}
out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused;
err = OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR) &out_port);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port));
err = OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition,
(OMX_PTR) &out_port);
assert(err == OMX_ErrorNone);
this->num_out_bufs = out_port.nBufferCountActual;
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port));
this->out_buf_headers.resize(out_port.nBufferCountActual);
OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0};
bitrate_type.nSize = sizeof(bitrate_type);
bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
err = OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate,
(OMX_PTR) &bitrate_type);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type));
bitrate_type.eControlRate = OMX_Video_ControlRateVariable;
bitrate_type.nTargetBitrate = bitrate;
err = OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate,
(OMX_PTR) &bitrate_type);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type));
if (h265) {
// setup HEVC
@ -272,23 +256,18 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
#endif
hevc_type.nSize = sizeof(hevc_type);
hevc_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
err = OMX_GetParameter(this->handle, index_type,
(OMX_PTR) &hevc_type);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_GetParameter(this->handle, index_type, (OMX_PTR) &hevc_type));
hevc_type.eProfile = OMX_VIDEO_HEVCProfileMain;
hevc_type.eLevel = OMX_VIDEO_HEVCHighTierLevel5;
err = OMX_SetParameter(this->handle, index_type,
(OMX_PTR) &hevc_type);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SetParameter(this->handle, index_type, (OMX_PTR) &hevc_type));
} else {
// setup h264
OMX_VIDEO_PARAM_AVCTYPE avc = { 0 };
avc.nSize = sizeof(avc);
avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
err = OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc));
avc.nBFrames = 0;
avc.nPFrames = 15;
@ -299,8 +278,7 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB;
avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable;
err = OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc));
}
@ -326,40 +304,33 @@ OmxEncoder::OmxEncoder(const char* filename, int width, int height, int fps, int
// printf("profile %d level 0x%x\n", params.eProfile, params.eLevel);
// }
err = OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL));
this->in_buf_headers = (OMX_BUFFERHEADERTYPE **)calloc(this->num_in_bufs, sizeof(OMX_BUFFERHEADERTYPE*));
for (int i=0; i<this->num_in_bufs; i++) {
err = OMX_AllocateBuffer(this->handle, &this->in_buf_headers[i], PORT_INDEX_IN, this,
in_port.nBufferSize);
assert(err == OMX_ErrorNone);
for (auto &buf : this->in_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_IN, this,
in_port.nBufferSize));
}
this->out_buf_headers = (OMX_BUFFERHEADERTYPE **)calloc(this->num_out_bufs, sizeof(OMX_BUFFERHEADERTYPE*));
for (int i=0; i<this->num_out_bufs; i++) {
err = OMX_AllocateBuffer(this->handle, &this->out_buf_headers[i], PORT_INDEX_OUT, this,
out_port.nBufferSize);
assert(err == OMX_ErrorNone);
for (auto &buf : this->out_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_OUT, this,
out_port.nBufferSize));
}
wait_for_state(OMX_StateIdle);
err = OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL));
wait_for_state(OMX_StateExecuting);
// give omx all the output buffers
for (int i = 0; i < this->num_out_bufs; i++) {
for (auto &buf : this->out_buf_headers) {
// printf("fill %p\n", this->out_buf_headers[i]);
err = OMX_FillThisBuffer(this->handle, this->out_buf_headers[i]);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_FillThisBuffer(this->handle, buf));
}
// fill the input free queue
for (int i = 0; i < this->num_in_bufs; i++) {
queue_push(&this->free_in, (void*)this->in_buf_headers[i]);
for (auto &buf : this->in_buf_headers) {
queue_push(&this->free_in, (void*)buf);
}
}
@ -430,8 +401,7 @@ void OmxEncoder::handle_out_buf(OmxEncoder *e, OMX_BUFFERHEADERTYPE *out_buf) {
out_buf->nTimeStamp = 0;
}
#endif
err = OMX_FillThisBuffer(e->handle, out_buf);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_FillThisBuffer(e->handle, out_buf));
}
int OmxEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr,
@ -491,8 +461,7 @@ int OmxEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const u
in_buf->nTimeStamp = extra->timestamp_eof/1000LL; // OMX_TICKS, in microseconds
this->last_t = in_buf->nTimeStamp;
err = OMX_EmptyThisBuffer(this->handle, in_buf);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf));
// pump output
while (true) {
@ -572,8 +541,6 @@ void OmxEncoder::encoder_open(const char* path, int segment) {
}
void OmxEncoder::encoder_close() {
int err;
pthread_mutex_lock(&this->lock);
if (this->is_open) {
@ -586,8 +553,7 @@ void OmxEncoder::encoder_close() {
in_buf->nFlags = OMX_BUFFERFLAG_EOS;
in_buf->nTimeStamp = this->last_t + 1000000LL/this->fps;
err = OMX_EmptyThisBuffer(this->handle, in_buf);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf));
while (true) {
OMX_BUFFERHEADERTYPE *out_buf = (OMX_BUFFERHEADERTYPE *)queue_pop(&this->done_out);
@ -617,34 +583,25 @@ void OmxEncoder::encoder_close() {
}
OmxEncoder::~OmxEncoder() {
int err;
assert(!this->is_open);
err = OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL));
wait_for_state(OMX_StateIdle);
err = OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL));
for (int i=0; i<this->num_in_bufs; i++) {
err = OMX_FreeBuffer(this->handle, PORT_INDEX_IN, this->in_buf_headers[i]);
assert(err == OMX_ErrorNone);
for (auto &buf : this->in_buf_headers) {
OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_IN, buf));
}
free(this->in_buf_headers);
for (int i=0; i<this->num_out_bufs; i++) {
err = OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, this->out_buf_headers[i]);
assert(err == OMX_ErrorNone);
for (auto &buf : this->out_buf_headers) {
OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, buf));
}
free(this->out_buf_headers);
wait_for_state(OMX_StateLoaded);
err = OMX_FreeHandle(this->handle);
assert(err == OMX_ErrorNone);
OMX_CHECK(OMX_FreeHandle(this->handle));
while (queue_try_pop(&this->free_in));
while (queue_try_pop(&this->done_out));

@ -5,6 +5,7 @@
#include <stdbool.h>
#include <pthread.h>
#include <vector>
#include <OMX_Component.h>
extern "C" {
@ -60,11 +61,8 @@ private:
OMX_HANDLETYPE handle;
int num_in_bufs;
OMX_BUFFERHEADERTYPE** in_buf_headers;
int num_out_bufs;
OMX_BUFFERHEADERTYPE** out_buf_headers;
std::vector<OMX_BUFFERHEADERTYPE *> in_buf_headers;
std::vector<OMX_BUFFERHEADERTYPE *> out_buf_headers;
uint64_t last_t;

@ -47,7 +47,7 @@ class TestLoggerd(unittest.TestCase):
def _gen_bootlog(self):
with Timeout(5):
out = subprocess.check_output(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd"), encoding='utf-8')
out = subprocess.check_output("./bootlog", cwd=os.path.join(BASEDIR, "selfdrive/loggerd"), encoding='utf-8')
# check existence
d = self._get_log_dir(out)

@ -58,6 +58,7 @@ class Uploader():
self.last_resp = None
self.last_exc = None
self.immediate_folders = ["crash/"]
self.immediate_priority = {"qlog.bz2": 0, "qcamera.ts": 1}
self.high_priority = {"rlog.bz2": 0, "fcamera.hevc": 1, "dcamera.hevc": 2, "ecamera.hevc": 3}
@ -98,7 +99,7 @@ class Uploader():
# try to upload qlog files first
for name, key, fn in upload_files:
if name in self.immediate_priority:
if name in self.immediate_priority or any(f in fn for f in self.immediate_folders):
return (key, fn)
if with_raw:

@ -440,7 +440,7 @@ def manager_thread():
cloudlog.info({"environ": os.environ})
# save boot log
subprocess.call(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd"))
subprocess.call("./bootlog", cwd=os.path.join(BASEDIR, "selfdrive/loggerd"))
# start daemon processes
for p in daemon_processes:

@ -64,7 +64,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_
const int global_x_offset = full_width_tici / 2 - adapt_width_tici / 2;
const int global_y_offset = full_height_tici / 2 - cropped_height / 2;
const int crop_x_offset = adapt_width_tici - cropped_width + 32;
const int crop_y_offset = 0;
const int crop_y_offset = -196;
#endif
int resized_width = MODEL_WIDTH;
@ -75,16 +75,16 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_
for (int r = 0; r < cropped_height/2; r++) {
memcpy(cropped_y_buf + 2*r*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset)*width + global_x_offset + crop_x_offset, cropped_width);
memcpy(cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset + 1)*width + global_x_offset + crop_x_offset, cropped_width);
memcpy(cropped_u_buf + r*cropped_width/2, raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2);
memcpy(cropped_v_buf + r*cropped_width/2, raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2);
memcpy(cropped_u_buf + r*(cropped_width/2), raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2);
memcpy(cropped_v_buf + r*(cropped_width/2), raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + (global_x_offset + crop_x_offset)/2, cropped_width/2);
}
} else {
auto [premirror_cropped_y_buf, premirror_cropped_u_buf, premirror_cropped_v_buf] = get_yuv_buf(s->premirror_cropped_buf, cropped_width, cropped_height);
for (int r = 0; r < cropped_height/2; r++) {
memcpy(premirror_cropped_y_buf + (2*r)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset)*width + global_x_offset, cropped_width);
memcpy(premirror_cropped_y_buf + (2*r+1)*cropped_width, raw_y_buf + (2*r + global_y_offset + crop_y_offset + 1)*width + global_x_offset, cropped_width);
memcpy(premirror_cropped_u_buf + r*cropped_width/2, raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2);
memcpy(premirror_cropped_v_buf + r*cropped_width/2, raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2);
memcpy(premirror_cropped_u_buf + r*(cropped_width/2), raw_u_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2);
memcpy(premirror_cropped_v_buf + r*(cropped_width/2), raw_v_buf + (r + (global_y_offset + crop_y_offset)/2)*width/2 + global_x_offset/2, cropped_width/2);
}
libyuv::I420Mirror(premirror_cropped_y_buf, cropped_width,
premirror_cropped_u_buf, cropped_width/2,

@ -10,6 +10,11 @@
#include "driving.h"
#include "clutil.h"
constexpr int MODEL_PATH_DISTANCE = 192;
constexpr int POLYFIT_DEGREE = 4;
constexpr int DESIRE_PRED_SIZE = 32;
constexpr int OTHER_META_SIZE = 4;
constexpr int MODEL_WIDTH = 512;
constexpr int MODEL_HEIGHT = 256;
constexpr int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2;
@ -28,8 +33,6 @@ constexpr int LEAD_MHP_GROUP_SIZE = (2*LEAD_MHP_VALS + LEAD_MHP_SELECTION);
constexpr int POSE_SIZE = 12;
constexpr int MIN_VALID_LEN = 10;
constexpr int TRAJECTORY_TIME = 10;
constexpr float TRAJECTORY_DISTANCE = 192.0;
constexpr int PLAN_IDX = 0;
constexpr int LL_IDX = PLAN_IDX + PLAN_MHP_N*PLAN_MHP_GROUP_SIZE;
constexpr int LL_PROB_IDX = LL_IDX + 4*2*2*33;
@ -49,8 +52,6 @@ constexpr int OUTPUT_SIZE = POSE_IDX + POSE_SIZE;
// #define DUMP_YUV
Eigen::Matrix<float, MODEL_PATH_DISTANCE, POLYFIT_DEGREE - 1> vander;
float X_IDXS[TRAJECTORY_SIZE];
float T_IDXS[TRAJECTORY_SIZE];
void model_init(ModelState* s, cl_device_id device_id, cl_context context) {
frame_init(&s->frame, MODEL_WIDTH, MODEL_HEIGHT, device_id, context);
@ -77,8 +78,6 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context) {
// Build Vandermonde matrix
for(int i = 0; i < TRAJECTORY_SIZE; i++) {
for(int j = 0; j < POLYFIT_DEGREE - 1; j++) {
X_IDXS[i] = (TRAJECTORY_DISTANCE/1024.0) * (pow(i,2));
T_IDXS[i] = (TRAJECTORY_TIME/1024.0) * (pow(i,2));
vander(i, j) = pow(X_IDXS[i], POLYFIT_DEGREE-j-1);
}
}

@ -26,7 +26,10 @@ def register(spinner=None):
params.put("GitRemote", get_git_remote(default=""))
params.put("SubscriberInfo", HARDWARE.get_subscriber_info())
needs_registration = False
IMEI = params.get("IMEI", encoding='utf8')
HardwareSerial = params.get("HardwareSerial", encoding='utf8')
needs_registration = (None in [IMEI, HardwareSerial])
# create a key for auth
# your private key is kept on your device persist partition and never sent to our servers
@ -65,11 +68,15 @@ def register(spinner=None):
cloudlog.exception("Error getting imei, trying again...")
time.sleep(1)
serial = HARDWARE.get_serial()
params.put("IMEI", imei1)
params.put("HardwareSerial", serial)
while True:
try:
cloudlog.info("getting pilotauth")
resp = api_get("v2/pilotauth/", method='POST', timeout=15,
imei=imei1, imei2=imei2, serial=HARDWARE.get_serial(), public_key=public_key, register_token=register_token)
imei=imei1, imei2=imei2, serial=serial, public_key=public_key, register_token=register_token)
dongleauth = json.loads(resp.text)
dongle_id = dongleauth["dongle_id"]
params.put("DongleId", dongle_id)

@ -110,10 +110,11 @@ class Plant():
self.rate = rate
if not Plant.messaging_initialized:
Plant.pm = messaging.PubMaster(['frame', 'frontFrame', 'ubloxRaw', 'modelV2'])
Plant.logcan = messaging.pub_sock('can')
Plant.sendcan = messaging.sub_sock('sendcan')
Plant.model = messaging.pub_sock('model')
Plant.front_frame = messaging.pub_sock('frontFrame')
Plant.live_params = messaging.pub_sock('liveParameters')
Plant.live_location_kalman = messaging.pub_sock('liveLocationKalman')
Plant.health = messaging.pub_sock('health')
@ -163,7 +164,6 @@ class Plant():
def close(self):
Plant.logcan.close()
Plant.model.close()
Plant.front_frame.close()
Plant.live_params.close()
Plant.live_location_kalman.close()
@ -394,7 +394,6 @@ class Plant():
if publish_model and self.frame % 5 == 0:
md = messaging.new_message('model')
cal = messaging.new_message('liveCalibration')
fp = messaging.new_message('frontFrame')
md.model.frameId = 0
for x in [md.model.path, md.model.leftLane, md.model.rightLane]:
x.points = [0.0]*50
@ -426,7 +425,11 @@ class Plant():
# fake values?
Plant.model.send(md.to_bytes())
Plant.cal.send(cal.to_bytes())
Plant.front_frame.send(fp.to_bytes())
for s in Plant.pm.sock.keys():
try:
Plant.pm.send(s, messaging.new_message(s))
except Exception:
Plant.pm.send(s, messaging.new_message(s, 1))
Plant.logcan.send(can_list_to_can_capnp(can_msgs))

@ -318,6 +318,7 @@ def setup_output():
class LongitudinalControl(unittest.TestCase):
@classmethod
def setUpClass(cls):
os.environ['SIMULATION'] = "1"
os.environ['SKIP_FW_QUERY'] = "1"
os.environ['NO_CAN_TIMEOUT'] = "1"

@ -1 +1 @@
852c79998828975cce184114537b0067b80bc608
4d71a89ccbfd351cbe58fcf217ee2eefa48eee2d

@ -222,7 +222,7 @@ CONFIGS = [
pub_sub={
"can": ["controlsState", "carState", "carControl", "sendcan", "carEvents", "carParams"],
"thermal": [], "health": [], "liveCalibration": [], "dMonitoringState": [], "plan": [], "pathPlan": [], "gpsLocation": [], "liveLocationKalman": [],
"model": [], "frontFrame": [],
"model": [], "frontFrame": [], "frame": [], "ubloxRaw": [],
},
ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"],
init_callback=fingerprint,
@ -243,7 +243,7 @@ CONFIGS = [
ProcessConfig(
proc_name="plannerd",
pub_sub={
"model": ["pathPlan"], "radarState": ["plan"],
"modelV2": ["pathPlan"], "radarState": ["plan"],
"carState": [], "controlsState": [], "liveParameters": [],
},
ignore=["logMonoTime", "valid", "plan.processingDelay"],

@ -1 +1 @@
196c58580ec9cfd9691a9c4ebaad2dcd01cc0777
9ffa2b9927f188bdc07be62b2cc4ee00e5632522

@ -16,12 +16,12 @@ segments = [
("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI)
("TOYOTA", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR)
("HONDA", "0982d79ebb0de295|2021-01-08--10-13-10--6"), # HONDA.CIVIC (NIDEC)
("HONDA", "a8e8bf6a3864361b|2021-01-04--03-01-18--2"), # HONDA.ACCORD (BOSCH)
("CHRYSLER", "52d86230ee29aa84|2021-01-10--17-16-34--30"), # CHRYSLER.PACIFICA
("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA
("GM", "ae3ed0eb20960a20|2021-01-15--15-04-06--8"), # GM.VOLT
# TODO: update this route
("GM", "7cc2a8365b4dd8a9|2018-12-02--12-10-44--2"), # GM.ACADIA
("HONDA", "d83f36766f8012a5|2020-02-05--18-42-21--2"), # HONDA.CIVIC_BOSCH_DIESEL (BOSCH)
("CHRYSLER", "b6849f5cf2c926b1|2020-02-28--07-29-48--13"), # CHRYSLER.PACIFICA
("SUBARU", "c321c6b697c5a5ff|2020-06-23--11-04-33--12"), # SUBARU.FORESTER
("VOLKSWAGEN", "76b83eb0245de90e|2020-03-05--19-16-05--3"), # VW.GOLF
("NISSAN", "fbbfa6af821552b9|2020-03-03--08-09-43--0"), # NISSAN.XTRAIL
@ -160,6 +160,9 @@ if __name__ == "__main__":
if (procs_whitelisted and cfg.proc_name not in args.whitelist_procs) or \
(not procs_whitelisted and cfg.proc_name in args.blacklist_procs):
continue
# TODO remove this hack
if cfg.proc_name == 'plannerd' and car_brand in ["GM", "SUBARU", "VOLKSWAGEN", "NISSAN"]:
continue
cmp_log_fn = os.path.join(process_replay_dir, "%s_%s_%s.bz2" % (segment, cfg.proc_name, ref_commit))
results[segment][cfg.proc_name] = test_process(cfg, lr, cmp_log_fn, args.ignore_fields, args.ignore_msgs)

@ -1,108 +0,0 @@
#!/usr/bin/env python3
import os
import time
import sys
import subprocess
import cereal.messaging as messaging
from common.basedir import BASEDIR
from selfdrive.test.helpers import set_params_enabled
def cputime_total(ct):
return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem
def print_cpu_usage(first_proc, last_proc):
procs = [
("selfdrive.controls.controlsd", 47.0),
("./loggerd", 42.0),
("selfdrive.locationd.locationd", 35.0),
("selfdrive.locationd.paramsd", 12.0),
("selfdrive.controls.plannerd", 10.0),
("./_modeld", 7.12),
("./camerad", 7.07),
("./_sensord", 6.17),
("./_ui", 5.82),
("selfdrive.controls.radard", 5.67),
("./boardd", 3.63),
("./_dmonitoringmodeld", 2.67),
("selfdrive.logmessaged", 1.7),
("selfdrive.thermald.thermald", 2.41),
("selfdrive.locationd.calibrationd", 2.0),
("selfdrive.monitoring.dmonitoringd", 1.90),
("./proclogd", 1.54),
("./_gpsd", 0.09),
("./clocksd", 0.02),
("./ubloxd", 0.02),
("selfdrive.tombstoned", 0),
("./logcatd", 0),
]
r = True
dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9
result = "------------------------------------------------\n"
for proc_name, normal_cpu_usage in procs:
try:
first = [p for p in first_proc.procLog.procs if proc_name in p.cmdline][0]
last = [p for p in last_proc.procLog.procs if proc_name in p.cmdline][0]
cpu_time = cputime_total(last) - cputime_total(first)
cpu_usage = cpu_time / dt * 100.
if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0):
result += f"Warning {proc_name} using more CPU than normal\n"
r = False
elif cpu_usage < min(normal_cpu_usage * 0.65, max(normal_cpu_usage - 1.0, 0.0)):
result += f"Warning {proc_name} using less CPU than normal\n"
r = False
result += f"{proc_name.ljust(35)} {cpu_usage:.2f}%\n"
except IndexError:
result += f"{proc_name.ljust(35)} NO METRICS FOUND\n"
r = False
result += "------------------------------------------------\n"
print(result)
return r
def test_cpu_usage():
cpu_ok = False
# start manager
os.environ['SKIP_FW_QUERY'] = "1"
os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019"
manager_path = os.path.join(BASEDIR, "selfdrive/manager.py")
manager_proc = subprocess.Popen(["python", manager_path])
try:
proc_sock = messaging.sub_sock('procLog', conflate=True, timeout=2000)
cs_sock = messaging.sub_sock('controlsState')
# wait until everything's started
msg = None
start_time = time.monotonic()
while msg is None and time.monotonic() - start_time < 240:
msg = messaging.recv_sock(cs_sock)
# take first sample
time.sleep(15)
first_proc = messaging.recv_sock(proc_sock, wait=True)
if first_proc is None:
raise Exception("\n\nTEST FAILED: progLog recv timed out\n\n")
# run for a minute and get last sample
time.sleep(60)
last_proc = messaging.recv_sock(proc_sock, wait=True)
cpu_ok = print_cpu_usage(first_proc, last_proc)
finally:
manager_proc.terminate()
ret = manager_proc.wait(20)
if ret is None:
manager_proc.kill()
return cpu_ok
if __name__ == "__main__":
set_params_enabled()
passed = False
try:
passed = test_cpu_usage()
except Exception as e:
print("\n\n\n", "TEST FAILED:", str(e), "\n\n\n")
finally:
sys.exit(int(not passed))

@ -0,0 +1,112 @@
#!/usr/bin/env python3
import os
import time
import subprocess
import unittest
from pathlib import Path
import cereal.messaging as messaging
from common.basedir import BASEDIR
from common.timeout import Timeout
from selfdrive.loggerd.config import ROOT
from selfdrive.test.helpers import set_params_enabled
from tools.lib.logreader import LogReader
PROCS = [
("selfdrive.controls.controlsd", 47.0),
("./loggerd", 45.0),
("selfdrive.locationd.locationd", 35.0),
("selfdrive.controls.plannerd", 20.0),
("selfdrive.locationd.paramsd", 12.0),
("./_modeld", 7.12),
("./camerad", 7.07),
("./_sensord", 6.17),
("./_ui", 5.82),
("selfdrive.controls.radard", 5.67),
("./boardd", 3.63),
("./_dmonitoringmodeld", 2.67),
("selfdrive.logmessaged", 1.7),
("selfdrive.thermald.thermald", 2.41),
("selfdrive.locationd.calibrationd", 2.0),
("selfdrive.monitoring.dmonitoringd", 1.90),
("./proclogd", 1.54),
("./_gpsd", 0.09),
("./clocksd", 0.02),
("./ubloxd", 0.02),
("selfdrive.tombstoned", 0),
("./logcatd", 0),
]
# ***** test helpers *****
def cputime_total(ct):
return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem
def check_cpu_usage(first_proc, last_proc):
result = "------------------------------------------------\n"
result += "------------------ CPU Usage -------------------\n"
result += "------------------------------------------------\n"
r = True
dt = (last_proc.logMonoTime - first_proc.logMonoTime) / 1e9
for proc_name, normal_cpu_usage in PROCS:
first, last = None, None
try:
first = [p for p in first_proc.procLog.procs if proc_name in p.cmdline][0]
last = [p for p in last_proc.procLog.procs if proc_name in p.cmdline][0]
cpu_time = cputime_total(last) - cputime_total(first)
cpu_usage = cpu_time / dt * 100.
if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0):
result += f"Warning {proc_name} using more CPU than normal\n"
r = False
elif cpu_usage < min(normal_cpu_usage * 0.65, max(normal_cpu_usage - 1.0, 0.0)):
result += f"Warning {proc_name} using less CPU than normal\n"
r = False
result += f"{proc_name.ljust(35)} {cpu_usage:.2f}%\n"
except IndexError:
result += f"{proc_name.ljust(35)} NO METRICS FOUND {first=} {last=}\n"
r = False
result += "------------------------------------------------\n"
print(result)
return r
class TestOnroad(unittest.TestCase):
@classmethod
def setUpClass(cls):
os.environ['SKIP_FW_QUERY'] = "1"
os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019"
set_params_enabled()
initial_segments = set(Path(ROOT).iterdir())
# start manager and run openpilot for a minute
try:
manager_path = os.path.join(BASEDIR, "selfdrive/manager.py")
proc = subprocess.Popen(["python", manager_path])
sm = messaging.SubMaster(['carState'])
with Timeout(60, "controls didn't start"):
while not sm.updated['carState']:
sm.update(1000)
time.sleep(60)
finally:
proc.terminate()
if proc.wait(20) is None:
proc.kill()
new_segments = set(Path(ROOT).iterdir()) - initial_segments
segments = [p for p in new_segments if len(list(p.iterdir())) > 1]
cls.segment = [s for s in segments if str(s).endswith("--0")][0]
cls.lr = list(LogReader(os.path.join(str(cls.segment), "rlog.bz2")))
def test_cpu_usage(self):
proclogs = [m for m in self.lr if m.which() == 'procLog']
cpu_ok = check_cpu_usage(proclogs[5], proclogs[-3])
self.assertTrue(cpu_ok)
if __name__ == "__main__":
unittest.main()

@ -1,86 +0,0 @@
#!/usr/bin/env python3
import errno
import fcntl
import os
import signal
import subprocess
import sys
import time
import requests
from common.params import Params
from common.timeout import Timeout
HOST = "testing.comma.life"
def unblock_stdout():
# get a non-blocking stdout
child_pid, child_pty = os.forkpty()
if child_pid != 0: # parent
# child is in its own process group, manually pass kill signals
signal.signal(signal.SIGINT, lambda signum, frame: os.kill(child_pid, signal.SIGINT))
signal.signal(signal.SIGTERM, lambda signum, frame: os.kill(child_pid, signal.SIGTERM))
fcntl.fcntl(sys.stdout, fcntl.F_SETFL, fcntl.fcntl(sys.stdout, fcntl.F_GETFL) | os.O_NONBLOCK)
while True:
try:
dat = os.read(child_pty, 4096)
except OSError as e:
if e.errno == errno.EIO:
break
continue
if not dat:
break
try:
sys.stdout.write(dat.decode('utf8'))
except (OSError, IOError, UnicodeDecodeError):
pass
# os.wait() returns a tuple with the pid and a 16 bit value
# whose low byte is the signal number and whose high byte is the exit satus
exit_status = os.wait()[1] >> 8
os._exit(exit_status)
def heartbeat():
work_dir = '/data/openpilot'
while True:
try:
with open(os.path.join(work_dir, "selfdrive", "common", "version.h")) as _versionf:
version = _versionf.read().split('"')[1]
tmux = ""
# try:
# tmux = os.popen('tail -n 100 /tmp/tmux_out').read()
# except Exception:
# pass
params = Params()
msg = {
'version': version,
'dongle_id': params.get("DongleId").rstrip().decode('utf8'),
'remote': subprocess.check_output(["git", "config", "--get", "remote.origin.url"], cwd=work_dir).decode('utf8').rstrip(),
'branch': subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"], cwd=work_dir).decode('utf8').rstrip(),
'revision': subprocess.check_output(["git", "rev-parse", "HEAD"], cwd=work_dir).decode('utf8').rstrip(),
'serial': subprocess.check_output(["getprop", "ro.boot.serialno"]).decode('utf8').rstrip(),
'tmux': tmux,
}
with Timeout(10):
requests.post('http://%s/eon/heartbeat/' % HOST, json=msg, timeout=5.0)
except Exception as e:
print("Unable to send heartbeat", e)
time.sleep(5)
if __name__ == "__main__":
unblock_stdout()
heartbeat()

@ -276,7 +276,6 @@ def thermald_thread():
# If device is offroad we want to cool down before going onroad
# since going onroad increases load and can make temps go over 107
# We only do this if there is a relay that prevents the car from faulting
thermal_status = ThermalStatus.green # default to good condition
is_offroad_for_5_min = (started_ts is None) and ((not started_seen) or (off_ts is None) or (sec_since_boot() - off_ts > 60 * 5))
if max_cpu_temp > 107. or bat_temp >= 63. or (is_offroad_for_5_min and max_cpu_temp > 70.0):
# onroad not allowed
@ -293,6 +292,8 @@ def thermald_thread():
elif max_cpu_temp > 75.0:
# hysteresis between uploader not allowed and all good
thermal_status = clip(thermal_status, ThermalStatus.green, ThermalStatus.yellow)
else:
thermal_status = ThermalStatus.green # default to good condition
# **** starting logic ****

@ -1,23 +1,70 @@
#!/usr/bin/env python3
import datetime
import os
import re
import shutil
import signal
import subprocess
import time
import glob
from raven import Client
from raven.transport.http import HTTPTransport
from common.file_helpers import mkdirs_exists_ok
from selfdrive.hardware import TICI
from selfdrive.loggerd.config import ROOT
from selfdrive.swaglog import cloudlog
from selfdrive.version import version, origin, branch, dirty
from selfdrive.version import branch, commit, dirty, origin, version
MAX_SIZE = 100000 * 10 # Normal size is 40-100k, allow up to 1M
MAX_SIZE = 100000 * 10 # mal size is 40-100k, allow up to 1M
if TICI:
MAX_SIZE = MAX_SIZE * 10 # Allow larger size for tici
MAX_SIZE = MAX_SIZE * 100 # Allow larger size for tici since files contain coredump
MAX_TOMBSTONE_FN_LEN = 62 # 85 - 23 ("<dongle id>/crash/")
TOMBSTONE_DIR = "/data/tombstones/"
APPORT_DIR = "/var/crash/"
def safe_fn(s):
extra = ['_']
return "".join(c for c in s if c.isalnum() or c in extra).rstrip()
def sentry_report(client, fn, message, contents):
cloudlog.error({'tombstone': message})
client.captureMessage(
message=message,
sdk={'name': 'tombstoned', 'version': '0'},
extra={
'tombstone_fn': fn,
'tombstone': contents
},
)
def clear_apport_folder():
for f in glob.glob(APPORT_DIR + '*'):
try:
os.remove(f)
except Exception:
pass
def get_apport_stacktrace(fn):
try:
cmd = f'apport-retrace -s <(cat <(echo "Package: openpilot") "{fn}")'
return subprocess.check_output(cmd, shell=True, encoding='utf8', timeout=30, executable='/bin/bash') # pylint: disable=unexpected-keyword-arg
except subprocess.CalledProcessError:
return "Error getting stacktrace"
except subprocess.TimeoutExpired:
return "Timeout getting stacktrace"
def get_tombstones():
"""Returns list of (filename, ctime) for all tombstones in /data/tombstones
and apport crashlogs in /var/crash"""
files = []
for folder in ["/data/tombstones/", "/var/crash/"]:
for folder in [TOMBSTONE_DIR, APPORT_DIR]:
if os.path.exists(folder):
with os.scandir(folder) as d:
@ -30,7 +77,7 @@ def get_tombstones():
return files
def report_tombstone(fn, client):
def report_tombstone_android(fn, client):
f_size = os.path.getsize(fn)
if f_size > MAX_SIZE:
cloudlog.error(f"Tombstone {fn} too big, {f_size}. Skipping...")
@ -39,41 +86,100 @@ def report_tombstone(fn, client):
with open(fn, encoding='ISO-8859-1') as f:
contents = f.read()
# Get summary for sentry title
if fn.endswith(".crash"):
lines = contents.split('\n')
message = lines[6]
message = " ".join(contents.split('\n')[5:7])
status_idx = contents.find('ProcStatus')
if status_idx >= 0:
lines = contents[status_idx:].split('\n')
message += " " + lines[1]
else:
message = " ".join(contents.split('\n')[5:7])
# Cut off pid/tid, since that varies per run
name_idx = message.find('name')
if name_idx >= 0:
message = message[name_idx:]
# Cut off pid/tid, since that varies per run
name_idx = message.find('name')
if name_idx >= 0:
message = message[name_idx:]
# Cut off fault addr
fault_idx = message.find(', fault addr')
if fault_idx >= 0:
message = message[:fault_idx]
# Cut off fault addr
fault_idx = message.find(', fault addr')
if fault_idx >= 0:
message = message[:fault_idx]
sentry_report(client, fn, message, contents)
cloudlog.error({'tombstone': message})
client.captureMessage(
message=message,
sdk={'name': 'tombstoned', 'version': '0'},
extra={
'tombstone_fn': fn,
'tombstone': contents
},
)
def report_tombstone_apport(fn, client):
f_size = os.path.getsize(fn)
if f_size > MAX_SIZE:
cloudlog.error(f"Tombstone {fn} too big, {f_size}. Skipping...")
return
message = "" # One line description of the crash
contents = "" # Full file contents without coredump
path = "" # File path relative to openpilot directory
proc_maps = False
with open(fn) as f:
for line in f:
if "CoreDump" in line:
break
elif "ProcMaps" in line:
proc_maps = True
elif "ProcStatus" in line:
proc_maps = False
if not proc_maps:
contents += line
if "ExecutablePath" in line:
path = line.strip().split(': ')[-1]
path = path.replace('/data/openpilot/', '')
message += path
elif "Signal" in line:
message += " - " + line.strip()
try:
sig_num = int(line.strip().split(': ')[-1])
message += " (" + signal.Signals(sig_num).name + ")" # pylint: disable=no-member
except ValueError:
pass
stacktrace = get_apport_stacktrace(fn)
stacktrace_s = stacktrace.split('\n')
crash_function = "No stacktrace"
if len(stacktrace_s) > 2:
found = False
# Try to find first entry in openpilot, fall back to first line
for line in stacktrace_s:
if "at selfdrive/" in line:
crash_function = line
found = True
break
if not found:
crash_function = stacktrace_s[1]
# Remove arguments that can contain pointers to make sentry one-liner unique
crash_function = " ".join(crash_function.split(' ')[2:])
crash_function = re.sub(r'\(.*?\)', '', crash_function)
contents = stacktrace + "\n\n" + contents
message = message + " - " + crash_function
sentry_report(client, fn, message, contents)
# Copy crashlog to upload folder
clean_path = path.replace('/', '_')
date = datetime.datetime.now().strftime("%Y-%m-%d--%H-%M-%S")
new_fn = f"{date}_{commit[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN]
crashlog_dir = os.path.join(ROOT, "crash")
mkdirs_exists_ok(crashlog_dir)
# Files could be on different filesystems, copy, then delete
shutil.copy(fn, os.path.join(crashlog_dir, new_fn))
os.remove(fn)
def main():
# TODO: turn on when all tombstones are recovered
# clear_apport_folder() # Clear apport folder on start, otherwise duplicate crashes won't register
initial_tombstones = set(get_tombstones())
tags = {
@ -91,7 +197,10 @@ def main():
for fn, _ in (now_tombstones - initial_tombstones):
try:
cloudlog.info(f"reporting new tombstone {fn}")
report_tombstone(fn, client)
if fn.endswith(".crash"):
report_tombstone_apport(fn, client)
else:
report_tombstone_android(fn, client)
except Exception:
cloudlog.exception(f"Error reporting tombstone {fn}")

@ -5,7 +5,6 @@ Import('env', 'qt_env', 'arch', 'common', 'messaging', 'gpucommon', 'visionipc',
src = ['ui.cc', 'paint.cc', 'sidebar.cc', '#phonelibs/nanovg/nanovg.c']
libs = [common, 'zmq', 'capnp', 'kj', 'm', 'OpenCL', cereal, messaging, gpucommon, visionipc]
if qt_env is None:
libs += ['EGL', 'GLESv3', 'gnustl_shared', 'log', 'utils', 'gui', 'hardware',
'ui', 'CB', 'gsl', 'adreno_utils', 'OpenSLES', 'cutils', 'uuid', 'OpenCL']
@ -20,16 +19,18 @@ else:
widgets = qt_env.Library("qt_widgets",
["qt/qt_window.cc", "qt/qt_sound.cc", "qt/widgets/keyboard.cc", "qt/widgets/input_field.cc", "qt/widgets/drive_stats.cc",
"qt/offroad/wifi.cc", "qt/offroad/wifiManager.cc", "qt/widgets/toggle.cc", "qt/widgets/offroad_alerts.cc"],
"qt/offroad/wifi.cc", "qt/offroad/wifiManager.cc", "qt/widgets/toggle.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/setup.cc", "qt/widgets/QrCode.cc"],
LIBS=qt_libs)
qt_libs.append(widgets)
if arch == "Darwin":
# fix OpenCL
del qt_libs[qt_libs.index('OpenCL')]
qt_env['FRAMEWORKS'] += ['OpenCL']
qt_src = ["qt/ui.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", "qt/offroad/onboarding.cc"] + src
qt_src = ["qt/ui.cc", "qt/window.cc", "qt/home.cc", "qt/api.cc", "qt/offroad/settings.cc", "qt/offroad/onboarding.cc"] + src
qt_env.Program("_ui", qt_src, LIBS=qt_libs)
# spinner and text window

@ -44,17 +44,6 @@ opensans_regular.o: ../../../assets/fonts/opensans_regular.ttf
@echo "[ bin2o ] $@"
cd '$(dir $<)' && ld -r -b binary '$(notdir $<)' -o '$(abspath $@)'
%.o: %.c
mkdir -p $(@D)
@echo "[ CC ] $@"
$(CC) $(CPPFLAGS) $(CFLAGS) \
-I../../.. \
-I$(PHONELIBS)/android_frameworks_native/include \
-I$(PHONELIBS)/android_system_core/include \
-I$(PHONELIBS)/android_hardware_libhardware/include \
$(NANOVG_FLAGS) \
-c -o '$@' '$<'
%.o: %.cc
mkdir -p $(@D)
@echo "[ CXX ] $@"

@ -21,8 +21,9 @@
#define COLOR_WHITE nvgRGBA(255, 255, 255, 255)
#define MAX_TEXT_SIZE 2048
extern const unsigned char _binary_opensans_regular_ttf_start[];
extern const unsigned char _binary_opensans_regular_ttf_end[];
extern const uint8_t bin_opensans_regular[] asm("_binary_opensans_regular_ttf_start");
extern const uint8_t *bin_opensans_regular_end asm("_binary_opensans_regular_ttf_end");
int main(int argc, char** argv) {
int err;
@ -36,8 +37,8 @@ int main(int argc, char** argv) {
NVGcontext *vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES);
assert(vg);
int font = nvgCreateFontMem(vg, "regular", (unsigned char*)_binary_opensans_regular_ttf_start, _binary_opensans_regular_ttf_end-_binary_opensans_regular_ttf_start, 0);
assert(font >= 0);
int font = nvgCreateFontMem(vg, "regular", (unsigned char*)bin_opensans_regular, (bin_opensans_regular_end - bin_opensans_regular), 0);
assert(font >= 0);
// Awake
framebuffer_set_power(fb, HWC_POWER_MODE_NORMAL);
@ -67,7 +68,7 @@ assert(font >= 0);
float y = 150;
// Copy text
char * text = malloc(MAX_TEXT_SIZE);
char * text = (char *)malloc(MAX_TEXT_SIZE);
strncpy(text, argv[1], MAX_TEXT_SIZE);
float lineh;

@ -48,27 +48,30 @@ bool car_space_to_full_frame(const UIState *s, float in_x, float in_y, float in_
const vec3 KEp = matvecmul3(intrinsic_matrix, Ep);
// Project.
out->x = KEp.v[0] / KEp.v[2];
out->y = KEp.v[1] / KEp.v[2];
float x = KEp.v[0] / KEp.v[2];
float y = KEp.v[1] / KEp.v[2];
nvgTransformPoint(&out->x, &out->y, s->car_space_transform, x, y);
return out->x >= -margin && out->x <= s->fb_w + margin && out->y >= -margin && out->y <= s->fb_h + margin;
}
static void ui_draw_text(NVGcontext *vg, float x, float y, const char* string, float size, NVGcolor color, int font){
nvgFontFaceId(vg, font);
nvgFontSize(vg, size);
nvgFillColor(vg, color);
nvgText(vg, x, y, string, NULL);
static void ui_draw_text(const UIState *s, float x, float y, const char* string, float size, NVGcolor color, const char *font_name){
nvgFontFace(s->vg, font_name);
nvgFontSize(s->vg, size);
nvgFillColor(s->vg, color);
nvgText(s->vg, x, y, string, NULL);
}
static void draw_chevron(UIState *s, float x_in, float y_in, float sz,
NVGcolor fillColor, NVGcolor glowColor) {
vertex_data out;
if (!car_space_to_full_frame(s, x_in, y_in, 0.0, &out)) return;
vertex_data out = {};
car_space_to_full_frame(s, x_in, y_in, 0.0, &out);
auto [x, y] = out;
sz = std::clamp((sz * 30) / (x_in / 3 + 30), 15.0f, 30.0f);
sz = std::clamp((sz * 30) / (x_in / 3 + 30), 15.0f, 30.0f) * zoom;
y = std::fmin(s->scene.viz_rect.bottom() - sz * .6, y);
x = std::clamp(x, 0.f, s->scene.viz_rect.right() - sz / 2);
// glow
float g_xo = sz/5;
@ -91,20 +94,19 @@ static void draw_chevron(UIState *s, float x_in, float y_in, float sz,
nvgFill(s->vg);
}
static void ui_draw_circle_image(NVGcontext *vg, int x, int y, int size, int image, NVGcolor color, float img_alpha, int img_y = 0) {
static void ui_draw_circle_image(const UIState *s, int x, int y, int size, const char *image, NVGcolor color, float img_alpha, int img_y = 0) {
const int img_size = size * 1.5;
nvgBeginPath(vg);
nvgCircle(vg, x, y + (bdr_s * 1.5), size);
nvgFillColor(vg, color);
nvgFill(vg);
const Rect rect = {x - (img_size / 2), img_y ? img_y : y - (size / 4), img_size, img_size};
ui_draw_image(vg, rect, image, img_alpha);
nvgBeginPath(s->vg);
nvgCircle(s->vg, x, y + (bdr_s * 1.5), size);
nvgFillColor(s->vg, color);
nvgFill(s->vg);
ui_draw_image(s, {x - (img_size / 2), img_y ? img_y : y - (size / 4), img_size, img_size}, image, img_alpha);
}
static void ui_draw_circle_image(NVGcontext *vg, int x, int y, int size, int image, bool active) {
static void ui_draw_circle_image(const UIState *s, int x, int y, int size, const char *image, bool active) {
float bg_alpha = active ? 0.3f : 0.1f;
float img_alpha = active ? 1.0f : 0.15f;
ui_draw_circle_image(vg, x, y, size, image, nvgRGBA(0, 0, 0, (255 * bg_alpha)), img_alpha);
ui_draw_circle_image(s, x, y, size, image, nvgRGBA(0, 0, 0, (255 * bg_alpha)), img_alpha);
}
static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &lead){
@ -195,22 +197,9 @@ static void ui_draw_vision_lane_lines(UIState *s) {
// Draw all world space objects.
static void ui_draw_world(UIState *s) {
const UIScene *scene = &s->scene;
nvgSave(s->vg);
// Don't draw on top of sidebar
nvgScissor(s->vg, scene->viz_rect.x, scene->viz_rect.y, scene->viz_rect.w, scene->viz_rect.h);
// Apply transformation such that video pixel coordinates match video
// 1) Put (0, 0) in the middle of the video
nvgTranslate(s->vg, s->video_rect.x + s->video_rect.w / 2, s->video_rect.y + s->video_rect.h / 2 + y_offset);
// 2) Apply same scaling as video
nvgScale(s->vg, zoom, zoom);
// 3) Put (0, 0) in top left corner of video
nvgTranslate(s->vg, -intrinsic_matrix.v[2], -intrinsic_matrix.v[5]);
// Draw lane edges and vision/mpc tracks
ui_draw_vision_lane_lines(s);
@ -223,7 +212,7 @@ static void ui_draw_world(UIState *s) {
draw_lead(s, scene->lead_data[1]);
}
}
nvgRestore(s->vg);
nvgResetScissor(s->vg);
}
static void ui_draw_vision_maxspeed(UIState *s) {
@ -231,18 +220,17 @@ static void ui_draw_vision_maxspeed(UIState *s) {
const bool is_cruise_set = maxspeed != 0 && maxspeed != SET_SPEED_NA;
if (is_cruise_set && !s->is_metric) { maxspeed *= 0.6225; }
auto [x, y, w, h] = std::tuple(s->scene.viz_rect.x + (bdr_s * 2), s->scene.viz_rect.y + (bdr_s * 1.5), 184, 202);
ui_draw_rect(s->vg, x, y, w, h, COLOR_BLACK_ALPHA(100), 30);
ui_draw_rect(s->vg, x, y, w, h, COLOR_WHITE_ALPHA(100), 20, 10);
const Rect rect = {s->scene.viz_rect.x + (bdr_s * 2), int(s->scene.viz_rect.y + (bdr_s * 1.5)), 184, 202};
ui_fill_rect(s->vg, rect, COLOR_BLACK_ALPHA(100), 30.);
ui_draw_rect(s->vg, rect, COLOR_WHITE_ALPHA(100), 10, 20.);
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
ui_draw_text(s->vg, x + w / 2, 148, "MAX", 26 * 2.5, COLOR_WHITE_ALPHA(is_cruise_set ? 200 : 100), s->font_sans_regular);
ui_draw_text(s, rect.centerX(), 148, "MAX", 26 * 2.5, COLOR_WHITE_ALPHA(is_cruise_set ? 200 : 100), "sans-regular");
if (is_cruise_set) {
const std::string maxspeed_str = std::to_string((int)std::nearbyint(maxspeed));
ui_draw_text(s->vg, x + w / 2, 242, maxspeed_str.c_str(), 48 * 2.5, COLOR_WHITE, s->font_sans_bold);
ui_draw_text(s, rect.centerX(), 242, maxspeed_str.c_str(), 48 * 2.5, COLOR_WHITE, "sans-bold");
} else {
ui_draw_text(s->vg, x + w / 2, 242, "N/A", 42 * 2.5, COLOR_WHITE_ALPHA(100), s->font_sans_semibold);
ui_draw_text(s, rect.centerX(), 242, "N/A", 42 * 2.5, COLOR_WHITE_ALPHA(100), "sans-semibold");
}
}
@ -250,8 +238,8 @@ static void ui_draw_vision_speed(UIState *s) {
const float speed = std::max(0.0, s->scene.controls_state.getVEgo() * (s->is_metric ? 3.6 : 2.2369363));
const std::string speed_str = std::to_string((int)std::nearbyint(speed));
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
ui_draw_text(s->vg, s->scene.viz_rect.centerX(), 240, speed_str.c_str(), 96 * 2.5, COLOR_WHITE, s->font_sans_bold);
ui_draw_text(s->vg, s->scene.viz_rect.centerX(), 320, s->is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), s->font_sans_regular);
ui_draw_text(s, s->scene.viz_rect.centerX(), 240, speed_str.c_str(), 96 * 2.5, COLOR_WHITE, "sans-bold");
ui_draw_text(s, s->scene.viz_rect.centerX(), 320, s->is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular");
}
static void ui_draw_vision_event(UIState *s) {
@ -262,7 +250,7 @@ static void ui_draw_vision_event(UIState *s) {
// draw winding road sign
const int img_turn_size = 160*1.5;
const Rect rect = {viz_event_x - (img_turn_size / 4), viz_event_y + bdr_s - 25, img_turn_size, img_turn_size};
ui_draw_image(s->vg, rect, s->img_turn, 1.0f);
ui_draw_image(s, rect, "trafficSign_turn", 1.0f);
} else if (s->scene.controls_state.getEngageable()) {
// draw steering wheel
const int bg_wheel_size = 96;
@ -270,7 +258,7 @@ static void ui_draw_vision_event(UIState *s) {
const int bg_wheel_y = viz_event_y + (bg_wheel_size/2);
const NVGcolor color = bg_colors[s->status];
ui_draw_circle_image(s->vg, bg_wheel_x, bg_wheel_y, bg_wheel_size, s->img_wheel, color, 1.0f, bg_wheel_y - 25);
ui_draw_circle_image(s, bg_wheel_x, bg_wheel_y, bg_wheel_size, "wheel", color, 1.0f, bg_wheel_y - 25);
}
}
@ -278,7 +266,7 @@ static void ui_draw_vision_face(UIState *s) {
const int face_size = 96;
const int face_x = (s->scene.viz_rect.x + face_size + (bdr_s * 2));
const int face_y = (s->scene.viz_rect.bottom() - footer_h + ((footer_h - face_size) / 2));
ui_draw_circle_image(s->vg, face_x, face_y, face_size, s->img_face, s->scene.dmonitoring_state.getFaceDetected());
ui_draw_circle_image(s, face_x, face_y, face_size, "driver_face", s->scene.dmonitoring_state.getFaceDetected());
}
static void ui_draw_driver_view(UIState *s) {
@ -294,32 +282,32 @@ static void ui_draw_driver_view(UIState *s) {
const int blackout_w = rect.w - valid_rect.w;
NVGpaint gradient = nvgLinearGradient(s->vg, blackout_x, rect.y, blackout_x + blackout_w, rect.y,
COLOR_BLACK_ALPHA(is_rhd ? 255 : 0), COLOR_BLACK_ALPHA(is_rhd ? 0 : 255));
ui_draw_rect(s->vg, blackout_x, rect.y, blackout_w, rect.h, gradient);
ui_draw_rect(s->vg, blackout_x, rect.y, blackout_w, rect.h, COLOR_BLACK_ALPHA(144));
ui_fill_rect(s->vg, {blackout_x, rect.y, blackout_w, rect.h}, gradient);
ui_fill_rect(s->vg, {blackout_x, rect.y, blackout_w, rect.h}, COLOR_BLACK_ALPHA(144));
// border
ui_draw_rect(s->vg, rect.x, rect.y, rect.w, rect.h, bg_colors[STATUS_OFFROAD], 0, 1);
ui_draw_rect(s->vg, rect, bg_colors[STATUS_OFFROAD], 1);
const bool face_detected = s->scene.dmonitoring_state.getFaceDetected();
if (face_detected) {
auto fxy_list = s->scene.driver_state.getFacePosition();
float face_x = fxy_list[0];
float face_y = fxy_list[1];
float fbox_x = valid_rect.centerX() + (is_rhd ? face_x : -face_x) * valid_rect.w;
float fbox_y = valid_rect.centerY() + face_y * valid_rect.h;
int fbox_x = valid_rect.centerX() + (is_rhd ? face_x : -face_x) * valid_rect.w;
int fbox_y = valid_rect.centerY() + face_y * valid_rect.h;
float alpha = 0.2;
if (face_x = std::abs(face_x), face_y = std::abs(face_y); face_x <= 0.35 && face_y <= 0.4)
alpha = 0.8 - (face_x > face_y ? face_x : face_y) * 0.6 / 0.375;
const float box_size = 0.6 * rect.h / 2;
ui_draw_rect(s->vg, fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size, nvgRGBAf(1.0, 1.0, 1.0, alpha), 35, 10);
const int box_size = 0.6 * rect.h / 2;
ui_draw_rect(s->vg, {fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size}, nvgRGBAf(1.0, 1.0, 1.0, alpha), 10, 35.);
}
// draw face icon
const int face_size = 85;
const int icon_x = is_rhd ? rect.right() - face_size - bdr_s * 2 : rect.x + face_size + bdr_s * 2;
const int icon_y = rect.bottom() - face_size - bdr_s * 2.5;
ui_draw_circle_image(s->vg, icon_x, icon_y, face_size, s->img_face, face_detected);
ui_draw_circle_image(s, icon_x, icon_y, face_size, "driver_face", face_detected);
}
static void ui_draw_vision_header(UIState *s) {
@ -329,7 +317,7 @@ static void ui_draw_vision_header(UIState *s) {
viz_rect.x, viz_rect.y+header_h,
nvgRGBAf(0,0,0,0.45), nvgRGBAf(0,0,0,0));
ui_draw_rect(s->vg, viz_rect.x, viz_rect.y, viz_rect.w, header_h, gradient);
ui_fill_rect(s->vg, {viz_rect.x, viz_rect.y, viz_rect.w, header_h}, gradient);
ui_draw_vision_maxspeed(s);
ui_draw_vision_speed(s);
@ -354,36 +342,33 @@ static void ui_draw_vision_alert(UIState *s) {
NVGcolor color = bg_colors[s->status];
color.a *= get_alert_alpha(scene->alert_blinking_rate);
int alr_s = alert_size_map[scene->alert_size];
const int alr_x = scene->viz_rect.x - bdr_s;
const int alr_w = scene->viz_rect.w + (bdr_s * 2);
const int alr_h = alr_s + bdr_s;
const int alr_y = s->fb_h - alr_h;
ui_draw_rect(s->vg, alr_x, alr_y, alr_w, alr_h, color);
const int alr_h = alert_size_map[scene->alert_size] + bdr_s;
const Rect rect = {.x = scene->viz_rect.x - bdr_s,
.y = s->fb_h - alr_h,
.w = scene->viz_rect.w + (bdr_s * 2),
.h = alr_h};
NVGpaint gradient = nvgLinearGradient(s->vg, alr_x, alr_y, alr_x, alr_y+alr_h,
nvgRGBAf(0.0,0.0,0.0,0.05), nvgRGBAf(0.0,0.0,0.0,0.35));
ui_draw_rect(s->vg, alr_x, alr_y, alr_w, alr_h, gradient);
ui_fill_rect(s->vg, rect, color);
ui_fill_rect(s->vg, rect, nvgLinearGradient(s->vg, rect.x, rect.y, rect.x, rect.bottom(),
nvgRGBAf(0.0, 0.0, 0.0, 0.05), nvgRGBAf(0.0, 0.0, 0.0, 0.35)));
nvgFillColor(s->vg, COLOR_WHITE);
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
if (scene->alert_size == cereal::ControlsState::AlertSize::SMALL) {
ui_draw_text(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+15, scene->alert_text1.c_str(), 40*2.5, COLOR_WHITE, s->font_sans_semibold);
ui_draw_text(s, rect.centerX(), rect.centerY() + 15, scene->alert_text1.c_str(), 40*2.5, COLOR_WHITE, "sans-semibold");
} else if (scene->alert_size == cereal::ControlsState::AlertSize::MID) {
ui_draw_text(s->vg, alr_x+alr_w/2, alr_y+alr_h/2-45, scene->alert_text1.c_str(), 48*2.5, COLOR_WHITE, s->font_sans_bold);
ui_draw_text(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+75, scene->alert_text2.c_str(), 36*2.5, COLOR_WHITE, s->font_sans_regular);
ui_draw_text(s, rect.centerX(), rect.centerY() - 45, scene->alert_text1.c_str(), 48*2.5, COLOR_WHITE, "sans-bold");
ui_draw_text(s, rect.centerX(), rect.centerY() + 75, scene->alert_text2.c_str(), 36*2.5, COLOR_WHITE, "sans-regular");
} else if (scene->alert_size == cereal::ControlsState::AlertSize::FULL) {
nvgFontSize(s->vg, (longAlert1?72:96)*2.5);
nvgFontFaceId(s->vg, s->font_sans_bold);
nvgFontFace(s->vg, "sans-bold");
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE);
nvgTextBox(s->vg, alr_x, alr_y+(longAlert1?360:420), alr_w-60, scene->alert_text1.c_str(), NULL);
nvgTextBox(s->vg, rect.x, rect.y+(longAlert1?360:420), rect.w-60, scene->alert_text1.c_str(), NULL);
nvgFontSize(s->vg, 48*2.5);
nvgFontFaceId(s->vg, s->font_sans_regular);
nvgFontFace(s->vg, "sans-regular");
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BOTTOM);
nvgTextBox(s->vg, alr_x, alr_h-(longAlert1?300:360), alr_w-60, scene->alert_text2.c_str(), NULL);
nvgTextBox(s->vg, rect.x, rect.h-(longAlert1?300:360), rect.w-60, scene->alert_text2.c_str(), NULL);
}
}
@ -431,8 +416,9 @@ void ui_draw(UIState *s) {
s->scene.viz_rect.w -= sbr_w;
}
const bool draw_vision = s->started && s->status != STATUS_OFFROAD &&
s->active_app == cereal::UiLayoutState::App::NONE && s->vipc_client->connected;
const bool draw_alerts = s->started && s->status != STATUS_OFFROAD &&
s->active_app == cereal::UiLayoutState::App::NONE;
const bool draw_vision = draw_alerts && s->vipc_client->connected;
// GL drawing functions
ui_draw_background(s);
@ -450,40 +436,42 @@ void ui_draw(UIState *s) {
ui_draw_vision(s);
}
if (draw_vision && s->scene.alert_size != cereal::ControlsState::AlertSize::NONE) {
if (draw_alerts && s->scene.alert_size != cereal::ControlsState::AlertSize::NONE) {
ui_draw_vision_alert(s);
}
nvgEndFrame(s->vg);
glDisable(GL_BLEND);
}
void ui_draw_image(NVGcontext *vg, const Rect &r, int image, float alpha){
nvgBeginPath(vg);
NVGpaint imgPaint = nvgImagePattern(vg, r.x, r.y, r.w, r.h, 0, image, alpha);
nvgRect(vg, r.x, r.y, r.w, r.h);
nvgFillPaint(vg, imgPaint);
nvgFill(vg);
void ui_draw_image(const UIState *s, const Rect &r, const char *name, float alpha){
nvgBeginPath(s->vg);
NVGpaint imgPaint = nvgImagePattern(s->vg, r.x, r.y, r.w, r.h, 0, s->images.at(name), alpha);
nvgRect(s->vg, r.x, r.y, r.w, r.h);
nvgFillPaint(s->vg, imgPaint);
nvgFill(s->vg);
}
void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r, int width) {
void ui_draw_rect(NVGcontext *vg, const Rect &r, NVGcolor color, int width, float radius) {
nvgBeginPath(vg);
r > 0 ? nvgRoundedRect(vg, x, y, w, h, r) : nvgRect(vg, x, y, w, h);
if (width) {
nvgStrokeColor(vg, color);
nvgStrokeWidth(vg, width);
nvgStroke(vg);
} else {
nvgFillColor(vg, color);
nvgFill(vg);
}
radius > 0 ? nvgRoundedRect(vg, r.x, r.y, r.w, r.h, radius) : nvgRect(vg, r.x, r.y, r.w, r.h);
nvgStrokeColor(vg, color);
nvgStrokeWidth(vg, width);
nvgStroke(vg);
}
void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r){
static inline void fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor *color, const NVGpaint *paint, float radius) {
nvgBeginPath(vg);
r > 0? nvgRoundedRect(vg, x, y, w, h, r) : nvgRect(vg, x, y, w, h);
nvgFillPaint(vg, paint);
radius > 0? nvgRoundedRect(vg, r.x, r.y, r.w, r.h, radius) : nvgRect(vg, r.x, r.y, r.w, r.h);
if (color) nvgFillColor(vg, *color);
if (paint) nvgFillPaint(vg, *paint);
nvgFill(vg);
}
void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor &color, float radius) {
fill_rect(vg, r, &color, nullptr, radius);
}
void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGpaint &paint, float radius){
fill_rect(vg, r, nullptr, &paint, radius);
}
static const char frame_vertex_shader[] =
#ifdef NANOVG_GL3_IMPLEMENTATION
@ -537,36 +525,38 @@ void ui_nvg_init(UIState *s) {
#else
s->vg = nvgCreate(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG);
#endif
assert(s->vg);
s->font_sans_regular = nvgCreateFont(s->vg, "sans-regular", "../assets/fonts/opensans_regular.ttf");
assert(s->font_sans_regular >= 0);
s->font_sans_semibold = nvgCreateFont(s->vg, "sans-semibold", "../assets/fonts/opensans_semibold.ttf");
assert(s->font_sans_semibold >= 0);
s->font_sans_bold = nvgCreateFont(s->vg, "sans-bold", "../assets/fonts/opensans_bold.ttf");
assert(s->font_sans_bold >= 0);
s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1);
assert(s->img_wheel != 0);
s->img_turn = nvgCreateImage(s->vg, "../assets/img_trafficSign_turn.png", 1);
assert(s->img_turn != 0);
s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1);
assert(s->img_face != 0);
s->img_button_settings = nvgCreateImage(s->vg, "../assets/images/button_settings.png", 1);
assert(s->img_button_settings != 0);
s->img_button_home = nvgCreateImage(s->vg, "../assets/images/button_home.png", 1);
assert(s->img_button_home != 0);
s->img_battery = nvgCreateImage(s->vg, "../assets/images/battery.png", 1);
assert(s->img_battery != 0);
s->img_battery_charging = nvgCreateImage(s->vg, "../assets/images/battery_charging.png", 1);
assert(s->img_battery_charging != 0);
for(int i=0;i<=5;++i) {
char network_asset[32];
snprintf(network_asset, sizeof(network_asset), "../assets/images/network_%d.png", i);
s->img_network[i] = nvgCreateImage(s->vg, network_asset, 1);
assert(s->img_network[i] != 0);
// init fonts
std::pair<const char *, const char *> fonts[] = {
{"sans-regular", "../assets/fonts/opensans_regular.ttf"},
{"sans-semibold", "../assets/fonts/opensans_semibold.ttf"},
{"sans-bold", "../assets/fonts/opensans_bold.ttf"},
};
for (auto [name, file] : fonts) {
int font_id = nvgCreateFont(s->vg, name, file);
assert(font_id >= 0);
}
// init images
std::vector<std::pair<const char *, const char *>> images = {
{"wheel", "../assets/img_chffr_wheel.png"},
{"trafficSign_turn", "../assets/img_trafficSign_turn.png"},
{"driver_face", "../assets/img_driver_face.png"},
{"button_settings", "../assets/images/button_settings.png"},
{"button_home", "../assets/images/button_home.png"},
{"battery", "../assets/images/battery.png"},
{"battery_charging", "../assets/images/battery_charging.png"},
{"network_0", "../assets/images/network_0.png"},
{"network_1", "../assets/images/network_1.png"},
{"network_2", "../assets/images/network_2.png"},
{"network_3", "../assets/images/network_3.png"},
{"network_4", "../assets/images/network_4.png"},
{"network_5", "../assets/images/network_5.png"},
};
for (auto [name, file] : images) {
s->images[name] = nvgCreateImage(s->vg, file, 1);
assert(s->images[name] != 0);
}
// init gl
@ -633,4 +623,17 @@ void ui_nvg_init(UIState *s) {
s->front_frame_mat = matmul(device_transform, full_to_wide_frame_transform);
s->rear_frame_mat = matmul(device_transform, frame_transform);
// Apply transformation such that video pixel coordinates match video
// 1) Put (0, 0) in the middle of the video
nvgTranslate(s->vg, s->video_rect.x + s->video_rect.w / 2, s->video_rect.y + s->video_rect.h / 2 + y_offset);
// 2) Apply same scaling as video
nvgScale(s->vg, zoom, zoom);
// 3) Put (0, 0) in top left corner of video
nvgTranslate(s->vg, -intrinsic_matrix.v[2], -intrinsic_matrix.v[5]);
nvgCurrentTransform(s->vg, s->car_space_transform);
nvgResetTransform(s->vg);
}

@ -3,7 +3,8 @@
bool car_space_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, vertex_data *out, float margin=0.0);
void ui_draw(UIState *s);
void ui_draw_image(NVGcontext *vg, const Rect &r, int image, float alpha);
void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGcolor color, float r = 0, int width = 0);
void ui_draw_rect(NVGcontext *vg, float x, float y, float w, float h, NVGpaint &paint, float r = 0);
void ui_draw_image(const UIState *s, const Rect &r, const char *name, float alpha);
void ui_draw_rect(NVGcontext *vg, const Rect &r, NVGcolor color, int width, float radius = 0);
void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGpaint &paint, float radius = 0);
void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor &color, float radius = 0);
void ui_nvg_init(UIState *s);

@ -0,0 +1,127 @@
#include <QDateTime>
#include <QDebug>
#include <QFile>
#include <QJsonDocument>
#include <QJsonObject>
#include <QNetworkReply>
#include <QNetworkRequest>
#include <QString>
#include <QWidget>
#include <QTimer>
#include <QRandomGenerator>
#include "api.hpp"
#include "home.hpp"
#include "common/params.h"
#include "common/util.h"
#if defined(QCOM) || defined(QCOM2)
const std::string private_key_path = "/persist/comma/id_rsa";
#else
const std::string private_key_path = util::getenv_default("HOME", "/.comma/persist/comma/id_rsa", "/persist/comma/id_rsa");
#endif
QByteArray CommaApi::rsa_sign(QByteArray data) {
auto file = QFile(private_key_path.c_str());
if (!file.open(QIODevice::ReadOnly)) {
qDebug() << "No RSA private key found, please run manager.py or registration.py";
return QByteArray();
}
auto key = file.readAll();
file.close();
file.deleteLater();
BIO* mem = BIO_new_mem_buf(key.data(), key.size());
assert(mem);
RSA* rsa_private = PEM_read_bio_RSAPrivateKey(mem, NULL, NULL, NULL);
assert(rsa_private);
auto sig = QByteArray();
sig.resize(RSA_size(rsa_private));
unsigned int sig_len;
int ret = RSA_sign(NID_sha256, (unsigned char*)data.data(), data.size(), (unsigned char*)sig.data(), &sig_len, rsa_private);
assert(ret == 1);
assert(sig_len == sig.size());
BIO_free(mem);
RSA_free(rsa_private);
return sig;
}
QString CommaApi::create_jwt(QVector<QPair<QString, QJsonValue>> payloads, int expiry) {
QJsonObject header;
header.insert("alg", "RS256");
QJsonObject payload;
QString dongle_id = QString::fromStdString(Params().get("DongleId"));
payload.insert("identity", dongle_id);
auto t = QDateTime::currentSecsSinceEpoch();
payload.insert("nbf", t);
payload.insert("iat", t);
payload.insert("exp", t + expiry);
for (auto load : payloads) {
payload.insert(load.first, load.second);
}
QString jwt =
QJsonDocument(header).toJson(QJsonDocument::Compact).toBase64(QByteArray::Base64UrlEncoding | QByteArray::OmitTrailingEquals) +
'.' +
QJsonDocument(payload).toJson(QJsonDocument::Compact).toBase64(QByteArray::Base64UrlEncoding | QByteArray::OmitTrailingEquals);
auto hash = QCryptographicHash::hash(jwt.toUtf8(), QCryptographicHash::Sha256);
auto sig = rsa_sign(hash);
jwt += '.' + sig.toBase64(QByteArray::Base64UrlEncoding | QByteArray::OmitTrailingEquals);
return jwt;
}
QString CommaApi::create_jwt() {
return create_jwt(*(new QVector<QPair<QString, QJsonValue>>()));
}
RequestRepeater::RequestRepeater(QWidget* parent, QString requestURL, int period_seconds, QVector<QPair<QString, QJsonValue>> payloads, bool disableWithScreen)
: disableWithScreen(disableWithScreen) {
networkAccessManager = new QNetworkAccessManager(parent);
QTimer* timer = new QTimer(this);
QObject::connect(timer, &QTimer::timeout, [=](){sendRequest(requestURL, payloads);});
timer->start(period_seconds * 1000);
networkTimer = new QTimer(this);
networkTimer->setSingleShot(true);
networkTimer->setInterval(20000); // 20s before aborting
connect(networkTimer, SIGNAL(timeout()), this, SLOT(requestTimeout()));
}
void RequestRepeater::sendRequest(QString requestURL, QVector<QPair<QString, QJsonValue>> payloads){
// No network calls onroad
if(GLWindow::ui_state.started){
return;
}
if (!active || (!GLWindow::ui_state.awake && disableWithScreen)) {
return;
}
if(reply != NULL){
return;
}
aborted = false;
callId = QRandomGenerator::global()->bounded(1000);
QString token = CommaApi::create_jwt(payloads);
QNetworkRequest request;
request.setUrl(QUrl(requestURL));
request.setRawHeader("Authorization", ("JWT " + token).toUtf8());
reply = networkAccessManager->get(request);
networkTimer->start();
connect(reply, SIGNAL(finished()), this, SLOT(requestFinished()));
}
void RequestRepeater::requestTimeout(){
aborted = true;
reply->abort();
}
// This function should always emit something
void RequestRepeater::requestFinished(){
if(!aborted){
networkTimer->stop();
QString response = reply->readAll();
if (reply->error() == QNetworkReply::NoError) {
emit receivedResponse(response);
} else {
emit failedResponse(reply->errorString());
}
}else{
emit failedResponse("Custom Openpilot network timeout");
}
reply->deleteLater();
reply = NULL;
}

@ -0,0 +1,47 @@
#pragma once
#include <QCryptographicHash>
#include <QJsonValue>
#include <QNetworkReply>
#include <QNetworkRequest>
#include <QPair>
#include <QString>
#include <QVector>
#include <QWidget>
#include <atomic>
#include <openssl/bio.h>
#include <openssl/pem.h>
#include <openssl/rsa.h>
class CommaApi : public QObject {
Q_OBJECT
public:
static QByteArray rsa_sign(QByteArray data);
static QString create_jwt(QVector<QPair<QString, QJsonValue>> payloads, int expiry = 60);
static QString create_jwt();
private:
QNetworkAccessManager* networkAccessManager;
};
/**
* Makes repeated requests to the request endpoint.
*/
class RequestRepeater : public QObject {
Q_OBJECT
public:
explicit RequestRepeater(QWidget* parent, QString requestURL, int period = 10, QVector<QPair<QString, QJsonValue>> payloads = *(new QVector<QPair<QString, QJsonValue>>()), bool disableWithScreen = true);
bool active = true;
private:
bool disableWithScreen;
int callId;
QNetworkReply* reply;
QNetworkAccessManager* networkAccessManager;
QTimer* networkTimer;
std::atomic<bool> aborted = false; // Not 100% sure we need atomic
void sendRequest(QString requestURL, QVector<QPair<QString, QJsonValue>> payloads);
private slots:
void requestTimeout();
void requestFinished();
signals:
void receivedResponse(QString response);
void failedResponse(QString errorString);
};

@ -1,15 +1,15 @@
#include <cmath>
#include <iostream>
#include <fstream>
#include <iostream>
#include <thread>
#include <QWidget>
#include <QMouseEvent>
#include <QDateTime>
#include <QHBoxLayout>
#include <QVBoxLayout>
#include <QStackedLayout>
#include <QLayout>
#include <QDateTime>
#include <QMouseEvent>
#include <QStackedLayout>
#include <QVBoxLayout>
#include <QWidget>
#include "common/params.h"
@ -17,23 +17,23 @@
#include "paint.hpp"
#include "qt_window.hpp"
#include "widgets/drive_stats.hpp"
#include "widgets/setup.hpp"
#define BACKLIGHT_DT 0.25
#define BACKLIGHT_TS 2.00
OffroadHome::OffroadHome(QWidget *parent) : QWidget(parent) {
QVBoxLayout *main_layout = new QVBoxLayout();
OffroadHome::OffroadHome(QWidget* parent) : QWidget(parent) {
QVBoxLayout* main_layout = new QVBoxLayout();
main_layout->setContentsMargins(sbr_w + 50, 50, 50, 50);
// top header
QHBoxLayout *header_layout = new QHBoxLayout();
QHBoxLayout* header_layout = new QHBoxLayout();
date = new QLabel();
date->setStyleSheet(R"(font-size: 55px;)");
header_layout->addWidget(date, 0, Qt::AlignTop | Qt::AlignLeft);
QLabel *version = new QLabel(QString::fromStdString("openpilot v" + Params().get("Version")));
QLabel* version = new QLabel(QString::fromStdString("openpilot v" + Params().get("Version")));
version->setStyleSheet(R"(font-size: 45px;)");
header_layout->addWidget(version, 0, Qt::AlignTop | Qt::AlignRight);
@ -47,9 +47,19 @@ OffroadHome::OffroadHome(QWidget *parent) : QWidget(parent) {
main_layout->addSpacing(25);
center_layout = new QStackedLayout();
DriveStats *drive = new DriveStats;
QHBoxLayout* statsAndSetup = new QHBoxLayout();
DriveStats* drive = new DriveStats;
drive->setFixedSize(1000, 800);
center_layout->addWidget(drive);
statsAndSetup->addWidget(drive);
SetupWidget* setup = new SetupWidget;
statsAndSetup->addWidget(setup);
QWidget* statsAndSetupWidget = new QWidget();
statsAndSetupWidget->setLayout(statsAndSetup);
center_layout->addWidget(statsAndSetupWidget);
alerts_widget = new OffroadAlert();
QObject::connect(alerts_widget, SIGNAL(closeAlerts()), this, SLOT(closeAlerts()));
@ -113,14 +123,13 @@ void OffroadHome::refresh() {
font-weight: bold;
background-color: #E22C2C;
)");
if (alerts_widget->updateAvailable){
if (alerts_widget->updateAvailable) {
style.replace("#E22C2C", "#364DEF");
}
alert_notification->setStyleSheet(style);
}
HomeWindow::HomeWindow(QWidget *parent) : QWidget(parent) {
HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
layout = new QGridLayout;
layout->setMargin(0);
@ -145,8 +154,8 @@ void HomeWindow::setVisibility(bool offroad) {
home->setVisible(offroad);
}
void HomeWindow::mousePressEvent(QMouseEvent *e) {
UIState *ui_state = glWindow->ui_state;
void HomeWindow::mousePressEvent(QMouseEvent* e) {
UIState* ui_state = &glWindow->ui_state;
glWindow->wake();
@ -161,14 +170,13 @@ void HomeWindow::mousePressEvent(QMouseEvent *e) {
}
}
static void handle_display_state(UIState *s, int dt, bool user_input) {
static int awake_timeout = 0;
awake_timeout = std::max(awake_timeout-dt, 0);
static void handle_display_state(UIState* s, bool user_input) {
static int awake_timeout = 0; // Somehow this only gets called on program start
awake_timeout = std::max(awake_timeout - 1, 0);
if (user_input || s->ignition || s->started) {
s->awake = true;
awake_timeout = 30*UI_FREQ;
awake_timeout = 30 * UI_FREQ;
} else if (awake_timeout == 0) {
s->awake = false;
}
@ -182,8 +190,7 @@ static void set_backlight(int brightness) {
}
}
GLWindow::GLWindow(QWidget *parent) : QOpenGLWidget(parent) {
GLWindow::GLWindow(QWidget* parent) : QOpenGLWidget(parent) {
timer = new QTimer(this);
QObject::connect(timer, SIGNAL(timeout()), this, SLOT(timerUpdate()));
@ -211,15 +218,12 @@ void GLWindow::initializeGL() {
std::cout << "OpenGL renderer: " << glGetString(GL_RENDERER) << std::endl;
std::cout << "OpenGL language version: " << glGetString(GL_SHADING_LANGUAGE_VERSION) << std::endl;
ui_state = new UIState();
ui_state->sound = &sound;
ui_state->fb_w = vwp_w;
ui_state->fb_h = vwp_h;
ui_init(ui_state);
ui_state.sound = &sound;
ui_init(&ui_state);
wake();
timer->start(0);
timer->start(1000 / UI_FREQ);
backlight_timer->start(BACKLIGHT_DT * 1000);
}
@ -227,11 +231,11 @@ void GLWindow::backlightUpdate() {
// Update brightness
float k = (BACKLIGHT_DT / BACKLIGHT_TS) / (1.0f + BACKLIGHT_DT / BACKLIGHT_TS);
float clipped_brightness = std::min(1023.0f, (ui_state->light_sensor*brightness_m) + brightness_b);
float clipped_brightness = std::min(1023.0f, (ui_state.light_sensor * brightness_m) + brightness_b);
smooth_brightness = clipped_brightness * k + smooth_brightness * (1.0f - k);
int brightness = smooth_brightness;
if (!ui_state->awake) {
if (!ui_state.awake) {
brightness = 0;
}
@ -239,19 +243,23 @@ void GLWindow::backlightUpdate() {
}
void GLWindow::timerUpdate() {
if (ui_state->started != onroad) {
onroad = ui_state->started;
// Connecting to visionIPC requires opengl to be current
if (!ui_state.vipc_client->connected){
makeCurrent();
}
if (ui_state.started != onroad) {
onroad = ui_state.started;
emit offroadTransition(!onroad);
#ifdef QCOM2
timer->setInterval(onroad ? 0 : 1000);
#endif
// Change timeout to 0 when onroad, this will call timerUpdate continously.
// This puts visionIPC in charge of update frequency, reducing video latency
timer->start(onroad ? 0 : 1000 / UI_FREQ);
}
// Fix awake timeout if running 1 Hz when offroad
int dt = timer->interval() == 0 ? 1 : 20;
handle_display_state(ui_state, dt, false);
handle_display_state(&ui_state, false);
ui_update(ui_state);
ui_update(&ui_state);
repaint();
}
@ -260,18 +268,18 @@ void GLWindow::resizeGL(int w, int h) {
}
void GLWindow::paintGL() {
ui_draw(ui_state);
if(GLWindow::ui_state.awake){
ui_draw(&ui_state);
}
}
void GLWindow::wake() {
// UI state might not be initialized yet
if (ui_state != nullptr) {
handle_display_state(ui_state, 1, true);
}
handle_display_state(&ui_state, true);
}
FramebufferState* framebuffer_init(const char* name, int32_t layer, int alpha,
int *out_w, int *out_h) {
*out_w = vwp_w;
*out_h = vwp_h;
return (FramebufferState*)1; // not null
}

@ -1,19 +1,18 @@
#pragma once
#include <QLabel>
#include <QTimer>
#include <QWidget>
#include <QGridLayout>
#include <QStackedWidget>
#include <QStackedLayout>
#include <QOpenGLWidget>
#include <QLabel>
#include <QOpenGLFunctions>
#include <QOpenGLWidget>
#include <QPushButton>
#include <QStackedLayout>
#include <QStackedWidget>
#include <QTimer>
#include <QWidget>
#include "qt_sound.hpp"
#include "widgets/offroad_alerts.hpp"
#include "ui/ui.hpp"
#include "widgets/offroad_alerts.hpp"
// container window for onroad NVG UI
class GLWindow : public QOpenGLWidget, protected QOpenGLFunctions {
@ -21,11 +20,11 @@ class GLWindow : public QOpenGLWidget, protected QOpenGLFunctions {
public:
using QOpenGLWidget::QOpenGLWidget;
explicit GLWindow(QWidget *parent = 0);
explicit GLWindow(QWidget* parent = 0);
void wake();
~GLWindow();
UIState *ui_state = nullptr;
inline static UIState ui_state = {0};
signals:
void offroadTransition(bool offroad);
@ -36,8 +35,8 @@ protected:
void paintGL() override;
private:
QTimer *timer;
QTimer *backlight_timer;
QTimer* timer;
QTimer* backlight_timer;
QtSound sound;
@ -58,42 +57,40 @@ class OffroadHome : public QWidget {
Q_OBJECT
public:
explicit OffroadHome(QWidget *parent = 0);
explicit OffroadHome(QWidget* parent = 0);
private:
QTimer *timer;
QTimer* timer;
// offroad home screen widgets
QLabel *date;
QStackedLayout *center_layout;
OffroadAlert *alerts_widget;
QPushButton *alert_notification;
QLabel* date;
QStackedLayout* center_layout;
OffroadAlert* alerts_widget;
QPushButton* alert_notification;
public slots:
void closeAlerts();
void closeAlerts();
void openAlerts();
void refresh();
};
class HomeWindow : public QWidget {
Q_OBJECT
public:
explicit HomeWindow(QWidget *parent = 0);
GLWindow *glWindow;
explicit HomeWindow(QWidget* parent = 0);
GLWindow* glWindow;
signals:
void openSettings();
protected:
void mousePressEvent(QMouseEvent *e) override;
void mousePressEvent(QMouseEvent* e) override;
private:
QGridLayout *layout;
OffroadHome *home;
QGridLayout* layout;
OffroadHome* home;
private slots:
void setVisibility(bool offroad);
};

@ -0,0 +1,862 @@
/*
* QR Code generator library (C++)
*
* Copyright (c) Project Nayuki. (MIT License)
* https://www.nayuki.io/page/qr-code-generator-library
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
* - The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
* - The Software is provided "as is", without warranty of any kind, express or
* implied, including but not limited to the warranties of merchantability,
* fitness for a particular purpose and noninfringement. In no event shall the
* authors or copyright holders be liable for any claim, damages or other
* liability, whether in an action of contract, tort or otherwise, arising from,
* out of or in connection with the Software or the use or other dealings in the
* Software.
*/
#include <algorithm>
#include <climits>
#include <cstddef>
#include <cstdlib>
#include <cstring>
#include <sstream>
#include <stdexcept>
#include <utility>
#include "QrCode.hpp"
using std::int8_t;
using std::uint8_t;
using std::size_t;
using std::vector;
namespace qrcodegen {
QrSegment::Mode::Mode(int mode, int cc0, int cc1, int cc2) :
modeBits(mode) {
numBitsCharCount[0] = cc0;
numBitsCharCount[1] = cc1;
numBitsCharCount[2] = cc2;
}
int QrSegment::Mode::getModeBits() const {
return modeBits;
}
int QrSegment::Mode::numCharCountBits(int ver) const {
return numBitsCharCount[(ver + 7) / 17];
}
const QrSegment::Mode QrSegment::Mode::NUMERIC (0x1, 10, 12, 14);
const QrSegment::Mode QrSegment::Mode::ALPHANUMERIC(0x2, 9, 11, 13);
const QrSegment::Mode QrSegment::Mode::BYTE (0x4, 8, 16, 16);
const QrSegment::Mode QrSegment::Mode::KANJI (0x8, 8, 10, 12);
const QrSegment::Mode QrSegment::Mode::ECI (0x7, 0, 0, 0);
QrSegment QrSegment::makeBytes(const vector<uint8_t> &data) {
if (data.size() > static_cast<unsigned int>(INT_MAX))
throw std::length_error("Data too long");
BitBuffer bb;
for (uint8_t b : data)
bb.appendBits(b, 8);
return QrSegment(Mode::BYTE, static_cast<int>(data.size()), std::move(bb));
}
QrSegment QrSegment::makeNumeric(const char *digits) {
BitBuffer bb;
int accumData = 0;
int accumCount = 0;
int charCount = 0;
for (; *digits != '\0'; digits++, charCount++) {
char c = *digits;
if (c < '0' || c > '9')
throw std::domain_error("String contains non-numeric characters");
accumData = accumData * 10 + (c - '0');
accumCount++;
if (accumCount == 3) {
bb.appendBits(static_cast<uint32_t>(accumData), 10);
accumData = 0;
accumCount = 0;
}
}
if (accumCount > 0) // 1 or 2 digits remaining
bb.appendBits(static_cast<uint32_t>(accumData), accumCount * 3 + 1);
return QrSegment(Mode::NUMERIC, charCount, std::move(bb));
}
QrSegment QrSegment::makeAlphanumeric(const char *text) {
BitBuffer bb;
int accumData = 0;
int accumCount = 0;
int charCount = 0;
for (; *text != '\0'; text++, charCount++) {
const char *temp = std::strchr(ALPHANUMERIC_CHARSET, *text);
if (temp == nullptr)
throw std::domain_error("String contains unencodable characters in alphanumeric mode");
accumData = accumData * 45 + static_cast<int>(temp - ALPHANUMERIC_CHARSET);
accumCount++;
if (accumCount == 2) {
bb.appendBits(static_cast<uint32_t>(accumData), 11);
accumData = 0;
accumCount = 0;
}
}
if (accumCount > 0) // 1 character remaining
bb.appendBits(static_cast<uint32_t>(accumData), 6);
return QrSegment(Mode::ALPHANUMERIC, charCount, std::move(bb));
}
vector<QrSegment> QrSegment::makeSegments(const char *text) {
// Select the most efficient segment encoding automatically
vector<QrSegment> result;
if (*text == '\0'); // Leave result empty
else if (isNumeric(text))
result.push_back(makeNumeric(text));
else if (isAlphanumeric(text))
result.push_back(makeAlphanumeric(text));
else {
vector<uint8_t> bytes;
for (; *text != '\0'; text++)
bytes.push_back(static_cast<uint8_t>(*text));
result.push_back(makeBytes(bytes));
}
return result;
}
QrSegment QrSegment::makeEci(long assignVal) {
BitBuffer bb;
if (assignVal < 0)
throw std::domain_error("ECI assignment value out of range");
else if (assignVal < (1 << 7))
bb.appendBits(static_cast<uint32_t>(assignVal), 8);
else if (assignVal < (1 << 14)) {
bb.appendBits(2, 2);
bb.appendBits(static_cast<uint32_t>(assignVal), 14);
} else if (assignVal < 1000000L) {
bb.appendBits(6, 3);
bb.appendBits(static_cast<uint32_t>(assignVal), 21);
} else
throw std::domain_error("ECI assignment value out of range");
return QrSegment(Mode::ECI, 0, std::move(bb));
}
QrSegment::QrSegment(Mode md, int numCh, const std::vector<bool> &dt) :
mode(md),
numChars(numCh),
data(dt) {
if (numCh < 0)
throw std::domain_error("Invalid value");
}
QrSegment::QrSegment(Mode md, int numCh, std::vector<bool> &&dt) :
mode(md),
numChars(numCh),
data(std::move(dt)) {
if (numCh < 0)
throw std::domain_error("Invalid value");
}
int QrSegment::getTotalBits(const vector<QrSegment> &segs, int version) {
int result = 0;
for (const QrSegment &seg : segs) {
int ccbits = seg.mode.numCharCountBits(version);
if (seg.numChars >= (1L << ccbits))
return -1; // The segment's length doesn't fit the field's bit width
if (4 + ccbits > INT_MAX - result)
return -1; // The sum will overflow an int type
result += 4 + ccbits;
if (seg.data.size() > static_cast<unsigned int>(INT_MAX - result))
return -1; // The sum will overflow an int type
result += static_cast<int>(seg.data.size());
}
return result;
}
bool QrSegment::isAlphanumeric(const char *text) {
for (; *text != '\0'; text++) {
if (std::strchr(ALPHANUMERIC_CHARSET, *text) == nullptr)
return false;
}
return true;
}
bool QrSegment::isNumeric(const char *text) {
for (; *text != '\0'; text++) {
char c = *text;
if (c < '0' || c > '9')
return false;
}
return true;
}
QrSegment::Mode QrSegment::getMode() const {
return mode;
}
int QrSegment::getNumChars() const {
return numChars;
}
const std::vector<bool> &QrSegment::getData() const {
return data;
}
const char *QrSegment::ALPHANUMERIC_CHARSET = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ $%*+-./:";
int QrCode::getFormatBits(Ecc ecl) {
switch (ecl) {
case Ecc::LOW : return 1;
case Ecc::MEDIUM : return 0;
case Ecc::QUARTILE: return 3;
case Ecc::HIGH : return 2;
default: throw std::logic_error("Assertion error");
}
}
QrCode QrCode::encodeText(const char *text, Ecc ecl) {
vector<QrSegment> segs = QrSegment::makeSegments(text);
return encodeSegments(segs, ecl);
}
QrCode QrCode::encodeBinary(const vector<uint8_t> &data, Ecc ecl) {
vector<QrSegment> segs{QrSegment::makeBytes(data)};
return encodeSegments(segs, ecl);
}
QrCode QrCode::encodeSegments(const vector<QrSegment> &segs, Ecc ecl,
int minVersion, int maxVersion, int mask, bool boostEcl) {
if (!(MIN_VERSION <= minVersion && minVersion <= maxVersion && maxVersion <= MAX_VERSION) || mask < -1 || mask > 7)
throw std::invalid_argument("Invalid value");
// Find the minimal version number to use
int version, dataUsedBits;
for (version = minVersion; ; version++) {
int dataCapacityBits = getNumDataCodewords(version, ecl) * 8; // Number of data bits available
dataUsedBits = QrSegment::getTotalBits(segs, version);
if (dataUsedBits != -1 && dataUsedBits <= dataCapacityBits)
break; // This version number is found to be suitable
if (version >= maxVersion) { // All versions in the range could not fit the given data
std::ostringstream sb;
if (dataUsedBits == -1)
sb << "Segment too long";
else {
sb << "Data length = " << dataUsedBits << " bits, ";
sb << "Max capacity = " << dataCapacityBits << " bits";
}
throw data_too_long(sb.str());
}
}
if (dataUsedBits == -1)
throw std::logic_error("Assertion error");
// Increase the error correction level while the data still fits in the current version number
for (Ecc newEcl : vector<Ecc>{Ecc::MEDIUM, Ecc::QUARTILE, Ecc::HIGH}) { // From low to high
if (boostEcl && dataUsedBits <= getNumDataCodewords(version, newEcl) * 8)
ecl = newEcl;
}
// Concatenate all segments to create the data bit string
BitBuffer bb;
for (const QrSegment &seg : segs) {
bb.appendBits(static_cast<uint32_t>(seg.getMode().getModeBits()), 4);
bb.appendBits(static_cast<uint32_t>(seg.getNumChars()), seg.getMode().numCharCountBits(version));
bb.insert(bb.end(), seg.getData().begin(), seg.getData().end());
}
if (bb.size() != static_cast<unsigned int>(dataUsedBits))
throw std::logic_error("Assertion error");
// Add terminator and pad up to a byte if applicable
size_t dataCapacityBits = static_cast<size_t>(getNumDataCodewords(version, ecl)) * 8;
if (bb.size() > dataCapacityBits)
throw std::logic_error("Assertion error");
bb.appendBits(0, std::min(4, static_cast<int>(dataCapacityBits - bb.size())));
bb.appendBits(0, (8 - static_cast<int>(bb.size() % 8)) % 8);
if (bb.size() % 8 != 0)
throw std::logic_error("Assertion error");
// Pad with alternating bytes until data capacity is reached
for (uint8_t padByte = 0xEC; bb.size() < dataCapacityBits; padByte ^= 0xEC ^ 0x11)
bb.appendBits(padByte, 8);
// Pack bits into bytes in big endian
vector<uint8_t> dataCodewords(bb.size() / 8);
for (size_t i = 0; i < bb.size(); i++)
dataCodewords[i >> 3] |= (bb.at(i) ? 1 : 0) << (7 - (i & 7));
// Create the QR Code object
return QrCode(version, ecl, dataCodewords, mask);
}
QrCode::QrCode(int ver, Ecc ecl, const vector<uint8_t> &dataCodewords, int msk) :
// Initialize fields and check arguments
version(ver),
errorCorrectionLevel(ecl) {
if (ver < MIN_VERSION || ver > MAX_VERSION)
throw std::domain_error("Version value out of range");
if (msk < -1 || msk > 7)
throw std::domain_error("Mask value out of range");
size = ver * 4 + 17;
size_t sz = static_cast<size_t>(size);
modules = vector<vector<bool> >(sz, vector<bool>(sz)); // Initially all white
isFunction = vector<vector<bool> >(sz, vector<bool>(sz));
// Compute ECC, draw modules
drawFunctionPatterns();
const vector<uint8_t> allCodewords = addEccAndInterleave(dataCodewords);
drawCodewords(allCodewords);
// Do masking
if (msk == -1) { // Automatically choose best mask
long minPenalty = LONG_MAX;
for (int i = 0; i < 8; i++) {
applyMask(i);
drawFormatBits(i);
long penalty = getPenaltyScore();
if (penalty < minPenalty) {
msk = i;
minPenalty = penalty;
}
applyMask(i); // Undoes the mask due to XOR
}
}
if (msk < 0 || msk > 7)
throw std::logic_error("Assertion error");
this->mask = msk;
applyMask(msk); // Apply the final choice of mask
drawFormatBits(msk); // Overwrite old format bits
isFunction.clear();
isFunction.shrink_to_fit();
}
int QrCode::getVersion() const {
return version;
}
int QrCode::getSize() const {
return size;
}
QrCode::Ecc QrCode::getErrorCorrectionLevel() const {
return errorCorrectionLevel;
}
int QrCode::getMask() const {
return mask;
}
bool QrCode::getModule(int x, int y) const {
return 0 <= x && x < size && 0 <= y && y < size && module(x, y);
}
std::string QrCode::toSvgString(int border) const {
if (border < 0)
throw std::domain_error("Border must be non-negative");
if (border > INT_MAX / 2 || border * 2 > INT_MAX - size)
throw std::overflow_error("Border too large");
std::ostringstream sb;
sb << "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n";
sb << "<!DOCTYPE svg PUBLIC \"-//W3C//DTD SVG 1.1//EN\" \"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd\">\n";
sb << "<svg xmlns=\"http://www.w3.org/2000/svg\" version=\"1.1\" viewBox=\"0 0 ";
sb << (size + border * 2) << " " << (size + border * 2) << "\" stroke=\"none\">\n";
sb << "\t<rect width=\"100%\" height=\"100%\" fill=\"#FFFFFF\"/>\n";
sb << "\t<path d=\"";
for (int y = 0; y < size; y++) {
for (int x = 0; x < size; x++) {
if (getModule(x, y)) {
if (x != 0 || y != 0)
sb << " ";
sb << "M" << (x + border) << "," << (y + border) << "h1v1h-1z";
}
}
}
sb << "\" fill=\"#000000\"/>\n";
sb << "</svg>\n";
return sb.str();
}
void QrCode::drawFunctionPatterns() {
// Draw horizontal and vertical timing patterns
for (int i = 0; i < size; i++) {
setFunctionModule(6, i, i % 2 == 0);
setFunctionModule(i, 6, i % 2 == 0);
}
// Draw 3 finder patterns (all corners except bottom right; overwrites some timing modules)
drawFinderPattern(3, 3);
drawFinderPattern(size - 4, 3);
drawFinderPattern(3, size - 4);
// Draw numerous alignment patterns
const vector<int> alignPatPos = getAlignmentPatternPositions();
size_t numAlign = alignPatPos.size();
for (size_t i = 0; i < numAlign; i++) {
for (size_t j = 0; j < numAlign; j++) {
// Don't draw on the three finder corners
if (!((i == 0 && j == 0) || (i == 0 && j == numAlign - 1) || (i == numAlign - 1 && j == 0)))
drawAlignmentPattern(alignPatPos.at(i), alignPatPos.at(j));
}
}
// Draw configuration data
drawFormatBits(0); // Dummy mask value; overwritten later in the constructor
drawVersion();
}
void QrCode::drawFormatBits(int msk) {
// Calculate error correction code and pack bits
int data = getFormatBits(errorCorrectionLevel) << 3 | msk; // errCorrLvl is uint2, msk is uint3
int rem = data;
for (int i = 0; i < 10; i++)
rem = (rem << 1) ^ ((rem >> 9) * 0x537);
int bits = (data << 10 | rem) ^ 0x5412; // uint15
if (bits >> 15 != 0)
throw std::logic_error("Assertion error");
// Draw first copy
for (int i = 0; i <= 5; i++)
setFunctionModule(8, i, getBit(bits, i));
setFunctionModule(8, 7, getBit(bits, 6));
setFunctionModule(8, 8, getBit(bits, 7));
setFunctionModule(7, 8, getBit(bits, 8));
for (int i = 9; i < 15; i++)
setFunctionModule(14 - i, 8, getBit(bits, i));
// Draw second copy
for (int i = 0; i < 8; i++)
setFunctionModule(size - 1 - i, 8, getBit(bits, i));
for (int i = 8; i < 15; i++)
setFunctionModule(8, size - 15 + i, getBit(bits, i));
setFunctionModule(8, size - 8, true); // Always black
}
void QrCode::drawVersion() {
if (version < 7)
return;
// Calculate error correction code and pack bits
int rem = version; // version is uint6, in the range [7, 40]
for (int i = 0; i < 12; i++)
rem = (rem << 1) ^ ((rem >> 11) * 0x1F25);
long bits = static_cast<long>(version) << 12 | rem; // uint18
if (bits >> 18 != 0)
throw std::logic_error("Assertion error");
// Draw two copies
for (int i = 0; i < 18; i++) {
bool bit = getBit(bits, i);
int a = size - 11 + i % 3;
int b = i / 3;
setFunctionModule(a, b, bit);
setFunctionModule(b, a, bit);
}
}
void QrCode::drawFinderPattern(int x, int y) {
for (int dy = -4; dy <= 4; dy++) {
for (int dx = -4; dx <= 4; dx++) {
int dist = std::max(std::abs(dx), std::abs(dy)); // Chebyshev/infinity norm
int xx = x + dx, yy = y + dy;
if (0 <= xx && xx < size && 0 <= yy && yy < size)
setFunctionModule(xx, yy, dist != 2 && dist != 4);
}
}
}
void QrCode::drawAlignmentPattern(int x, int y) {
for (int dy = -2; dy <= 2; dy++) {
for (int dx = -2; dx <= 2; dx++)
setFunctionModule(x + dx, y + dy, std::max(std::abs(dx), std::abs(dy)) != 1);
}
}
void QrCode::setFunctionModule(int x, int y, bool isBlack) {
size_t ux = static_cast<size_t>(x);
size_t uy = static_cast<size_t>(y);
modules .at(uy).at(ux) = isBlack;
isFunction.at(uy).at(ux) = true;
}
bool QrCode::module(int x, int y) const {
return modules.at(static_cast<size_t>(y)).at(static_cast<size_t>(x));
}
vector<uint8_t> QrCode::addEccAndInterleave(const vector<uint8_t> &data) const {
if (data.size() != static_cast<unsigned int>(getNumDataCodewords(version, errorCorrectionLevel)))
throw std::invalid_argument("Invalid argument");
// Calculate parameter numbers
int numBlocks = NUM_ERROR_CORRECTION_BLOCKS[static_cast<int>(errorCorrectionLevel)][version];
int blockEccLen = ECC_CODEWORDS_PER_BLOCK [static_cast<int>(errorCorrectionLevel)][version];
int rawCodewords = getNumRawDataModules(version) / 8;
int numShortBlocks = numBlocks - rawCodewords % numBlocks;
int shortBlockLen = rawCodewords / numBlocks;
// Split data into blocks and append ECC to each block
vector<vector<uint8_t> > blocks;
const vector<uint8_t> rsDiv = reedSolomonComputeDivisor(blockEccLen);
for (int i = 0, k = 0; i < numBlocks; i++) {
vector<uint8_t> dat(data.cbegin() + k, data.cbegin() + (k + shortBlockLen - blockEccLen + (i < numShortBlocks ? 0 : 1)));
k += static_cast<int>(dat.size());
const vector<uint8_t> ecc = reedSolomonComputeRemainder(dat, rsDiv);
if (i < numShortBlocks)
dat.push_back(0);
dat.insert(dat.end(), ecc.cbegin(), ecc.cend());
blocks.push_back(std::move(dat));
}
// Interleave (not concatenate) the bytes from every block into a single sequence
vector<uint8_t> result;
for (size_t i = 0; i < blocks.at(0).size(); i++) {
for (size_t j = 0; j < blocks.size(); j++) {
// Skip the padding byte in short blocks
if (i != static_cast<unsigned int>(shortBlockLen - blockEccLen) || j >= static_cast<unsigned int>(numShortBlocks))
result.push_back(blocks.at(j).at(i));
}
}
if (result.size() != static_cast<unsigned int>(rawCodewords))
throw std::logic_error("Assertion error");
return result;
}
void QrCode::drawCodewords(const vector<uint8_t> &data) {
if (data.size() != static_cast<unsigned int>(getNumRawDataModules(version) / 8))
throw std::invalid_argument("Invalid argument");
size_t i = 0; // Bit index into the data
// Do the funny zigzag scan
for (int right = size - 1; right >= 1; right -= 2) { // Index of right column in each column pair
if (right == 6)
right = 5;
for (int vert = 0; vert < size; vert++) { // Vertical counter
for (int j = 0; j < 2; j++) {
size_t x = static_cast<size_t>(right - j); // Actual x coordinate
bool upward = ((right + 1) & 2) == 0;
size_t y = static_cast<size_t>(upward ? size - 1 - vert : vert); // Actual y coordinate
if (!isFunction.at(y).at(x) && i < data.size() * 8) {
modules.at(y).at(x) = getBit(data.at(i >> 3), 7 - static_cast<int>(i & 7));
i++;
}
// If this QR Code has any remainder bits (0 to 7), they were assigned as
// 0/false/white by the constructor and are left unchanged by this method
}
}
}
if (i != data.size() * 8)
throw std::logic_error("Assertion error");
}
void QrCode::applyMask(int msk) {
if (msk < 0 || msk > 7)
throw std::domain_error("Mask value out of range");
size_t sz = static_cast<size_t>(size);
for (size_t y = 0; y < sz; y++) {
for (size_t x = 0; x < sz; x++) {
bool invert;
switch (msk) {
case 0: invert = (x + y) % 2 == 0; break;
case 1: invert = y % 2 == 0; break;
case 2: invert = x % 3 == 0; break;
case 3: invert = (x + y) % 3 == 0; break;
case 4: invert = (x / 3 + y / 2) % 2 == 0; break;
case 5: invert = x * y % 2 + x * y % 3 == 0; break;
case 6: invert = (x * y % 2 + x * y % 3) % 2 == 0; break;
case 7: invert = ((x + y) % 2 + x * y % 3) % 2 == 0; break;
default: throw std::logic_error("Assertion error");
}
modules.at(y).at(x) = modules.at(y).at(x) ^ (invert & !isFunction.at(y).at(x));
}
}
}
long QrCode::getPenaltyScore() const {
long result = 0;
// Adjacent modules in row having same color, and finder-like patterns
for (int y = 0; y < size; y++) {
bool runColor = false;
int runX = 0;
std::array<int,7> runHistory = {};
for (int x = 0; x < size; x++) {
if (module(x, y) == runColor) {
runX++;
if (runX == 5)
result += PENALTY_N1;
else if (runX > 5)
result++;
} else {
finderPenaltyAddHistory(runX, runHistory);
if (!runColor)
result += finderPenaltyCountPatterns(runHistory) * PENALTY_N3;
runColor = module(x, y);
runX = 1;
}
}
result += finderPenaltyTerminateAndCount(runColor, runX, runHistory) * PENALTY_N3;
}
// Adjacent modules in column having same color, and finder-like patterns
for (int x = 0; x < size; x++) {
bool runColor = false;
int runY = 0;
std::array<int,7> runHistory = {};
for (int y = 0; y < size; y++) {
if (module(x, y) == runColor) {
runY++;
if (runY == 5)
result += PENALTY_N1;
else if (runY > 5)
result++;
} else {
finderPenaltyAddHistory(runY, runHistory);
if (!runColor)
result += finderPenaltyCountPatterns(runHistory) * PENALTY_N3;
runColor = module(x, y);
runY = 1;
}
}
result += finderPenaltyTerminateAndCount(runColor, runY, runHistory) * PENALTY_N3;
}
// 2*2 blocks of modules having same color
for (int y = 0; y < size - 1; y++) {
for (int x = 0; x < size - 1; x++) {
bool color = module(x, y);
if ( color == module(x + 1, y) &&
color == module(x, y + 1) &&
color == module(x + 1, y + 1))
result += PENALTY_N2;
}
}
// Balance of black and white modules
int black = 0;
for (const vector<bool> &row : modules) {
for (bool color : row) {
if (color)
black++;
}
}
int total = size * size; // Note that size is odd, so black/total != 1/2
// Compute the smallest integer k >= 0 such that (45-5k)% <= black/total <= (55+5k)%
int k = static_cast<int>((std::abs(black * 20L - total * 10L) + total - 1) / total) - 1;
result += k * PENALTY_N4;
return result;
}
vector<int> QrCode::getAlignmentPatternPositions() const {
if (version == 1)
return vector<int>();
else {
int numAlign = version / 7 + 2;
int step = (version == 32) ? 26 :
(version*4 + numAlign*2 + 1) / (numAlign*2 - 2) * 2;
vector<int> result;
for (int i = 0, pos = size - 7; i < numAlign - 1; i++, pos -= step)
result.insert(result.begin(), pos);
result.insert(result.begin(), 6);
return result;
}
}
int QrCode::getNumRawDataModules(int ver) {
if (ver < MIN_VERSION || ver > MAX_VERSION)
throw std::domain_error("Version number out of range");
int result = (16 * ver + 128) * ver + 64;
if (ver >= 2) {
int numAlign = ver / 7 + 2;
result -= (25 * numAlign - 10) * numAlign - 55;
if (ver >= 7)
result -= 36;
}
if (!(208 <= result && result <= 29648))
throw std::logic_error("Assertion error");
return result;
}
int QrCode::getNumDataCodewords(int ver, Ecc ecl) {
return getNumRawDataModules(ver) / 8
- ECC_CODEWORDS_PER_BLOCK [static_cast<int>(ecl)][ver]
* NUM_ERROR_CORRECTION_BLOCKS[static_cast<int>(ecl)][ver];
}
vector<uint8_t> QrCode::reedSolomonComputeDivisor(int degree) {
if (degree < 1 || degree > 255)
throw std::domain_error("Degree out of range");
// Polynomial coefficients are stored from highest to lowest power, excluding the leading term which is always 1.
// For example the polynomial x^3 + 255x^2 + 8x + 93 is stored as the uint8 array {255, 8, 93}.
vector<uint8_t> result(static_cast<size_t>(degree));
result.at(result.size() - 1) = 1; // Start off with the monomial x^0
// Compute the product polynomial (x - r^0) * (x - r^1) * (x - r^2) * ... * (x - r^{degree-1}),
// and drop the highest monomial term which is always 1x^degree.
// Note that r = 0x02, which is a generator element of this field GF(2^8/0x11D).
uint8_t root = 1;
for (int i = 0; i < degree; i++) {
// Multiply the current product by (x - r^i)
for (size_t j = 0; j < result.size(); j++) {
result.at(j) = reedSolomonMultiply(result.at(j), root);
if (j + 1 < result.size())
result.at(j) ^= result.at(j + 1);
}
root = reedSolomonMultiply(root, 0x02);
}
return result;
}
vector<uint8_t> QrCode::reedSolomonComputeRemainder(const vector<uint8_t> &data, const vector<uint8_t> &divisor) {
vector<uint8_t> result(divisor.size());
for (uint8_t b : data) { // Polynomial division
uint8_t factor = b ^ result.at(0);
result.erase(result.begin());
result.push_back(0);
for (size_t i = 0; i < result.size(); i++)
result.at(i) ^= reedSolomonMultiply(divisor.at(i), factor);
}
return result;
}
uint8_t QrCode::reedSolomonMultiply(uint8_t x, uint8_t y) {
// Russian peasant multiplication
int z = 0;
for (int i = 7; i >= 0; i--) {
z = (z << 1) ^ ((z >> 7) * 0x11D);
z ^= ((y >> i) & 1) * x;
}
if (z >> 8 != 0)
throw std::logic_error("Assertion error");
return static_cast<uint8_t>(z);
}
int QrCode::finderPenaltyCountPatterns(const std::array<int,7> &runHistory) const {
int n = runHistory.at(1);
if (n > size * 3)
throw std::logic_error("Assertion error");
bool core = n > 0 && runHistory.at(2) == n && runHistory.at(3) == n * 3 && runHistory.at(4) == n && runHistory.at(5) == n;
return (core && runHistory.at(0) >= n * 4 && runHistory.at(6) >= n ? 1 : 0)
+ (core && runHistory.at(6) >= n * 4 && runHistory.at(0) >= n ? 1 : 0);
}
int QrCode::finderPenaltyTerminateAndCount(bool currentRunColor, int currentRunLength, std::array<int,7> &runHistory) const {
if (currentRunColor) { // Terminate black run
finderPenaltyAddHistory(currentRunLength, runHistory);
currentRunLength = 0;
}
currentRunLength += size; // Add white border to final run
finderPenaltyAddHistory(currentRunLength, runHistory);
return finderPenaltyCountPatterns(runHistory);
}
void QrCode::finderPenaltyAddHistory(int currentRunLength, std::array<int,7> &runHistory) const {
if (runHistory.at(0) == 0)
currentRunLength += size; // Add white border to initial run
std::copy_backward(runHistory.cbegin(), runHistory.cend() - 1, runHistory.end());
runHistory.at(0) = currentRunLength;
}
bool QrCode::getBit(long x, int i) {
return ((x >> i) & 1) != 0;
}
/*---- Tables of constants ----*/
const int QrCode::PENALTY_N1 = 3;
const int QrCode::PENALTY_N2 = 3;
const int QrCode::PENALTY_N3 = 40;
const int QrCode::PENALTY_N4 = 10;
const int8_t QrCode::ECC_CODEWORDS_PER_BLOCK[4][41] = {
// Version: (note that index 0 is for padding, and is set to an illegal value)
//0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40 Error correction level
{-1, 7, 10, 15, 20, 26, 18, 20, 24, 30, 18, 20, 24, 26, 30, 22, 24, 28, 30, 28, 28, 28, 28, 30, 30, 26, 28, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // Low
{-1, 10, 16, 26, 18, 24, 16, 18, 22, 22, 26, 30, 22, 22, 24, 24, 28, 28, 26, 26, 26, 26, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28}, // Medium
{-1, 13, 22, 18, 26, 18, 24, 18, 22, 20, 24, 28, 26, 24, 20, 30, 24, 28, 28, 26, 30, 28, 30, 30, 30, 30, 28, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // Quartile
{-1, 17, 28, 22, 16, 22, 28, 26, 26, 24, 28, 24, 28, 22, 24, 24, 30, 28, 28, 26, 28, 30, 24, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // High
};
const int8_t QrCode::NUM_ERROR_CORRECTION_BLOCKS[4][41] = {
// Version: (note that index 0 is for padding, and is set to an illegal value)
//0, 1, 2, 3, 4, 5, 6, 7, 8, 9,10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40 Error correction level
{-1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 4, 4, 4, 4, 4, 6, 6, 6, 6, 7, 8, 8, 9, 9, 10, 12, 12, 12, 13, 14, 15, 16, 17, 18, 19, 19, 20, 21, 22, 24, 25}, // Low
{-1, 1, 1, 1, 2, 2, 4, 4, 4, 5, 5, 5, 8, 9, 9, 10, 10, 11, 13, 14, 16, 17, 17, 18, 20, 21, 23, 25, 26, 28, 29, 31, 33, 35, 37, 38, 40, 43, 45, 47, 49}, // Medium
{-1, 1, 1, 2, 2, 4, 4, 6, 6, 8, 8, 8, 10, 12, 16, 12, 17, 16, 18, 21, 20, 23, 23, 25, 27, 29, 34, 34, 35, 38, 40, 43, 45, 48, 51, 53, 56, 59, 62, 65, 68}, // Quartile
{-1, 1, 1, 2, 4, 4, 4, 5, 6, 8, 8, 11, 11, 16, 16, 18, 16, 19, 21, 25, 25, 25, 34, 30, 32, 35, 37, 40, 42, 45, 48, 51, 54, 57, 60, 63, 66, 70, 74, 77, 81}, // High
};
data_too_long::data_too_long(const std::string &msg) :
std::length_error(msg) {}
BitBuffer::BitBuffer()
: std::vector<bool>() {}
void BitBuffer::appendBits(std::uint32_t val, int len) {
if (len < 0 || len > 31 || val >> len != 0)
throw std::domain_error("Value out of range");
for (int i = len - 1; i >= 0; i--) // Append bit by bit
this->push_back(((val >> i) & 1) != 0);
}
}

@ -0,0 +1,556 @@
/*
* QR Code generator library (C++)
*
* Copyright (c) Project Nayuki. (MIT License)
* https://www.nayuki.io/page/qr-code-generator-library
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
* - The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
* - The Software is provided "as is", without warranty of any kind, express or
* implied, including but not limited to the warranties of merchantability,
* fitness for a particular purpose and noninfringement. In no event shall the
* authors or copyright holders be liable for any claim, damages or other
* liability, whether in an action of contract, tort or otherwise, arising from,
* out of or in connection with the Software or the use or other dealings in the
* Software.
*/
#pragma once
#include <array>
#include <cstdint>
#include <stdexcept>
#include <string>
#include <vector>
namespace qrcodegen {
/*
* A segment of character/binary/control data in a QR Code symbol.
* Instances of this class are immutable.
* The mid-level way to create a segment is to take the payload data
* and call a static factory function such as QrSegment::makeNumeric().
* The low-level way to create a segment is to custom-make the bit buffer
* and call the QrSegment() constructor with appropriate values.
* This segment class imposes no length restrictions, but QR Codes have restrictions.
* Even in the most favorable conditions, a QR Code can only hold 7089 characters of data.
* Any segment longer than this is meaningless for the purpose of generating QR Codes.
*/
class QrSegment final {
/*---- Public helper enumeration ----*/
/*
* Describes how a segment's data bits are interpreted. Immutable.
*/
public: class Mode final {
/*-- Constants --*/
public: static const Mode NUMERIC;
public: static const Mode ALPHANUMERIC;
public: static const Mode BYTE;
public: static const Mode KANJI;
public: static const Mode ECI;
/*-- Fields --*/
// The mode indicator bits, which is a uint4 value (range 0 to 15).
private: int modeBits;
// Number of character count bits for three different version ranges.
private: int numBitsCharCount[3];
/*-- Constructor --*/
private: Mode(int mode, int cc0, int cc1, int cc2);
/*-- Methods --*/
/*
* (Package-private) Returns the mode indicator bits, which is an unsigned 4-bit value (range 0 to 15).
*/
public: int getModeBits() const;
/*
* (Package-private) Returns the bit width of the character count field for a segment in
* this mode in a QR Code at the given version number. The result is in the range [0, 16].
*/
public: int numCharCountBits(int ver) const;
};
/*---- Static factory functions (mid level) ----*/
/*
* Returns a segment representing the given binary data encoded in
* byte mode. All input byte vectors are acceptable. Any text string
* can be converted to UTF-8 bytes and encoded as a byte mode segment.
*/
public: static QrSegment makeBytes(const std::vector<std::uint8_t> &data);
/*
* Returns a segment representing the given string of decimal digits encoded in numeric mode.
*/
public: static QrSegment makeNumeric(const char *digits);
/*
* Returns a segment representing the given text string encoded in alphanumeric mode.
* The characters allowed are: 0 to 9, A to Z (uppercase only), space,
* dollar, percent, asterisk, plus, hyphen, period, slash, colon.
*/
public: static QrSegment makeAlphanumeric(const char *text);
/*
* Returns a list of zero or more segments to represent the given text string. The result
* may use various segment modes and switch modes to optimize the length of the bit stream.
*/
public: static std::vector<QrSegment> makeSegments(const char *text);
/*
* Returns a segment representing an Extended Channel Interpretation
* (ECI) designator with the given assignment value.
*/
public: static QrSegment makeEci(long assignVal);
/*---- Public static helper functions ----*/
/*
* Tests whether the given string can be encoded as a segment in alphanumeric mode.
* A string is encodable iff each character is in the following set: 0 to 9, A to Z
* (uppercase only), space, dollar, percent, asterisk, plus, hyphen, period, slash, colon.
*/
public: static bool isAlphanumeric(const char *text);
/*
* Tests whether the given string can be encoded as a segment in numeric mode.
* A string is encodable iff each character is in the range 0 to 9.
*/
public: static bool isNumeric(const char *text);
/*---- Instance fields ----*/
/* The mode indicator of this segment. Accessed through getMode(). */
private: Mode mode;
/* The length of this segment's unencoded data. Measured in characters for
* numeric/alphanumeric/kanji mode, bytes for byte mode, and 0 for ECI mode.
* Always zero or positive. Not the same as the data's bit length.
* Accessed through getNumChars(). */
private: int numChars;
/* The data bits of this segment. Accessed through getData(). */
private: std::vector<bool> data;
/*---- Constructors (low level) ----*/
/*
* Creates a new QR Code segment with the given attributes and data.
* The character count (numCh) must agree with the mode and the bit buffer length,
* but the constraint isn't checked. The given bit buffer is copied and stored.
*/
public: QrSegment(Mode md, int numCh, const std::vector<bool> &dt);
/*
* Creates a new QR Code segment with the given parameters and data.
* The character count (numCh) must agree with the mode and the bit buffer length,
* but the constraint isn't checked. The given bit buffer is moved and stored.
*/
public: QrSegment(Mode md, int numCh, std::vector<bool> &&dt);
/*---- Methods ----*/
/*
* Returns the mode field of this segment.
*/
public: Mode getMode() const;
/*
* Returns the character count field of this segment.
*/
public: int getNumChars() const;
/*
* Returns the data bits of this segment.
*/
public: const std::vector<bool> &getData() const;
// (Package-private) Calculates the number of bits needed to encode the given segments at
// the given version. Returns a non-negative number if successful. Otherwise returns -1 if a
// segment has too many characters to fit its length field, or the total bits exceeds INT_MAX.
public: static int getTotalBits(const std::vector<QrSegment> &segs, int version);
/*---- Private constant ----*/
/* The set of all legal characters in alphanumeric mode, where
* each character value maps to the index in the string. */
private: static const char *ALPHANUMERIC_CHARSET;
};
/*
* A QR Code symbol, which is a type of two-dimension barcode.
* Invented by Denso Wave and described in the ISO/IEC 18004 standard.
* Instances of this class represent an immutable square grid of black and white cells.
* The class provides static factory functions to create a QR Code from text or binary data.
* The class covers the QR Code Model 2 specification, supporting all versions (sizes)
* from 1 to 40, all 4 error correction levels, and 4 character encoding modes.
*
* Ways to create a QR Code object:
* - High level: Take the payload data and call QrCode::encodeText() or QrCode::encodeBinary().
* - Mid level: Custom-make the list of segments and call QrCode::encodeSegments().
* - Low level: Custom-make the array of data codeword bytes (including
* segment headers and final padding, excluding error correction codewords),
* supply the appropriate version number, and call the QrCode() constructor.
* (Note that all ways require supplying the desired error correction level.)
*/
class QrCode final {
/*---- Public helper enumeration ----*/
/*
* The error correction level in a QR Code symbol.
*/
public: enum class Ecc {
LOW = 0 , // The QR Code can tolerate about 7% erroneous codewords
MEDIUM , // The QR Code can tolerate about 15% erroneous codewords
QUARTILE, // The QR Code can tolerate about 25% erroneous codewords
HIGH , // The QR Code can tolerate about 30% erroneous codewords
};
// Returns a value in the range 0 to 3 (unsigned 2-bit integer).
private: static int getFormatBits(Ecc ecl);
/*---- Static factory functions (high level) ----*/
/*
* Returns a QR Code representing the given Unicode text string at the given error correction level.
* As a conservative upper bound, this function is guaranteed to succeed for strings that have 2953 or fewer
* UTF-8 code units (not Unicode code points) if the low error correction level is used. The smallest possible
* QR Code version is automatically chosen for the output. The ECC level of the result may be higher than
* the ecl argument if it can be done without increasing the version.
*/
public: static QrCode encodeText(const char *text, Ecc ecl);
/*
* Returns a QR Code representing the given binary data at the given error correction level.
* This function always encodes using the binary segment mode, not any text mode. The maximum number of
* bytes allowed is 2953. The smallest possible QR Code version is automatically chosen for the output.
* The ECC level of the result may be higher than the ecl argument if it can be done without increasing the version.
*/
public: static QrCode encodeBinary(const std::vector<std::uint8_t> &data, Ecc ecl);
/*---- Static factory functions (mid level) ----*/
/*
* Returns a QR Code representing the given segments with the given encoding parameters.
* The smallest possible QR Code version within the given range is automatically
* chosen for the output. Iff boostEcl is true, then the ECC level of the result
* may be higher than the ecl argument if it can be done without increasing the
* version. The mask number is either between 0 to 7 (inclusive) to force that
* mask, or -1 to automatically choose an appropriate mask (which may be slow).
* This function allows the user to create a custom sequence of segments that switches
* between modes (such as alphanumeric and byte) to encode text in less space.
* This is a mid-level API; the high-level API is encodeText() and encodeBinary().
*/
public: static QrCode encodeSegments(const std::vector<QrSegment> &segs, Ecc ecl,
int minVersion=1, int maxVersion=40, int mask=-1, bool boostEcl=true); // All optional parameters
/*---- Instance fields ----*/
// Immutable scalar parameters:
/* The version number of this QR Code, which is between 1 and 40 (inclusive).
* This determines the size of this barcode. */
private: int version;
/* The width and height of this QR Code, measured in modules, between
* 21 and 177 (inclusive). This is equal to version * 4 + 17. */
private: int size;
/* The error correction level used in this QR Code. */
private: Ecc errorCorrectionLevel;
/* The index of the mask pattern used in this QR Code, which is between 0 and 7 (inclusive).
* Even if a QR Code is created with automatic masking requested (mask = -1),
* the resulting object still has a mask value between 0 and 7. */
private: int mask;
// Private grids of modules/pixels, with dimensions of size*size:
// The modules of this QR Code (false = white, true = black).
// Immutable after constructor finishes. Accessed through getModule().
private: std::vector<std::vector<bool> > modules;
// Indicates function modules that are not subjected to masking. Discarded when constructor finishes.
private: std::vector<std::vector<bool> > isFunction;
/*---- Constructor (low level) ----*/
/*
* Creates a new QR Code with the given version number,
* error correction level, data codeword bytes, and mask number.
* This is a low-level API that most users should not use directly.
* A mid-level API is the encodeSegments() function.
*/
public: QrCode(int ver, Ecc ecl, const std::vector<std::uint8_t> &dataCodewords, int msk);
/*---- Public instance methods ----*/
/*
* Returns this QR Code's version, in the range [1, 40].
*/
public: int getVersion() const;
/*
* Returns this QR Code's size, in the range [21, 177].
*/
public: int getSize() const;
/*
* Returns this QR Code's error correction level.
*/
public: Ecc getErrorCorrectionLevel() const;
/*
* Returns this QR Code's mask, in the range [0, 7].
*/
public: int getMask() const;
/*
* Returns the color of the module (pixel) at the given coordinates, which is false
* for white or true for black. The top left corner has the coordinates (x=0, y=0).
* If the given coordinates are out of bounds, then false (white) is returned.
*/
public: bool getModule(int x, int y) const;
/*
* Returns a string of SVG code for an image depicting this QR Code, with the given number
* of border modules. The string always uses Unix newlines (\n), regardless of the platform.
*/
public: std::string toSvgString(int border) const;
/*---- Private helper methods for constructor: Drawing function modules ----*/
// Reads this object's version field, and draws and marks all function modules.
private: void drawFunctionPatterns();
// Draws two copies of the format bits (with its own error correction code)
// based on the given mask and this object's error correction level field.
private: void drawFormatBits(int msk);
// Draws two copies of the version bits (with its own error correction code),
// based on this object's version field, iff 7 <= version <= 40.
private: void drawVersion();
// Draws a 9*9 finder pattern including the border separator,
// with the center module at (x, y). Modules can be out of bounds.
private: void drawFinderPattern(int x, int y);
// Draws a 5*5 alignment pattern, with the center module
// at (x, y). All modules must be in bounds.
private: void drawAlignmentPattern(int x, int y);
// Sets the color of a module and marks it as a function module.
// Only used by the constructor. Coordinates must be in bounds.
private: void setFunctionModule(int x, int y, bool isBlack);
// Returns the color of the module at the given coordinates, which must be in range.
private: bool module(int x, int y) const;
/*---- Private helper methods for constructor: Codewords and masking ----*/
// Returns a new byte string representing the given data with the appropriate error correction
// codewords appended to it, based on this object's version and error correction level.
private: std::vector<std::uint8_t> addEccAndInterleave(const std::vector<std::uint8_t> &data) const;
// Draws the given sequence of 8-bit codewords (data and error correction) onto the entire
// data area of this QR Code. Function modules need to be marked off before this is called.
private: void drawCodewords(const std::vector<std::uint8_t> &data);
// XORs the codeword modules in this QR Code with the given mask pattern.
// The function modules must be marked and the codeword bits must be drawn
// before masking. Due to the arithmetic of XOR, calling applyMask() with
// the same mask value a second time will undo the mask. A final well-formed
// QR Code needs exactly one (not zero, two, etc.) mask applied.
private: void applyMask(int msk);
// Calculates and returns the penalty score based on state of this QR Code's current modules.
// This is used by the automatic mask choice algorithm to find the mask pattern that yields the lowest score.
private: long getPenaltyScore() const;
/*---- Private helper functions ----*/
// Returns an ascending list of positions of alignment patterns for this version number.
// Each position is in the range [0,177), and are used on both the x and y axes.
// This could be implemented as lookup table of 40 variable-length lists of unsigned bytes.
private: std::vector<int> getAlignmentPatternPositions() const;
// Returns the number of data bits that can be stored in a QR Code of the given version number, after
// all function modules are excluded. This includes remainder bits, so it might not be a multiple of 8.
// The result is in the range [208, 29648]. This could be implemented as a 40-entry lookup table.
private: static int getNumRawDataModules(int ver);
// Returns the number of 8-bit data (i.e. not error correction) codewords contained in any
// QR Code of the given version number and error correction level, with remainder bits discarded.
// This stateless pure function could be implemented as a (40*4)-cell lookup table.
private: static int getNumDataCodewords(int ver, Ecc ecl);
// Returns a Reed-Solomon ECC generator polynomial for the given degree. This could be
// implemented as a lookup table over all possible parameter values, instead of as an algorithm.
private: static std::vector<std::uint8_t> reedSolomonComputeDivisor(int degree);
// Returns the Reed-Solomon error correction codeword for the given data and divisor polynomials.
private: static std::vector<std::uint8_t> reedSolomonComputeRemainder(const std::vector<std::uint8_t> &data, const std::vector<std::uint8_t> &divisor);
// Returns the product of the two given field elements modulo GF(2^8/0x11D).
// All inputs are valid. This could be implemented as a 256*256 lookup table.
private: static std::uint8_t reedSolomonMultiply(std::uint8_t x, std::uint8_t y);
// Can only be called immediately after a white run is added, and
// returns either 0, 1, or 2. A helper function for getPenaltyScore().
private: int finderPenaltyCountPatterns(const std::array<int,7> &runHistory) const;
// Must be called at the end of a line (row or column) of modules. A helper function for getPenaltyScore().
private: int finderPenaltyTerminateAndCount(bool currentRunColor, int currentRunLength, std::array<int,7> &runHistory) const;
// Pushes the given value to the front and drops the last value. A helper function for getPenaltyScore().
private: void finderPenaltyAddHistory(int currentRunLength, std::array<int,7> &runHistory) const;
// Returns true iff the i'th bit of x is set to 1.
private: static bool getBit(long x, int i);
/*---- Constants and tables ----*/
// The minimum version number supported in the QR Code Model 2 standard.
public: static constexpr int MIN_VERSION = 1;
// The maximum version number supported in the QR Code Model 2 standard.
public: static constexpr int MAX_VERSION = 40;
// For use in getPenaltyScore(), when evaluating which mask is best.
private: static const int PENALTY_N1;
private: static const int PENALTY_N2;
private: static const int PENALTY_N3;
private: static const int PENALTY_N4;
private: static const std::int8_t ECC_CODEWORDS_PER_BLOCK[4][41];
private: static const std::int8_t NUM_ERROR_CORRECTION_BLOCKS[4][41];
};
/*---- Public exception class ----*/
/*
* Thrown when the supplied data does not fit any QR Code version. Ways to handle this exception include:
* - Decrease the error correction level if it was greater than Ecc::LOW.
* - If the encodeSegments() function was called with a maxVersion argument, then increase
* it if it was less than QrCode::MAX_VERSION. (This advice does not apply to the other
* factory functions because they search all versions up to QrCode::MAX_VERSION.)
* - Split the text data into better or optimal segments in order to reduce the number of bits required.
* - Change the text or binary data to be shorter.
* - Change the text to fit the character set of a particular segment mode (e.g. alphanumeric).
* - Propagate the error upward to the caller/user.
*/
class data_too_long : public std::length_error {
public: explicit data_too_long(const std::string &msg);
};
/*
* An appendable sequence of bits (0s and 1s). Mainly used by QrSegment.
*/
class BitBuffer final : public std::vector<bool> {
/*---- Constructor ----*/
// Creates an empty bit buffer (length 0).
public: BitBuffer();
/*---- Method ----*/
// Appends the given number of low-order bits of the given value
// to this buffer. Requires 0 <= len <= 31 and val < 2^len.
public: void appendBits(std::uint32_t val, int len);
};
}

@ -1,27 +1,23 @@
#include <cassert>
#include <iostream>
#include <QFile>
#include <QDebug>
#include <QVBoxLayout>
#include <QLabel>
#include <QFile>
#include <QJsonDocument>
#include <QJsonObject>
#include <QNetworkAccessManager>
#include <QLabel>
#include <QNetworkRequest>
#include <QCryptographicHash>
#include <openssl/rsa.h>
#include <openssl/bio.h>
#include <openssl/pem.h>
#include <QStackedLayout>
#include <QTimer>
#include <QVBoxLayout>
#include "drive_stats.hpp"
#include "api.hpp"
#include "common/params.h"
#include "common/util.h"
#include "drive_stats.hpp"
#include "home.hpp"
constexpr double MILE_TO_KM = 1.60934;
const double MILE_TO_KM = 1.60934;
#if defined(QCOM) || defined(QCOM2)
const std::string private_key_path = "/persist/comma/id_rsa";
@ -29,128 +25,93 @@ const std::string private_key_path = "/persist/comma/id_rsa";
const std::string private_key_path = util::getenv_default("HOME", "/.comma/persist/comma/id_rsa", "/persist/comma/id_rsa");
#endif
QByteArray rsa_sign(QByteArray data) {
auto file = QFile(private_key_path.c_str());
bool r = file.open(QIODevice::ReadOnly);
assert(r);
auto key = file.readAll();
BIO *mem = BIO_new_mem_buf(key.data(), key.size());
assert(mem);
RSA *rsa_private = PEM_read_bio_RSAPrivateKey(mem, NULL, NULL, NULL);
assert(rsa_private);
auto sig = QByteArray();
sig.resize(RSA_size(rsa_private));
unsigned int sig_len;
int ret = RSA_sign(NID_sha256, (unsigned char*)data.data(), data.size(), (unsigned char*)sig.data(), &sig_len, rsa_private);
assert(ret == 1);
assert(sig_len == sig.size());
BIO_free(mem);
RSA_free(rsa_private);
return sig;
}
QString create_jwt(QString dongle_id, int expiry=3600) {
QJsonObject header;
header.insert("alg", "RS256");
header.insert("typ", "JWT");
auto t = QDateTime::currentSecsSinceEpoch();
QJsonObject payload;
payload.insert("identity", dongle_id);
payload.insert("nbf", t);
payload.insert("iat", t);
payload.insert("exp", t + expiry);
QString jwt =
QJsonDocument(header).toJson(QJsonDocument::Compact).toBase64() +
'.' +
QJsonDocument(payload).toJson(QJsonDocument::Compact).toBase64();
auto hash = QCryptographicHash::hash(jwt.toUtf8(), QCryptographicHash::Sha256);
auto sig = rsa_sign(hash);
jwt += '.' + sig.toBase64();
return jwt;
void clearLayouts(QLayout* layout) {
while (QLayoutItem* item = layout->takeAt(0)) {
if (QWidget* widget = item->widget()) {
widget->deleteLater();
}
if (QLayout* childLayout = item->layout()) {
clearLayouts(childLayout);
}
delete item;
}
}
QLayout *build_stat(QString name, int stat) {
QVBoxLayout *layout = new QVBoxLayout;
QLayout* build_stat(QString name, int stat) {
QVBoxLayout* layout = new QVBoxLayout;
QLabel *metric = new QLabel(QString("%1").arg(stat));
QLabel* metric = new QLabel(QString("%1").arg(stat));
metric->setStyleSheet(R"(
font-size: 72px;
font-weight: 700;
)");
layout->addWidget(metric, 0, Qt::AlignLeft);
QLabel *label = new QLabel(name);
QLabel* label = new QLabel(name);
label->setStyleSheet(R"(
font-size: 32px;
font-weight: 600;
)");
layout->addWidget(label, 0, Qt::AlignLeft);
return layout;
}
void DriveStats::replyFinished(QNetworkReply *l) {
QString answer = l->readAll();
answer.chop(1);
void DriveStats::parseError(QString response) {
clearLayouts(vlayout);
vlayout->addWidget(new QLabel("No internet connection"));
}
QJsonDocument doc = QJsonDocument::fromJson(answer.toUtf8());
void DriveStats::parseResponse(QString response) {
response.chop(1);
clearLayouts(vlayout);
QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8());
if (doc.isNull()) {
qDebug() << "JSON Parse failed";
qDebug() << "JSON Parse failed on getting past drives statistics";
return;
}
QString IsMetric = QString::fromStdString(Params().get("IsMetric"));
bool metric = (IsMetric =="1");
bool metric = (IsMetric == "1");
QJsonObject json = doc.object();
auto all = json["all"].toObject();
auto week = json["week"].toObject();
QGridLayout *gl = new QGridLayout();
QGridLayout* gl = new QGridLayout();
int all_distance = all["distance"].toDouble()*(metric ? MILE_TO_KM : 1);
int all_distance = all["distance"].toDouble() * (metric ? MILE_TO_KM : 1);
gl->addWidget(new QLabel("ALL TIME"), 0, 0, 1, 3);
gl->addLayout(build_stat("DRIVES", all["routes"].toDouble()), 1, 0, 3, 1);
gl->addLayout(build_stat(metric ? "KM" : "MILES", all_distance), 1, 1, 3, 1);
gl->addLayout(build_stat("HOURS", all["minutes"].toDouble() / 60), 1, 2, 3, 1);
int week_distance = week["distance"].toDouble()*(metric ? MILE_TO_KM : 1);
int week_distance = week["distance"].toDouble() * (metric ? MILE_TO_KM : 1);
gl->addWidget(new QLabel("PAST WEEK"), 6, 0, 1, 3);
gl->addLayout(build_stat("DRIVES", week["routes"].toDouble()), 7, 0, 3, 1);
gl->addLayout(build_stat(metric ? "KM" : "MILES", week_distance), 7, 1, 3, 1);
gl->addLayout(build_stat("HOURS", week["minutes"].toDouble() / 60), 7, 2, 3, 1);
setLayout(gl);
QWidget* q = new QWidget;
q->setLayout(gl);
vlayout->addWidget(q);
}
DriveStats::DriveStats(QWidget* parent) : QWidget(parent) {
vlayout = new QVBoxLayout(this);
setLayout(vlayout);
setStyleSheet(R"(
QLabel {
font-size: 48px;
font-weight: 600;
}
)");
}
DriveStats::DriveStats(QWidget *parent) : QWidget(parent) {
QString dongle_id = QString::fromStdString(Params().get("DongleId"));
QString token = create_jwt(dongle_id);
QNetworkAccessManager *manager = new QNetworkAccessManager(this);
connect(manager, &QNetworkAccessManager::finished, this, &DriveStats::replyFinished);
QNetworkRequest request;
request.setUrl(QUrl("https://api.commadotai.com/v1.1/devices/" + dongle_id + "/stats"));
request.setRawHeader("Authorization", ("JWT "+token).toUtf8());
QString dongleId = QString::fromStdString(Params().get("DongleId"));
QString url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/stats";
RequestRepeater* repeater = new RequestRepeater(this, url, 13);
QObject::connect(repeater, SIGNAL(receivedResponse(QString)), this, SLOT(parseResponse(QString)));
QObject::connect(repeater, SIGNAL(failedResponse(QString)), this, SLOT(parseError(QString)));
manager->get(request);
}

@ -1,15 +1,21 @@
#pragma once
#include <QWidget>
#include <QNetworkReply>
#include <QVBoxLayout>
#include <QWidget>
#include "api.hpp"
class DriveStats : public QWidget {
Q_OBJECT
public:
explicit DriveStats(QWidget *parent = 0);
explicit DriveStats(QWidget* parent = 0);
private:
void replyFinished(QNetworkReply *l);
QVBoxLayout* vlayout;
private slots:
void parseError(QString response);
void parseResponse(QString response);
};

@ -0,0 +1,276 @@
#include <QDebug>
#include <QJsonDocument>
#include <QJsonObject>
#include <QLabel>
#include <QStackedLayout>
#include <QTimer>
#include <QVBoxLayout>
#include "QrCode.hpp"
#include "api.hpp"
#include "common/params.h"
#include "common/util.h"
#include "home.hpp"
#include "setup.hpp"
using qrcodegen::QrCode;
#if defined(QCOM) || defined(QCOM2)
const std::string private_key_path = "/persist/comma/id_rsa";
#else
const std::string private_key_path = util::getenv_default("HOME", "/.comma/persist/comma/id_rsa", "/persist/comma/id_rsa");
#endif
PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) {
qrCode = new QLabel;
qrCode->setScaledContents(true);
QVBoxLayout* v = new QVBoxLayout;
v->addWidget(qrCode, 0, Qt::AlignCenter);
setLayout(v);
QTimer* timer = new QTimer(this);
timer->start(30 * 1000);// HaLf a minute
connect(timer, SIGNAL(timeout()), this, SLOT(refresh()));
refresh(); // Not waiting for the first refresh
}
void PairingQRWidget::refresh(){
QString IMEI = QString::fromStdString(Params().get("IMEI"));
QString serial = QString::fromStdString(Params().get("HardwareSerial"));
if (std::min(IMEI.length(), serial.length()) <= 5) {
qrCode->setText("Error getting serial: contact support");
qrCode->setWordWrap(true);
qrCode->setStyleSheet(R"(
font-size: 60px;
)");
return;
}
QVector<QPair<QString, QJsonValue>> payloads;
payloads.push_back(qMakePair(QString("pair"), true));
QString pairToken = CommaApi::create_jwt(payloads);
QString qrString = IMEI + "--" + serial + "--" + pairToken;
this->updateQrCode(qrString);
}
void PairingQRWidget::updateQrCode(QString text) {
QrCode qr = QrCode::encodeText(text.toUtf8().data(), QrCode::Ecc::LOW);
qint32 sz = qr.getSize();
// We make the image larger so we can have a white border
QImage im(sz + 2, sz + 2, QImage::Format_RGB32);
QRgb black = qRgb(0, 0, 0);
QRgb white = qRgb(255, 255, 255);
for (int y = 0; y < sz + 2; y++) {
for (int x = 0; x < sz + 2; x++) {
im.setPixel(x, y, white);
}
}
for (int y = 0; y < sz; y++) {
for (int x = 0; x < sz; x++) {
im.setPixel(x + 1, y + 1, qr.getModule(x, y) ? black : white);
}
}
// Integer division to prevent anti-aliasing
int approx500 = (500 / (sz + 2)) * (sz + 2);
qrCode->setPixmap(QPixmap::fromImage(im.scaled(approx500, approx500, Qt::KeepAspectRatio, Qt::FastTransformation), Qt::MonoOnly));
qrCode->setFixedSize(approx500, approx500);
}
PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) {
mainLayout = new QVBoxLayout(this);
QLabel* commaPrime = new QLabel("COMMA PRIME", this);
commaPrime->setStyleSheet(R"(
font-size: 60px;
)");
mainLayout->addWidget(commaPrime);
username = new QLabel("", this);
mainLayout->addWidget(username);
mainLayout->addSpacing(200);
QLabel* commaPoints = new QLabel("COMMA POINTS", this);
commaPoints->setStyleSheet(R"(
font-size: 60px;
color: #b8b8b8;
)");
mainLayout->addWidget(commaPoints);
points = new QLabel("", this);
mainLayout->addWidget(points);
setLayout(mainLayout);
QString dongleId = QString::fromStdString(Params().get("DongleId"));
QString url = "https://api.commadotai.com/v1/devices/" + dongleId + "/owner";
RequestRepeater* repeater = new RequestRepeater(this, url, 6);
QObject::connect(repeater, SIGNAL(receivedResponse(QString)), this, SLOT(replyFinished(QString)));
}
void PrimeUserWidget::replyFinished(QString response) {
QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8());
if (doc.isNull()) {
qDebug() << "JSON Parse failed on getting username and points";
return;
}
QJsonObject json = doc.object();
QString username_str = json["username"].toString();
if (username_str.length()) {
username_str = "@" + username_str;
}
QString points_str = QString::number(json["points"].toInt());
username->setText(username_str);
points->setText(points_str);
}
PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QWidget(parent) {
QVBoxLayout* vlayout = new QVBoxLayout(this);
QLabel* upgradeNow = new QLabel("Upgrade now", this);
vlayout->addWidget(upgradeNow);
QLabel* description = new QLabel("Become a comma prime member in the comma app and get premium features!", this);
description->setStyleSheet(R"(
font-size: 50px;
color: #b8b8b8;
)");
description->setWordWrap(true);
vlayout->addWidget(description);
vlayout->addSpacing(50);
QVector<QString> features = {"✓ REMOTE ACCESS", "✓ 14 DAYS OF STORAGE", "✓ DEVELOPER PERKS"};
for (auto featureContent : features) {
QLabel* feature = new QLabel(featureContent, this);
feature->setStyleSheet(R"(
font-size: 40px;
)");
vlayout->addWidget(feature);
vlayout->addSpacing(15);
}
setLayout(vlayout);
}
SetupWidget::SetupWidget(QWidget* parent) : QWidget(parent) {
QVBoxLayout* backgroundLayout = new QVBoxLayout(this);
backgroundLayout->addSpacing(100);
QFrame* background = new QFrame(this);
mainLayout = new QStackedLayout(this);
QWidget* blankWidget = new QWidget(this);
mainLayout->addWidget(blankWidget);
QWidget* finishRegistration = new QWidget(this);
QVBoxLayout* finishRegistationLayout = new QVBoxLayout(this);
finishRegistationLayout->addSpacing(50);
QPushButton* finishButton = new QPushButton("Finish registration", this);
finishButton->setFixedHeight(200);
finishButton->setStyleSheet(R"(
border-radius: 30px;
font-size: 60px;
font-weight: bold;
background: #787878;
)");
QObject::connect(finishButton, SIGNAL(released()), this, SLOT(showQrCode()));
finishRegistationLayout->addWidget(finishButton);
QLabel* registrationDescription = new QLabel("Pair your device with comma connect app", this);
registrationDescription->setStyleSheet(R"(
font-size: 50px;
)");
registrationDescription->setWordWrap(true);
finishRegistationLayout->addWidget(registrationDescription);
finishRegistration->setLayout(finishRegistationLayout);
mainLayout->addWidget(finishRegistration);
QVBoxLayout* qrLayout = new QVBoxLayout(this);
QLabel* qrLabel = new QLabel("Pair with Comma Connect app!", this);
qrLabel->setStyleSheet(R"(
font-size: 40px;
)");
qrLayout->addWidget(qrLabel);
qrLayout->addWidget(new PairingQRWidget(this));
QWidget* q = new QWidget(this);
q->setLayout(qrLayout);
mainLayout->addWidget(q);
PrimeAdWidget* primeAd = new PrimeAdWidget(this);
mainLayout->addWidget(primeAd);
PrimeUserWidget* primeUserWidget = new PrimeUserWidget(this);
mainLayout->addWidget(primeUserWidget);
background->setLayout(mainLayout);
background->setStyleSheet(R"(
.QFrame {
border-radius: 40px;
padding: 60px;
}
)");
backgroundLayout->addWidget(background);
setLayout(backgroundLayout);
QString dongleId = QString::fromStdString(Params().get("DongleId"));
QString url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/";
RequestRepeater* repeater = new RequestRepeater(this, url, 5);
QObject::connect(repeater, SIGNAL(receivedResponse(QString)), this, SLOT(replyFinished(QString)));
QObject::connect(repeater, SIGNAL(failedResponse(QString)), this, SLOT(parseError(QString)));
}
void SetupWidget::parseError(QString response) {
showQr = false;
mainLayout->setCurrentIndex(0);
setStyleSheet(R"(
font-size: 90px;
background-color: #000000;
)");
}
void SetupWidget::showQrCode(){
showQr = true;
mainLayout->setCurrentIndex(2);
}
void SetupWidget::replyFinished(QString response) {
QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8());
if (doc.isNull()) {
qDebug() << "JSON Parse failed on getting pairing and prime status";
return;
}
if (mainLayout->currentIndex() == 0) { // If we are still on the blank widget
setStyleSheet(R"(
font-size: 90px;
font-weight: bold;
background-color: #292929;
)");
}
QJsonObject json = doc.object();
bool is_paired = json["is_paired"].toBool();
bool is_prime = json["prime"].toBool();
if (!is_paired) {
mainLayout->setCurrentIndex(1 + showQr);
} else if (is_paired && !is_prime) {
showQr = false;
mainLayout->setCurrentIndex(3);
} else if (is_paired && is_prime) {
showQr = false;
mainLayout->setCurrentIndex(4);
}
}

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save