From 79ca8c9ec9763ec0f23839fa8389589451ed4e7c Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Tue, 29 Nov 2016 18:34:21 -0800 Subject: [PATCH] openpilot release old-commit-hash: e94a30bec07e719c5a7b037ca1f4db8312702cce --- .gitattributes | 87 + LICENSE.openpilot | 7 + README.md | 93 + SAFETY.md | 36 + TODO.md | 14 + board/Makefile | 43 + board/adc.h | 38 + board/can.h | 75 + board/dac.h | 16 + board/inc/core_cm3.h | 3 + board/inc/core_cmFunc.h | 3 + board/inc/core_cmInstr.h | 3 + board/inc/stm32f205xx.h | 3 + board/inc/stm32f2xx.h | 3 + board/inc/system_stm32f2xx.h | 3 + board/libc.h | 226 + board/main.c | 499 ++ board/startup_stm32f205xx.s | 511 ++ board/stm32_flash.ld | 163 + board/timer.h | 7 + board/tools/dfu-util-aarch64 | 3 + board/tools/dfu-util-x86_64 | 3 + board/tools/enter_download_mode.py | 20 + board/usb.h | 510 ++ cereal/__init__.py | 7 + cereal/c++.capnp | 26 + cereal/gen/c/c++.capnp.h | 0 cereal/gen/c/log.capnp.c | 1016 +++ cereal/gen/c/log.capnp.h | 667 ++ cereal/gen/cpp/log.capnp.c++ | 3732 +++++++++++ cereal/gen/cpp/log.capnp.h | 7251 ++++++++++++++++++++++ cereal/log.capnp | 272 + common/__init__.py | 0 common/api/__init__.py | 8 + common/crash.py | 26 + common/dbc.py | 182 + common/filters.py | 17 + common/kalman/__init__.py | 0 common/kalman/ekf.py | 300 + common/logging_extra.py | 134 + common/numpy_fast.py | 2 + common/realtime.py | 94 + common/services.py | 82 + dbcs/__init__.py | 2 + dbcs/acura_ilx_2016_can.dbc | 295 + dbcs/acura_ilx_2016_nidec.dbc | 175 + dbcs/honda_civic_touring_2016_can.dbc | 319 + installation/files/continue.sh | 28 + installation/files/id_rsa_openpilot_ro | 27 + installation/install.sh | 11 + phonelibs/hierarchy/lib/_hierarchy.so | 3 + phonelibs/nanovg/fontstash.h | 3 + phonelibs/nanovg/nanovg.c | 3 + phonelibs/nanovg/nanovg.h | 3 + phonelibs/nanovg/nanovg_gl.h | 3 + phonelibs/nanovg/nanovg_gl_utils.h | 3 + phonelibs/nanovg/stb_image.h | 3 + phonelibs/nanovg/stb_truetype.h | 3 + selfdrive/__init__.py | 0 selfdrive/assets/Roboto-Bold.ttf | 3 + selfdrive/assets/courbd.ttf | 3 + selfdrive/boardd/Makefile | 73 + selfdrive/boardd/__init__.py | 0 selfdrive/boardd/boardd.cc | 322 + selfdrive/boardd/boardd.py | 179 + selfdrive/calibrationd/__init__.py | 0 selfdrive/calibrationd/calibration.py | 208 + selfdrive/calibrationd/calibrationd.py | 116 + selfdrive/common/framebuffer.cc | 135 + selfdrive/common/framebuffer.h | 21 + selfdrive/common/mat.h | 68 + selfdrive/common/modeldata.h | 23 + selfdrive/common/mutex.h | 13 + selfdrive/common/swaglog.c | 90 + selfdrive/common/swaglog.h | 26 + selfdrive/common/timing.h | 31 + selfdrive/common/util.h | 22 + selfdrive/common/visionipc.c | 127 + selfdrive/common/visionipc.h | 50 + selfdrive/config.py | 68 + selfdrive/controls/__init__.py | 0 selfdrive/controls/controlsd.py | 358 ++ selfdrive/controls/lib/__init__.py | 0 selfdrive/controls/lib/adaptivecruise.py | 332 + selfdrive/controls/lib/alert_database.py | 178 + selfdrive/controls/lib/can_parser.py | 123 + selfdrive/controls/lib/carcontroller.py | 185 + selfdrive/controls/lib/carstate.py | 275 + selfdrive/controls/lib/drive_helpers.py | 52 + selfdrive/controls/lib/fingerprints.py | 8 + selfdrive/controls/lib/hondacan.py | 88 + selfdrive/controls/lib/latcontrol.py | 120 + selfdrive/controls/lib/longcontrol.py | 232 + selfdrive/controls/lib/pathplanner.py | 63 + selfdrive/controls/lib/radar_helpers.py | 256 + selfdrive/controls/radard.py | 268 + selfdrive/logcatd/Makefile | 58 + selfdrive/logcatd/logcatd.cc | 68 + selfdrive/loggerd/__init__.py | 0 selfdrive/loggerd/config.py | 9 + selfdrive/loggerd/logger.py | 65 + selfdrive/loggerd/loggerd.py | 86 + selfdrive/loggerd/uploader.py | 238 + selfdrive/logmessaged.py | 39 + selfdrive/manager.py | 278 + selfdrive/messaging.py | 52 + selfdrive/registration.py | 38 + selfdrive/sensord/Makefile | 60 + selfdrive/sensord/sensors.cc | 227 + selfdrive/swaglog.py | 38 + selfdrive/thermal.py | 19 + selfdrive/ui/Makefile | 73 + selfdrive/ui/touch.c | 63 + selfdrive/ui/touch.h | 12 + selfdrive/ui/ui.c | 1325 ++++ selfdrive/visiond/Makefile | 4 + selfdrive/visiond/README | 3 + selfdrive/visiond/visiond | 3 + 118 files changed, 23940 insertions(+) create mode 100644 .gitattributes create mode 100644 LICENSE.openpilot create mode 100644 README.md create mode 100644 SAFETY.md create mode 100644 TODO.md create mode 100644 board/Makefile create mode 100644 board/adc.h create mode 100644 board/can.h create mode 100644 board/dac.h create mode 100644 board/inc/core_cm3.h create mode 100644 board/inc/core_cmFunc.h create mode 100644 board/inc/core_cmInstr.h create mode 100644 board/inc/stm32f205xx.h create mode 100644 board/inc/stm32f2xx.h create mode 100644 board/inc/system_stm32f2xx.h create mode 100644 board/libc.h create mode 100644 board/main.c create mode 100644 board/startup_stm32f205xx.s create mode 100644 board/stm32_flash.ld create mode 100644 board/timer.h create mode 100755 board/tools/dfu-util-aarch64 create mode 100755 board/tools/dfu-util-x86_64 create mode 100755 board/tools/enter_download_mode.py create mode 100644 board/usb.h create mode 100644 cereal/__init__.py create mode 100644 cereal/c++.capnp create mode 100644 cereal/gen/c/c++.capnp.h create mode 100644 cereal/gen/c/log.capnp.c create mode 100644 cereal/gen/c/log.capnp.h create mode 100644 cereal/gen/cpp/log.capnp.c++ create mode 100644 cereal/gen/cpp/log.capnp.h create mode 100644 cereal/log.capnp create mode 100644 common/__init__.py create mode 100644 common/api/__init__.py create mode 100644 common/crash.py create mode 100755 common/dbc.py create mode 100644 common/filters.py create mode 100644 common/kalman/__init__.py create mode 100644 common/kalman/ekf.py create mode 100644 common/logging_extra.py create mode 100644 common/numpy_fast.py create mode 100644 common/realtime.py create mode 100644 common/services.py create mode 100644 dbcs/__init__.py create mode 100644 dbcs/acura_ilx_2016_can.dbc create mode 100644 dbcs/acura_ilx_2016_nidec.dbc create mode 100644 dbcs/honda_civic_touring_2016_can.dbc create mode 100755 installation/files/continue.sh create mode 100644 installation/files/id_rsa_openpilot_ro create mode 100755 installation/install.sh create mode 100755 phonelibs/hierarchy/lib/_hierarchy.so create mode 100644 phonelibs/nanovg/fontstash.h create mode 100644 phonelibs/nanovg/nanovg.c create mode 100644 phonelibs/nanovg/nanovg.h create mode 100644 phonelibs/nanovg/nanovg_gl.h create mode 100644 phonelibs/nanovg/nanovg_gl_utils.h create mode 100644 phonelibs/nanovg/stb_image.h create mode 100644 phonelibs/nanovg/stb_truetype.h create mode 100644 selfdrive/__init__.py create mode 100644 selfdrive/assets/Roboto-Bold.ttf create mode 100644 selfdrive/assets/courbd.ttf create mode 100644 selfdrive/boardd/Makefile create mode 100644 selfdrive/boardd/__init__.py create mode 100644 selfdrive/boardd/boardd.cc create mode 100755 selfdrive/boardd/boardd.py create mode 100644 selfdrive/calibrationd/__init__.py create mode 100644 selfdrive/calibrationd/calibration.py create mode 100755 selfdrive/calibrationd/calibrationd.py create mode 100644 selfdrive/common/framebuffer.cc create mode 100644 selfdrive/common/framebuffer.h create mode 100644 selfdrive/common/mat.h create mode 100644 selfdrive/common/modeldata.h create mode 100644 selfdrive/common/mutex.h create mode 100644 selfdrive/common/swaglog.c create mode 100644 selfdrive/common/swaglog.h create mode 100644 selfdrive/common/timing.h create mode 100644 selfdrive/common/util.h create mode 100644 selfdrive/common/visionipc.c create mode 100644 selfdrive/common/visionipc.h create mode 100644 selfdrive/config.py create mode 100644 selfdrive/controls/__init__.py create mode 100755 selfdrive/controls/controlsd.py create mode 100644 selfdrive/controls/lib/__init__.py create mode 100644 selfdrive/controls/lib/adaptivecruise.py create mode 100644 selfdrive/controls/lib/alert_database.py create mode 100644 selfdrive/controls/lib/can_parser.py create mode 100644 selfdrive/controls/lib/carcontroller.py create mode 100644 selfdrive/controls/lib/carstate.py create mode 100644 selfdrive/controls/lib/drive_helpers.py create mode 100644 selfdrive/controls/lib/fingerprints.py create mode 100644 selfdrive/controls/lib/hondacan.py create mode 100644 selfdrive/controls/lib/latcontrol.py create mode 100644 selfdrive/controls/lib/longcontrol.py create mode 100644 selfdrive/controls/lib/pathplanner.py create mode 100644 selfdrive/controls/lib/radar_helpers.py create mode 100755 selfdrive/controls/radard.py create mode 100644 selfdrive/logcatd/Makefile create mode 100644 selfdrive/logcatd/logcatd.cc create mode 100644 selfdrive/loggerd/__init__.py create mode 100644 selfdrive/loggerd/config.py create mode 100644 selfdrive/loggerd/logger.py create mode 100755 selfdrive/loggerd/loggerd.py create mode 100755 selfdrive/loggerd/uploader.py create mode 100755 selfdrive/logmessaged.py create mode 100755 selfdrive/manager.py create mode 100644 selfdrive/messaging.py create mode 100644 selfdrive/registration.py create mode 100644 selfdrive/sensord/Makefile create mode 100644 selfdrive/sensord/sensors.cc create mode 100644 selfdrive/swaglog.py create mode 100644 selfdrive/thermal.py create mode 100644 selfdrive/ui/Makefile create mode 100644 selfdrive/ui/touch.c create mode 100644 selfdrive/ui/touch.h create mode 100644 selfdrive/ui/ui.c create mode 100644 selfdrive/visiond/Makefile create mode 100644 selfdrive/visiond/README create mode 100755 selfdrive/visiond/visiond diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 0000000000..cadb2c30d4 --- /dev/null +++ b/.gitattributes @@ -0,0 +1,87 @@ +*.ico filter=lfs diff=lfs merge=lfs -text +*.dlc filter=lfs diff=lfs merge=lfs -text +*.onnx filter=lfs diff=lfs merge=lfs -text +*.svg filter=lfs diff=lfs merge=lfs -text +*.png filter=lfs diff=lfs merge=lfs -text +*.gif filter=lfs diff=lfs merge=lfs -text +*.ttf filter=lfs diff=lfs merge=lfs -text +*.wav filter=lfs diff=lfs merge=lfs -text +system/hardware/tici/updater filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/spinner_larch64 filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/text_larch64 filter=lfs diff=lfs merge=lfs -text +third_party/**/*.a filter=lfs diff=lfs merge=lfs -text +third_party/**/*.so filter=lfs diff=lfs merge=lfs -text +third_party/**/*.so.* filter=lfs diff=lfs merge=lfs -text +third_party/**/*.dylib filter=lfs diff=lfs merge=lfs -text +third_party/acados/*/t_renderer filter=lfs diff=lfs merge=lfs -text +third_party/qt5/larch64/bin/lrelease filter=lfs diff=lfs merge=lfs -text +third_party/qt5/larch64/bin/lupdate filter=lfs diff=lfs merge=lfs -text +third_party/catch2/include/catch2/catch.hpp filter=lfs diff=lfs merge=lfs -text +*.apk filter=lfs diff=lfs merge=lfs -text +*.apkpatch filter=lfs diff=lfs merge=lfs -text +*.jar filter=lfs diff=lfs merge=lfs -text +*.pdf filter=lfs diff=lfs merge=lfs -text +*.jpg filter=lfs diff=lfs merge=lfs -text +*.mp3 filter=lfs diff=lfs merge=lfs -text +*.thneed filter=lfs diff=lfs merge=lfs -text +*.tar.gz filter=lfs diff=lfs merge=lfs -text +*.npy filter=lfs diff=lfs merge=lfs -text +*.csv filter=lfs diff=lfs merge=lfs -text +*.a filter=lfs diff=lfs merge=lfs -text +*.so* filter=lfs diff=lfs merge=lfs -text +*.dylib filter=lfs diff=lfs merge=lfs -text +*.o filter=lfs diff=lfs merge=lfs -text +*.b64 filter=lfs diff=lfs merge=lfs -text +selfdrive/hardware/tici/updater filter=lfs diff=lfs merge=lfs -text +selfdrive/boardd/tests/test_boardd filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/spinner_aarch64 filter=lfs diff=lfs merge=lfs -text +installer/updater/updater filter=lfs diff=lfs merge=lfs -text +selfdrive/debug/profiling/simpleperf/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/hardware/eon/updater filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/text_aarch64 filter=lfs diff=lfs merge=lfs -text +selfdrive/debug/profiling/pyflame/**/* filter=lfs diff=lfs merge=lfs -text +installer/installers/installer_openpilot filter=lfs diff=lfs merge=lfs -text +installer/installers/installer_dashcam filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/text/text filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/android/text/text filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/spinner/spinner filter=lfs diff=lfs merge=lfs -text +selfdrive/visiond/visiond filter=lfs diff=lfs merge=lfs -text +selfdrive/loggerd/loggerd filter=lfs diff=lfs merge=lfs -text +selfdrive/sensord/sensord filter=lfs diff=lfs merge=lfs -text +selfdrive/sensord/gpsd filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/android/spinner/spinner filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/spinner filter=lfs diff=lfs merge=lfs -text +selfdrive/ui/qt/text filter=lfs diff=lfs merge=lfs -text +_stringdefs.py filter=lfs diff=lfs merge=lfs -text +dfu-util-aarch64-linux filter=lfs diff=lfs merge=lfs -text +dfu-util-aarch64 filter=lfs diff=lfs merge=lfs -text +dfu-util-x86_64-linux filter=lfs diff=lfs merge=lfs -text +dfu-util-x86_64 filter=lfs diff=lfs merge=lfs -text +stb_image.h filter=lfs diff=lfs merge=lfs -text +clpeak3 filter=lfs diff=lfs merge=lfs -text +clwaste filter=lfs diff=lfs merge=lfs -text +apk/**/* filter=lfs diff=lfs merge=lfs -text +external/**/* filter=lfs diff=lfs merge=lfs -text +phonelibs/**/* filter=lfs diff=lfs merge=lfs -text +third_party/boringssl/**/* filter=lfs diff=lfs merge=lfs -text +pyextra/**/* filter=lfs diff=lfs merge=lfs -text +panda/board/**/inc/*.h filter=lfs diff=lfs merge=lfs -text +panda/board/obj/*.elf filter=lfs diff=lfs merge=lfs -text +board/inc/*.h filter=lfs diff=lfs merge=lfs -text +third_party/nanovg/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/lateral_mpc/lib_mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +third_party/android_hardware_libhardware/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +*.pro filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/lateral_mpc/mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +third_party/curl/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/modeld/thneed/debug/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/modeld/thneed/include/**/* filter=lfs diff=lfs merge=lfs -text +third_party/openmax/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/longitudinal_mpc/mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/**/* filter=lfs diff=lfs merge=lfs -text +Pipfile filter=lfs diff=lfs merge=lfs -text +Pipfile.lock filter=lfs diff=lfs merge=lfs -text +poetry.lock filter=lfs diff=lfs merge=lfs -text +*.qm filter=lfs diff=lfs merge=lfs -text diff --git a/LICENSE.openpilot b/LICENSE.openpilot new file mode 100644 index 0000000000..d1b0147269 --- /dev/null +++ b/LICENSE.openpilot @@ -0,0 +1,7 @@ +Copyright (c) 2016, comma.ai + +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. diff --git a/README.md b/README.md new file mode 100644 index 0000000000..6c018638f5 --- /dev/null +++ b/README.md @@ -0,0 +1,93 @@ +Welcome to openpilot +====== + +[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. + +Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas and Acuras. It's about on par with Tesla Autopilot at launch, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). + +The openpilot codebase has been written to be concise and enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier. + +Hardware +------ + +Right now openpilot supports the [neo research platform](http://github.com/commaai/neo) for vehicle control. We'd like to support [Open Source Car Control](https://github.com/PolySync/OSCC) as well. + +To install it on the NEO: + +```bash +# Requires working adb in PATH +cd installation +./install.sh +``` + +Supported Cars +------ + +- Acura ILX 2016 with AcuraWatch Plus + - Limitations: Due to use of the cruise control for gas, it can only be enabled above 25 mph + +- Honda Civic 2016 Touring Edition + - Limitations: Due to limitations in steering firmware, steering is disabled below 18 mph + +Directory structure +------ + +- board -- Code that runs on the USB interface board +- cereal -- The messaging spec used for all logs on the phone +- common -- Library like functionality we've developed here +- dbcs -- Files showing how to interpret data from cars +- installation -- Installation on the neo platform +- phonelibs -- Libraries used on the phone +- selfdrive -- Code needed to drive the car + - assets -- Fonts for ui + - boardd -- Daemon to talk to the board + - calibrationd -- Camera calibration server + - common -- Shared C/C++ code for the daemons + - controls -- Python controls (PID loops etc) for the car + - logcatd -- Android logcat as a service + - loggerd -- Logger and uploader of car data + - sensord -- IMU / GPS interface code + - ui -- The UI + - visiond -- embedded vision pipeline + +To understand how the services interact, see `common/services.py` + +Adding Car Support +------ + +It should be relatively easy to add support for the Honda CR-V Touring. The brake message is the same. Steering has a slightly different message with a different message id. Sniff CAN while using LKAS to find it. + +The Honda Accord uses different signalling for the steering and probably requires new hardware. + +Adding other manufacturers besides Honda/Acura is doable but will be more of an undertaking. + + +User Data / chffr Account / Crash Reporting +------ + +By default openpilot creates an account and includes a client for chffr, our dashcam app. We use your data to train better models and improve openpilot for everyone. + +It's open source software, so you are free to disable it if you wish. + +It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +It does not log the user facing camera or the microphone. + +By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. + +Contributing +------ + +We welcome both pull requests and issues on +[github](http://github.com/commaai/openpilot). See the TODO file for a list of +good places to start. + + + +Licensing +------ + +openpilot is released under the MIT license. + +**THIS IS ALPHA QUALITY SOFTWARE FOR RESEARCH PURPOSES ONLY. THIS IS NOT A PRODUCT. +YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. +NO WARRANTY EXPRESSED OR IMPLIED.** diff --git a/SAFETY.md b/SAFETY.md new file mode 100644 index 0000000000..72297d8d7c --- /dev/null +++ b/SAFETY.md @@ -0,0 +1,36 @@ +openpilot Safety +====== + +openpilot is an Adaptive Cruise Control and Lane Keeping Assist System. Like +other ACC and LKAS systems, openpilot requires the driver to be alert and to pay +attention at all times. We repeat, **driver alertness is necessary, but not +sufficient, for openpilot to be used safely**. + +Even with an attentive driver, we must make further efforts for the system to be +safe. We have designed openpilot with two other safety considerations. + +1. The vehicle must always be controllable by the driver. +2. The vehicle must not alter its trajectory too quickly for the driver to safely + react. + +To address these, we came up with two safety principles. + +1. Enforced disengagements. Step on either pedal or press the cancel button to + retake manual control of the car immediately. + - These are hard enforced by the board, and soft enforced by the software. The + green led on the board signifies if the board is allowing control messages. + - Honda CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +2. Actuation limits. While the system is engaged, the actuators are constrained + to operate within reasonable limits; the same limits used by the stock system on + the Honda. + - Without an interceptor, the gas is controlled by the PCM. The PCM limits + acceleration to what is reasonable for a cruise control system. With an + interceptor, the gas is clipped to 60% in longcontrol.py + - The brake is controlled by the 0x1FA CAN message. This message allows full + braking, although the board and the software clip it to 1/4th of the max. + This is around .3g of braking. + - Steering is controlled by the 0xE4 CAN message. The EPS controller in the + car limits the torque to a very small amount, so regardless of the message, + the controller cannot jerk the wheel. diff --git a/TODO.md b/TODO.md new file mode 100644 index 0000000000..b7b842c609 --- /dev/null +++ b/TODO.md @@ -0,0 +1,14 @@ +TODO +====== + +An incomplete list of known issues and desired featues. + +- TX and RX amounts on UI are wrong for a few frames at startup because we + subtract (total sent - 0). We should initialize sent bytes before displaying. + +- Rewrite common/dbc.py to be faster and cleaner, potentially in C++. + +- Add module and class level documentation where appropriate. + +- Fix lock file cleanup so there isn't always 1 pending upload when the vehicle + shuts off. diff --git a/board/Makefile b/board/Makefile new file mode 100644 index 0000000000..4c0b6d38ac --- /dev/null +++ b/board/Makefile @@ -0,0 +1,43 @@ +# :set noet +PROJ_NAME = comma + +CFLAGS = -g -O0 -Wall +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 +CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx +CFLAGS += -I inc -nostdlib +CFLAGS += -Tstm32_flash.ld + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy +OBJDUMP = arm-none-eabi-objdump + +MACHINE = $(shell uname -m) + +all: obj/$(PROJ_NAME).bin + #$(OBJDUMP) -d obj/$(PROJ_NAME).elf + ./tools/enter_download_mode.py + ./tools/dfu-util-$(MACHINE) -a 0 -s 0x08000000 -D $< + ./tools/dfu-util-$(MACHINE) --reset-stm32 -a 0 -s 0x08000000 + +ifneq ($(wildcard ../.git/HEAD),) +obj/gitversion.h: ../.git/HEAD ../.git/index + echo "const uint8_t gitversion[] = \"$(shell git rev-parse HEAD)\";" > $@ +else +obj/gitversion.h: + echo "const uint8_t gitversion[] = \"RELEASE\";" > $@ +endif + +obj/main.o: main.c *.h obj/gitversion.h + $(CC) $(CFLAGS) -o $@ -c $< + +obj/startup_stm32f205xx.o: startup_stm32f205xx.s + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(PROJ_NAME).bin: obj/startup_stm32f205xx.o obj/main.o + $(CC) $(CFLAGS) -o obj/$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf $@ + +clean: + rm -f obj/* + diff --git a/board/adc.h b/board/adc.h new file mode 100644 index 0000000000..3ac2fe4fe4 --- /dev/null +++ b/board/adc.h @@ -0,0 +1,38 @@ +// ACCEL1 = ADC10 +// ACCEL2 = ADC11 +// VOLT_S = ADC12 +// CURR_S = ADC13 + +#define ADCCHAN_ACCEL0 10 +#define ADCCHAN_ACCEL1 11 +#define ADCCHAN_VOLTAGE 12 +#define ADCCHAN_CURRENT 13 + +void adc_init() { + // global setup + ADC->CCR = ADC_CCR_TSVREFE | ADC_CCR_VBATE; + //ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_EOCS | ADC_CR2_DDS; + ADC1->CR2 = ADC_CR2_ADON; + + // long + ADC1->SMPR1 = ADC_SMPR1_SMP10 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13; +} + +uint32_t adc_get(int channel) { + + // includes length + //ADC1->SQR1 = 0; + + // select channel + ADC1->JSQR = channel << 15; + + //ADC1->CR1 = ADC_CR1_DISCNUM_0; + //ADC1->CR1 = ADC_CR1_EOCIE; + + ADC1->SR &= ~(ADC_SR_JEOC); + ADC1->CR2 |= ADC_CR2_JSWSTART; + while (!(ADC1->SR & ADC_SR_JEOC)); + + return ADC1->JDR1; +} + diff --git a/board/can.h b/board/can.h new file mode 100644 index 0000000000..02053bafb6 --- /dev/null +++ b/board/can.h @@ -0,0 +1,75 @@ +void can_init(CAN_TypeDef *CAN) { + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ; + while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); + puts("CAN initting\n"); + + // PCLK = 24000000, 500000 is 48 clocks + // from http://www.bittiming.can-wiki.ino/ + CAN->BTR = 0x001c0002; + + // loopback mode for debugging + #ifdef CAN_LOOPBACK_MODE + CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; + #endif + + // reset + CAN->MCR = CAN_MCR_TTCM; + while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK); + puts("CAN init done\n"); + + // accept all filter + CAN->FMR |= CAN_FMR_FINIT; + + // no mask + CAN->sFilterRegister[0].FR1 = 0; + CAN->sFilterRegister[0].FR2 = 0; + CAN->sFilterRegister[14].FR1 = 0; + CAN->sFilterRegister[14].FR2 = 0; + CAN->FA1R |= 1 | (1 << 14); + + CAN->FMR &= ~(CAN_FMR_FINIT); + + // enable all CAN interrupts + CAN->IER = 0xFFFFFFFF; + //CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_FMPIE1; +} + +// CAN error +void can_sce(CAN_TypeDef *CAN) { + #ifdef DEBUG + puts("MSR:"); + puth(CAN->MSR); + puts(" TSR:"); + puth(CAN->TSR); + puts(" RF0R:"); + puth(CAN->RF0R); + puts(" RF1R:"); + puth(CAN->RF1R); + puts(" ESR:"); + puth(CAN->ESR); + puts("\n"); + #endif + + // clear + //CAN->sTxMailBox[0].TIR &= ~(CAN_TI0R_TXRQ); + CAN->TSR |= CAN_TSR_ABRQ0; + //CAN->ESR |= CAN_ESR_LEC; + //CAN->MSR &= ~(CAN_MSR_ERRI); + CAN->MSR = CAN->MSR; +} + +int can_cksum(uint8_t *dat, int len, int addr, int idx) { + int i; + int s = 0; + for (i = 0; i < len; i++) { + s += (dat[i] >> 4); + s += dat[i] & 0xF; + } + s += (addr>>0)&0xF; + s += (addr>>4)&0xF; + s += (addr>>8)&0xF; + s += idx; + s = 8-s; + return s&0xF; +} + diff --git a/board/dac.h b/board/dac.h new file mode 100644 index 0000000000..b8833dc4a6 --- /dev/null +++ b/board/dac.h @@ -0,0 +1,16 @@ +void dac_init() { + // no buffers required since we have an opamp + //DAC->CR = DAC_CR_EN1 | DAC_CR_BOFF1 | DAC_CR_EN2 | DAC_CR_BOFF2; + DAC->DHR12R1 = 0; + DAC->DHR12R2 = 0; + DAC->CR = DAC_CR_EN1 | DAC_CR_EN2; +} + +void dac_set(int channel, uint32_t value) { + if (channel == 0) { + DAC->DHR12R1 = value; + } else if (channel == 1) { + DAC->DHR12R2 = value; + } +} + diff --git a/board/inc/core_cm3.h b/board/inc/core_cm3.h new file mode 100644 index 0000000000..3230d27cb1 --- /dev/null +++ b/board/inc/core_cm3.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3bd14e0d9e44e2bdd8dce60a680f484dd33ef79b639c460e3c7f76f3a2e58dfe +size 68970 diff --git a/board/inc/core_cmFunc.h b/board/inc/core_cmFunc.h new file mode 100644 index 0000000000..9d7dad3e84 --- /dev/null +++ b/board/inc/core_cmFunc.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:eaab1efbdca39a8beef502bdd4fda19062a99f6f765f418b6ce90b2ecdd0a44b +size 15691 diff --git a/board/inc/core_cmInstr.h b/board/inc/core_cmInstr.h new file mode 100644 index 0000000000..6bb15f9f12 --- /dev/null +++ b/board/inc/core_cmInstr.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:50802216cbc740ecb847d6d9317aa131816b9f1c40cae4d9c8203207ef417fd8 +size 16117 diff --git a/board/inc/stm32f205xx.h b/board/inc/stm32f205xx.h new file mode 100644 index 0000000000..a5221edd5d --- /dev/null +++ b/board/inc/stm32f205xx.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:42cd116f10c4cd3814bd09d7ca6fa5d551de3b83ac27013f53962d6e1879c64f +size 614079 diff --git a/board/inc/stm32f2xx.h b/board/inc/stm32f2xx.h new file mode 100644 index 0000000000..3f80ca09a7 --- /dev/null +++ b/board/inc/stm32f2xx.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:92af21aaac6645199edf6b5ca2130b172652a0c929ae6ab8faa0bc72b0df6288 +size 5993 diff --git a/board/inc/system_stm32f2xx.h b/board/inc/system_stm32f2xx.h new file mode 100644 index 0000000000..33d731a777 --- /dev/null +++ b/board/inc/system_stm32f2xx.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:086226c6423159dc7856adb385add2f550dcb53459b6a1dd3d9647649646453e +size 2092 diff --git a/board/libc.h b/board/libc.h new file mode 100644 index 0000000000..4a2913b883 --- /dev/null +++ b/board/libc.h @@ -0,0 +1,226 @@ +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_))) +#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100) +#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) +#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F)) + +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF10_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS */ + +#ifdef OLD_BOARD + #define USART USART2 +#else + #define USART USART3 +#endif + + +// **** shitty libc **** + +void clock_init() { + #ifdef USE_INTERNAL_OSC + // enable internal oscillator + RCC->CR |= RCC_CR_HSION; + while ((RCC->CR & RCC_CR_HSIRDY) == 0); + #else + // enable external oscillator + RCC->CR |= RCC_CR_HSEON; + while ((RCC->CR & RCC_CR_HSERDY) == 0); + #endif + + // divide shit + RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4; + #ifdef USE_INTERNAL_OSC + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSI; + #else + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE; + #endif + + // start PLL + RCC->CR |= RCC_CR_PLLON; + while ((RCC->CR & RCC_CR_PLLRDY) == 0); + + // Configure Flash prefetch, Instruction cache, Data cache and wait state + // *** without this, it breaks *** + FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS; + + // switch to PLL + RCC->CFGR |= RCC_CFGR_SW_PLL; + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); + + // *** running on PLL *** + + // enable GPIOB, UART2, CAN, USB clock + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + RCC->APB1ENR |= RCC_APB1ENR_USART3EN; + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; + RCC->APB1ENR |= RCC_APB1ENR_DACEN; + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + //RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; + + // turn on alt USB + RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN; + + // fix interrupt vectors +} + +// board specific +void gpio_init() { + // analog mode + GPIOC->MODER = GPIO_MODER_MODER3 | GPIO_MODER_MODER2 | + GPIO_MODER_MODER1 | GPIO_MODER_MODER0; + + // FAN on C9, aka TIM3_CH4 + #ifdef OLD_BOARD + GPIOC->MODER |= GPIO_MODER_MODER9_1; + GPIOC->AFR[1] = GPIO_AF2_TIM3 << ((9-8)*4); + #else + GPIOC->MODER |= GPIO_MODER_MODER8_1; + GPIOC->AFR[1] = GPIO_AF2_TIM3 << ((8-8)*4); + #endif + // IGNITION on C13 + + // set mode for LEDs and CAN + GPIOB->MODER = GPIO_MODER_MODER10_0 | GPIO_MODER_MODER11_0; + // CAN 2 + GPIOB->MODER |= GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1; + // CAN 1 + GPIOB->MODER |= GPIO_MODER_MODER8_1 | GPIO_MODER_MODER9_1; + // CAN enables + GPIOB->MODER |= GPIO_MODER_MODER3_0 | GPIO_MODER_MODER4_0; + + // set mode for SERIAL and USB (DAC should be configured to in) + GPIOA->MODER = GPIO_MODER_MODER2_1 | GPIO_MODER_MODER3_1; + GPIOA->AFR[0] = GPIO_AF7_USART2 << (2*4) | GPIO_AF7_USART2 << (3*4); + + // GPIOC USART3 + GPIOC->MODER |= GPIO_MODER_MODER10_1 | GPIO_MODER_MODER11_1; + GPIOC->AFR[1] |= GPIO_AF7_USART3 << ((10-8)*4) | GPIO_AF7_USART3 << ((11-8)*4); + + if (USBx == USB_OTG_FS) { + GPIOA->MODER |= GPIO_MODER_MODER11_1 | GPIO_MODER_MODER12_1; + GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; + GPIOA->AFR[1] = GPIO_AF10_OTG_FS << ((11-8)*4) | GPIO_AF10_OTG_FS << ((12-8)*4); + } + + GPIOA->PUPDR = GPIO_PUPDR_PUPDR2_0 | GPIO_PUPDR_PUPDR3_0; + + // set mode for CAN / USB_HS pins + GPIOB->AFR[0] = GPIO_AF9_CAN1 << (5*4) | GPIO_AF9_CAN1 << (6*4); + GPIOB->AFR[1] = GPIO_AF9_CAN1 << ((8-8)*4) | GPIO_AF9_CAN1 << ((9-8)*4); + + if (USBx == USB_OTG_HS) { + GPIOB->AFR[1] |= GPIO_AF12_OTG_HS_FS << ((15-8)*4) | GPIO_AF12_OTG_HS_FS << ((14-8)*4); + GPIOB->MODER |= GPIO_MODER_MODER14_1 | GPIO_MODER_MODER15_1; + } + + GPIOB->OSPEEDR = GPIO_OSPEEDER_OSPEEDR14 | GPIO_OSPEEDER_OSPEEDR15; + + // enable CAN busses + GPIOB->ODR |= (1 << 3) | (1 << 4); + + // enable OTG out tied to ground + GPIOA->ODR = 0; + GPIOA->MODER |= GPIO_MODER_MODER1_0; + + // enable USB power tied to + + GPIOA->ODR |= 1; + GPIOA->MODER |= GPIO_MODER_MODER0_0; +} + +void uart_init() { + // enable uart and tx+rx mode + USART->CR1 = USART_CR1_UE; + USART->BRR = __USART_BRR(24000000, 115200); + USART->CR1 |= USART_CR1_TE | USART_CR1_RE; + USART->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1; + // ** UART is ready to work ** + + // enable interrupts + USART->CR1 |= USART_CR1_RXNEIE; +} + +void delay(int a) { + volatile int i; + for (i=0;iSR & USART_SR_TXE)); + USART->DR = a; +} + +int puts(const char *a) { + for (;*a;a++) { + if (*a == '\n') putch('\r'); + putch(*a); + } + return 0; +} + +void puth(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 28; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void puth2(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 4; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void hexdump(void *a, int l) { + int i; + for (i=0;iw_ptr != q->r_ptr) { + *elem = q->elems[q->r_ptr]; + q->r_ptr += 1; + return 1; + } + return 0; +} + +inline int push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + uint8_t next_w_ptr = q->w_ptr + 1; + if (next_w_ptr != q->r_ptr) { + q->elems[q->w_ptr] = *elem; + q->w_ptr = next_w_ptr; + return 1; + } + return 0; +} + +// ***************************** CAN ***************************** + +void process_can(CAN_TypeDef *CAN, can_ring *can_q, int can_number) { + #ifdef DEBUG + puts("process CAN TX\n"); + #endif + + // add successfully transmitted message to my fifo + if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) { + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sTxMailBox[0].TIR; + to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) | ((can_number+2) << 4); + to_push.RDLR = CAN->sTxMailBox[0].TDLR; + to_push.RDHR = CAN->sTxMailBox[0].TDHR; + push(&can_rx_q, &to_push); + } + + // check for empty mailbox + CAN_FIFOMailBox_TypeDef to_send; + if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { + if (pop(can_q, &to_send)) { + + // BRAKE: safety check + if ((to_send.RIR>>21) == 0x1FA) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFF3F; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // STEER: safety check + if ((to_send.RIR>>21) == 0xE4) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFFFF; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // GAS: safety check + if ((to_send.RIR>>21) == 0x200) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFFFF; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // only send if we have received a packet + CAN->sTxMailBox[0].TDLR = to_send.RDLR; + CAN->sTxMailBox[0].TDHR = to_send.RDHR; + CAN->sTxMailBox[0].TDTR = to_send.RDTR; + CAN->sTxMailBox[0].TIR = to_send.RIR; + } + } + + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +// send more, possible for these to not trigger? +void CAN1_TX_IRQHandler() { + process_can(CAN1, &can_tx1_q, 1); +} + +void CAN2_TX_IRQHandler() { + process_can(CAN2, &can_tx2_q, 0); +} + +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button + + +// all commands: brake and steering +// if controls_allowed +// allow all commands up to limit +// else +// block all commands that produce actuation + +// CAN receive handlers +void can_rx(CAN_TypeDef *CAN, int can_number) { + while (CAN->RF0R & CAN_RF0R_FMP0) { + // add to my fifo + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sFIFOMailBox[0].RIR; + // top 16-bits is the timestamp + to_push.RDTR = (CAN->sFIFOMailBox[0].RDTR & 0xFFFF000F) | (can_number << 4); + to_push.RDLR = CAN->sFIFOMailBox[0].RDLR; + to_push.RDHR = CAN->sFIFOMailBox[0].RDHR; + + // state machine to enter and exit controls + // 0x1A6 for the ILX, 0x296 for the Civic Touring + if ((to_push.RIR>>21) == 0x1A6 || (to_push.RIR>>21) == 0x296) { + int buttons = (to_push.RDLR & 0xE0) >> 5; + if (buttons == 4 || buttons == 3) { + controls_allowed = 1; + } else if (buttons == 2) { + controls_allowed = 0; + } + } + + // exit controls on brake press + if ((to_push.RIR>>21) == 0x17C) { + // bit 50 + if (to_push.RDHR & 0x200000) { + controls_allowed = 0; + } + } + + // exit controls on gas press if interceptor + if ((to_push.RIR>>21) == 0x201) { + gas_interceptor_detected = 1; + int gas = ((to_push.RDLR & 0xFF) << 8) | ((to_push.RDLR & 0xFF00) >> 8); + if (gas > 328) { + controls_allowed = 0; + } + } + + // exit controls on gas press if no interceptor + if (!gas_interceptor_detected) { + if ((to_push.RIR>>21) == 0x17C) { + if (to_push.RDLR & 0xFF) { + controls_allowed = 0; + } + } + } + + push(&can_rx_q, &to_push); + + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_RX0_IRQHandler() { + //puts("CANRX1"); + //delay(10000); + can_rx(CAN1, 1); +} + +void CAN2_RX0_IRQHandler() { + //puts("CANRX0"); + //delay(10000); + can_rx(CAN2, 0); +} + +void CAN1_SCE_IRQHandler() { + //puts("CAN1_SCE\n"); + can_sce(CAN1); +} + +void CAN2_SCE_IRQHandler() { + //puts("CAN2_SCE\n"); + can_sce(CAN2); +} + +// ***************************** serial port ***************************** + +void USART_IRQHandler(void) { + puts("S"); + + // echo characters + if (USART->SR & USART_SR_RXNE) { + char rcv = USART->DR; + putch(rcv); + + // jump to DFU flash + if (rcv == 'z') { + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + } +} + +void USART2_IRQHandler(void) { + USART_IRQHandler(); +} + +void USART3_IRQHandler(void) { + USART_IRQHandler(); +} + +// ***************************** USB port ***************************** + +int get_health_pkt(void *dat) { + struct { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + } *health = dat; + health->voltage = adc_get(ADCCHAN_VOLTAGE); + health->current = adc_get(ADCCHAN_CURRENT); + health->started = (GPIOC->IDR & (1 << 13)) != 0; + health->controls_allowed = controls_allowed; + health->gas_interceptor_detected = gas_interceptor_detected; + return sizeof(*health); +} + +void set_fan_speed(int fan_speed) { + #ifdef OLD_BOARD + TIM3->CCR4 = fan_speed; + #else + TIM3->CCR3 = fan_speed; + #endif +} + +void usb_cb_ep1_in(int len) { + CAN_FIFOMailBox_TypeDef reply[4]; + + int ilen = 0; + while (ilen < min(len/0x10, 4) && pop(&can_rx_q, &reply[ilen])) ilen++; + + #ifdef DEBUG + puts("FIFO SENDING "); + puth(ilen); + puts("\n"); + #endif + + USB_WritePacket((void *)reply, ilen*0x10, 1); +} + +void usb_cb_ep2_out(uint8_t *usbdata, int len) { +} + +// send on CAN +void usb_cb_ep3_out(uint8_t *usbdata, int len) { + int dpkt = 0; + for (dpkt = 0; dpkt < len; dpkt += 0x10) { + uint32_t *tf = (uint32_t*)(&usbdata[dpkt]); + + int flags = tf[1] >> 4; + CAN_TypeDef *CAN; + can_ring *can_q; + int can_number = 0; + if (flags & 1) { + CAN=CAN1; + can_q = &can_tx1_q; + can_number = 1; + } else { + CAN=CAN2; + can_q = &can_tx2_q; + } + + // add CAN packet to send queue + CAN_FIFOMailBox_TypeDef to_push; + to_push.RDHR = tf[3]; + to_push.RDLR = tf[2]; + to_push.RDTR = tf[1] & 0xF; + to_push.RIR = tf[0]; + push(can_q, &to_push); + + process_can(CAN, can_q, can_number); + } +} + + +void usb_cb_control_msg() { + uint8_t resp[0x20]; + int resp_len; + switch (setup.b.bRequest) { + case 0xd1: + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + break; + case 0xd2: + resp_len = get_health_pkt(resp); + USB_WritePacket(resp, resp_len, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd3: + set_fan_speed(setup.b.wValue.w); + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd6: // GET_VERSION + USB_WritePacket(gitversion, min(sizeof(gitversion), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd8: // RESET + NVIC_SystemReset(); + break; + default: + puts("NO HANDLER "); + puth(setup.b.bRequest); + puts("\n"); + break; + } +} + + +void OTG_FS_IRQHandler(void) { + NVIC_DisableIRQ(OTG_FS_IRQn); + //__disable_irq(); + usb_irqhandler(); + //__enable_irq(); + NVIC_EnableIRQ(OTG_FS_IRQn); +} + +void OTG_HS_IRQHandler(void) { + //puts("HS_IRQ\n"); + NVIC_DisableIRQ(OTG_FS_IRQn); + //__disable_irq(); + usb_irqhandler(); + //__enable_irq(); + NVIC_EnableIRQ(OTG_FS_IRQn); +} + +void ADC_IRQHandler(void) { + puts("ADC_IRQ\n"); +} + +// ***************************** main code ***************************** + +void __initialize_hardware_early() { + // set USB power + and OTG mode + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + + // enable OTG out tied to ground + GPIOA->ODR = 0; + GPIOA->MODER |= GPIO_MODER_MODER1_0; + + // enable USB power tied to + + GPIOA->ODR |= 1; + GPIOA->MODER |= GPIO_MODER_MODER0_0; + + // enable pull DOWN on OTG_FS_DP + // must be done a while before reading it + GPIOA->PUPDR = GPIO_PUPDR_PUPDR12_1; + + if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { + enter_bootloader_mode = 0; + void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004)); + + // jump to bootloader + bootloader(); + + // LOOP + while(1); + } +} + +int main() { + // init devices + clock_init(); + + // test the USB choice before GPIO init + if (GPIOA->IDR & (1 << 12)) { + USBx = USB_OTG_HS; + } + + gpio_init(); + uart_init(); + usb_init(); + can_init(CAN1); + can_init(CAN2); + adc_init(); + + // timer for fan PWM + #ifdef OLD_BOARD + TIM3->CCMR2 = TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1; + TIM3->CCER = TIM_CCER_CC4E; + #else + TIM3->CCMR2 = TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1; + TIM3->CCER = TIM_CCER_CC3E; + #endif + + // max value of the timer + // 64 makes it above the audible range + //TIM3->ARR = 64; + + // 10 prescale makes it below the audible range + timer_init(TIM3, 10); + + // set PWM + set_fan_speed(65535); + + puts("**** INTERRUPTS ON ****\n"); + __disable_irq(); + NVIC_EnableIRQ(USART2_IRQn); + NVIC_EnableIRQ(USART3_IRQn); + NVIC_EnableIRQ(OTG_FS_IRQn); + NVIC_EnableIRQ(OTG_HS_IRQn); + NVIC_EnableIRQ(ADC_IRQn); + // CAN has so many interrupts! + + NVIC_EnableIRQ(CAN1_TX_IRQn); + NVIC_EnableIRQ(CAN1_RX0_IRQn); + NVIC_EnableIRQ(CAN1_SCE_IRQn); + + NVIC_EnableIRQ(CAN2_TX_IRQn); + NVIC_EnableIRQ(CAN2_RX0_IRQn); + NVIC_EnableIRQ(CAN2_SCE_IRQn); + __enable_irq(); + + + // LED should keep on blinking all the time + while (1) { + #ifdef DEBUG + puts("** blink "); + puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); + puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); + puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); + #endif + + /*puts("voltage: "); puth(adc_get(ADCCHAN_VOLTAGE)); puts(" "); + puts("current: "); puth(adc_get(ADCCHAN_CURRENT)); puts("\n");*/ + + // set LED to be controls allowed + GPIOB->ODR = (GPIOB->ODR | (1 << 11)) & ~(controls_allowed << 11); + + // blink the other LED if in FS mode + if (USBx == USB_OTG_FS) { + GPIOB->ODR |= (1 << 10); + } + delay(1000000); + GPIOB->ODR &= ~(1 << 10); + delay(1000000); + + if (GPIOC->IDR & (1 << 13)) { + // turn on fan at half speed + set_fan_speed(32768); + } else { + // turn off fan + set_fan_speed(0); + } + + } + + return 0; +} + diff --git a/board/startup_stm32f205xx.s b/board/startup_stm32f205xx.s new file mode 100644 index 0000000000..6fb1d22fbb --- /dev/null +++ b/board/startup_stm32f205xx.s @@ -0,0 +1,511 @@ +/** + ****************************************************************************** + * @file startup_stm32f205xx.s + * @author MCD Application Team + * @version V2.0.1 + * @date 25-March-2014 + * @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + bl __initialize_hardware_early + ldr sp, =_estack /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + /* bl SystemInit */ +/* Call static constructors */ + /* bl __libc_init_array */ +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FSMC_IRQHandler /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/board/stm32_flash.ld b/board/stm32_flash.ld new file mode 100644 index 0000000000..3d3c4c4540 --- /dev/null +++ b/board/stm32_flash.ld @@ -0,0 +1,163 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F407VG Device with +** 1024KByte FLASH, 192KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Environment : Atollic TrueSTUDIO(R) +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +** (c)Copyright Atollic AB. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the Atollic TrueSTUDIO(R) toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of 128K RAM on AHB bus*/ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + _exit = .; + } >FLASH + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/board/timer.h b/board/timer.h new file mode 100644 index 0000000000..a14b619e4b --- /dev/null +++ b/board/timer.h @@ -0,0 +1,7 @@ +void timer_init(TIM_TypeDef *TIM, int psc) { + TIM->PSC = psc-1; + TIM->DIER = TIM_DIER_UIE; + TIM->CR1 = TIM_CR1_CEN; + TIM->SR = 0; +} + diff --git a/board/tools/dfu-util-aarch64 b/board/tools/dfu-util-aarch64 new file mode 100755 index 0000000000..73836c3598 --- /dev/null +++ b/board/tools/dfu-util-aarch64 @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:76a07bd598aacbfbc81b95b9b33ef1282fedfe6e49819179445a457c4982a979 +size 116048 diff --git a/board/tools/dfu-util-x86_64 b/board/tools/dfu-util-x86_64 new file mode 100755 index 0000000000..2167cdf686 --- /dev/null +++ b/board/tools/dfu-util-x86_64 @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d33372170341cf50a79ec72e6c0dca51d6116c73203beaaf307c729d2753d178 +size 152156 diff --git a/board/tools/enter_download_mode.py b/board/tools/enter_download_mode.py new file mode 100755 index 0000000000..2b3d906f6f --- /dev/null +++ b/board/tools/enter_download_mode.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python +import usb1 +import time +import traceback + +if __name__ == "__main__": + context = usb1.USBContext() + + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID()&0xFF00 == 0xdd00: + print "found device" + handle = device.open() + handle.claimInterface(0) + + try: + handle.controlWrite(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd1, 0, 0, '') + except Exception: + traceback.print_exc() + print "expected error, exiting cleanly" + time.sleep(1) diff --git a/board/usb.h b/board/usb.h new file mode 100644 index 0000000000..65799a7936 --- /dev/null +++ b/board/usb.h @@ -0,0 +1,510 @@ +// **** supporting defines **** + +typedef struct +{ + __IO uint32_t HPRT; +} +USB_OTG_HostPortTypeDef; + +#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) +#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) +#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) +#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + (i)*USB_OTG_EP_REG_SIZE)) +#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + (i)*USB_OTG_EP_REG_SIZE)) +#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + (i) * USB_OTG_FIFO_SIZE) +#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) + +#define USB_REQ_GET_STATUS 0x00 +#define USB_REQ_CLEAR_FEATURE 0x01 +#define USB_REQ_SET_FEATURE 0x03 +#define USB_REQ_SET_ADDRESS 0x05 +#define USB_REQ_GET_DESCRIPTOR 0x06 +#define USB_REQ_SET_DESCRIPTOR 0x07 +#define USB_REQ_GET_CONFIGURATION 0x08 +#define USB_REQ_SET_CONFIGURATION 0x09 +#define USB_REQ_GET_INTERFACE 0x0A +#define USB_REQ_SET_INTERFACE 0x0B +#define USB_REQ_SYNCH_FRAME 0x0C + +#define USB_DESC_TYPE_DEVICE 1 +#define USB_DESC_TYPE_CONFIGURATION 2 +#define USB_DESC_TYPE_STRING 3 +#define USB_DESC_TYPE_INTERFACE 4 +#define USB_DESC_TYPE_ENDPOINT 5 +#define USB_DESC_TYPE_DEVICE_QUALIFIER 6 +#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7 + +#define STS_GOUT_NAK 1 +#define STS_DATA_UPDT 2 +#define STS_XFER_COMP 3 +#define STS_SETUP_COMP 4 +#define STS_SETUP_UPDT 6 + +#define USBD_FS_TRDT_VALUE 5 + +// interfaces +void usb_cb_control_msg(); +void usb_cb_ep1_in(int len); +void usb_cb_ep2_out(uint8_t *usbdata, int len); +void usb_cb_ep3_out(uint8_t *usbdata, int len); + +uint8_t device_desc[] = { + 0x12,0x01,0x00,0x01, + 0xFF,0xFF,0xFF,0x40, + (USB_VID>>0)&0xFF,(USB_VID>>8)&0xFF, + (USB_PID>>0)&0xFF,(USB_PID>>8)&0xFF, + 0x00,0x22,0x00,0x00, + 0x00,0x01}; + +uint8_t configuration_desc[] = { + 0x09, 0x02, 0x27, 0x00, + 0x01, 0x01, 0x00, 0xc0, + 0x32, + // interface 0 + 0x09, 0x04, 0x00, 0x00, + 0x03, 0xff, 0xFF, 0xFF, + 0x00, + // endpoint 1, read CAN + 0x07, 0x05, 0x81, 0x02, 0x40, 0x00, 0x00, + // endpoint 2, AES load + 0x07, 0x05, 0x02, 0x02, 0x10, 0x00, 0x00, + // endpoint 3, send CAN + 0x07, 0x05, 0x03, 0x02, 0x40, 0x00, 0x00, +}; + +typedef union +{ + uint16_t w; + struct BW + { + uint8_t msb; + uint8_t lsb; + } + bw; +} +uint16_t_uint8_t; + + +typedef union _USB_Setup +{ + uint32_t d8[2]; + + struct _SetupPkt_Struc + { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t_uint8_t wValue; + uint16_t_uint8_t wIndex; + uint16_t_uint8_t wLength; + } b; +} +USB_Setup_TypeDef; + +// current packet +USB_Setup_TypeDef setup; +uint8_t usbdata[0x100]; + +// packet read and write + +void *USB_ReadPacket(void *dest, uint16_t len) { + uint32_t i=0; + uint32_t count32b = (len + 3) / 4; + + for ( i = 0; i < count32b; i++, dest += 4 ) { + // packed? + *(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0); + } + return ((void *)dest); +} + +void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) { + #ifdef DEBUG + puts("writing "); + hexdump(src, len); + #endif + uint32_t count32b = 0, i = 0; + count32b = (len + 3) / 4; + + // bullshit + USBx_INEP(ep)->DIEPTSIZ = (USB_OTG_DIEPTSIZ_PKTCNT & (1 << 19)) | (len & USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + // load the FIFO + for (i = 0; i < count32b; i++, src += 4) { + USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src); + } +} + +void usb_reset() { + // unmask endpoint interrupts, so many sets + USBx_DEVICE->DAINT = 0xFFFFFFFF; + USBx_DEVICE->DAINTMSK = 0xFFFFFFFF; + //USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM); + + // all interrupts for debugging + USBx_DEVICE->DIEPMSK = 0xFFFFFFFF; + USBx_DEVICE->DOEPMSK = 0xFFFFFFFF; + + // clear interrupts + USBx_INEP(0)->DIEPINT = 0xFF; + USBx_OUTEP(0)->DOEPINT = 0xFF; + + // unset the address + USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; + + // set up USB FIFOs + // RX start address is fixed to 0 + USBx->GRXFSIZ = 0x40; + + // 0x100 to offset past GRXFSIZ + USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40; + + // EP1, massive + USBx->DIEPTXF[0] = (0x40 << 16) | 0x80; + + // flush TX fifo + USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + // flush RX FIFO + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + // no global NAK + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; + + // ready to receive setup packets + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8); +} + +void usb_setup() { + uint8_t resp[0x20]; + // setup packet is ready + switch (setup.b.bRequest) { + case USB_REQ_SET_CONFIGURATION: + // enable other endpoints, has to be here? + USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP; + USBx_INEP(1)->DIEPINT = 0xFF; + + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x10; + USBx_OUTEP(2)->DOEPCTL = (0x10 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(2)->DOEPINT = 0xFF; + + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(3)->DOEPINT = 0xFF; + + // mark ready to receive + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_REQ_SET_ADDRESS: + // set now? + USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4); + + #ifdef DEBUG + puts(" set address\n"); + #endif + + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + break; + case USB_REQ_GET_DESCRIPTOR: + switch (setup.b.wValue.bw.lsb) { + case USB_DESC_TYPE_DEVICE: + //puts(" writing device descriptor\n"); + + // setup transfer + USB_WritePacket(device_desc, min(sizeof(device_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + //puts("D"); + break; + case USB_DESC_TYPE_CONFIGURATION: + USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + // nothing here? + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + } + break; + case USB_REQ_GET_STATUS: + // empty resp? + resp[0] = 0; + resp[1] = 0; + USB_WritePacket((void*)&resp, 2, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + usb_cb_control_msg(); + } +} + +void usb_init() { + // internal PHY set before reset + USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + + // full speed PHY, do reset and remove power down + puth(USBx->GRSTCTL); + puts(" resetting PHY\n"); + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); + puts("AHB idle\n"); + + // reset PHY here? + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + puts("reset done\n"); + + // power up the PHY + USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS; + + // be a device, slowest timings + //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL; + USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); + //USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + + // **** for debugging, doesn't seem to work **** + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT; + + // reset PHY clock + USBx_PCGCCTL = 0; + + // enable the fancy OTG things + USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP; + + USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD; + //USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD; + + // setup USB interrupts + // all interrupts except TXFIFO EMPTY + //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); + USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM); + + USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT; + USBx->GINTSTS = 0; +} + +// ***************************** USB port ***************************** + +void usb_irqhandler(void) { + USBx->GINTMSK = 0; + + unsigned int gintsts = USBx->GINTSTS; + + // gintsts SUSPEND? 04008428 + #ifdef DEBUG + unsigned int daint = USBx_DEVICE->DAINT; + puth(gintsts); + puts(" ep "); + puth(daint); + puts(" USB interrupt!\n"); + #endif + + if (gintsts & USB_OTG_GINTSTS_ESUSP) { + puts("ESUSP detected\n"); + } + + if (gintsts & USB_OTG_GINTSTS_USBRST) { + puts("USB reset\n"); + usb_reset(); + } + + if (gintsts & USB_OTG_GINTSTS_ENUMDNE) { + puts("enumeration done "); + // Full speed, ENUMSPD + puth(USBx_DEVICE->DSTS); + puts("\n"); + } + + if (gintsts & USB_OTG_GINTSTS_OTGINT) { + puts("OTG int:"); + puth(USBx->GOTGINT); + puts("\n"); + + // getting ADTOCHG + USBx->GOTGINT = USBx->GOTGINT; + } + + // RX FIFO first + if (gintsts & USB_OTG_GINTSTS_RXFLVL) { + // 1. Read the Receive status pop register + volatile unsigned int rxst = USBx->GRXSTSP; + + #ifdef DEBUG + puts(" RX FIFO:"); + puth(rxst); + puts(" status: "); + puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17); + puts(" len: "); + puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4); + puts("\n"); + #endif + + + if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) { + int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM); + int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4; + USB_ReadPacket(&usbdata, len); + #ifdef DEBUG + puts(" data "); + puth(len); + puts("\n"); + hexdump(&usbdata, len); + #endif + + if (endpoint == 2) { + usb_cb_ep2_out(usbdata, len); + } + + if (endpoint == 3) { + usb_cb_ep3_out(usbdata, len); + } + } else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) { + USB_ReadPacket(&setup, 8); + #ifdef DEBUG + puts(" setup "); + hexdump(&setup, 8); + puts("\n"); + #endif + } + } + + if (gintsts & USB_OTG_GINTSTS_HPRTINT) { + // host + puts("HPRT:"); + puth(USBx_HOST_PORT->HPRT); + puts("\n"); + if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) { + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST; + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET; + } + + } + + if (gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) { + // no global NAK, why is this getting set? + #ifdef DEBUG + puts("GLOBAL NAK\n"); + #endif + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK; + } + + if (gintsts & USB_OTG_GINTSTS_SRQINT) { + // we want to do "A-device host negotiation protocol" since we are the A-device + puts("start request\n"); + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + //USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA; + } + + // out endpoint hit + if (gintsts & USB_OTG_GINTSTS_OEPINT) { + #ifdef DEBUG + puts(" 0:"); + puth(USBx_OUTEP(0)->DOEPINT); + puts(" 2:"); + puth(USBx_OUTEP(2)->DOEPINT); + puts(" 3:"); + puth(USBx_OUTEP(3)->DOEPINT); + puts(" "); + puth(USBx_OUTEP(3)->DOEPCTL); + puts(" 4:"); + puth(USBx_OUTEP(4)->DOEPINT); + puts(" OUT ENDPOINT\n"); + #endif + + if (USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG + puts(" OUT2 PACKET XFRC\n"); + #endif + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x10; + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } + + if (USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG + puts(" OUT3 PACKET XFRC\n"); + #endif + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT & 0x2000) { + #ifdef DEBUG + puts(" OUT3 PACKET WTF\n"); + #endif + // if NAK was set trigger this, unknown interrupt + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT) { + puts("OUTEP3 error "); + puth(USBx_OUTEP(3)->DOEPINT); + puts("\n"); + } + + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) { + // ready for next packet + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8); + } + + // respond to setup packets + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) { + usb_setup(); + } + + USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT; + USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT; + USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT; + } + + + // in endpoint hit + if (gintsts & USB_OTG_GINTSTS_IEPINT) { + #ifdef DEBUG + puts(" "); + puth(USBx_INEP(0)->DIEPINT); + puts(" "); + puth(USBx_INEP(1)->DIEPINT); + puts(" IN ENDPOINT\n"); + #endif + + // this happens first + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPINT_XFRC) { + #ifdef DEBUG + puts(" IN PACKET SEND\n"); + #endif + //USBx_DEVICE->DIEPEMPMSK = ~(1 << 1); + } + + // *** IN token received when TxFIFO is empty + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG + puts(" IN PACKET QUEUE\n"); + #endif + // TODO: always assuming max len, can we get the length? + usb_cb_ep1_in(0x40); + } + + // clear interrupts + USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; + USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT; + } + + + // clear all interrupts + USBx_DEVICE->DAINT = USBx_DEVICE->DAINT; + USBx->GINTSTS = USBx->GINTSTS; + + USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); +} + diff --git a/cereal/__init__.py b/cereal/__init__.py new file mode 100644 index 0000000000..b083b67399 --- /dev/null +++ b/cereal/__init__.py @@ -0,0 +1,7 @@ +import os +import capnp +capnp.remove_import_hook() + +CEREAL_PATH = os.path.dirname(os.path.abspath(__file__)) +log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) + diff --git a/cereal/c++.capnp b/cereal/c++.capnp new file mode 100644 index 0000000000..2bda547179 --- /dev/null +++ b/cereal/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# 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. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/cereal/gen/c/c++.capnp.h b/cereal/gen/c/c++.capnp.h new file mode 100644 index 0000000000..e69de29bb2 diff --git a/cereal/gen/c/log.capnp.c b/cereal/gen/c/log.capnp.c new file mode 100644 index 0000000000..b7b8692ff4 --- /dev/null +++ b/cereal/gen/c/log.capnp.c @@ -0,0 +1,1016 @@ +#include "log.capnp.h" +/* AUTO GENERATED - DO NOT EDIT */ +static const capn_text capn_val0 = {0,""}; +int32_t cereal_logVersion = 1; + +cereal_InitData_ptr cereal_new_InitData(struct capn_segment *s) { + cereal_InitData_ptr p; + p.p = capn_new_struct(s, 0, 3); + return p; +} +cereal_InitData_list cereal_new_InitData_list(struct capn_segment *s, int len) { + cereal_InitData_list p; + p.p = capn_new_list(s, len, 0, 3); + return p; +} +void cereal_read_InitData(struct cereal_InitData *s, cereal_InitData_ptr p) { + capn_resolve(&p.p); + s->kernelArgs = capn_getp(p.p, 0, 0); + s->gctx = capn_get_text(p.p, 1, capn_val0); + s->dongleId = capn_get_text(p.p, 2, capn_val0); +} +void cereal_write_InitData(const struct cereal_InitData *s, cereal_InitData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->kernelArgs); + capn_set_text(p.p, 1, s->gctx); + capn_set_text(p.p, 2, s->dongleId); +} +void cereal_get_InitData(struct cereal_InitData *s, cereal_InitData_list l, int i) { + cereal_InitData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_InitData(s, p); +} +void cereal_set_InitData(const struct cereal_InitData *s, cereal_InitData_list l, int i) { + cereal_InitData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_InitData(s, p); +} + +cereal_FrameData_ptr cereal_new_FrameData(struct capn_segment *s) { + cereal_FrameData_ptr p; + p.p = capn_new_struct(s, 32, 1); + return p; +} +cereal_FrameData_list cereal_new_FrameData_list(struct capn_segment *s, int len) { + cereal_FrameData_list p; + p.p = capn_new_list(s, len, 32, 1); + return p; +} +void cereal_read_FrameData(struct cereal_FrameData *s, cereal_FrameData_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->encodeId = capn_read32(p.p, 4); + s->timestampEof = capn_read64(p.p, 8); + s->frameLength = (int32_t) ((int32_t)capn_read32(p.p, 16)); + s->integLines = (int32_t) ((int32_t)capn_read32(p.p, 20)); + s->globalGain = (int32_t) ((int32_t)capn_read32(p.p, 24)); + s->image = capn_get_data(p.p, 0); +} +void cereal_write_FrameData(const struct cereal_FrameData *s, cereal_FrameData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_write32(p.p, 4, s->encodeId); + capn_write64(p.p, 8, s->timestampEof); + capn_write32(p.p, 16, (uint32_t) (s->frameLength)); + capn_write32(p.p, 20, (uint32_t) (s->integLines)); + capn_write32(p.p, 24, (uint32_t) (s->globalGain)); + capn_setp(p.p, 0, s->image.p); +} +void cereal_get_FrameData(struct cereal_FrameData *s, cereal_FrameData_list l, int i) { + cereal_FrameData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_FrameData(s, p); +} +void cereal_set_FrameData(const struct cereal_FrameData *s, cereal_FrameData_list l, int i) { + cereal_FrameData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_FrameData(s, p); +} + +cereal_GPSNMEAData_ptr cereal_new_GPSNMEAData(struct capn_segment *s) { + cereal_GPSNMEAData_ptr p; + p.p = capn_new_struct(s, 16, 1); + return p; +} +cereal_GPSNMEAData_list cereal_new_GPSNMEAData_list(struct capn_segment *s, int len) { + cereal_GPSNMEAData_list p; + p.p = capn_new_list(s, len, 16, 1); + return p; +} +void cereal_read_GPSNMEAData(struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_ptr p) { + capn_resolve(&p.p); + s->timestamp = (int64_t) ((int64_t)(capn_read64(p.p, 0))); + s->localWallTime = capn_read64(p.p, 8); + s->nmea = capn_get_text(p.p, 0, capn_val0); +} +void cereal_write_GPSNMEAData(const struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 0, (uint64_t) (s->timestamp)); + capn_write64(p.p, 8, s->localWallTime); + capn_set_text(p.p, 0, s->nmea); +} +void cereal_get_GPSNMEAData(struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_list l, int i) { + cereal_GPSNMEAData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_GPSNMEAData(s, p); +} +void cereal_set_GPSNMEAData(const struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_list l, int i) { + cereal_GPSNMEAData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_GPSNMEAData(s, p); +} + +cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment *s) { + cereal_SensorEventData_ptr p; + p.p = capn_new_struct(s, 24, 1); + return p; +} +cereal_SensorEventData_list cereal_new_SensorEventData_list(struct capn_segment *s, int len) { + cereal_SensorEventData_list p; + p.p = capn_new_list(s, len, 24, 1); + return p; +} +void cereal_read_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_ptr p) { + capn_resolve(&p.p); + s->version = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->sensor = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->type = (int32_t) ((int32_t)capn_read32(p.p, 8)); + s->timestamp = (int64_t) ((int64_t)(capn_read64(p.p, 16))); + s->which = (enum cereal_SensorEventData_which)(int) capn_read16(p.p, 12); + switch (s->which) { + case cereal_SensorEventData_acceleration: + case cereal_SensorEventData_magnetic: + case cereal_SensorEventData_orientation: + case cereal_SensorEventData_gyro: + s->gyro.p = capn_getp(p.p, 0, 0); + break; + default: + break; + } +} +void cereal_write_SensorEventData(const struct cereal_SensorEventData *s, cereal_SensorEventData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->version)); + capn_write32(p.p, 4, (uint32_t) (s->sensor)); + capn_write32(p.p, 8, (uint32_t) (s->type)); + capn_write64(p.p, 16, (uint64_t) (s->timestamp)); + capn_write16(p.p, 12, s->which); + switch (s->which) { + case cereal_SensorEventData_acceleration: + case cereal_SensorEventData_magnetic: + case cereal_SensorEventData_orientation: + case cereal_SensorEventData_gyro: + capn_setp(p.p, 0, s->gyro.p); + break; + default: + break; + } +} +void cereal_get_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) { + cereal_SensorEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_SensorEventData(s, p); +} +void cereal_set_SensorEventData(const struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) { + cereal_SensorEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_SensorEventData(s, p); +} + +cereal_SensorEventData_SensorVec_ptr cereal_new_SensorEventData_SensorVec(struct capn_segment *s) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_SensorEventData_SensorVec_list cereal_new_SensorEventData_SensorVec_list(struct capn_segment *s, int len) { + cereal_SensorEventData_SensorVec_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_ptr p) { + capn_resolve(&p.p); + s->v.p = capn_getp(p.p, 0, 0); + s->status = (int8_t) ((int8_t)capn_read8(p.p, 0)); +} +void cereal_write_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->v.p); + capn_write8(p.p, 0, (uint8_t) (s->status)); +} +void cereal_get_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_list l, int i) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_SensorEventData_SensorVec(s, p); +} +void cereal_set_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_list l, int i) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_SensorEventData_SensorVec(s, p); +} + +cereal_CanData_ptr cereal_new_CanData(struct capn_segment *s) { + cereal_CanData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_CanData_list cereal_new_CanData_list(struct capn_segment *s, int len) { + cereal_CanData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_CanData(struct cereal_CanData *s, cereal_CanData_ptr p) { + capn_resolve(&p.p); + s->address = capn_read32(p.p, 0); + s->busTime = capn_read16(p.p, 4); + s->dat = capn_get_data(p.p, 0); + s->src = (int8_t) ((int8_t)capn_read8(p.p, 6)); +} +void cereal_write_CanData(const struct cereal_CanData *s, cereal_CanData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->address); + capn_write16(p.p, 4, s->busTime); + capn_setp(p.p, 0, s->dat.p); + capn_write8(p.p, 6, (uint8_t) (s->src)); +} +void cereal_get_CanData(struct cereal_CanData *s, cereal_CanData_list l, int i) { + cereal_CanData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_CanData(s, p); +} +void cereal_set_CanData(const struct cereal_CanData *s, cereal_CanData_list l, int i) { + cereal_CanData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_CanData(s, p); +} + +cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment *s) { + cereal_ThermalData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment *s, int len) { + cereal_ThermalData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { + capn_resolve(&p.p); + s->cpu0 = capn_read16(p.p, 0); + s->cpu1 = capn_read16(p.p, 2); + s->cpu2 = capn_read16(p.p, 4); + s->cpu3 = capn_read16(p.p, 6); + s->mem = capn_read16(p.p, 8); + s->gpu = capn_read16(p.p, 10); + s->bat = capn_read32(p.p, 12); +} +void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { + capn_resolve(&p.p); + capn_write16(p.p, 0, s->cpu0); + capn_write16(p.p, 2, s->cpu1); + capn_write16(p.p, 4, s->cpu2); + capn_write16(p.p, 6, s->cpu3); + capn_write16(p.p, 8, s->mem); + capn_write16(p.p, 10, s->gpu); + capn_write32(p.p, 12, s->bat); +} +void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { + cereal_ThermalData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ThermalData(s, p); +} +void cereal_set_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { + cereal_ThermalData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ThermalData(s, p); +} + +cereal_HealthData_ptr cereal_new_HealthData(struct capn_segment *s) { + cereal_HealthData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_HealthData_list cereal_new_HealthData_list(struct capn_segment *s, int len) { + cereal_HealthData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_HealthData(struct cereal_HealthData *s, cereal_HealthData_ptr p) { + capn_resolve(&p.p); + s->voltage = capn_read32(p.p, 0); + s->current = capn_read32(p.p, 4); + s->started = (capn_read8(p.p, 8) & 1) != 0; + s->controlsAllowed = (capn_read8(p.p, 8) & 2) != 0; + s->gasInterceptorDetected = (capn_read8(p.p, 8) & 4) != 0; +} +void cereal_write_HealthData(const struct cereal_HealthData *s, cereal_HealthData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->voltage); + capn_write32(p.p, 4, s->current); + capn_write1(p.p, 64, s->started != 0); + capn_write1(p.p, 65, s->controlsAllowed != 0); + capn_write1(p.p, 66, s->gasInterceptorDetected != 0); +} +void cereal_get_HealthData(struct cereal_HealthData *s, cereal_HealthData_list l, int i) { + cereal_HealthData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_HealthData(s, p); +} +void cereal_set_HealthData(const struct cereal_HealthData *s, cereal_HealthData_list l, int i) { + cereal_HealthData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_HealthData(s, p); +} + +cereal_LiveUI_ptr cereal_new_LiveUI(struct capn_segment *s) { + cereal_LiveUI_ptr p; + p.p = capn_new_struct(s, 8, 2); + return p; +} +cereal_LiveUI_list cereal_new_LiveUI_list(struct capn_segment *s, int len) { + cereal_LiveUI_list p; + p.p = capn_new_list(s, len, 8, 2); + return p; +} +void cereal_read_LiveUI(struct cereal_LiveUI *s, cereal_LiveUI_ptr p) { + capn_resolve(&p.p); + s->rearViewCam = (capn_read8(p.p, 0) & 1) != 0; + s->alertText1 = capn_get_text(p.p, 0, capn_val0); + s->alertText2 = capn_get_text(p.p, 1, capn_val0); + s->awarenessStatus = capn_to_f32(capn_read32(p.p, 4)); +} +void cereal_write_LiveUI(const struct cereal_LiveUI *s, cereal_LiveUI_ptr p) { + capn_resolve(&p.p); + capn_write1(p.p, 0, s->rearViewCam != 0); + capn_set_text(p.p, 0, s->alertText1); + capn_set_text(p.p, 1, s->alertText2); + capn_write32(p.p, 4, capn_from_f32(s->awarenessStatus)); +} +void cereal_get_LiveUI(struct cereal_LiveUI *s, cereal_LiveUI_list l, int i) { + cereal_LiveUI_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveUI(s, p); +} +void cereal_set_LiveUI(const struct cereal_LiveUI *s, cereal_LiveUI_list l, int i) { + cereal_LiveUI_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveUI(s, p); +} + +cereal_Live20Data_ptr cereal_new_Live20Data(struct capn_segment *s) { + cereal_Live20Data_ptr p; + p.p = capn_new_struct(s, 32, 4); + return p; +} +cereal_Live20Data_list cereal_new_Live20Data_list(struct capn_segment *s, int len) { + cereal_Live20Data_list p; + p.p = capn_new_list(s, len, 32, 4); + return p; +} +void cereal_read_Live20Data(struct cereal_Live20Data *s, cereal_Live20Data_ptr p) { + capn_resolve(&p.p); + s->canMonoTimes.p = capn_getp(p.p, 3, 0); + s->mdMonoTime = capn_read64(p.p, 16); + s->ftMonoTime = capn_read64(p.p, 24); + s->warpMatrix.p = capn_getp(p.p, 0, 0); + s->angleOffset = capn_to_f32(capn_read32(p.p, 0)); + s->calStatus = (int8_t) ((int8_t)capn_read8(p.p, 4)); + s->calCycle = (int32_t) ((int32_t)capn_read32(p.p, 12)); + s->calPerc = (int8_t) ((int8_t)capn_read8(p.p, 5)); + s->leadOne.p = capn_getp(p.p, 1, 0); + s->leadTwo.p = capn_getp(p.p, 2, 0); + s->cumLagMs = capn_to_f32(capn_read32(p.p, 8)); +} +void cereal_write_Live20Data(const struct cereal_Live20Data *s, cereal_Live20Data_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 3, s->canMonoTimes.p); + capn_write64(p.p, 16, s->mdMonoTime); + capn_write64(p.p, 24, s->ftMonoTime); + capn_setp(p.p, 0, s->warpMatrix.p); + capn_write32(p.p, 0, capn_from_f32(s->angleOffset)); + capn_write8(p.p, 4, (uint8_t) (s->calStatus)); + capn_write32(p.p, 12, (uint32_t) (s->calCycle)); + capn_write8(p.p, 5, (uint8_t) (s->calPerc)); + capn_setp(p.p, 1, s->leadOne.p); + capn_setp(p.p, 2, s->leadTwo.p); + capn_write32(p.p, 8, capn_from_f32(s->cumLagMs)); +} +void cereal_get_Live20Data(struct cereal_Live20Data *s, cereal_Live20Data_list l, int i) { + cereal_Live20Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live20Data(s, p); +} +void cereal_set_Live20Data(const struct cereal_Live20Data *s, cereal_Live20Data_list l, int i) { + cereal_Live20Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live20Data(s, p); +} + +cereal_Live20Data_LeadData_ptr cereal_new_Live20Data_LeadData(struct capn_segment *s) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_new_struct(s, 48, 0); + return p; +} +cereal_Live20Data_LeadData_list cereal_new_Live20Data_LeadData_list(struct capn_segment *s, int len) { + cereal_Live20Data_LeadData_list p; + p.p = capn_new_list(s, len, 48, 0); + return p; +} +void cereal_read_Live20Data_LeadData(struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_ptr p) { + capn_resolve(&p.p); + s->dRel = capn_to_f32(capn_read32(p.p, 0)); + s->yRel = capn_to_f32(capn_read32(p.p, 4)); + s->vRel = capn_to_f32(capn_read32(p.p, 8)); + s->aRel = capn_to_f32(capn_read32(p.p, 12)); + s->vLead = capn_to_f32(capn_read32(p.p, 16)); + s->aLead = capn_to_f32(capn_read32(p.p, 20)); + s->dPath = capn_to_f32(capn_read32(p.p, 24)); + s->vLat = capn_to_f32(capn_read32(p.p, 28)); + s->vLeadK = capn_to_f32(capn_read32(p.p, 32)); + s->aLeadK = capn_to_f32(capn_read32(p.p, 36)); + s->fcw = (capn_read8(p.p, 40) & 1) != 0; + s->status = (capn_read8(p.p, 40) & 2) != 0; +} +void cereal_write_Live20Data_LeadData(const struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, capn_from_f32(s->dRel)); + capn_write32(p.p, 4, capn_from_f32(s->yRel)); + capn_write32(p.p, 8, capn_from_f32(s->vRel)); + capn_write32(p.p, 12, capn_from_f32(s->aRel)); + capn_write32(p.p, 16, capn_from_f32(s->vLead)); + capn_write32(p.p, 20, capn_from_f32(s->aLead)); + capn_write32(p.p, 24, capn_from_f32(s->dPath)); + capn_write32(p.p, 28, capn_from_f32(s->vLat)); + capn_write32(p.p, 32, capn_from_f32(s->vLeadK)); + capn_write32(p.p, 36, capn_from_f32(s->aLeadK)); + capn_write1(p.p, 320, s->fcw != 0); + capn_write1(p.p, 321, s->status != 0); +} +void cereal_get_Live20Data_LeadData(struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_list l, int i) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live20Data_LeadData(s, p); +} +void cereal_set_Live20Data_LeadData(const struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_list l, int i) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live20Data_LeadData(s, p); +} + +cereal_LiveCalibrationData_ptr cereal_new_LiveCalibrationData(struct capn_segment *s) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LiveCalibrationData_list cereal_new_LiveCalibrationData_list(struct capn_segment *s, int len) { + cereal_LiveCalibrationData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LiveCalibrationData(struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_ptr p) { + capn_resolve(&p.p); + s->warpMatrix.p = capn_getp(p.p, 0, 0); + s->calStatus = (int8_t) ((int8_t)capn_read8(p.p, 0)); + s->calCycle = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->calPerc = (int8_t) ((int8_t)capn_read8(p.p, 1)); +} +void cereal_write_LiveCalibrationData(const struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->warpMatrix.p); + capn_write8(p.p, 0, (uint8_t) (s->calStatus)); + capn_write32(p.p, 4, (uint32_t) (s->calCycle)); + capn_write8(p.p, 1, (uint8_t) (s->calPerc)); +} +void cereal_get_LiveCalibrationData(struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_list l, int i) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveCalibrationData(s, p); +} +void cereal_set_LiveCalibrationData(const struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_list l, int i) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveCalibrationData(s, p); +} + +cereal_LiveTracks_ptr cereal_new_LiveTracks(struct capn_segment *s) { + cereal_LiveTracks_ptr p; + p.p = capn_new_struct(s, 40, 0); + return p; +} +cereal_LiveTracks_list cereal_new_LiveTracks_list(struct capn_segment *s, int len) { + cereal_LiveTracks_list p; + p.p = capn_new_list(s, len, 40, 0); + return p; +} +void cereal_read_LiveTracks(struct cereal_LiveTracks *s, cereal_LiveTracks_ptr p) { + capn_resolve(&p.p); + s->trackId = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->dRel = capn_to_f32(capn_read32(p.p, 4)); + s->yRel = capn_to_f32(capn_read32(p.p, 8)); + s->vRel = capn_to_f32(capn_read32(p.p, 12)); + s->aRel = capn_to_f32(capn_read32(p.p, 16)); + s->timeStamp = capn_to_f32(capn_read32(p.p, 20)); + s->status = capn_to_f32(capn_read32(p.p, 24)); + s->currentTime = capn_to_f32(capn_read32(p.p, 28)); + s->stationary = (capn_read8(p.p, 32) & 1) != 0; + s->oncoming = (capn_read8(p.p, 32) & 2) != 0; +} +void cereal_write_LiveTracks(const struct cereal_LiveTracks *s, cereal_LiveTracks_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->trackId)); + capn_write32(p.p, 4, capn_from_f32(s->dRel)); + capn_write32(p.p, 8, capn_from_f32(s->yRel)); + capn_write32(p.p, 12, capn_from_f32(s->vRel)); + capn_write32(p.p, 16, capn_from_f32(s->aRel)); + capn_write32(p.p, 20, capn_from_f32(s->timeStamp)); + capn_write32(p.p, 24, capn_from_f32(s->status)); + capn_write32(p.p, 28, capn_from_f32(s->currentTime)); + capn_write1(p.p, 256, s->stationary != 0); + capn_write1(p.p, 257, s->oncoming != 0); +} +void cereal_get_LiveTracks(struct cereal_LiveTracks *s, cereal_LiveTracks_list l, int i) { + cereal_LiveTracks_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveTracks(s, p); +} +void cereal_set_LiveTracks(const struct cereal_LiveTracks *s, cereal_LiveTracks_list l, int i) { + cereal_LiveTracks_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveTracks(s, p); +} + +cereal_Live100Data_ptr cereal_new_Live100Data(struct capn_segment *s) { + cereal_Live100Data_ptr p; + p.p = capn_new_struct(s, 104, 3); + return p; +} +cereal_Live100Data_list cereal_new_Live100Data_list(struct capn_segment *s, int len) { + cereal_Live100Data_list p; + p.p = capn_new_list(s, len, 104, 3); + return p; +} +void cereal_read_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_ptr p) { + capn_resolve(&p.p); + s->canMonoTime = capn_read64(p.p, 64); + s->canMonoTimes.p = capn_getp(p.p, 0, 0); + s->l20MonoTime = capn_read64(p.p, 72); + s->mdMonoTime = capn_read64(p.p, 80); + s->vEgo = capn_to_f32(capn_read32(p.p, 0)); + s->aEgo = capn_to_f32(capn_read32(p.p, 4)); + s->vPid = capn_to_f32(capn_read32(p.p, 8)); + s->vTargetLead = capn_to_f32(capn_read32(p.p, 12)); + s->upAccelCmd = capn_to_f32(capn_read32(p.p, 16)); + s->uiAccelCmd = capn_to_f32(capn_read32(p.p, 20)); + s->yActual = capn_to_f32(capn_read32(p.p, 24)); + s->yDes = capn_to_f32(capn_read32(p.p, 28)); + s->upSteer = capn_to_f32(capn_read32(p.p, 32)); + s->uiSteer = capn_to_f32(capn_read32(p.p, 36)); + s->aTargetMin = capn_to_f32(capn_read32(p.p, 40)); + s->aTargetMax = capn_to_f32(capn_read32(p.p, 44)); + s->jerkFactor = capn_to_f32(capn_read32(p.p, 48)); + s->angleSteers = capn_to_f32(capn_read32(p.p, 52)); + s->hudLead = (int32_t) ((int32_t)capn_read32(p.p, 56)); + s->cumLagMs = capn_to_f32(capn_read32(p.p, 60)); + s->enabled = (capn_read8(p.p, 88) & 1) != 0; + s->steerOverride = (capn_read8(p.p, 88) & 2) != 0; + s->vCruise = capn_to_f32(capn_read32(p.p, 92)); + s->rearViewCam = (capn_read8(p.p, 88) & 4) != 0; + s->alertText1 = capn_get_text(p.p, 1, capn_val0); + s->alertText2 = capn_get_text(p.p, 2, capn_val0); + s->awarenessStatus = capn_to_f32(capn_read32(p.p, 96)); +} +void cereal_write_Live100Data(const struct cereal_Live100Data *s, cereal_Live100Data_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 64, s->canMonoTime); + capn_setp(p.p, 0, s->canMonoTimes.p); + capn_write64(p.p, 72, s->l20MonoTime); + capn_write64(p.p, 80, s->mdMonoTime); + capn_write32(p.p, 0, capn_from_f32(s->vEgo)); + capn_write32(p.p, 4, capn_from_f32(s->aEgo)); + capn_write32(p.p, 8, capn_from_f32(s->vPid)); + capn_write32(p.p, 12, capn_from_f32(s->vTargetLead)); + capn_write32(p.p, 16, capn_from_f32(s->upAccelCmd)); + capn_write32(p.p, 20, capn_from_f32(s->uiAccelCmd)); + capn_write32(p.p, 24, capn_from_f32(s->yActual)); + capn_write32(p.p, 28, capn_from_f32(s->yDes)); + capn_write32(p.p, 32, capn_from_f32(s->upSteer)); + capn_write32(p.p, 36, capn_from_f32(s->uiSteer)); + capn_write32(p.p, 40, capn_from_f32(s->aTargetMin)); + capn_write32(p.p, 44, capn_from_f32(s->aTargetMax)); + capn_write32(p.p, 48, capn_from_f32(s->jerkFactor)); + capn_write32(p.p, 52, capn_from_f32(s->angleSteers)); + capn_write32(p.p, 56, (uint32_t) (s->hudLead)); + capn_write32(p.p, 60, capn_from_f32(s->cumLagMs)); + capn_write1(p.p, 704, s->enabled != 0); + capn_write1(p.p, 705, s->steerOverride != 0); + capn_write32(p.p, 92, capn_from_f32(s->vCruise)); + capn_write1(p.p, 706, s->rearViewCam != 0); + capn_set_text(p.p, 1, s->alertText1); + capn_set_text(p.p, 2, s->alertText2); + capn_write32(p.p, 96, capn_from_f32(s->awarenessStatus)); +} +void cereal_get_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_list l, int i) { + cereal_Live100Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live100Data(s, p); +} +void cereal_set_Live100Data(const struct cereal_Live100Data *s, cereal_Live100Data_list l, int i) { + cereal_Live100Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live100Data(s, p); +} + +cereal_LiveEventData_ptr cereal_new_LiveEventData(struct capn_segment *s) { + cereal_LiveEventData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LiveEventData_list cereal_new_LiveEventData_list(struct capn_segment *s, int len) { + cereal_LiveEventData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LiveEventData(struct cereal_LiveEventData *s, cereal_LiveEventData_ptr p) { + capn_resolve(&p.p); + s->name = capn_get_text(p.p, 0, capn_val0); + s->value = (int32_t) ((int32_t)capn_read32(p.p, 0)); +} +void cereal_write_LiveEventData(const struct cereal_LiveEventData *s, cereal_LiveEventData_ptr p) { + capn_resolve(&p.p); + capn_set_text(p.p, 0, s->name); + capn_write32(p.p, 0, (uint32_t) (s->value)); +} +void cereal_get_LiveEventData(struct cereal_LiveEventData *s, cereal_LiveEventData_list l, int i) { + cereal_LiveEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveEventData(s, p); +} +void cereal_set_LiveEventData(const struct cereal_LiveEventData *s, cereal_LiveEventData_list l, int i) { + cereal_LiveEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveEventData(s, p); +} + +cereal_ModelData_ptr cereal_new_ModelData(struct capn_segment *s) { + cereal_ModelData_ptr p; + p.p = capn_new_struct(s, 8, 5); + return p; +} +cereal_ModelData_list cereal_new_ModelData_list(struct capn_segment *s, int len) { + cereal_ModelData_list p; + p.p = capn_new_list(s, len, 8, 5); + return p; +} +void cereal_read_ModelData(struct cereal_ModelData *s, cereal_ModelData_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->path.p = capn_getp(p.p, 0, 0); + s->leftLane.p = capn_getp(p.p, 1, 0); + s->rightLane.p = capn_getp(p.p, 2, 0); + s->lead.p = capn_getp(p.p, 3, 0); + s->settings.p = capn_getp(p.p, 4, 0); +} +void cereal_write_ModelData(const struct cereal_ModelData *s, cereal_ModelData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_setp(p.p, 0, s->path.p); + capn_setp(p.p, 1, s->leftLane.p); + capn_setp(p.p, 2, s->rightLane.p); + capn_setp(p.p, 3, s->lead.p); + capn_setp(p.p, 4, s->settings.p); +} +void cereal_get_ModelData(struct cereal_ModelData *s, cereal_ModelData_list l, int i) { + cereal_ModelData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData(s, p); +} +void cereal_set_ModelData(const struct cereal_ModelData *s, cereal_ModelData_list l, int i) { + cereal_ModelData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData(s, p); +} + +cereal_ModelData_PathData_ptr cereal_new_ModelData_PathData(struct capn_segment *s) { + cereal_ModelData_PathData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_ModelData_PathData_list cereal_new_ModelData_PathData_list(struct capn_segment *s, int len) { + cereal_ModelData_PathData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_ModelData_PathData(struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_ptr p) { + capn_resolve(&p.p); + s->points.p = capn_getp(p.p, 0, 0); + s->prob = capn_to_f32(capn_read32(p.p, 0)); + s->std = capn_to_f32(capn_read32(p.p, 4)); +} +void cereal_write_ModelData_PathData(const struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->points.p); + capn_write32(p.p, 0, capn_from_f32(s->prob)); + capn_write32(p.p, 4, capn_from_f32(s->std)); +} +void cereal_get_ModelData_PathData(struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_list l, int i) { + cereal_ModelData_PathData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_PathData(s, p); +} +void cereal_set_ModelData_PathData(const struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_list l, int i) { + cereal_ModelData_PathData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_PathData(s, p); +} + +cereal_ModelData_LeadData_ptr cereal_new_ModelData_LeadData(struct capn_segment *s) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_ModelData_LeadData_list cereal_new_ModelData_LeadData_list(struct capn_segment *s, int len) { + cereal_ModelData_LeadData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_ModelData_LeadData(struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_ptr p) { + capn_resolve(&p.p); + s->dist = capn_to_f32(capn_read32(p.p, 0)); + s->prob = capn_to_f32(capn_read32(p.p, 4)); + s->std = capn_to_f32(capn_read32(p.p, 8)); +} +void cereal_write_ModelData_LeadData(const struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, capn_from_f32(s->dist)); + capn_write32(p.p, 4, capn_from_f32(s->prob)); + capn_write32(p.p, 8, capn_from_f32(s->std)); +} +void cereal_get_ModelData_LeadData(struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_list l, int i) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_LeadData(s, p); +} +void cereal_set_ModelData_LeadData(const struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_list l, int i) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_LeadData(s, p); +} + +cereal_ModelData_ModelSettings_ptr cereal_new_ModelData_ModelSettings(struct capn_segment *s) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_new_struct(s, 8, 2); + return p; +} +cereal_ModelData_ModelSettings_list cereal_new_ModelData_ModelSettings_list(struct capn_segment *s, int len) { + cereal_ModelData_ModelSettings_list p; + p.p = capn_new_list(s, len, 8, 2); + return p; +} +void cereal_read_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_ptr p) { + capn_resolve(&p.p); + s->bigBoxX = capn_read16(p.p, 0); + s->bigBoxY = capn_read16(p.p, 2); + s->bigBoxWidth = capn_read16(p.p, 4); + s->bigBoxHeight = capn_read16(p.p, 6); + s->boxProjection.p = capn_getp(p.p, 0, 0); + s->yuvCorrection.p = capn_getp(p.p, 1, 0); +} +void cereal_write_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_ptr p) { + capn_resolve(&p.p); + capn_write16(p.p, 0, s->bigBoxX); + capn_write16(p.p, 2, s->bigBoxY); + capn_write16(p.p, 4, s->bigBoxWidth); + capn_write16(p.p, 6, s->bigBoxHeight); + capn_setp(p.p, 0, s->boxProjection.p); + capn_setp(p.p, 1, s->yuvCorrection.p); +} +void cereal_get_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_list l, int i) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_ModelSettings(s, p); +} +void cereal_set_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_list l, int i) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_ModelSettings(s, p); +} + +cereal_CalibrationFeatures_ptr cereal_new_CalibrationFeatures(struct capn_segment *s) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_new_struct(s, 8, 3); + return p; +} +cereal_CalibrationFeatures_list cereal_new_CalibrationFeatures_list(struct capn_segment *s, int len) { + cereal_CalibrationFeatures_list p; + p.p = capn_new_list(s, len, 8, 3); + return p; +} +void cereal_read_CalibrationFeatures(struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->p0.p = capn_getp(p.p, 0, 0); + s->p1.p = capn_getp(p.p, 1, 0); + s->status.p = capn_getp(p.p, 2, 0); +} +void cereal_write_CalibrationFeatures(const struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_setp(p.p, 0, s->p0.p); + capn_setp(p.p, 1, s->p1.p); + capn_setp(p.p, 2, s->status.p); +} +void cereal_get_CalibrationFeatures(struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_list l, int i) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_CalibrationFeatures(s, p); +} +void cereal_set_CalibrationFeatures(const struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_list l, int i) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_CalibrationFeatures(s, p); +} + +cereal_EncodeIndex_ptr cereal_new_EncodeIndex(struct capn_segment *s) { + cereal_EncodeIndex_ptr p; + p.p = capn_new_struct(s, 24, 0); + return p; +} +cereal_EncodeIndex_list cereal_new_EncodeIndex_list(struct capn_segment *s, int len) { + cereal_EncodeIndex_list p; + p.p = capn_new_list(s, len, 24, 0); + return p; +} +void cereal_read_EncodeIndex(struct cereal_EncodeIndex *s, cereal_EncodeIndex_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->type = (enum cereal_EncodeIndex_Type)(int) capn_read16(p.p, 4); + s->encodeId = capn_read32(p.p, 8); + s->segmentNum = (int32_t) ((int32_t)capn_read32(p.p, 12)); + s->segmentId = capn_read32(p.p, 16); +} +void cereal_write_EncodeIndex(const struct cereal_EncodeIndex *s, cereal_EncodeIndex_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_write16(p.p, 4, (uint16_t) (s->type)); + capn_write32(p.p, 8, s->encodeId); + capn_write32(p.p, 12, (uint32_t) (s->segmentNum)); + capn_write32(p.p, 16, s->segmentId); +} +void cereal_get_EncodeIndex(struct cereal_EncodeIndex *s, cereal_EncodeIndex_list l, int i) { + cereal_EncodeIndex_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_EncodeIndex(s, p); +} +void cereal_set_EncodeIndex(const struct cereal_EncodeIndex *s, cereal_EncodeIndex_list l, int i) { + cereal_EncodeIndex_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_EncodeIndex(s, p); +} + +cereal_AndroidLogEntry_ptr cereal_new_AndroidLogEntry(struct capn_segment *s) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_new_struct(s, 24, 2); + return p; +} +cereal_AndroidLogEntry_list cereal_new_AndroidLogEntry_list(struct capn_segment *s, int len) { + cereal_AndroidLogEntry_list p; + p.p = capn_new_list(s, len, 24, 2); + return p; +} +void cereal_read_AndroidLogEntry(struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_ptr p) { + capn_resolve(&p.p); + s->id = capn_read8(p.p, 0); + s->ts = capn_read64(p.p, 8); + s->priority = capn_read8(p.p, 1); + s->pid = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->tid = (int32_t) ((int32_t)capn_read32(p.p, 16)); + s->tag = capn_get_text(p.p, 0, capn_val0); + s->message = capn_get_text(p.p, 1, capn_val0); +} +void cereal_write_AndroidLogEntry(const struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_ptr p) { + capn_resolve(&p.p); + capn_write8(p.p, 0, s->id); + capn_write64(p.p, 8, s->ts); + capn_write8(p.p, 1, s->priority); + capn_write32(p.p, 4, (uint32_t) (s->pid)); + capn_write32(p.p, 16, (uint32_t) (s->tid)); + capn_set_text(p.p, 0, s->tag); + capn_set_text(p.p, 1, s->message); +} +void cereal_get_AndroidLogEntry(struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_list l, int i) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_AndroidLogEntry(s, p); +} +void cereal_set_AndroidLogEntry(const struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_list l, int i) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_AndroidLogEntry(s, p); +} + +cereal_LogRotate_ptr cereal_new_LogRotate(struct capn_segment *s) { + cereal_LogRotate_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LogRotate_list cereal_new_LogRotate_list(struct capn_segment *s, int len) { + cereal_LogRotate_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LogRotate(struct cereal_LogRotate *s, cereal_LogRotate_ptr p) { + capn_resolve(&p.p); + s->segmentNum = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->path = capn_get_text(p.p, 0, capn_val0); +} +void cereal_write_LogRotate(const struct cereal_LogRotate *s, cereal_LogRotate_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->segmentNum)); + capn_set_text(p.p, 0, s->path); +} +void cereal_get_LogRotate(struct cereal_LogRotate *s, cereal_LogRotate_list l, int i) { + cereal_LogRotate_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LogRotate(s, p); +} +void cereal_set_LogRotate(const struct cereal_LogRotate *s, cereal_LogRotate_list l, int i) { + cereal_LogRotate_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LogRotate(s, p); +} + +cereal_Event_ptr cereal_new_Event(struct capn_segment *s) { + cereal_Event_ptr p; + p.p = capn_new_struct(s, 16, 1); + return p; +} +cereal_Event_list cereal_new_Event_list(struct capn_segment *s, int len) { + cereal_Event_list p; + p.p = capn_new_list(s, len, 16, 1); + return p; +} +void cereal_read_Event(struct cereal_Event *s, cereal_Event_ptr p) { + capn_resolve(&p.p); + s->logMonoTime = capn_read64(p.p, 0); + s->which = (enum cereal_Event_which)(int) capn_read16(p.p, 8); + switch (s->which) { + case cereal_Event_logMessage: + s->logMessage = capn_get_text(p.p, 0, capn_val0); + break; + case cereal_Event_initData: + case cereal_Event_frame: + case cereal_Event_gpsNMEA: + case cereal_Event_sensorEventDEPRECATED: + case cereal_Event_can: + case cereal_Event_thermal: + case cereal_Event_live100: + case cereal_Event_liveEventDEPRECATED: + case cereal_Event_model: + case cereal_Event_features: + case cereal_Event_sensorEvents: + case cereal_Event_health: + case cereal_Event_live20: + case cereal_Event_liveUIDEPRECATED: + case cereal_Event_encodeIdx: + case cereal_Event_liveTracks: + case cereal_Event_sendcan: + case cereal_Event_liveCalibration: + case cereal_Event_androidLogEntry: + s->androidLogEntry.p = capn_getp(p.p, 0, 0); + break; + default: + break; + } +} +void cereal_write_Event(const struct cereal_Event *s, cereal_Event_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 0, s->logMonoTime); + capn_write16(p.p, 8, s->which); + switch (s->which) { + case cereal_Event_logMessage: + capn_set_text(p.p, 0, s->logMessage); + break; + case cereal_Event_initData: + case cereal_Event_frame: + case cereal_Event_gpsNMEA: + case cereal_Event_sensorEventDEPRECATED: + case cereal_Event_can: + case cereal_Event_thermal: + case cereal_Event_live100: + case cereal_Event_liveEventDEPRECATED: + case cereal_Event_model: + case cereal_Event_features: + case cereal_Event_sensorEvents: + case cereal_Event_health: + case cereal_Event_live20: + case cereal_Event_liveUIDEPRECATED: + case cereal_Event_encodeIdx: + case cereal_Event_liveTracks: + case cereal_Event_sendcan: + case cereal_Event_liveCalibration: + case cereal_Event_androidLogEntry: + capn_setp(p.p, 0, s->androidLogEntry.p); + break; + default: + break; + } +} +void cereal_get_Event(struct cereal_Event *s, cereal_Event_list l, int i) { + cereal_Event_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Event(s, p); +} +void cereal_set_Event(const struct cereal_Event *s, cereal_Event_list l, int i) { + cereal_Event_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Event(s, p); +} diff --git a/cereal/gen/c/log.capnp.h b/cereal/gen/c/log.capnp.h new file mode 100644 index 0000000000..865e4d0ff9 --- /dev/null +++ b/cereal/gen/c/log.capnp.h @@ -0,0 +1,667 @@ +#ifndef CAPN_F3B1F17E25A4285B +#define CAPN_F3B1F17E25A4285B +/* AUTO GENERATED - DO NOT EDIT */ +#include + +#if CAPN_VERSION != 1 +#error "version mismatch between capnp_c.h and generated code" +#endif + +#include "c++.capnp.h" + +#ifdef __cplusplus +extern "C" { +#endif + +struct cereal_InitData; +struct cereal_FrameData; +struct cereal_GPSNMEAData; +struct cereal_SensorEventData; +struct cereal_SensorEventData_SensorVec; +struct cereal_CanData; +struct cereal_ThermalData; +struct cereal_HealthData; +struct cereal_LiveUI; +struct cereal_Live20Data; +struct cereal_Live20Data_LeadData; +struct cereal_LiveCalibrationData; +struct cereal_LiveTracks; +struct cereal_Live100Data; +struct cereal_LiveEventData; +struct cereal_ModelData; +struct cereal_ModelData_PathData; +struct cereal_ModelData_LeadData; +struct cereal_ModelData_ModelSettings; +struct cereal_CalibrationFeatures; +struct cereal_EncodeIndex; +struct cereal_AndroidLogEntry; +struct cereal_LogRotate; +struct cereal_Event; + +typedef struct {capn_ptr p;} cereal_InitData_ptr; +typedef struct {capn_ptr p;} cereal_FrameData_ptr; +typedef struct {capn_ptr p;} cereal_GPSNMEAData_ptr; +typedef struct {capn_ptr p;} cereal_SensorEventData_ptr; +typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_ptr; +typedef struct {capn_ptr p;} cereal_CanData_ptr; +typedef struct {capn_ptr p;} cereal_ThermalData_ptr; +typedef struct {capn_ptr p;} cereal_HealthData_ptr; +typedef struct {capn_ptr p;} cereal_LiveUI_ptr; +typedef struct {capn_ptr p;} cereal_Live20Data_ptr; +typedef struct {capn_ptr p;} cereal_Live20Data_LeadData_ptr; +typedef struct {capn_ptr p;} cereal_LiveCalibrationData_ptr; +typedef struct {capn_ptr p;} cereal_LiveTracks_ptr; +typedef struct {capn_ptr p;} cereal_Live100Data_ptr; +typedef struct {capn_ptr p;} cereal_LiveEventData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_PathData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_LeadData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_ModelSettings_ptr; +typedef struct {capn_ptr p;} cereal_CalibrationFeatures_ptr; +typedef struct {capn_ptr p;} cereal_EncodeIndex_ptr; +typedef struct {capn_ptr p;} cereal_AndroidLogEntry_ptr; +typedef struct {capn_ptr p;} cereal_LogRotate_ptr; +typedef struct {capn_ptr p;} cereal_Event_ptr; + +typedef struct {capn_ptr p;} cereal_InitData_list; +typedef struct {capn_ptr p;} cereal_FrameData_list; +typedef struct {capn_ptr p;} cereal_GPSNMEAData_list; +typedef struct {capn_ptr p;} cereal_SensorEventData_list; +typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_list; +typedef struct {capn_ptr p;} cereal_CanData_list; +typedef struct {capn_ptr p;} cereal_ThermalData_list; +typedef struct {capn_ptr p;} cereal_HealthData_list; +typedef struct {capn_ptr p;} cereal_LiveUI_list; +typedef struct {capn_ptr p;} cereal_Live20Data_list; +typedef struct {capn_ptr p;} cereal_Live20Data_LeadData_list; +typedef struct {capn_ptr p;} cereal_LiveCalibrationData_list; +typedef struct {capn_ptr p;} cereal_LiveTracks_list; +typedef struct {capn_ptr p;} cereal_Live100Data_list; +typedef struct {capn_ptr p;} cereal_LiveEventData_list; +typedef struct {capn_ptr p;} cereal_ModelData_list; +typedef struct {capn_ptr p;} cereal_ModelData_PathData_list; +typedef struct {capn_ptr p;} cereal_ModelData_LeadData_list; +typedef struct {capn_ptr p;} cereal_ModelData_ModelSettings_list; +typedef struct {capn_ptr p;} cereal_CalibrationFeatures_list; +typedef struct {capn_ptr p;} cereal_EncodeIndex_list; +typedef struct {capn_ptr p;} cereal_AndroidLogEntry_list; +typedef struct {capn_ptr p;} cereal_LogRotate_list; +typedef struct {capn_ptr p;} cereal_Event_list; + +enum cereal_EncodeIndex_Type { + cereal_EncodeIndex_Type_bigBoxLossless = 0, + cereal_EncodeIndex_Type_fullHEVC = 1, + cereal_EncodeIndex_Type_bigBoxHEVC = 2 +}; +extern int32_t cereal_logVersion; + +struct cereal_InitData { + capn_ptr kernelArgs; + capn_text gctx; + capn_text dongleId; +}; + +static const size_t cereal_InitData_word_count = 0; + +static const size_t cereal_InitData_pointer_count = 3; + +static const size_t cereal_InitData_struct_bytes_count = 24; + +struct cereal_FrameData { + uint32_t frameId; + uint32_t encodeId; + uint64_t timestampEof; + int32_t frameLength; + int32_t integLines; + int32_t globalGain; + capn_data image; +}; + +static const size_t cereal_FrameData_word_count = 4; + +static const size_t cereal_FrameData_pointer_count = 1; + +static const size_t cereal_FrameData_struct_bytes_count = 40; + +struct cereal_GPSNMEAData { + int64_t timestamp; + uint64_t localWallTime; + capn_text nmea; +}; + +static const size_t cereal_GPSNMEAData_word_count = 2; + +static const size_t cereal_GPSNMEAData_pointer_count = 1; + +static const size_t cereal_GPSNMEAData_struct_bytes_count = 24; +enum cereal_SensorEventData_which { + cereal_SensorEventData_acceleration = 0, + cereal_SensorEventData_magnetic = 1, + cereal_SensorEventData_orientation = 2, + cereal_SensorEventData_gyro = 3 +}; + +struct cereal_SensorEventData { + int32_t version; + int32_t sensor; + int32_t type; + int64_t timestamp; + enum cereal_SensorEventData_which which; + union { + cereal_SensorEventData_SensorVec_ptr acceleration; + cereal_SensorEventData_SensorVec_ptr magnetic; + cereal_SensorEventData_SensorVec_ptr orientation; + cereal_SensorEventData_SensorVec_ptr gyro; + }; +}; + +static const size_t cereal_SensorEventData_word_count = 3; + +static const size_t cereal_SensorEventData_pointer_count = 1; + +static const size_t cereal_SensorEventData_struct_bytes_count = 32; + +struct cereal_SensorEventData_SensorVec { + capn_list32 v; + int8_t status; +}; + +static const size_t cereal_SensorEventData_SensorVec_word_count = 1; + +static const size_t cereal_SensorEventData_SensorVec_pointer_count = 1; + +static const size_t cereal_SensorEventData_SensorVec_struct_bytes_count = 16; + +struct cereal_CanData { + uint32_t address; + uint16_t busTime; + capn_data dat; + int8_t src; +}; + +static const size_t cereal_CanData_word_count = 1; + +static const size_t cereal_CanData_pointer_count = 1; + +static const size_t cereal_CanData_struct_bytes_count = 16; + +struct cereal_ThermalData { + uint16_t cpu0; + uint16_t cpu1; + uint16_t cpu2; + uint16_t cpu3; + uint16_t mem; + uint16_t gpu; + uint32_t bat; +}; + +static const size_t cereal_ThermalData_word_count = 2; + +static const size_t cereal_ThermalData_pointer_count = 0; + +static const size_t cereal_ThermalData_struct_bytes_count = 16; + +struct cereal_HealthData { + uint32_t voltage; + uint32_t current; + unsigned started : 1; + unsigned controlsAllowed : 1; + unsigned gasInterceptorDetected : 1; +}; + +static const size_t cereal_HealthData_word_count = 2; + +static const size_t cereal_HealthData_pointer_count = 0; + +static const size_t cereal_HealthData_struct_bytes_count = 16; + +struct cereal_LiveUI { + unsigned rearViewCam : 1; + capn_text alertText1; + capn_text alertText2; + float awarenessStatus; +}; + +static const size_t cereal_LiveUI_word_count = 1; + +static const size_t cereal_LiveUI_pointer_count = 2; + +static const size_t cereal_LiveUI_struct_bytes_count = 24; + +struct cereal_Live20Data { + capn_list64 canMonoTimes; + uint64_t mdMonoTime; + uint64_t ftMonoTime; + capn_list32 warpMatrix; + float angleOffset; + int8_t calStatus; + int32_t calCycle; + int8_t calPerc; + cereal_Live20Data_LeadData_ptr leadOne; + cereal_Live20Data_LeadData_ptr leadTwo; + float cumLagMs; +}; + +static const size_t cereal_Live20Data_word_count = 4; + +static const size_t cereal_Live20Data_pointer_count = 4; + +static const size_t cereal_Live20Data_struct_bytes_count = 64; + +struct cereal_Live20Data_LeadData { + float dRel; + float yRel; + float vRel; + float aRel; + float vLead; + float aLead; + float dPath; + float vLat; + float vLeadK; + float aLeadK; + unsigned fcw : 1; + unsigned status : 1; +}; + +static const size_t cereal_Live20Data_LeadData_word_count = 6; + +static const size_t cereal_Live20Data_LeadData_pointer_count = 0; + +static const size_t cereal_Live20Data_LeadData_struct_bytes_count = 48; + +struct cereal_LiveCalibrationData { + capn_list32 warpMatrix; + int8_t calStatus; + int32_t calCycle; + int8_t calPerc; +}; + +static const size_t cereal_LiveCalibrationData_word_count = 1; + +static const size_t cereal_LiveCalibrationData_pointer_count = 1; + +static const size_t cereal_LiveCalibrationData_struct_bytes_count = 16; + +struct cereal_LiveTracks { + int32_t trackId; + float dRel; + float yRel; + float vRel; + float aRel; + float timeStamp; + float status; + float currentTime; + unsigned stationary : 1; + unsigned oncoming : 1; +}; + +static const size_t cereal_LiveTracks_word_count = 5; + +static const size_t cereal_LiveTracks_pointer_count = 0; + +static const size_t cereal_LiveTracks_struct_bytes_count = 40; + +struct cereal_Live100Data { + uint64_t canMonoTime; + capn_list64 canMonoTimes; + uint64_t l20MonoTime; + uint64_t mdMonoTime; + float vEgo; + float aEgo; + float vPid; + float vTargetLead; + float upAccelCmd; + float uiAccelCmd; + float yActual; + float yDes; + float upSteer; + float uiSteer; + float aTargetMin; + float aTargetMax; + float jerkFactor; + float angleSteers; + int32_t hudLead; + float cumLagMs; + unsigned enabled : 1; + unsigned steerOverride : 1; + float vCruise; + unsigned rearViewCam : 1; + capn_text alertText1; + capn_text alertText2; + float awarenessStatus; +}; + +static const size_t cereal_Live100Data_word_count = 13; + +static const size_t cereal_Live100Data_pointer_count = 3; + +static const size_t cereal_Live100Data_struct_bytes_count = 128; + +struct cereal_LiveEventData { + capn_text name; + int32_t value; +}; + +static const size_t cereal_LiveEventData_word_count = 1; + +static const size_t cereal_LiveEventData_pointer_count = 1; + +static const size_t cereal_LiveEventData_struct_bytes_count = 16; + +struct cereal_ModelData { + uint32_t frameId; + cereal_ModelData_PathData_ptr path; + cereal_ModelData_PathData_ptr leftLane; + cereal_ModelData_PathData_ptr rightLane; + cereal_ModelData_LeadData_ptr lead; + cereal_ModelData_ModelSettings_ptr settings; +}; + +static const size_t cereal_ModelData_word_count = 1; + +static const size_t cereal_ModelData_pointer_count = 5; + +static const size_t cereal_ModelData_struct_bytes_count = 48; + +struct cereal_ModelData_PathData { + capn_list32 points; + float prob; + float std; +}; + +static const size_t cereal_ModelData_PathData_word_count = 1; + +static const size_t cereal_ModelData_PathData_pointer_count = 1; + +static const size_t cereal_ModelData_PathData_struct_bytes_count = 16; + +struct cereal_ModelData_LeadData { + float dist; + float prob; + float std; +}; + +static const size_t cereal_ModelData_LeadData_word_count = 2; + +static const size_t cereal_ModelData_LeadData_pointer_count = 0; + +static const size_t cereal_ModelData_LeadData_struct_bytes_count = 16; + +struct cereal_ModelData_ModelSettings { + uint16_t bigBoxX; + uint16_t bigBoxY; + uint16_t bigBoxWidth; + uint16_t bigBoxHeight; + capn_list32 boxProjection; + capn_list32 yuvCorrection; +}; + +static const size_t cereal_ModelData_ModelSettings_word_count = 1; + +static const size_t cereal_ModelData_ModelSettings_pointer_count = 2; + +static const size_t cereal_ModelData_ModelSettings_struct_bytes_count = 24; + +struct cereal_CalibrationFeatures { + uint32_t frameId; + capn_list32 p0; + capn_list32 p1; + capn_list8 status; +}; + +static const size_t cereal_CalibrationFeatures_word_count = 1; + +static const size_t cereal_CalibrationFeatures_pointer_count = 3; + +static const size_t cereal_CalibrationFeatures_struct_bytes_count = 32; + +struct cereal_EncodeIndex { + uint32_t frameId; + enum cereal_EncodeIndex_Type type; + uint32_t encodeId; + int32_t segmentNum; + uint32_t segmentId; +}; + +static const size_t cereal_EncodeIndex_word_count = 3; + +static const size_t cereal_EncodeIndex_pointer_count = 0; + +static const size_t cereal_EncodeIndex_struct_bytes_count = 24; + +struct cereal_AndroidLogEntry { + uint8_t id; + uint64_t ts; + uint8_t priority; + int32_t pid; + int32_t tid; + capn_text tag; + capn_text message; +}; + +static const size_t cereal_AndroidLogEntry_word_count = 3; + +static const size_t cereal_AndroidLogEntry_pointer_count = 2; + +static const size_t cereal_AndroidLogEntry_struct_bytes_count = 40; + +struct cereal_LogRotate { + int32_t segmentNum; + capn_text path; +}; + +static const size_t cereal_LogRotate_word_count = 1; + +static const size_t cereal_LogRotate_pointer_count = 1; + +static const size_t cereal_LogRotate_struct_bytes_count = 16; +enum cereal_Event_which { + cereal_Event_initData = 0, + cereal_Event_frame = 1, + cereal_Event_gpsNMEA = 2, + cereal_Event_sensorEventDEPRECATED = 3, + cereal_Event_can = 4, + cereal_Event_thermal = 5, + cereal_Event_live100 = 6, + cereal_Event_liveEventDEPRECATED = 7, + cereal_Event_model = 8, + cereal_Event_features = 9, + cereal_Event_sensorEvents = 10, + cereal_Event_health = 11, + cereal_Event_live20 = 12, + cereal_Event_liveUIDEPRECATED = 13, + cereal_Event_encodeIdx = 14, + cereal_Event_liveTracks = 15, + cereal_Event_sendcan = 16, + cereal_Event_logMessage = 17, + cereal_Event_liveCalibration = 18, + cereal_Event_androidLogEntry = 19 +}; + +struct cereal_Event { + uint64_t logMonoTime; + enum cereal_Event_which which; + union { + cereal_InitData_ptr initData; + cereal_FrameData_ptr frame; + cereal_GPSNMEAData_ptr gpsNMEA; + cereal_SensorEventData_ptr sensorEventDEPRECATED; + cereal_CanData_list can; + cereal_ThermalData_ptr thermal; + cereal_Live100Data_ptr live100; + cereal_LiveEventData_list liveEventDEPRECATED; + cereal_ModelData_ptr model; + cereal_CalibrationFeatures_ptr features; + cereal_SensorEventData_list sensorEvents; + cereal_HealthData_ptr health; + cereal_Live20Data_ptr live20; + cereal_LiveUI_ptr liveUIDEPRECATED; + cereal_EncodeIndex_ptr encodeIdx; + cereal_LiveTracks_list liveTracks; + cereal_CanData_list sendcan; + capn_text logMessage; + cereal_LiveCalibrationData_ptr liveCalibration; + cereal_AndroidLogEntry_ptr androidLogEntry; + }; +}; + +static const size_t cereal_Event_word_count = 2; + +static const size_t cereal_Event_pointer_count = 1; + +static const size_t cereal_Event_struct_bytes_count = 24; + +cereal_InitData_ptr cereal_new_InitData(struct capn_segment*); +cereal_FrameData_ptr cereal_new_FrameData(struct capn_segment*); +cereal_GPSNMEAData_ptr cereal_new_GPSNMEAData(struct capn_segment*); +cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment*); +cereal_SensorEventData_SensorVec_ptr cereal_new_SensorEventData_SensorVec(struct capn_segment*); +cereal_CanData_ptr cereal_new_CanData(struct capn_segment*); +cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment*); +cereal_HealthData_ptr cereal_new_HealthData(struct capn_segment*); +cereal_LiveUI_ptr cereal_new_LiveUI(struct capn_segment*); +cereal_Live20Data_ptr cereal_new_Live20Data(struct capn_segment*); +cereal_Live20Data_LeadData_ptr cereal_new_Live20Data_LeadData(struct capn_segment*); +cereal_LiveCalibrationData_ptr cereal_new_LiveCalibrationData(struct capn_segment*); +cereal_LiveTracks_ptr cereal_new_LiveTracks(struct capn_segment*); +cereal_Live100Data_ptr cereal_new_Live100Data(struct capn_segment*); +cereal_LiveEventData_ptr cereal_new_LiveEventData(struct capn_segment*); +cereal_ModelData_ptr cereal_new_ModelData(struct capn_segment*); +cereal_ModelData_PathData_ptr cereal_new_ModelData_PathData(struct capn_segment*); +cereal_ModelData_LeadData_ptr cereal_new_ModelData_LeadData(struct capn_segment*); +cereal_ModelData_ModelSettings_ptr cereal_new_ModelData_ModelSettings(struct capn_segment*); +cereal_CalibrationFeatures_ptr cereal_new_CalibrationFeatures(struct capn_segment*); +cereal_EncodeIndex_ptr cereal_new_EncodeIndex(struct capn_segment*); +cereal_AndroidLogEntry_ptr cereal_new_AndroidLogEntry(struct capn_segment*); +cereal_LogRotate_ptr cereal_new_LogRotate(struct capn_segment*); +cereal_Event_ptr cereal_new_Event(struct capn_segment*); + +cereal_InitData_list cereal_new_InitData_list(struct capn_segment*, int len); +cereal_FrameData_list cereal_new_FrameData_list(struct capn_segment*, int len); +cereal_GPSNMEAData_list cereal_new_GPSNMEAData_list(struct capn_segment*, int len); +cereal_SensorEventData_list cereal_new_SensorEventData_list(struct capn_segment*, int len); +cereal_SensorEventData_SensorVec_list cereal_new_SensorEventData_SensorVec_list(struct capn_segment*, int len); +cereal_CanData_list cereal_new_CanData_list(struct capn_segment*, int len); +cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment*, int len); +cereal_HealthData_list cereal_new_HealthData_list(struct capn_segment*, int len); +cereal_LiveUI_list cereal_new_LiveUI_list(struct capn_segment*, int len); +cereal_Live20Data_list cereal_new_Live20Data_list(struct capn_segment*, int len); +cereal_Live20Data_LeadData_list cereal_new_Live20Data_LeadData_list(struct capn_segment*, int len); +cereal_LiveCalibrationData_list cereal_new_LiveCalibrationData_list(struct capn_segment*, int len); +cereal_LiveTracks_list cereal_new_LiveTracks_list(struct capn_segment*, int len); +cereal_Live100Data_list cereal_new_Live100Data_list(struct capn_segment*, int len); +cereal_LiveEventData_list cereal_new_LiveEventData_list(struct capn_segment*, int len); +cereal_ModelData_list cereal_new_ModelData_list(struct capn_segment*, int len); +cereal_ModelData_PathData_list cereal_new_ModelData_PathData_list(struct capn_segment*, int len); +cereal_ModelData_LeadData_list cereal_new_ModelData_LeadData_list(struct capn_segment*, int len); +cereal_ModelData_ModelSettings_list cereal_new_ModelData_ModelSettings_list(struct capn_segment*, int len); +cereal_CalibrationFeatures_list cereal_new_CalibrationFeatures_list(struct capn_segment*, int len); +cereal_EncodeIndex_list cereal_new_EncodeIndex_list(struct capn_segment*, int len); +cereal_AndroidLogEntry_list cereal_new_AndroidLogEntry_list(struct capn_segment*, int len); +cereal_LogRotate_list cereal_new_LogRotate_list(struct capn_segment*, int len); +cereal_Event_list cereal_new_Event_list(struct capn_segment*, int len); + +void cereal_read_InitData(struct cereal_InitData*, cereal_InitData_ptr); +void cereal_read_FrameData(struct cereal_FrameData*, cereal_FrameData_ptr); +void cereal_read_GPSNMEAData(struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr); +void cereal_read_SensorEventData(struct cereal_SensorEventData*, cereal_SensorEventData_ptr); +void cereal_read_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_ptr); +void cereal_read_CanData(struct cereal_CanData*, cereal_CanData_ptr); +void cereal_read_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_ptr); +void cereal_read_HealthData(struct cereal_HealthData*, cereal_HealthData_ptr); +void cereal_read_LiveUI(struct cereal_LiveUI*, cereal_LiveUI_ptr); +void cereal_read_Live20Data(struct cereal_Live20Data*, cereal_Live20Data_ptr); +void cereal_read_Live20Data_LeadData(struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_ptr); +void cereal_read_LiveCalibrationData(struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_ptr); +void cereal_read_LiveTracks(struct cereal_LiveTracks*, cereal_LiveTracks_ptr); +void cereal_read_Live100Data(struct cereal_Live100Data*, cereal_Live100Data_ptr); +void cereal_read_LiveEventData(struct cereal_LiveEventData*, cereal_LiveEventData_ptr); +void cereal_read_ModelData(struct cereal_ModelData*, cereal_ModelData_ptr); +void cereal_read_ModelData_PathData(struct cereal_ModelData_PathData*, cereal_ModelData_PathData_ptr); +void cereal_read_ModelData_LeadData(struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_ptr); +void cereal_read_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_ptr); +void cereal_read_CalibrationFeatures(struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_ptr); +void cereal_read_EncodeIndex(struct cereal_EncodeIndex*, cereal_EncodeIndex_ptr); +void cereal_read_AndroidLogEntry(struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_ptr); +void cereal_read_LogRotate(struct cereal_LogRotate*, cereal_LogRotate_ptr); +void cereal_read_Event(struct cereal_Event*, cereal_Event_ptr); + +void cereal_write_InitData(const struct cereal_InitData*, cereal_InitData_ptr); +void cereal_write_FrameData(const struct cereal_FrameData*, cereal_FrameData_ptr); +void cereal_write_GPSNMEAData(const struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr); +void cereal_write_SensorEventData(const struct cereal_SensorEventData*, cereal_SensorEventData_ptr); +void cereal_write_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_ptr); +void cereal_write_CanData(const struct cereal_CanData*, cereal_CanData_ptr); +void cereal_write_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_ptr); +void cereal_write_HealthData(const struct cereal_HealthData*, cereal_HealthData_ptr); +void cereal_write_LiveUI(const struct cereal_LiveUI*, cereal_LiveUI_ptr); +void cereal_write_Live20Data(const struct cereal_Live20Data*, cereal_Live20Data_ptr); +void cereal_write_Live20Data_LeadData(const struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_ptr); +void cereal_write_LiveCalibrationData(const struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_ptr); +void cereal_write_LiveTracks(const struct cereal_LiveTracks*, cereal_LiveTracks_ptr); +void cereal_write_Live100Data(const struct cereal_Live100Data*, cereal_Live100Data_ptr); +void cereal_write_LiveEventData(const struct cereal_LiveEventData*, cereal_LiveEventData_ptr); +void cereal_write_ModelData(const struct cereal_ModelData*, cereal_ModelData_ptr); +void cereal_write_ModelData_PathData(const struct cereal_ModelData_PathData*, cereal_ModelData_PathData_ptr); +void cereal_write_ModelData_LeadData(const struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_ptr); +void cereal_write_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_ptr); +void cereal_write_CalibrationFeatures(const struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_ptr); +void cereal_write_EncodeIndex(const struct cereal_EncodeIndex*, cereal_EncodeIndex_ptr); +void cereal_write_AndroidLogEntry(const struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_ptr); +void cereal_write_LogRotate(const struct cereal_LogRotate*, cereal_LogRotate_ptr); +void cereal_write_Event(const struct cereal_Event*, cereal_Event_ptr); + +void cereal_get_InitData(struct cereal_InitData*, cereal_InitData_list, int i); +void cereal_get_FrameData(struct cereal_FrameData*, cereal_FrameData_list, int i); +void cereal_get_GPSNMEAData(struct cereal_GPSNMEAData*, cereal_GPSNMEAData_list, int i); +void cereal_get_SensorEventData(struct cereal_SensorEventData*, cereal_SensorEventData_list, int i); +void cereal_get_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_list, int i); +void cereal_get_CanData(struct cereal_CanData*, cereal_CanData_list, int i); +void cereal_get_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_list, int i); +void cereal_get_HealthData(struct cereal_HealthData*, cereal_HealthData_list, int i); +void cereal_get_LiveUI(struct cereal_LiveUI*, cereal_LiveUI_list, int i); +void cereal_get_Live20Data(struct cereal_Live20Data*, cereal_Live20Data_list, int i); +void cereal_get_Live20Data_LeadData(struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_list, int i); +void cereal_get_LiveCalibrationData(struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_list, int i); +void cereal_get_LiveTracks(struct cereal_LiveTracks*, cereal_LiveTracks_list, int i); +void cereal_get_Live100Data(struct cereal_Live100Data*, cereal_Live100Data_list, int i); +void cereal_get_LiveEventData(struct cereal_LiveEventData*, cereal_LiveEventData_list, int i); +void cereal_get_ModelData(struct cereal_ModelData*, cereal_ModelData_list, int i); +void cereal_get_ModelData_PathData(struct cereal_ModelData_PathData*, cereal_ModelData_PathData_list, int i); +void cereal_get_ModelData_LeadData(struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_list, int i); +void cereal_get_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_list, int i); +void cereal_get_CalibrationFeatures(struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_list, int i); +void cereal_get_EncodeIndex(struct cereal_EncodeIndex*, cereal_EncodeIndex_list, int i); +void cereal_get_AndroidLogEntry(struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_list, int i); +void cereal_get_LogRotate(struct cereal_LogRotate*, cereal_LogRotate_list, int i); +void cereal_get_Event(struct cereal_Event*, cereal_Event_list, int i); + +void cereal_set_InitData(const struct cereal_InitData*, cereal_InitData_list, int i); +void cereal_set_FrameData(const struct cereal_FrameData*, cereal_FrameData_list, int i); +void cereal_set_GPSNMEAData(const struct cereal_GPSNMEAData*, cereal_GPSNMEAData_list, int i); +void cereal_set_SensorEventData(const struct cereal_SensorEventData*, cereal_SensorEventData_list, int i); +void cereal_set_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_list, int i); +void cereal_set_CanData(const struct cereal_CanData*, cereal_CanData_list, int i); +void cereal_set_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_list, int i); +void cereal_set_HealthData(const struct cereal_HealthData*, cereal_HealthData_list, int i); +void cereal_set_LiveUI(const struct cereal_LiveUI*, cereal_LiveUI_list, int i); +void cereal_set_Live20Data(const struct cereal_Live20Data*, cereal_Live20Data_list, int i); +void cereal_set_Live20Data_LeadData(const struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_list, int i); +void cereal_set_LiveCalibrationData(const struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_list, int i); +void cereal_set_LiveTracks(const struct cereal_LiveTracks*, cereal_LiveTracks_list, int i); +void cereal_set_Live100Data(const struct cereal_Live100Data*, cereal_Live100Data_list, int i); +void cereal_set_LiveEventData(const struct cereal_LiveEventData*, cereal_LiveEventData_list, int i); +void cereal_set_ModelData(const struct cereal_ModelData*, cereal_ModelData_list, int i); +void cereal_set_ModelData_PathData(const struct cereal_ModelData_PathData*, cereal_ModelData_PathData_list, int i); +void cereal_set_ModelData_LeadData(const struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_list, int i); +void cereal_set_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_list, int i); +void cereal_set_CalibrationFeatures(const struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_list, int i); +void cereal_set_EncodeIndex(const struct cereal_EncodeIndex*, cereal_EncodeIndex_list, int i); +void cereal_set_AndroidLogEntry(const struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_list, int i); +void cereal_set_LogRotate(const struct cereal_LogRotate*, cereal_LogRotate_list, int i); +void cereal_set_Event(const struct cereal_Event*, cereal_Event_list, int i); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ new file mode 100644 index 0000000000..b981eedac1 --- /dev/null +++ b/cereal/gen/cpp/log.capnp.c++ @@ -0,0 +1,3732 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: log.capnp + +#include "log.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<23> b_d578fb3372ed5043 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 80, 237, 114, 51, 251, 120, 213, + 10, 0, 0, 0, 4, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 108, 111, 103, 86, 101, 114, + 115, 105, 111, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d578fb3372ed5043 = b_d578fb3372ed5043.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d578fb3372ed5043 = { + 0xd578fb3372ed5043, b_d578fb3372ed5043.words, 23, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d578fb3372ed5043, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<68> b_e71008caeb3fb65c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 107, 101, 114, 110, 101, 108, 65, 114, + 103, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 99, 116, 120, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 110, 103, 108, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e71008caeb3fb65c = b_e71008caeb3fb65c.words; +#if !CAPNP_LITE +static const uint16_t m_e71008caeb3fb65c[] = {2, 1, 0}; +static const uint16_t i_e71008caeb3fb65c[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e71008caeb3fb65c = { + 0xe71008caeb3fb65c, b_e71008caeb3fb65c.words, 68, nullptr, m_e71008caeb3fb65c, + 0, 3, i_e71008caeb3fb65c, nullptr, nullptr, { &s_e71008caeb3fb65c, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<127> b_ea0245f695ae0a33 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 76, 101, 110, + 103, 116, 104, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 103, 76, 105, 110, + 101, 115, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 98, 97, 108, 71, 97, + 105, 110, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 97, 103, 101, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea0245f695ae0a33 = b_ea0245f695ae0a33.words; +#if !CAPNP_LITE +static const uint16_t m_ea0245f695ae0a33[] = {1, 0, 3, 5, 6, 4, 2}; +static const uint16_t i_ea0245f695ae0a33[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ea0245f695ae0a33 = { + 0xea0245f695ae0a33, b_ea0245f695ae0a33.words, 127, nullptr, m_ea0245f695ae0a33, + 0, 7, i_ea0245f695ae0a33, nullptr, nullptr, { &s_ea0245f695ae0a33, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_9d291d7813ba4a88 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 80, 83, 78, 77, 69, + 65, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 108, 87, 97, 108, + 108, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 109, 101, 97, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d291d7813ba4a88 = b_9d291d7813ba4a88.words; +#if !CAPNP_LITE +static const uint16_t m_9d291d7813ba4a88[] = {1, 2, 0}; +static const uint16_t i_9d291d7813ba4a88[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_9d291d7813ba4a88 = { + 0x9d291d7813ba4a88, b_9d291d7813ba4a88.words, 64, nullptr, m_9d291d7813ba4a88, + 0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 4, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 1, 0, 0, 0, 82, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 86, 101, + 99, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2b29a69d44529a1 = b_a2b29a69d44529a1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = { + &s_a43429bd2bfc24fc, +}; +static const uint16_t m_a2b29a69d44529a1[] = {4, 7, 5, 6, 1, 3, 2, 0}; +static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 0, 1, 2, 3}; +const ::capnp::_::RawSchema s_a2b29a69d44529a1 = { + 0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 146, d_a2b29a69d44529a1, m_a2b29a69d44529a1, + 1, 8, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a43429bd2bfc24fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 26, 0, 0, 0, 1, 0, 1, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 46, 83, 101, 110, 115, 111, 114, + 86, 101, 99, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 118, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a43429bd2bfc24fc = b_a43429bd2bfc24fc.words; +#if !CAPNP_LITE +static const uint16_t m_a43429bd2bfc24fc[] = {1, 0}; +static const uint16_t i_a43429bd2bfc24fc[] = {0, 1}; +const ::capnp::_::RawSchema s_a43429bd2bfc24fc = { + 0xa43429bd2bfc24fc, b_a43429bd2bfc24fc.words, 53, nullptr, m_a43429bd2bfc24fc, + 0, 2, i_a43429bd2bfc24fc, nullptr, nullptr, { &s_a43429bd2bfc24fc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<77> b_8785009a964c7c59 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 110, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 97, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 115, 84, 105, 109, 101, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 114, 99, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8785009a964c7c59 = b_8785009a964c7c59.words; +#if !CAPNP_LITE +static const uint16_t m_8785009a964c7c59[] = {0, 1, 2, 3}; +static const uint16_t i_8785009a964c7c59[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8785009a964c7c59 = { + 0x8785009a964c7c59, b_8785009a964c7c59.words, 77, nullptr, m_8785009a964c7c59, + 0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<122> b_8d8231a40b7fe6e0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 224, 230, 127, 11, 164, 49, 130, 141, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 84, 104, 101, 114, 109, 97, + 108, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 99, 112, 117, 48, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 49, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 50, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 51, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words; +#if !CAPNP_LITE +static const uint16_t m_8d8231a40b7fe6e0[] = {6, 0, 1, 2, 3, 5, 4}; +static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { + 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 122, nullptr, m_8d8231a40b7fe6e0, + 0, 7, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 228, 241, 42, 200, 194, 176, 162, 207, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 72, 101, 97, 108, 116, 104, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 118, 111, 108, 116, 97, 103, 101, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 65, 108, 108, 111, 119, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 73, 110, 116, 101, 114, + 99, 101, 112, 116, 111, 114, 68, 101, + 116, 101, 99, 116, 101, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cfa2b0c2c82af1e4 = b_cfa2b0c2c82af1e4.words; +#if !CAPNP_LITE +static const uint16_t m_cfa2b0c2c82af1e4[] = {3, 1, 4, 2, 0}; +static const uint16_t i_cfa2b0c2c82af1e4[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_cfa2b0c2c82af1e4 = { + 0xcfa2b0c2c82af1e4, b_cfa2b0c2c82af1e4.words, 95, nullptr, m_cfa2b0c2c82af1e4, + 0, 5, i_cfa2b0c2c82af1e4, nullptr, nullptr, { &s_cfa2b0c2c82af1e4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<81> b_c08240f996aefced = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 85, 73, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c08240f996aefced = b_c08240f996aefced.words; +#if !CAPNP_LITE +static const uint16_t m_c08240f996aefced[] = {1, 2, 3, 0}; +static const uint16_t i_c08240f996aefced[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c08240f996aefced = { + 0xc08240f996aefced, b_c08240f996aefced.words, 81, nullptr, m_c08240f996aefced, + 0, 4, i_c08240f996aefced, nullptr, nullptr, { &s_c08240f996aefced, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 50, 48, + 68, 97, 116, 97, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 1, 0, 0, 0, 74, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 79, 110, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 84, 119, 111, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 116, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9a185389d6fdd05f = b_9a185389d6fdd05f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9a185389d6fdd05f[] = { + &s_b96f3ad9170cf085, +}; +static const uint16_t m_9a185389d6fdd05f[] = {1, 8, 9, 2, 10, 5, 7, 3, 4, 6, 0}; +static const uint16_t i_9a185389d6fdd05f[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_9a185389d6fdd05f = { + 0x9a185389d6fdd05f, b_9a185389d6fdd05f.words, 202, d_9a185389d6fdd05f, m_9a185389d6fdd05f, + 1, 11, i_9a185389d6fdd05f, nullptr, nullptr, { &s_9a185389d6fdd05f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<198> b_b96f3ad9170cf085 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 21, 0, 0, 0, 1, 0, 6, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 167, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 50, 48, + 68, 97, 116, 97, 46, 76, 101, 97, + 100, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 64, 1, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 65, 1, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 97, 116, 104, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 97, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b96f3ad9170cf085 = b_b96f3ad9170cf085.words; +#if !CAPNP_LITE +static const uint16_t m_b96f3ad9170cf085[] = {5, 9, 3, 6, 0, 10, 11, 7, 4, 8, 2, 1}; +static const uint16_t i_b96f3ad9170cf085[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; +const ::capnp::_::RawSchema s_b96f3ad9170cf085 = { + 0xb96f3ad9170cf085, b_b96f3ad9170cf085.words, 198, nullptr, m_b96f3ad9170cf085, + 0, 12, i_b96f3ad9170cf085, nullptr, nullptr, { &s_b96f3ad9170cf085, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<85> b_96df70754d8390bc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 67, 97, + 108, 105, 98, 114, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_96df70754d8390bc = b_96df70754d8390bc.words; +#if !CAPNP_LITE +static const uint16_t m_96df70754d8390bc[] = {2, 3, 1, 0}; +static const uint16_t i_96df70754d8390bc[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_96df70754d8390bc = { + 0x96df70754d8390bc, b_96df70754d8390bc.words, 85, nullptr, m_96df70754d8390bc, + 0, 4, i_96df70754d8390bc, nullptr, nullptr, { &s_96df70754d8390bc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<171> b_8faa644732dec251 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 84, 114, + 97, 99, 107, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 0, 1, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 1, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 99, 107, 73, 100, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 83, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 105, 111, 110, 97, + 114, 121, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 110, 99, 111, 109, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8faa644732dec251 = b_8faa644732dec251.words; +#if !CAPNP_LITE +static const uint16_t m_8faa644732dec251[] = {4, 7, 1, 9, 8, 6, 5, 0, 3, 2}; +static const uint16_t i_8faa644732dec251[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_8faa644732dec251 = { + 0x8faa644732dec251, b_8faa644732dec251.words, 171, nullptr, m_8faa644732dec251, + 0, 10, i_8faa644732dec251, nullptr, nullptr, { &s_8faa644732dec251, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 10, 0, 0, 0, 1, 0, 13, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 239, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 49, 48, + 48, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 108, 0, 0, 0, 3, 0, 4, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 3, 0, 0, 3, 0, 1, 0, + 80, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 192, 2, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 193, 2, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 132, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 194, 2, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 3, 0, 0, 3, 0, 1, 0, + 168, 3, 0, 0, 2, 0, 1, 0, + 118, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 80, 105, 100, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 84, 97, 114, 103, 101, 116, 76, + 101, 97, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 65, 99, 116, 117, 97, 108, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 68, 101, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 83, 116, 101, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 83, 116, 101, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 105, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 97, 120, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 101, 114, 107, 70, 97, 99, 116, + 111, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 83, 116, 101, + 101, 114, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 117, 100, 76, 101, 97, 100, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 50, 48, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_97ff69c53601abf1 = b_97ff69c53601abf1.words; +#if !CAPNP_LITE +static const uint16_t m_97ff69c53601abf1[] = {1, 11, 10, 24, 25, 13, 26, 16, 21, 15, 19, 14, 12, 17, 18, 23, 20, 5, 9, 4, 8, 22, 0, 2, 3, 6, 7}; +static const uint16_t i_97ff69c53601abf1[] = {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}; +const ::capnp::_::RawSchema s_97ff69c53601abf1 = { + 0x97ff69c53601abf1, b_97ff69c53601abf1.words, 443, nullptr, m_97ff69c53601abf1, + 0, 27, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<47> b_94b7baa90c5c321e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 69, 118, + 101, 110, 116, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_94b7baa90c5c321e = b_94b7baa90c5c321e.words; +#if !CAPNP_LITE +static const uint16_t m_94b7baa90c5c321e[] = {0, 1}; +static const uint16_t i_94b7baa90c5c321e[] = {0, 1}; +const ::capnp::_::RawSchema s_94b7baa90c5c321e = { + 0x94b7baa90c5c321e, b_94b7baa90c5c321e.words, 47, nullptr, m_94b7baa90c5c321e, + 0, 2, i_94b7baa90c5c321e, nullptr, nullptr, { &s_94b7baa90c5c321e, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<122> b_b8aad62cffef28a9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 17, 0, 0, 0, 74, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 17, 0, 0, 0, 74, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 17, 0, 0, 0, 114, 0, 0, 0, + 80, 97, 116, 104, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 111, 100, 101, 108, 83, 101, 116, + 116, 105, 110, 103, 115, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 76, 97, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 76, 97, 110, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 116, 116, 105, 110, 103, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b8aad62cffef28a9 = b_b8aad62cffef28a9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b8aad62cffef28a9[] = { + &s_8817eeea389e9f08, + &s_a26e3710efd3e914, + &s_d1c9bef96d26fa91, +}; +static const uint16_t m_b8aad62cffef28a9[] = {0, 4, 2, 1, 3, 5}; +static const uint16_t i_b8aad62cffef28a9[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_b8aad62cffef28a9 = { + 0xb8aad62cffef28a9, b_b8aad62cffef28a9.words, 122, d_b8aad62cffef28a9, m_b8aad62cffef28a9, + 3, 6, i_b8aad62cffef28a9, nullptr, nullptr, { &s_b8aad62cffef28a9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_8817eeea389e9f08 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 20, 0, 0, 0, 1, 0, 1, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 80, 97, 116, 104, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8817eeea389e9f08 = b_8817eeea389e9f08.words; +#if !CAPNP_LITE +static const uint16_t m_8817eeea389e9f08[] = {0, 1, 2}; +static const uint16_t i_8817eeea389e9f08[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_8817eeea389e9f08 = { + 0x8817eeea389e9f08, b_8817eeea389e9f08.words, 67, nullptr, m_8817eeea389e9f08, + 0, 3, i_8817eeea389e9f08, nullptr, nullptr, { &s_8817eeea389e9f08, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_d1c9bef96d26fa91 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 20, 0, 0, 0, 1, 0, 2, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 76, 101, 97, 100, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 100, 105, 115, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d1c9bef96d26fa91 = b_d1c9bef96d26fa91.words; +#if !CAPNP_LITE +static const uint16_t m_d1c9bef96d26fa91[] = {0, 1, 2}; +static const uint16_t i_d1c9bef96d26fa91[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d1c9bef96d26fa91 = { + 0xd1c9bef96d26fa91, b_d1c9bef96d26fa91.words, 63, nullptr, m_d1c9bef96d26fa91, + 0, 3, i_d1c9bef96d26fa91, nullptr, nullptr, { &s_d1c9bef96d26fa91, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<121> b_a26e3710efd3e914 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 20, 0, 0, 0, 1, 0, 1, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 77, 111, 100, 101, + 108, 83, 101, 116, 116, 105, 110, 103, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 98, 105, 103, 66, 111, 120, 88, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 89, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 87, 105, + 100, 116, 104, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 101, + 105, 103, 104, 116, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 111, 120, 80, 114, 111, 106, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 117, 118, 67, 111, 114, 114, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a26e3710efd3e914 = b_a26e3710efd3e914.words; +#if !CAPNP_LITE +static const uint16_t m_a26e3710efd3e914[] = {3, 2, 0, 1, 4, 5}; +static const uint16_t i_a26e3710efd3e914[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_a26e3710efd3e914 = { + 0xa26e3710efd3e914, b_a26e3710efd3e914.words, 121, nullptr, m_a26e3710efd3e914, + 0, 6, i_a26e3710efd3e914, nullptr, nullptr, { &s_a26e3710efd3e914, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<90> b_8fdfadb254ea867a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 108, 105, 98, 114, + 97, 116, 105, 111, 110, 70, 101, 97, + 116, 117, 114, 101, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 48, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 49, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8fdfadb254ea867a = b_8fdfadb254ea867a.words; +#if !CAPNP_LITE +static const uint16_t m_8fdfadb254ea867a[] = {0, 1, 2, 3}; +static const uint16_t i_8fdfadb254ea867a[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8fdfadb254ea867a = { + 0x8fdfadb254ea867a, b_8fdfadb254ea867a.words, 90, nullptr, m_8fdfadb254ea867a, + 0, 4, i_8fdfadb254ea867a, nullptr, nullptr, { &s_8fdfadb254ea867a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<98> b_89d394e3541735fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 1, 0, 0, 0, 42, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 73, + 100, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_89d394e3541735fc = b_89d394e3541735fc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_89d394e3541735fc[] = { + &s_c0ad259ec157ccd3, +}; +static const uint16_t m_89d394e3541735fc[] = {2, 0, 4, 3, 1}; +static const uint16_t i_89d394e3541735fc[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_89d394e3541735fc = { + 0x89d394e3541735fc, b_89d394e3541735fc.words, 98, d_89d394e3541735fc, m_89d394e3541735fc, + 1, 5, i_89d394e3541735fc, nullptr, nullptr, { &s_89d394e3541735fc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_c0ad259ec157ccd3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 22, 0, 0, 0, 2, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 46, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 76, 111, + 115, 115, 108, 101, 115, 115, 0, 0, + 102, 117, 108, 108, 72, 69, 86, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 69, + 86, 67, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0ad259ec157ccd3 = b_c0ad259ec157ccd3.words; +#if !CAPNP_LITE +static const uint16_t m_c0ad259ec157ccd3[] = {2, 0, 1}; +const ::capnp::_::RawSchema s_c0ad259ec157ccd3 = { + 0xc0ad259ec157ccd3, b_c0ad259ec157ccd3.words, 33, nullptr, m_c0ad259ec157ccd3, + 0, 3, nullptr, nullptr, nullptr, { &s_c0ad259ec157ccd3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_c0ad259ec157ccd3, c0ad259ec157ccd3); +static const ::capnp::_::AlignedData<124> b_ea095da1894f7d85 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 65, 110, 100, 114, 111, 105, + 100, 76, 111, 103, 69, 110, 116, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 115, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 105, 111, 114, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 103, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 115, 97, 103, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea095da1894f7d85 = b_ea095da1894f7d85.words; +#if !CAPNP_LITE +static const uint16_t m_ea095da1894f7d85[] = {0, 6, 3, 2, 5, 4, 1}; +static const uint16_t i_ea095da1894f7d85[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ea095da1894f7d85 = { + 0xea095da1894f7d85, b_ea095da1894f7d85.words, 124, nullptr, m_ea095da1894f7d85, + 0, 7, i_ea095da1894f7d85, nullptr, nullptr, { &s_ea095da1894f7d85, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_9811e1f38f62f2d1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 209, 242, 98, 143, 243, 225, 17, 152, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 103, 82, 111, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9811e1f38f62f2d1 = b_9811e1f38f62f2d1.words; +#if !CAPNP_LITE +static const uint16_t m_9811e1f38f62f2d1[] = {1, 0}; +static const uint16_t i_9811e1f38f62f2d1[] = {0, 1}; +const ::capnp::_::RawSchema s_9811e1f38f62f2d1 = { + 0x9811e1f38f62f2d1, b_9811e1f38f62f2d1.words, 48, nullptr, m_9811e1f38f62f2d1, + 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<366> b_d314cfd957229c11 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 17, 156, 34, 87, 217, 207, 20, 211, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 20, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 0, 0, 0, + 25, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 159, 4, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 118, 101, 110, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 84, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 72, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 2, 0, 0, 3, 0, 1, 0, + 80, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 2, 0, 0, 3, 0, 1, 0, + 84, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 2, 0, 0, 3, 0, 1, 0, + 100, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 2, 0, 0, 3, 0, 1, 0, + 120, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 250, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 249, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 248, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 247, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 2, 0, 0, 3, 0, 1, 0, + 160, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 246, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 2, 0, 0, 3, 0, 1, 0, + 168, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 245, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 2, 0, 0, 3, 0, 1, 0, + 192, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 244, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 243, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 2, 0, 0, 3, 0, 1, 0, + 200, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 242, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 241, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 240, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 239, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 238, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 237, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 236, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 3, 0, 0, 3, 0, 1, 0, + 32, 3, 0, 0, 2, 0, 1, 0, + 108, 111, 103, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 105, 116, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 78, 77, 69, 65, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 114, 109, 97, 108, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 224, 230, 127, 11, 164, 49, 130, 141, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 49, 48, 48, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 69, 118, 101, 110, + 116, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 97, 116, 117, 114, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 108, 116, 104, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 228, 241, 42, 200, 194, 176, 162, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 50, 48, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 85, 73, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 120, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 84, 114, 97, 99, + 107, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 100, 99, 97, 110, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 77, 101, 115, 115, 97, + 103, 101, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 67, 97, 108, 105, + 98, 114, 97, 116, 105, 111, 110, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 76, + 111, 103, 69, 110, 116, 114, 121, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d314cfd957229c11 = b_d314cfd957229c11.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { + &s_8785009a964c7c59, + &s_89d394e3541735fc, + &s_8d8231a40b7fe6e0, + &s_8faa644732dec251, + &s_8fdfadb254ea867a, + &s_94b7baa90c5c321e, + &s_96df70754d8390bc, + &s_97ff69c53601abf1, + &s_9a185389d6fdd05f, + &s_9d291d7813ba4a88, + &s_a2b29a69d44529a1, + &s_b8aad62cffef28a9, + &s_c08240f996aefced, + &s_cfa2b0c2c82af1e4, + &s_e71008caeb3fb65c, + &s_ea0245f695ae0a33, + &s_ea095da1894f7d85, +}; +static const uint16_t m_d314cfd957229c11[] = {20, 5, 15, 10, 2, 3, 12, 1, 7, 13, 19, 8, 16, 14, 18, 0, 9, 17, 4, 11, 6}; +static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 0}; +const ::capnp::_::RawSchema s_d314cfd957229c11 = { + 0xd314cfd957229c11, b_d314cfd957229c11.words, 366, d_d314cfd957229c11, m_d314cfd957229c11, + 17, 21, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// InitData +#ifndef _MSC_VER +constexpr uint16_t InitData::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind InitData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* InitData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// FrameData +#ifndef _MSC_VER +constexpr uint16_t FrameData::_capnpPrivate::dataWordSize; +constexpr uint16_t FrameData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind FrameData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrameData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* FrameData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// GPSNMEAData +#ifndef _MSC_VER +constexpr uint16_t GPSNMEAData::_capnpPrivate::dataWordSize; +constexpr uint16_t GPSNMEAData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind GPSNMEAData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GPSNMEAData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* GPSNMEAData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// SensorEventData +#ifndef _MSC_VER +constexpr uint16_t SensorEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind SensorEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// SensorEventData::SensorVec +#ifndef _MSC_VER +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind SensorEventData::SensorVec::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::SensorVec::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::SensorVec::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// CanData +#ifndef _MSC_VER +constexpr uint16_t CanData::_capnpPrivate::dataWordSize; +constexpr uint16_t CanData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind CanData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CanData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* CanData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ThermalData +#ifndef _MSC_VER +constexpr uint16_t ThermalData::_capnpPrivate::dataWordSize; +constexpr uint16_t ThermalData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ThermalData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ThermalData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ThermalData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// HealthData +#ifndef _MSC_VER +constexpr uint16_t HealthData::_capnpPrivate::dataWordSize; +constexpr uint16_t HealthData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind HealthData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* HealthData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* HealthData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveUI +#ifndef _MSC_VER +constexpr uint16_t LiveUI::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveUI::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveUI::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveUI::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveUI::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live20Data +#ifndef _MSC_VER +constexpr uint16_t Live20Data::_capnpPrivate::dataWordSize; +constexpr uint16_t Live20Data::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live20Data::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live20Data::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live20Data::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live20Data::LeadData +#ifndef _MSC_VER +constexpr uint16_t Live20Data::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t Live20Data::LeadData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live20Data::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live20Data::LeadData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live20Data::LeadData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveCalibrationData +#ifndef _MSC_VER +constexpr uint16_t LiveCalibrationData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveCalibrationData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveCalibrationData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveCalibrationData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveCalibrationData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveTracks +#ifndef _MSC_VER +constexpr uint16_t LiveTracks::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveTracks::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveTracks::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveTracks::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveTracks::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live100Data +#ifndef _MSC_VER +constexpr uint16_t Live100Data::_capnpPrivate::dataWordSize; +constexpr uint16_t Live100Data::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live100Data::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live100Data::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live100Data::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveEventData +#ifndef _MSC_VER +constexpr uint16_t LiveEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveEventData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveEventData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveEventData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData +#ifndef _MSC_VER +constexpr uint16_t ModelData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::PathData +#ifndef _MSC_VER +constexpr uint16_t ModelData::PathData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::PathData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::PathData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::PathData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::PathData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::LeadData +#ifndef _MSC_VER +constexpr uint16_t ModelData::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::LeadData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::LeadData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::LeadData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::ModelSettings +#ifndef _MSC_VER +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::ModelSettings::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::ModelSettings::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::ModelSettings::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// CalibrationFeatures +#ifndef _MSC_VER +constexpr uint16_t CalibrationFeatures::_capnpPrivate::dataWordSize; +constexpr uint16_t CalibrationFeatures::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind CalibrationFeatures::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CalibrationFeatures::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* CalibrationFeatures::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// EncodeIndex +#ifndef _MSC_VER +constexpr uint16_t EncodeIndex::_capnpPrivate::dataWordSize; +constexpr uint16_t EncodeIndex::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind EncodeIndex::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* EncodeIndex::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* EncodeIndex::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// AndroidLogEntry +#ifndef _MSC_VER +constexpr uint16_t AndroidLogEntry::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidLogEntry::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind AndroidLogEntry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidLogEntry::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* AndroidLogEntry::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LogRotate +#ifndef _MSC_VER +constexpr uint16_t LogRotate::_capnpPrivate::dataWordSize; +constexpr uint16_t LogRotate::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LogRotate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LogRotate::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LogRotate::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Event +#ifndef _MSC_VER +constexpr uint16_t Event::_capnpPrivate::dataWordSize; +constexpr uint16_t Event::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Event::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Event::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Event::_capnpPrivate::brand; +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/gen/cpp/log.capnp.h b/cereal/gen/cpp/log.capnp.h new file mode 100644 index 0000000000..d5a4456386 --- /dev/null +++ b/cereal/gen/cpp/log.capnp.h @@ -0,0 +1,7251 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: log.capnp + +#ifndef CAPNP_INCLUDED_f3b1f17e25a4285b_ +#define CAPNP_INCLUDED_f3b1f17e25a4285b_ + +#include + +#if CAPNP_VERSION != 5003 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(d578fb3372ed5043); +CAPNP_DECLARE_SCHEMA(e71008caeb3fb65c); +CAPNP_DECLARE_SCHEMA(ea0245f695ae0a33); +CAPNP_DECLARE_SCHEMA(9d291d7813ba4a88); +CAPNP_DECLARE_SCHEMA(a2b29a69d44529a1); +CAPNP_DECLARE_SCHEMA(a43429bd2bfc24fc); +CAPNP_DECLARE_SCHEMA(8785009a964c7c59); +CAPNP_DECLARE_SCHEMA(8d8231a40b7fe6e0); +CAPNP_DECLARE_SCHEMA(cfa2b0c2c82af1e4); +CAPNP_DECLARE_SCHEMA(c08240f996aefced); +CAPNP_DECLARE_SCHEMA(9a185389d6fdd05f); +CAPNP_DECLARE_SCHEMA(b96f3ad9170cf085); +CAPNP_DECLARE_SCHEMA(96df70754d8390bc); +CAPNP_DECLARE_SCHEMA(8faa644732dec251); +CAPNP_DECLARE_SCHEMA(97ff69c53601abf1); +CAPNP_DECLARE_SCHEMA(94b7baa90c5c321e); +CAPNP_DECLARE_SCHEMA(b8aad62cffef28a9); +CAPNP_DECLARE_SCHEMA(8817eeea389e9f08); +CAPNP_DECLARE_SCHEMA(d1c9bef96d26fa91); +CAPNP_DECLARE_SCHEMA(a26e3710efd3e914); +CAPNP_DECLARE_SCHEMA(8fdfadb254ea867a); +CAPNP_DECLARE_SCHEMA(89d394e3541735fc); +CAPNP_DECLARE_SCHEMA(c0ad259ec157ccd3); +enum class Type_c0ad259ec157ccd3: uint16_t { + BIG_BOX_LOSSLESS, + FULL_H_E_V_C, + BIG_BOX_H_E_V_C, +}; +CAPNP_DECLARE_ENUM(Type, c0ad259ec157ccd3); +CAPNP_DECLARE_SCHEMA(ea095da1894f7d85); +CAPNP_DECLARE_SCHEMA(9811e1f38f62f2d1); +CAPNP_DECLARE_SCHEMA(d314cfd957229c11); + +} // namespace schemas +} // namespace capnp + +namespace cereal { + +static constexpr ::int32_t LOG_VERSION = 1; +struct InitData { + InitData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e71008caeb3fb65c, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct FrameData { + FrameData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ea0245f695ae0a33, 4, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct GPSNMEAData { + GPSNMEAData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9d291d7813ba4a88, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct SensorEventData { + SensorEventData() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + ACCELERATION, + MAGNETIC, + ORIENTATION, + GYRO, + }; + struct SensorVec; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a2b29a69d44529a1, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct SensorEventData::SensorVec { + SensorVec() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a43429bd2bfc24fc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct CanData { + CanData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8785009a964c7c59, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ThermalData { + ThermalData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct HealthData { + HealthData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cfa2b0c2c82af1e4, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveUI { + LiveUI() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c08240f996aefced, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live20Data { + Live20Data() = delete; + + class Reader; + class Builder; + class Pipeline; + struct LeadData; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9a185389d6fdd05f, 4, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live20Data::LeadData { + LeadData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b96f3ad9170cf085, 6, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveCalibrationData { + LiveCalibrationData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(96df70754d8390bc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveTracks { + LiveTracks() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8faa644732dec251, 5, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live100Data { + Live100Data() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(97ff69c53601abf1, 13, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveEventData { + LiveEventData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(94b7baa90c5c321e, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData { + ModelData() = delete; + + class Reader; + class Builder; + class Pipeline; + struct PathData; + struct LeadData; + struct ModelSettings; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b8aad62cffef28a9, 1, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::PathData { + PathData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8817eeea389e9f08, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::LeadData { + LeadData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d1c9bef96d26fa91, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::ModelSettings { + ModelSettings() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a26e3710efd3e914, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct CalibrationFeatures { + CalibrationFeatures() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8fdfadb254ea867a, 1, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct EncodeIndex { + EncodeIndex() = delete; + + class Reader; + class Builder; + class Pipeline; + typedef ::capnp::schemas::Type_c0ad259ec157ccd3 Type; + + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(89d394e3541735fc, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct AndroidLogEntry { + AndroidLogEntry() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ea095da1894f7d85, 3, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LogRotate { + LogRotate() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9811e1f38f62f2d1, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Event { + Event() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + INIT_DATA, + FRAME, + GPS_N_M_E_A, + SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + CAN, + THERMAL, + LIVE100, + LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + MODEL, + FEATURES, + SENSOR_EVENTS, + HEALTH, + LIVE20, + LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + ENCODE_IDX, + LIVE_TRACKS, + SENDCAN, + LOG_MESSAGE, + LIVE_CALIBRATION, + ANDROID_LOG_ENTRY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d314cfd957229c11, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class InitData::Reader { +public: + typedef InitData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasKernelArgs() const; + inline ::capnp::List< ::capnp::Text>::Reader getKernelArgs() const; + + inline bool hasGctx() const; + inline ::capnp::Text::Reader getGctx() const; + + inline bool hasDongleId() const; + inline ::capnp::Text::Reader getDongleId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InitData::Builder { +public: + typedef InitData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasKernelArgs(); + inline ::capnp::List< ::capnp::Text>::Builder getKernelArgs(); + inline void setKernelArgs( ::capnp::List< ::capnp::Text>::Reader value); + inline void setKernelArgs(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text>::Builder initKernelArgs(unsigned int size); + inline void adoptKernelArgs(::capnp::Orphan< ::capnp::List< ::capnp::Text>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text>> disownKernelArgs(); + + inline bool hasGctx(); + inline ::capnp::Text::Builder getGctx(); + inline void setGctx( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initGctx(unsigned int size); + inline void adoptGctx(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownGctx(); + + inline bool hasDongleId(); + inline ::capnp::Text::Builder getDongleId(); + inline void setDongleId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDongleId(unsigned int size); + inline void adoptDongleId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDongleId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InitData::Pipeline { +public: + typedef InitData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class FrameData::Reader { +public: + typedef FrameData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline ::uint32_t getEncodeId() const; + + inline ::uint64_t getTimestampEof() const; + + inline ::int32_t getFrameLength() const; + + inline ::int32_t getIntegLines() const; + + inline ::int32_t getGlobalGain() const; + + inline bool hasImage() const; + inline ::capnp::Data::Reader getImage() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class FrameData::Builder { +public: + typedef FrameData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline ::uint32_t getEncodeId(); + inline void setEncodeId( ::uint32_t value); + + inline ::uint64_t getTimestampEof(); + inline void setTimestampEof( ::uint64_t value); + + inline ::int32_t getFrameLength(); + inline void setFrameLength( ::int32_t value); + + inline ::int32_t getIntegLines(); + inline void setIntegLines( ::int32_t value); + + inline ::int32_t getGlobalGain(); + inline void setGlobalGain( ::int32_t value); + + inline bool hasImage(); + inline ::capnp::Data::Builder getImage(); + inline void setImage( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initImage(unsigned int size); + inline void adoptImage(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownImage(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class FrameData::Pipeline { +public: + typedef FrameData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GPSNMEAData::Reader { +public: + typedef GPSNMEAData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int64_t getTimestamp() const; + + inline ::uint64_t getLocalWallTime() const; + + inline bool hasNmea() const; + inline ::capnp::Text::Reader getNmea() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GPSNMEAData::Builder { +public: + typedef GPSNMEAData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int64_t getTimestamp(); + inline void setTimestamp( ::int64_t value); + + inline ::uint64_t getLocalWallTime(); + inline void setLocalWallTime( ::uint64_t value); + + inline bool hasNmea(); + inline ::capnp::Text::Builder getNmea(); + inline void setNmea( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initNmea(unsigned int size); + inline void adoptNmea(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownNmea(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GPSNMEAData::Pipeline { +public: + typedef GPSNMEAData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class SensorEventData::Reader { +public: + typedef SensorEventData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::int32_t getVersion() const; + + inline ::int32_t getSensor() const; + + inline ::int32_t getType() const; + + inline ::int64_t getTimestamp() const; + + inline bool isAcceleration() const; + inline bool hasAcceleration() const; + inline ::cereal::SensorEventData::SensorVec::Reader getAcceleration() const; + + inline bool isMagnetic() const; + inline bool hasMagnetic() const; + inline ::cereal::SensorEventData::SensorVec::Reader getMagnetic() const; + + inline bool isOrientation() const; + inline bool hasOrientation() const; + inline ::cereal::SensorEventData::SensorVec::Reader getOrientation() const; + + inline bool isGyro() const; + inline bool hasGyro() const; + inline ::cereal::SensorEventData::SensorVec::Reader getGyro() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class SensorEventData::Builder { +public: + typedef SensorEventData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::int32_t getVersion(); + inline void setVersion( ::int32_t value); + + inline ::int32_t getSensor(); + inline void setSensor( ::int32_t value); + + inline ::int32_t getType(); + inline void setType( ::int32_t value); + + inline ::int64_t getTimestamp(); + inline void setTimestamp( ::int64_t value); + + inline bool isAcceleration(); + inline bool hasAcceleration(); + inline ::cereal::SensorEventData::SensorVec::Builder getAcceleration(); + inline void setAcceleration( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initAcceleration(); + inline void adoptAcceleration(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownAcceleration(); + + inline bool isMagnetic(); + inline bool hasMagnetic(); + inline ::cereal::SensorEventData::SensorVec::Builder getMagnetic(); + inline void setMagnetic( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initMagnetic(); + inline void adoptMagnetic(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownMagnetic(); + + inline bool isOrientation(); + inline bool hasOrientation(); + inline ::cereal::SensorEventData::SensorVec::Builder getOrientation(); + inline void setOrientation( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initOrientation(); + inline void adoptOrientation(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownOrientation(); + + inline bool isGyro(); + inline bool hasGyro(); + inline ::cereal::SensorEventData::SensorVec::Builder getGyro(); + inline void setGyro( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initGyro(); + inline void adoptGyro(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownGyro(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class SensorEventData::Pipeline { +public: + typedef SensorEventData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class SensorEventData::SensorVec::Reader { +public: + typedef SensorVec Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasV() const; + inline ::capnp::List::Reader getV() const; + + inline ::int8_t getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class SensorEventData::SensorVec::Builder { +public: + typedef SensorVec Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasV(); + inline ::capnp::List::Builder getV(); + inline void setV( ::capnp::List::Reader value); + inline void setV(::kj::ArrayPtr value); + inline ::capnp::List::Builder initV(unsigned int size); + inline void adoptV(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownV(); + + inline ::int8_t getStatus(); + inline void setStatus( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class SensorEventData::SensorVec::Pipeline { +public: + typedef SensorVec Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CanData::Reader { +public: + typedef CanData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getAddress() const; + + inline ::uint16_t getBusTime() const; + + inline bool hasDat() const; + inline ::capnp::Data::Reader getDat() const; + + inline ::int8_t getSrc() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CanData::Builder { +public: + typedef CanData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getAddress(); + inline void setAddress( ::uint32_t value); + + inline ::uint16_t getBusTime(); + inline void setBusTime( ::uint16_t value); + + inline bool hasDat(); + inline ::capnp::Data::Builder getDat(); + inline void setDat( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initDat(unsigned int size); + inline void adoptDat(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownDat(); + + inline ::int8_t getSrc(); + inline void setSrc( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CanData::Pipeline { +public: + typedef CanData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThermalData::Reader { +public: + typedef ThermalData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getCpu0() const; + + inline ::uint16_t getCpu1() const; + + inline ::uint16_t getCpu2() const; + + inline ::uint16_t getCpu3() const; + + inline ::uint16_t getMem() const; + + inline ::uint16_t getGpu() const; + + inline ::uint32_t getBat() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThermalData::Builder { +public: + typedef ThermalData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getCpu0(); + inline void setCpu0( ::uint16_t value); + + inline ::uint16_t getCpu1(); + inline void setCpu1( ::uint16_t value); + + inline ::uint16_t getCpu2(); + inline void setCpu2( ::uint16_t value); + + inline ::uint16_t getCpu3(); + inline void setCpu3( ::uint16_t value); + + inline ::uint16_t getMem(); + inline void setMem( ::uint16_t value); + + inline ::uint16_t getGpu(); + inline void setGpu( ::uint16_t value); + + inline ::uint32_t getBat(); + inline void setBat( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThermalData::Pipeline { +public: + typedef ThermalData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class HealthData::Reader { +public: + typedef HealthData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getVoltage() const; + + inline ::uint32_t getCurrent() const; + + inline bool getStarted() const; + + inline bool getControlsAllowed() const; + + inline bool getGasInterceptorDetected() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class HealthData::Builder { +public: + typedef HealthData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getVoltage(); + inline void setVoltage( ::uint32_t value); + + inline ::uint32_t getCurrent(); + inline void setCurrent( ::uint32_t value); + + inline bool getStarted(); + inline void setStarted(bool value); + + inline bool getControlsAllowed(); + inline void setControlsAllowed(bool value); + + inline bool getGasInterceptorDetected(); + inline void setGasInterceptorDetected(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class HealthData::Pipeline { +public: + typedef HealthData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveUI::Reader { +public: + typedef LiveUI Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool getRearViewCam() const; + + inline bool hasAlertText1() const; + inline ::capnp::Text::Reader getAlertText1() const; + + inline bool hasAlertText2() const; + inline ::capnp::Text::Reader getAlertText2() const; + + inline float getAwarenessStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveUI::Builder { +public: + typedef LiveUI Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool getRearViewCam(); + inline void setRearViewCam(bool value); + + inline bool hasAlertText1(); + inline ::capnp::Text::Builder getAlertText1(); + inline void setAlertText1( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText1(unsigned int size); + inline void adoptAlertText1(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText1(); + + inline bool hasAlertText2(); + inline ::capnp::Text::Builder getAlertText2(); + inline void setAlertText2( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText2(unsigned int size); + inline void adoptAlertText2(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText2(); + + inline float getAwarenessStatus(); + inline void setAwarenessStatus(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveUI::Pipeline { +public: + typedef LiveUI Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live20Data::Reader { +public: + typedef Live20Data Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix() const; + inline ::capnp::List::Reader getWarpMatrix() const; + + inline float getAngleOffset() const; + + inline ::int8_t getCalStatus() const; + + inline bool hasLeadOne() const; + inline ::cereal::Live20Data::LeadData::Reader getLeadOne() const; + + inline bool hasLeadTwo() const; + inline ::cereal::Live20Data::LeadData::Reader getLeadTwo() const; + + inline float getCumLagMs() const; + + inline ::uint64_t getMdMonoTime() const; + + inline ::uint64_t getFtMonoTime() const; + + inline ::int32_t getCalCycle() const; + + inline ::int8_t getCalPerc() const; + + inline bool hasCanMonoTimes() const; + inline ::capnp::List< ::uint64_t>::Reader getCanMonoTimes() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live20Data::Builder { +public: + typedef Live20Data Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix(); + inline ::capnp::List::Builder getWarpMatrix(); + inline void setWarpMatrix( ::capnp::List::Reader value); + inline void setWarpMatrix(::kj::ArrayPtr value); + inline ::capnp::List::Builder initWarpMatrix(unsigned int size); + inline void adoptWarpMatrix(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownWarpMatrix(); + + inline float getAngleOffset(); + inline void setAngleOffset(float value); + + inline ::int8_t getCalStatus(); + inline void setCalStatus( ::int8_t value); + + inline bool hasLeadOne(); + inline ::cereal::Live20Data::LeadData::Builder getLeadOne(); + inline void setLeadOne( ::cereal::Live20Data::LeadData::Reader value); + inline ::cereal::Live20Data::LeadData::Builder initLeadOne(); + inline void adoptLeadOne(::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> disownLeadOne(); + + inline bool hasLeadTwo(); + inline ::cereal::Live20Data::LeadData::Builder getLeadTwo(); + inline void setLeadTwo( ::cereal::Live20Data::LeadData::Reader value); + inline ::cereal::Live20Data::LeadData::Builder initLeadTwo(); + inline void adoptLeadTwo(::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> disownLeadTwo(); + + inline float getCumLagMs(); + inline void setCumLagMs(float value); + + inline ::uint64_t getMdMonoTime(); + inline void setMdMonoTime( ::uint64_t value); + + inline ::uint64_t getFtMonoTime(); + inline void setFtMonoTime( ::uint64_t value); + + inline ::int32_t getCalCycle(); + inline void setCalCycle( ::int32_t value); + + inline ::int8_t getCalPerc(); + inline void setCalPerc( ::int8_t value); + + inline bool hasCanMonoTimes(); + inline ::capnp::List< ::uint64_t>::Builder getCanMonoTimes(); + inline void setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value); + inline void setCanMonoTimes(::kj::ArrayPtr value); + inline ::capnp::List< ::uint64_t>::Builder initCanMonoTimes(unsigned int size); + inline void adoptCanMonoTimes(::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> disownCanMonoTimes(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live20Data::Pipeline { +public: + typedef Live20Data Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::cereal::Live20Data::LeadData::Pipeline getLeadOne(); + inline ::cereal::Live20Data::LeadData::Pipeline getLeadTwo(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live20Data::LeadData::Reader { +public: + typedef LeadData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getDRel() const; + + inline float getYRel() const; + + inline float getVRel() const; + + inline float getARel() const; + + inline float getVLead() const; + + inline float getALead() const; + + inline float getDPath() const; + + inline float getVLat() const; + + inline float getVLeadK() const; + + inline float getALeadK() const; + + inline bool getFcw() const; + + inline bool getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live20Data::LeadData::Builder { +public: + typedef LeadData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getDRel(); + inline void setDRel(float value); + + inline float getYRel(); + inline void setYRel(float value); + + inline float getVRel(); + inline void setVRel(float value); + + inline float getARel(); + inline void setARel(float value); + + inline float getVLead(); + inline void setVLead(float value); + + inline float getALead(); + inline void setALead(float value); + + inline float getDPath(); + inline void setDPath(float value); + + inline float getVLat(); + inline void setVLat(float value); + + inline float getVLeadK(); + inline void setVLeadK(float value); + + inline float getALeadK(); + inline void setALeadK(float value); + + inline bool getFcw(); + inline void setFcw(bool value); + + inline bool getStatus(); + inline void setStatus(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live20Data::LeadData::Pipeline { +public: + typedef LeadData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveCalibrationData::Reader { +public: + typedef LiveCalibrationData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix() const; + inline ::capnp::List::Reader getWarpMatrix() const; + + inline ::int8_t getCalStatus() const; + + inline ::int32_t getCalCycle() const; + + inline ::int8_t getCalPerc() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveCalibrationData::Builder { +public: + typedef LiveCalibrationData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix(); + inline ::capnp::List::Builder getWarpMatrix(); + inline void setWarpMatrix( ::capnp::List::Reader value); + inline void setWarpMatrix(::kj::ArrayPtr value); + inline ::capnp::List::Builder initWarpMatrix(unsigned int size); + inline void adoptWarpMatrix(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownWarpMatrix(); + + inline ::int8_t getCalStatus(); + inline void setCalStatus( ::int8_t value); + + inline ::int32_t getCalCycle(); + inline void setCalCycle( ::int32_t value); + + inline ::int8_t getCalPerc(); + inline void setCalPerc( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveCalibrationData::Pipeline { +public: + typedef LiveCalibrationData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveTracks::Reader { +public: + typedef LiveTracks Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int32_t getTrackId() const; + + inline float getDRel() const; + + inline float getYRel() const; + + inline float getVRel() const; + + inline float getARel() const; + + inline float getTimeStamp() const; + + inline float getStatus() const; + + inline float getCurrentTime() const; + + inline bool getStationary() const; + + inline bool getOncoming() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveTracks::Builder { +public: + typedef LiveTracks Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int32_t getTrackId(); + inline void setTrackId( ::int32_t value); + + inline float getDRel(); + inline void setDRel(float value); + + inline float getYRel(); + inline void setYRel(float value); + + inline float getVRel(); + inline void setVRel(float value); + + inline float getARel(); + inline void setARel(float value); + + inline float getTimeStamp(); + inline void setTimeStamp(float value); + + inline float getStatus(); + inline void setStatus(float value); + + inline float getCurrentTime(); + inline void setCurrentTime(float value); + + inline bool getStationary(); + inline void setStationary(bool value); + + inline bool getOncoming(); + inline void setOncoming(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveTracks::Pipeline { +public: + typedef LiveTracks Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live100Data::Reader { +public: + typedef Live100Data Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getVEgo() const; + + inline float getAEgo() const; + + inline float getVPid() const; + + inline float getVTargetLead() const; + + inline float getUpAccelCmd() const; + + inline float getUiAccelCmd() const; + + inline float getYActual() const; + + inline float getYDes() const; + + inline float getUpSteer() const; + + inline float getUiSteer() const; + + inline float getATargetMin() const; + + inline float getATargetMax() const; + + inline float getJerkFactor() const; + + inline float getAngleSteers() const; + + inline ::int32_t getHudLead() const; + + inline float getCumLagMs() const; + + inline ::uint64_t getCanMonoTime() const; + + inline ::uint64_t getL20MonoTime() const; + + inline ::uint64_t getMdMonoTime() const; + + inline bool getEnabled() const; + + inline bool getSteerOverride() const; + + inline bool hasCanMonoTimes() const; + inline ::capnp::List< ::uint64_t>::Reader getCanMonoTimes() const; + + inline float getVCruise() const; + + inline bool getRearViewCam() const; + + inline bool hasAlertText1() const; + inline ::capnp::Text::Reader getAlertText1() const; + + inline bool hasAlertText2() const; + inline ::capnp::Text::Reader getAlertText2() const; + + inline float getAwarenessStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live100Data::Builder { +public: + typedef Live100Data Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getVEgo(); + inline void setVEgo(float value); + + inline float getAEgo(); + inline void setAEgo(float value); + + inline float getVPid(); + inline void setVPid(float value); + + inline float getVTargetLead(); + inline void setVTargetLead(float value); + + inline float getUpAccelCmd(); + inline void setUpAccelCmd(float value); + + inline float getUiAccelCmd(); + inline void setUiAccelCmd(float value); + + inline float getYActual(); + inline void setYActual(float value); + + inline float getYDes(); + inline void setYDes(float value); + + inline float getUpSteer(); + inline void setUpSteer(float value); + + inline float getUiSteer(); + inline void setUiSteer(float value); + + inline float getATargetMin(); + inline void setATargetMin(float value); + + inline float getATargetMax(); + inline void setATargetMax(float value); + + inline float getJerkFactor(); + inline void setJerkFactor(float value); + + inline float getAngleSteers(); + inline void setAngleSteers(float value); + + inline ::int32_t getHudLead(); + inline void setHudLead( ::int32_t value); + + inline float getCumLagMs(); + inline void setCumLagMs(float value); + + inline ::uint64_t getCanMonoTime(); + inline void setCanMonoTime( ::uint64_t value); + + inline ::uint64_t getL20MonoTime(); + inline void setL20MonoTime( ::uint64_t value); + + inline ::uint64_t getMdMonoTime(); + inline void setMdMonoTime( ::uint64_t value); + + inline bool getEnabled(); + inline void setEnabled(bool value); + + inline bool getSteerOverride(); + inline void setSteerOverride(bool value); + + inline bool hasCanMonoTimes(); + inline ::capnp::List< ::uint64_t>::Builder getCanMonoTimes(); + inline void setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value); + inline void setCanMonoTimes(::kj::ArrayPtr value); + inline ::capnp::List< ::uint64_t>::Builder initCanMonoTimes(unsigned int size); + inline void adoptCanMonoTimes(::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> disownCanMonoTimes(); + + inline float getVCruise(); + inline void setVCruise(float value); + + inline bool getRearViewCam(); + inline void setRearViewCam(bool value); + + inline bool hasAlertText1(); + inline ::capnp::Text::Builder getAlertText1(); + inline void setAlertText1( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText1(unsigned int size); + inline void adoptAlertText1(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText1(); + + inline bool hasAlertText2(); + inline ::capnp::Text::Builder getAlertText2(); + inline void setAlertText2( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText2(unsigned int size); + inline void adoptAlertText2(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText2(); + + inline float getAwarenessStatus(); + inline void setAwarenessStatus(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live100Data::Pipeline { +public: + typedef Live100Data Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveEventData::Reader { +public: + typedef LiveEventData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::int32_t getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveEventData::Builder { +public: + typedef LiveEventData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::int32_t getValue(); + inline void setValue( ::int32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveEventData::Pipeline { +public: + typedef LiveEventData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::Reader { +public: + typedef ModelData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline bool hasPath() const; + inline ::cereal::ModelData::PathData::Reader getPath() const; + + inline bool hasLeftLane() const; + inline ::cereal::ModelData::PathData::Reader getLeftLane() const; + + inline bool hasRightLane() const; + inline ::cereal::ModelData::PathData::Reader getRightLane() const; + + inline bool hasLead() const; + inline ::cereal::ModelData::LeadData::Reader getLead() const; + + inline bool hasSettings() const; + inline ::cereal::ModelData::ModelSettings::Reader getSettings() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::Builder { +public: + typedef ModelData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline bool hasPath(); + inline ::cereal::ModelData::PathData::Builder getPath(); + inline void setPath( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initPath(); + inline void adoptPath(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownPath(); + + inline bool hasLeftLane(); + inline ::cereal::ModelData::PathData::Builder getLeftLane(); + inline void setLeftLane( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initLeftLane(); + inline void adoptLeftLane(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownLeftLane(); + + inline bool hasRightLane(); + inline ::cereal::ModelData::PathData::Builder getRightLane(); + inline void setRightLane( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initRightLane(); + inline void adoptRightLane(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownRightLane(); + + inline bool hasLead(); + inline ::cereal::ModelData::LeadData::Builder getLead(); + inline void setLead( ::cereal::ModelData::LeadData::Reader value); + inline ::cereal::ModelData::LeadData::Builder initLead(); + inline void adoptLead(::capnp::Orphan< ::cereal::ModelData::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::LeadData> disownLead(); + + inline bool hasSettings(); + inline ::cereal::ModelData::ModelSettings::Builder getSettings(); + inline void setSettings( ::cereal::ModelData::ModelSettings::Reader value); + inline ::cereal::ModelData::ModelSettings::Builder initSettings(); + inline void adoptSettings(::capnp::Orphan< ::cereal::ModelData::ModelSettings>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::ModelSettings> disownSettings(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::Pipeline { +public: + typedef ModelData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::cereal::ModelData::PathData::Pipeline getPath(); + inline ::cereal::ModelData::PathData::Pipeline getLeftLane(); + inline ::cereal::ModelData::PathData::Pipeline getRightLane(); + inline ::cereal::ModelData::LeadData::Pipeline getLead(); + inline ::cereal::ModelData::ModelSettings::Pipeline getSettings(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::PathData::Reader { +public: + typedef PathData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasPoints() const; + inline ::capnp::List::Reader getPoints() const; + + inline float getProb() const; + + inline float getStd() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::PathData::Builder { +public: + typedef PathData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPoints(); + inline ::capnp::List::Builder getPoints(); + inline void setPoints( ::capnp::List::Reader value); + inline void setPoints(::kj::ArrayPtr value); + inline ::capnp::List::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownPoints(); + + inline float getProb(); + inline void setProb(float value); + + inline float getStd(); + inline void setStd(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::PathData::Pipeline { +public: + typedef PathData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::LeadData::Reader { +public: + typedef LeadData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getDist() const; + + inline float getProb() const; + + inline float getStd() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::LeadData::Builder { +public: + typedef LeadData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getDist(); + inline void setDist(float value); + + inline float getProb(); + inline void setProb(float value); + + inline float getStd(); + inline void setStd(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::LeadData::Pipeline { +public: + typedef LeadData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::ModelSettings::Reader { +public: + typedef ModelSettings Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getBigBoxX() const; + + inline ::uint16_t getBigBoxY() const; + + inline ::uint16_t getBigBoxWidth() const; + + inline ::uint16_t getBigBoxHeight() const; + + inline bool hasBoxProjection() const; + inline ::capnp::List::Reader getBoxProjection() const; + + inline bool hasYuvCorrection() const; + inline ::capnp::List::Reader getYuvCorrection() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::ModelSettings::Builder { +public: + typedef ModelSettings Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getBigBoxX(); + inline void setBigBoxX( ::uint16_t value); + + inline ::uint16_t getBigBoxY(); + inline void setBigBoxY( ::uint16_t value); + + inline ::uint16_t getBigBoxWidth(); + inline void setBigBoxWidth( ::uint16_t value); + + inline ::uint16_t getBigBoxHeight(); + inline void setBigBoxHeight( ::uint16_t value); + + inline bool hasBoxProjection(); + inline ::capnp::List::Builder getBoxProjection(); + inline void setBoxProjection( ::capnp::List::Reader value); + inline void setBoxProjection(::kj::ArrayPtr value); + inline ::capnp::List::Builder initBoxProjection(unsigned int size); + inline void adoptBoxProjection(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownBoxProjection(); + + inline bool hasYuvCorrection(); + inline ::capnp::List::Builder getYuvCorrection(); + inline void setYuvCorrection( ::capnp::List::Reader value); + inline void setYuvCorrection(::kj::ArrayPtr value); + inline ::capnp::List::Builder initYuvCorrection(unsigned int size); + inline void adoptYuvCorrection(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownYuvCorrection(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::ModelSettings::Pipeline { +public: + typedef ModelSettings Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CalibrationFeatures::Reader { +public: + typedef CalibrationFeatures Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline bool hasP0() const; + inline ::capnp::List::Reader getP0() const; + + inline bool hasP1() const; + inline ::capnp::List::Reader getP1() const; + + inline bool hasStatus() const; + inline ::capnp::List< ::int8_t>::Reader getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CalibrationFeatures::Builder { +public: + typedef CalibrationFeatures Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline bool hasP0(); + inline ::capnp::List::Builder getP0(); + inline void setP0( ::capnp::List::Reader value); + inline void setP0(::kj::ArrayPtr value); + inline ::capnp::List::Builder initP0(unsigned int size); + inline void adoptP0(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownP0(); + + inline bool hasP1(); + inline ::capnp::List::Builder getP1(); + inline void setP1( ::capnp::List::Reader value); + inline void setP1(::kj::ArrayPtr value); + inline ::capnp::List::Builder initP1(unsigned int size); + inline void adoptP1(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownP1(); + + inline bool hasStatus(); + inline ::capnp::List< ::int8_t>::Builder getStatus(); + inline void setStatus( ::capnp::List< ::int8_t>::Reader value); + inline void setStatus(::kj::ArrayPtr value); + inline ::capnp::List< ::int8_t>::Builder initStatus(unsigned int size); + inline void adoptStatus(::capnp::Orphan< ::capnp::List< ::int8_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int8_t>> disownStatus(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CalibrationFeatures::Pipeline { +public: + typedef CalibrationFeatures Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class EncodeIndex::Reader { +public: + typedef EncodeIndex Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline ::cereal::EncodeIndex::Type getType() const; + + inline ::uint32_t getEncodeId() const; + + inline ::int32_t getSegmentNum() const; + + inline ::uint32_t getSegmentId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class EncodeIndex::Builder { +public: + typedef EncodeIndex Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline ::cereal::EncodeIndex::Type getType(); + inline void setType( ::cereal::EncodeIndex::Type value); + + inline ::uint32_t getEncodeId(); + inline void setEncodeId( ::uint32_t value); + + inline ::int32_t getSegmentNum(); + inline void setSegmentNum( ::int32_t value); + + inline ::uint32_t getSegmentId(); + inline void setSegmentId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class EncodeIndex::Pipeline { +public: + typedef EncodeIndex Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class AndroidLogEntry::Reader { +public: + typedef AndroidLogEntry Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getId() const; + + inline ::uint64_t getTs() const; + + inline ::uint8_t getPriority() const; + + inline ::int32_t getPid() const; + + inline ::int32_t getTid() const; + + inline bool hasTag() const; + inline ::capnp::Text::Reader getTag() const; + + inline bool hasMessage() const; + inline ::capnp::Text::Reader getMessage() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class AndroidLogEntry::Builder { +public: + typedef AndroidLogEntry Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getId(); + inline void setId( ::uint8_t value); + + inline ::uint64_t getTs(); + inline void setTs( ::uint64_t value); + + inline ::uint8_t getPriority(); + inline void setPriority( ::uint8_t value); + + inline ::int32_t getPid(); + inline void setPid( ::int32_t value); + + inline ::int32_t getTid(); + inline void setTid( ::int32_t value); + + inline bool hasTag(); + inline ::capnp::Text::Builder getTag(); + inline void setTag( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initTag(unsigned int size); + inline void adoptTag(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownTag(); + + inline bool hasMessage(); + inline ::capnp::Text::Builder getMessage(); + inline void setMessage( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initMessage(unsigned int size); + inline void adoptMessage(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownMessage(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class AndroidLogEntry::Pipeline { +public: + typedef AndroidLogEntry Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LogRotate::Reader { +public: + typedef LogRotate Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int32_t getSegmentNum() const; + + inline bool hasPath() const; + inline ::capnp::Text::Reader getPath() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LogRotate::Builder { +public: + typedef LogRotate Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int32_t getSegmentNum(); + inline void setSegmentNum( ::int32_t value); + + inline bool hasPath(); + inline ::capnp::Text::Builder getPath(); + inline void setPath( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initPath(unsigned int size); + inline void adoptPath(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownPath(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LogRotate::Pipeline { +public: + typedef LogRotate Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Event::Reader { +public: + typedef Event Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getLogMonoTime() const; + + inline bool isInitData() const; + inline bool hasInitData() const; + inline ::cereal::InitData::Reader getInitData() const; + + inline bool isFrame() const; + inline bool hasFrame() const; + inline ::cereal::FrameData::Reader getFrame() const; + + inline bool isGpsNMEA() const; + inline bool hasGpsNMEA() const; + inline ::cereal::GPSNMEAData::Reader getGpsNMEA() const; + + inline bool isSensorEventDEPRECATED() const; + inline bool hasSensorEventDEPRECATED() const; + inline ::cereal::SensorEventData::Reader getSensorEventDEPRECATED() const; + + inline bool isCan() const; + inline bool hasCan() const; + inline ::capnp::List< ::cereal::CanData>::Reader getCan() const; + + inline bool isThermal() const; + inline bool hasThermal() const; + inline ::cereal::ThermalData::Reader getThermal() const; + + inline bool isLive100() const; + inline bool hasLive100() const; + inline ::cereal::Live100Data::Reader getLive100() const; + + inline bool isLiveEventDEPRECATED() const; + inline bool hasLiveEventDEPRECATED() const; + inline ::capnp::List< ::cereal::LiveEventData>::Reader getLiveEventDEPRECATED() const; + + inline bool isModel() const; + inline bool hasModel() const; + inline ::cereal::ModelData::Reader getModel() const; + + inline bool isFeatures() const; + inline bool hasFeatures() const; + inline ::cereal::CalibrationFeatures::Reader getFeatures() const; + + inline bool isSensorEvents() const; + inline bool hasSensorEvents() const; + inline ::capnp::List< ::cereal::SensorEventData>::Reader getSensorEvents() const; + + inline bool isHealth() const; + inline bool hasHealth() const; + inline ::cereal::HealthData::Reader getHealth() const; + + inline bool isLive20() const; + inline bool hasLive20() const; + inline ::cereal::Live20Data::Reader getLive20() const; + + inline bool isLiveUIDEPRECATED() const; + inline bool hasLiveUIDEPRECATED() const; + inline ::cereal::LiveUI::Reader getLiveUIDEPRECATED() const; + + inline bool isEncodeIdx() const; + inline bool hasEncodeIdx() const; + inline ::cereal::EncodeIndex::Reader getEncodeIdx() const; + + inline bool isLiveTracks() const; + inline bool hasLiveTracks() const; + inline ::capnp::List< ::cereal::LiveTracks>::Reader getLiveTracks() const; + + inline bool isSendcan() const; + inline bool hasSendcan() const; + inline ::capnp::List< ::cereal::CanData>::Reader getSendcan() const; + + inline bool isLogMessage() const; + inline bool hasLogMessage() const; + inline ::capnp::Text::Reader getLogMessage() const; + + inline bool isLiveCalibration() const; + inline bool hasLiveCalibration() const; + inline ::cereal::LiveCalibrationData::Reader getLiveCalibration() const; + + inline bool isAndroidLogEntry() const; + inline bool hasAndroidLogEntry() const; + inline ::cereal::AndroidLogEntry::Reader getAndroidLogEntry() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Event::Builder { +public: + typedef Event Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getLogMonoTime(); + inline void setLogMonoTime( ::uint64_t value); + + inline bool isInitData(); + inline bool hasInitData(); + inline ::cereal::InitData::Builder getInitData(); + inline void setInitData( ::cereal::InitData::Reader value); + inline ::cereal::InitData::Builder initInitData(); + inline void adoptInitData(::capnp::Orphan< ::cereal::InitData>&& value); + inline ::capnp::Orphan< ::cereal::InitData> disownInitData(); + + inline bool isFrame(); + inline bool hasFrame(); + inline ::cereal::FrameData::Builder getFrame(); + inline void setFrame( ::cereal::FrameData::Reader value); + inline ::cereal::FrameData::Builder initFrame(); + inline void adoptFrame(::capnp::Orphan< ::cereal::FrameData>&& value); + inline ::capnp::Orphan< ::cereal::FrameData> disownFrame(); + + inline bool isGpsNMEA(); + inline bool hasGpsNMEA(); + inline ::cereal::GPSNMEAData::Builder getGpsNMEA(); + inline void setGpsNMEA( ::cereal::GPSNMEAData::Reader value); + inline ::cereal::GPSNMEAData::Builder initGpsNMEA(); + inline void adoptGpsNMEA(::capnp::Orphan< ::cereal::GPSNMEAData>&& value); + inline ::capnp::Orphan< ::cereal::GPSNMEAData> disownGpsNMEA(); + + inline bool isSensorEventDEPRECATED(); + inline bool hasSensorEventDEPRECATED(); + inline ::cereal::SensorEventData::Builder getSensorEventDEPRECATED(); + inline void setSensorEventDEPRECATED( ::cereal::SensorEventData::Reader value); + inline ::cereal::SensorEventData::Builder initSensorEventDEPRECATED(); + inline void adoptSensorEventDEPRECATED(::capnp::Orphan< ::cereal::SensorEventData>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData> disownSensorEventDEPRECATED(); + + inline bool isCan(); + inline bool hasCan(); + inline ::capnp::List< ::cereal::CanData>::Builder getCan(); + inline void setCan( ::capnp::List< ::cereal::CanData>::Reader value); + inline ::capnp::List< ::cereal::CanData>::Builder initCan(unsigned int size); + inline void adoptCan(::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> disownCan(); + + inline bool isThermal(); + inline bool hasThermal(); + inline ::cereal::ThermalData::Builder getThermal(); + inline void setThermal( ::cereal::ThermalData::Reader value); + inline ::cereal::ThermalData::Builder initThermal(); + inline void adoptThermal(::capnp::Orphan< ::cereal::ThermalData>&& value); + inline ::capnp::Orphan< ::cereal::ThermalData> disownThermal(); + + inline bool isLive100(); + inline bool hasLive100(); + inline ::cereal::Live100Data::Builder getLive100(); + inline void setLive100( ::cereal::Live100Data::Reader value); + inline ::cereal::Live100Data::Builder initLive100(); + inline void adoptLive100(::capnp::Orphan< ::cereal::Live100Data>&& value); + inline ::capnp::Orphan< ::cereal::Live100Data> disownLive100(); + + inline bool isLiveEventDEPRECATED(); + inline bool hasLiveEventDEPRECATED(); + inline ::capnp::List< ::cereal::LiveEventData>::Builder getLiveEventDEPRECATED(); + inline void setLiveEventDEPRECATED( ::capnp::List< ::cereal::LiveEventData>::Reader value); + inline ::capnp::List< ::cereal::LiveEventData>::Builder initLiveEventDEPRECATED(unsigned int size); + inline void adoptLiveEventDEPRECATED(::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>> disownLiveEventDEPRECATED(); + + inline bool isModel(); + inline bool hasModel(); + inline ::cereal::ModelData::Builder getModel(); + inline void setModel( ::cereal::ModelData::Reader value); + inline ::cereal::ModelData::Builder initModel(); + inline void adoptModel(::capnp::Orphan< ::cereal::ModelData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData> disownModel(); + + inline bool isFeatures(); + inline bool hasFeatures(); + inline ::cereal::CalibrationFeatures::Builder getFeatures(); + inline void setFeatures( ::cereal::CalibrationFeatures::Reader value); + inline ::cereal::CalibrationFeatures::Builder initFeatures(); + inline void adoptFeatures(::capnp::Orphan< ::cereal::CalibrationFeatures>&& value); + inline ::capnp::Orphan< ::cereal::CalibrationFeatures> disownFeatures(); + + inline bool isSensorEvents(); + inline bool hasSensorEvents(); + inline ::capnp::List< ::cereal::SensorEventData>::Builder getSensorEvents(); + inline void setSensorEvents( ::capnp::List< ::cereal::SensorEventData>::Reader value); + inline ::capnp::List< ::cereal::SensorEventData>::Builder initSensorEvents(unsigned int size); + inline void adoptSensorEvents(::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>> disownSensorEvents(); + + inline bool isHealth(); + inline bool hasHealth(); + inline ::cereal::HealthData::Builder getHealth(); + inline void setHealth( ::cereal::HealthData::Reader value); + inline ::cereal::HealthData::Builder initHealth(); + inline void adoptHealth(::capnp::Orphan< ::cereal::HealthData>&& value); + inline ::capnp::Orphan< ::cereal::HealthData> disownHealth(); + + inline bool isLive20(); + inline bool hasLive20(); + inline ::cereal::Live20Data::Builder getLive20(); + inline void setLive20( ::cereal::Live20Data::Reader value); + inline ::cereal::Live20Data::Builder initLive20(); + inline void adoptLive20(::capnp::Orphan< ::cereal::Live20Data>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data> disownLive20(); + + inline bool isLiveUIDEPRECATED(); + inline bool hasLiveUIDEPRECATED(); + inline ::cereal::LiveUI::Builder getLiveUIDEPRECATED(); + inline void setLiveUIDEPRECATED( ::cereal::LiveUI::Reader value); + inline ::cereal::LiveUI::Builder initLiveUIDEPRECATED(); + inline void adoptLiveUIDEPRECATED(::capnp::Orphan< ::cereal::LiveUI>&& value); + inline ::capnp::Orphan< ::cereal::LiveUI> disownLiveUIDEPRECATED(); + + inline bool isEncodeIdx(); + inline bool hasEncodeIdx(); + inline ::cereal::EncodeIndex::Builder getEncodeIdx(); + inline void setEncodeIdx( ::cereal::EncodeIndex::Reader value); + inline ::cereal::EncodeIndex::Builder initEncodeIdx(); + inline void adoptEncodeIdx(::capnp::Orphan< ::cereal::EncodeIndex>&& value); + inline ::capnp::Orphan< ::cereal::EncodeIndex> disownEncodeIdx(); + + inline bool isLiveTracks(); + inline bool hasLiveTracks(); + inline ::capnp::List< ::cereal::LiveTracks>::Builder getLiveTracks(); + inline void setLiveTracks( ::capnp::List< ::cereal::LiveTracks>::Reader value); + inline ::capnp::List< ::cereal::LiveTracks>::Builder initLiveTracks(unsigned int size); + inline void adoptLiveTracks(::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>> disownLiveTracks(); + + inline bool isSendcan(); + inline bool hasSendcan(); + inline ::capnp::List< ::cereal::CanData>::Builder getSendcan(); + inline void setSendcan( ::capnp::List< ::cereal::CanData>::Reader value); + inline ::capnp::List< ::cereal::CanData>::Builder initSendcan(unsigned int size); + inline void adoptSendcan(::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> disownSendcan(); + + inline bool isLogMessage(); + inline bool hasLogMessage(); + inline ::capnp::Text::Builder getLogMessage(); + inline void setLogMessage( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initLogMessage(unsigned int size); + inline void adoptLogMessage(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownLogMessage(); + + inline bool isLiveCalibration(); + inline bool hasLiveCalibration(); + inline ::cereal::LiveCalibrationData::Builder getLiveCalibration(); + inline void setLiveCalibration( ::cereal::LiveCalibrationData::Reader value); + inline ::cereal::LiveCalibrationData::Builder initLiveCalibration(); + inline void adoptLiveCalibration(::capnp::Orphan< ::cereal::LiveCalibrationData>&& value); + inline ::capnp::Orphan< ::cereal::LiveCalibrationData> disownLiveCalibration(); + + inline bool isAndroidLogEntry(); + inline bool hasAndroidLogEntry(); + inline ::cereal::AndroidLogEntry::Builder getAndroidLogEntry(); + inline void setAndroidLogEntry( ::cereal::AndroidLogEntry::Reader value); + inline ::cereal::AndroidLogEntry::Builder initAndroidLogEntry(); + inline void adoptAndroidLogEntry(::capnp::Orphan< ::cereal::AndroidLogEntry>&& value); + inline ::capnp::Orphan< ::cereal::AndroidLogEntry> disownAndroidLogEntry(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Event::Pipeline { +public: + typedef Event Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool InitData::Reader::hasKernelArgs() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasKernelArgs() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text>::Reader InitData::Reader::getKernelArgs() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text>::Builder InitData::Builder::getKernelArgs() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setKernelArgs( ::capnp::List< ::capnp::Text>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void InitData::Builder::setKernelArgs(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text>::Builder InitData::Builder::initKernelArgs(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptKernelArgs( + ::capnp::Orphan< ::capnp::List< ::capnp::Text>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text>> InitData::Builder::disownKernelArgs() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool InitData::Reader::hasGctx() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasGctx() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InitData::Reader::getGctx() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InitData::Builder::getGctx() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setGctx( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InitData::Builder::initGctx(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptGctx( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InitData::Builder::disownGctx() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool InitData::Reader::hasDongleId() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasDongleId() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InitData::Reader::getDongleId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InitData::Builder::getDongleId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setDongleId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InitData::Builder::initDongleId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptDongleId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InitData::Builder::disownDongleId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline ::uint32_t FrameData::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t FrameData::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t FrameData::Reader::getEncodeId() const { + return _reader.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint32_t FrameData::Builder::getEncodeId() { + return _builder.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setEncodeId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t FrameData::Reader::getTimestampEof() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t FrameData::Builder::getTimestampEof() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setTimestampEof( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getFrameLength() const { + return _reader.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getFrameLength() { + return _builder.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setFrameLength( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getIntegLines() const { + return _reader.getDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getIntegLines() { + return _builder.getDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setIntegLines( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getGlobalGain() const { + return _reader.getDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getGlobalGain() { + return _builder.getDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setGlobalGain( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS, value); +} + +inline bool FrameData::Reader::hasImage() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool FrameData::Builder::hasImage() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader FrameData::Reader::getImage() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder FrameData::Builder::getImage() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void FrameData::Builder::setImage( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder FrameData::Builder::initImage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void FrameData::Builder::adoptImage( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> FrameData::Builder::disownImage() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int64_t GPSNMEAData::Reader::getTimestamp() const { + return _reader.getDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int64_t GPSNMEAData::Builder::getTimestamp() { + return _builder.getDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS); +} +inline void GPSNMEAData::Builder::setTimestamp( ::int64_t value) { + _builder.setDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t GPSNMEAData::Reader::getLocalWallTime() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t GPSNMEAData::Builder::getLocalWallTime() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void GPSNMEAData::Builder::setLocalWallTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool GPSNMEAData::Reader::hasNmea() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool GPSNMEAData::Builder::hasNmea() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader GPSNMEAData::Reader::getNmea() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder GPSNMEAData::Builder::getNmea() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void GPSNMEAData::Builder::setNmea( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder GPSNMEAData::Builder::initNmea(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void GPSNMEAData::Builder::adoptNmea( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> GPSNMEAData::Builder::disownNmea() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::cereal::SensorEventData::Which SensorEventData::Reader::which() const { + return _reader.getDataField(6 * ::capnp::ELEMENTS); +} +inline ::cereal::SensorEventData::Which SensorEventData::Builder::which() { + return _builder.getDataField(6 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Reader::getVersion() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getVersion() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setVersion( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t SensorEventData::Reader::getSensor() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getSensor() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setSensor( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t SensorEventData::Reader::getType() const { + return _reader.getDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getType() { + return _builder.getDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setType( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::int64_t SensorEventData::Reader::getTimestamp() const { + return _reader.getDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::int64_t SensorEventData::Builder::getTimestamp() { + return _builder.getDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setTimestamp( ::int64_t value) { + _builder.setDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline bool SensorEventData::Reader::isAcceleration() const { + return which() == SensorEventData::ACCELERATION; +} +inline bool SensorEventData::Builder::isAcceleration() { + return which() == SensorEventData::ACCELERATION; +} +inline bool SensorEventData::Reader::hasAcceleration() const { + if (which() != SensorEventData::ACCELERATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasAcceleration() { + if (which() != SensorEventData::ACCELERATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getAcceleration() const { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getAcceleration() { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setAcceleration( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initAcceleration() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptAcceleration( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownAcceleration() { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isMagnetic() const { + return which() == SensorEventData::MAGNETIC; +} +inline bool SensorEventData::Builder::isMagnetic() { + return which() == SensorEventData::MAGNETIC; +} +inline bool SensorEventData::Reader::hasMagnetic() const { + if (which() != SensorEventData::MAGNETIC) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasMagnetic() { + if (which() != SensorEventData::MAGNETIC) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getMagnetic() const { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getMagnetic() { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setMagnetic( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initMagnetic() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptMagnetic( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownMagnetic() { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isOrientation() const { + return which() == SensorEventData::ORIENTATION; +} +inline bool SensorEventData::Builder::isOrientation() { + return which() == SensorEventData::ORIENTATION; +} +inline bool SensorEventData::Reader::hasOrientation() const { + if (which() != SensorEventData::ORIENTATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasOrientation() { + if (which() != SensorEventData::ORIENTATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getOrientation() const { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getOrientation() { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setOrientation( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initOrientation() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptOrientation( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownOrientation() { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isGyro() const { + return which() == SensorEventData::GYRO; +} +inline bool SensorEventData::Builder::isGyro() { + return which() == SensorEventData::GYRO; +} +inline bool SensorEventData::Reader::hasGyro() const { + if (which() != SensorEventData::GYRO) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasGyro() { + if (which() != SensorEventData::GYRO) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getGyro() const { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getGyro() { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setGyro( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initGyro() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptGyro( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownGyro() { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::SensorVec::Reader::hasV() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::SensorVec::Builder::hasV() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader SensorEventData::SensorVec::Reader::getV() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder SensorEventData::SensorVec::Builder::getV() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::SensorVec::Builder::setV( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void SensorEventData::SensorVec::Builder::setV(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder SensorEventData::SensorVec::Builder::initV(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void SensorEventData::SensorVec::Builder::adoptV( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> SensorEventData::SensorVec::Builder::disownV() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t SensorEventData::SensorVec::Reader::getStatus() const { + return _reader.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int8_t SensorEventData::SensorVec::Builder::getStatus() { + return _builder.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void SensorEventData::SensorVec::Builder::setStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t CanData::Reader::getAddress() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t CanData::Builder::getAddress() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setAddress( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t CanData::Reader::getBusTime() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t CanData::Builder::getBusTime() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setBusTime( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline bool CanData::Reader::hasDat() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool CanData::Builder::hasDat() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader CanData::Reader::getDat() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder CanData::Builder::getDat() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void CanData::Builder::setDat( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder CanData::Builder::initDat(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void CanData::Builder::adoptDat( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> CanData::Builder::disownDat() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t CanData::Reader::getSrc() const { + return _reader.getDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS); +} + +inline ::int8_t CanData::Builder::getSrc() { + return _builder.getDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setSrc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu0() const { + return _reader.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu0() { + return _builder.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu0( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu1() const { + return _reader.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu1() { + return _builder.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu1( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu2() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu2() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu2( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu3() const { + return _reader.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu3() { + return _builder.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu3( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getMem() const { + return _reader.getDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getMem() { + return _builder.getDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setMem( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getGpu() const { + return _reader.getDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getGpu() { + return _builder.getDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setGpu( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ThermalData::Reader::getBat() const { + return _reader.getDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint32_t ThermalData::Builder::getBat() { + return _builder.getDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setBat( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t HealthData::Reader::getVoltage() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t HealthData::Builder::getVoltage() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setVoltage( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t HealthData::Reader::getCurrent() const { + return _reader.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint32_t HealthData::Builder::getCurrent() { + return _builder.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setCurrent( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getStarted() const { + return _reader.getDataField( + 64 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getStarted() { + return _builder.getDataField( + 64 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setStarted(bool value) { + _builder.setDataField( + 64 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getControlsAllowed() const { + return _reader.getDataField( + 65 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getControlsAllowed() { + return _builder.getDataField( + 65 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setControlsAllowed(bool value) { + _builder.setDataField( + 65 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getGasInterceptorDetected() const { + return _reader.getDataField( + 66 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getGasInterceptorDetected() { + return _builder.getDataField( + 66 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setGasInterceptorDetected(bool value) { + _builder.setDataField( + 66 * ::capnp::ELEMENTS, value); +} + +inline bool LiveUI::Reader::getRearViewCam() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline bool LiveUI::Builder::getRearViewCam() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void LiveUI::Builder::setRearViewCam(bool value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool LiveUI::Reader::hasAlertText1() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveUI::Builder::hasAlertText1() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveUI::Reader::getAlertText1() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveUI::Builder::getAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveUI::Builder::setAlertText1( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveUI::Builder::initAlertText1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveUI::Builder::adoptAlertText1( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveUI::Builder::disownAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool LiveUI::Reader::hasAlertText2() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool LiveUI::Builder::hasAlertText2() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveUI::Reader::getAlertText2() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveUI::Builder::getAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void LiveUI::Builder::setAlertText2( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveUI::Builder::initAlertText2(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void LiveUI::Builder::adoptAlertText2( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveUI::Builder::disownAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline float LiveUI::Reader::getAwarenessStatus() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float LiveUI::Builder::getAwarenessStatus() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void LiveUI::Builder::setAwarenessStatus(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasWarpMatrix() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasWarpMatrix() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Live20Data::Reader::getWarpMatrix() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Live20Data::Builder::getWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::setWarpMatrix( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void Live20Data::Builder::setWarpMatrix(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Live20Data::Builder::initWarpMatrix(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Live20Data::Builder::adoptWarpMatrix( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Live20Data::Builder::disownWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float Live20Data::Reader::getAngleOffset() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live20Data::Builder::getAngleOffset() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setAngleOffset(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t Live20Data::Reader::getCalStatus() const { + return _reader.getDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int8_t Live20Data::Builder::getCalStatus() { + return _builder.getDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasLeadOne() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasLeadOne() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::LeadData::Reader Live20Data::Reader::getLeadOne() const { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::getLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::Live20Data::LeadData::Pipeline Live20Data::Pipeline::getLeadOne() { + return ::cereal::Live20Data::LeadData::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Live20Data::Builder::setLeadOne( ::cereal::Live20Data::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::initLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::init( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::adoptLeadOne( + ::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> Live20Data::Builder::disownLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool Live20Data::Reader::hasLeadTwo() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasLeadTwo() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::LeadData::Reader Live20Data::Reader::getLeadTwo() const { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::getLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::Live20Data::LeadData::Pipeline Live20Data::Pipeline::getLeadTwo() { + return ::cereal::Live20Data::LeadData::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Live20Data::Builder::setLeadTwo( ::cereal::Live20Data::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::initLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::init( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::adoptLeadTwo( + ::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> Live20Data::Builder::disownLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline float Live20Data::Reader::getCumLagMs() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live20Data::Builder::getCumLagMs() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCumLagMs(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live20Data::Reader::getMdMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live20Data::Builder::getMdMonoTime() { + return _builder.getDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setMdMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live20Data::Reader::getFtMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live20Data::Builder::getFtMonoTime() { + return _builder.getDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setFtMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Live20Data::Reader::getCalCycle() const { + return _reader.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::int32_t Live20Data::Builder::getCalCycle() { + return _builder.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalCycle( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t Live20Data::Reader::getCalPerc() const { + return _reader.getDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::int8_t Live20Data::Builder::getCalPerc() { + return _builder.getDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalPerc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasCanMonoTimes() const { + return !_reader.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasCanMonoTimes() { + return !_builder.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint64_t>::Reader Live20Data::Reader::getCanMonoTimes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _reader.getPointerField(3 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint64_t>::Builder Live20Data::Builder::getCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline void Live20Data::Builder::setCanMonoTimes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint64_t>::Builder Live20Data::Builder::initCanMonoTimes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( + _builder.getPointerField(3 * ::capnp::POINTERS), size); +} +inline void Live20Data::Builder::adoptCanMonoTimes( + ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( + _builder.getPointerField(3 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> Live20Data::Builder::disownCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} + +inline float Live20Data::LeadData::Reader::getDRel() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getDRel() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setDRel(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getYRel() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getYRel() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setYRel(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVRel() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVRel() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVRel(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getARel() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getARel() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setARel(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLead() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLead() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLead(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getALead() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getALead() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setALead(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getDPath() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getDPath() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setDPath(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLat() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLat() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLat(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLeadK() const { + return _reader.getDataField( + 8 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLeadK() { + return _builder.getDataField( + 8 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLeadK(float value) { + _builder.setDataField( + 8 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getALeadK() const { + return _reader.getDataField( + 9 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getALeadK() { + return _builder.getDataField( + 9 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setALeadK(float value) { + _builder.setDataField( + 9 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::LeadData::Reader::getFcw() const { + return _reader.getDataField( + 320 * ::capnp::ELEMENTS); +} + +inline bool Live20Data::LeadData::Builder::getFcw() { + return _builder.getDataField( + 320 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setFcw(bool value) { + _builder.setDataField( + 320 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::LeadData::Reader::getStatus() const { + return _reader.getDataField( + 321 * ::capnp::ELEMENTS); +} + +inline bool Live20Data::LeadData::Builder::getStatus() { + return _builder.getDataField( + 321 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setStatus(bool value) { + _builder.setDataField( + 321 * ::capnp::ELEMENTS, value); +} + +inline bool LiveCalibrationData::Reader::hasWarpMatrix() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveCalibrationData::Builder::hasWarpMatrix() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LiveCalibrationData::Reader::getWarpMatrix() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LiveCalibrationData::Builder::getWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveCalibrationData::Builder::setWarpMatrix( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void LiveCalibrationData::Builder::setWarpMatrix(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LiveCalibrationData::Builder::initWarpMatrix(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveCalibrationData::Builder::adoptWarpMatrix( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LiveCalibrationData::Builder::disownWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t LiveCalibrationData::Reader::getCalStatus() const { + return _reader.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int8_t LiveCalibrationData::Builder::getCalStatus() { + return _builder.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t LiveCalibrationData::Reader::getCalCycle() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveCalibrationData::Builder::getCalCycle() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalCycle( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t LiveCalibrationData::Reader::getCalPerc() const { + return _reader.getDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int8_t LiveCalibrationData::Builder::getCalPerc() { + return _builder.getDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalPerc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t LiveTracks::Reader::getTrackId() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveTracks::Builder::getTrackId() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setTrackId( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getDRel() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getDRel() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setDRel(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getYRel() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getYRel() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setYRel(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getVRel() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getVRel() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setVRel(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getARel() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getARel() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setARel(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getTimeStamp() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getTimeStamp() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setTimeStamp(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getStatus() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getStatus() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setStatus(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getCurrentTime() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getCurrentTime() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setCurrentTime(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline bool LiveTracks::Reader::getStationary() const { + return _reader.getDataField( + 256 * ::capnp::ELEMENTS); +} + +inline bool LiveTracks::Builder::getStationary() { + return _builder.getDataField( + 256 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setStationary(bool value) { + _builder.setDataField( + 256 * ::capnp::ELEMENTS, value); +} + +inline bool LiveTracks::Reader::getOncoming() const { + return _reader.getDataField( + 257 * ::capnp::ELEMENTS); +} + +inline bool LiveTracks::Builder::getOncoming() { + return _builder.getDataField( + 257 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setOncoming(bool value) { + _builder.setDataField( + 257 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVEgo() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVEgo() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVEgo(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getAEgo() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAEgo() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAEgo(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVPid() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVPid() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVPid(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVTargetLead() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVTargetLead() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVTargetLead(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUpAccelCmd() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUpAccelCmd() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUpAccelCmd(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUiAccelCmd() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUiAccelCmd() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUiAccelCmd(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getYActual() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getYActual() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setYActual(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getYDes() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getYDes() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setYDes(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUpSteer() const { + return _reader.getDataField( + 8 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUpSteer() { + return _builder.getDataField( + 8 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUpSteer(float value) { + _builder.setDataField( + 8 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUiSteer() const { + return _reader.getDataField( + 9 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUiSteer() { + return _builder.getDataField( + 9 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUiSteer(float value) { + _builder.setDataField( + 9 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getATargetMin() const { + return _reader.getDataField( + 10 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getATargetMin() { + return _builder.getDataField( + 10 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setATargetMin(float value) { + _builder.setDataField( + 10 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getATargetMax() const { + return _reader.getDataField( + 11 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getATargetMax() { + return _builder.getDataField( + 11 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setATargetMax(float value) { + _builder.setDataField( + 11 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getJerkFactor() const { + return _reader.getDataField( + 12 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getJerkFactor() { + return _builder.getDataField( + 12 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setJerkFactor(float value) { + _builder.setDataField( + 12 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getAngleSteers() const { + return _reader.getDataField( + 13 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAngleSteers() { + return _builder.getDataField( + 13 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAngleSteers(float value) { + _builder.setDataField( + 13 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Live100Data::Reader::getHudLead() const { + return _reader.getDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS); +} + +inline ::int32_t Live100Data::Builder::getHudLead() { + return _builder.getDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setHudLead( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getCumLagMs() const { + return _reader.getDataField( + 15 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getCumLagMs() { + return _builder.getDataField( + 15 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setCumLagMs(float value) { + _builder.setDataField( + 15 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getCanMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getCanMonoTime() { + return _builder.getDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setCanMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getL20MonoTime() const { + return _reader.getDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getL20MonoTime() { + return _builder.getDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setL20MonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getMdMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getMdMonoTime() { + return _builder.getDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setMdMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getEnabled() const { + return _reader.getDataField( + 704 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getEnabled() { + return _builder.getDataField( + 704 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setEnabled(bool value) { + _builder.setDataField( + 704 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getSteerOverride() const { + return _reader.getDataField( + 705 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getSteerOverride() { + return _builder.getDataField( + 705 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setSteerOverride(bool value) { + _builder.setDataField( + 705 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::hasCanMonoTimes() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasCanMonoTimes() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint64_t>::Reader Live100Data::Reader::getCanMonoTimes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint64_t>::Builder Live100Data::Builder::getCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void Live100Data::Builder::setCanMonoTimes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint64_t>::Builder Live100Data::Builder::initCanMonoTimes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptCanMonoTimes( + ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> Live100Data::Builder::disownCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float Live100Data::Reader::getVCruise() const { + return _reader.getDataField( + 23 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVCruise() { + return _builder.getDataField( + 23 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVCruise(float value) { + _builder.setDataField( + 23 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getRearViewCam() const { + return _reader.getDataField( + 706 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getRearViewCam() { + return _builder.getDataField( + 706 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setRearViewCam(bool value) { + _builder.setDataField( + 706 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::hasAlertText1() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasAlertText1() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Live100Data::Reader::getAlertText1() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Live100Data::Builder::getAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setAlertText1( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Live100Data::Builder::initAlertText1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptAlertText1( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Live100Data::Builder::disownAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool Live100Data::Reader::hasAlertText2() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasAlertText2() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Live100Data::Reader::getAlertText2() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Live100Data::Builder::getAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setAlertText2( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Live100Data::Builder::initAlertText2(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptAlertText2( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Live100Data::Builder::disownAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline float Live100Data::Reader::getAwarenessStatus() const { + return _reader.getDataField( + 24 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAwarenessStatus() { + return _builder.getDataField( + 24 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAwarenessStatus(float value) { + _builder.setDataField( + 24 * ::capnp::ELEMENTS, value); +} + +inline bool LiveEventData::Reader::hasName() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveEventData::Builder::hasName() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveEventData::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveEventData::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveEventData::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveEventData::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveEventData::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveEventData::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int32_t LiveEventData::Reader::getValue() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveEventData::Builder::getValue() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveEventData::Builder::setValue( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ModelData::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t ModelData::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool ModelData::Reader::hasPath() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasPath() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getPath() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getPath() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setPath( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptPath( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasLeftLane() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasLeftLane() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getLeftLane() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getLeftLane() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setLeftLane( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptLeftLane( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasRightLane() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasRightLane() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getRightLane() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getRightLane() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setRightLane( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptRightLane( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasLead() const { + return !_reader.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasLead() { + return !_builder.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::LeadData::Reader ModelData::Reader::getLead() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::get( + _reader.getPointerField(3 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::LeadData::Builder ModelData::Builder::getLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::get( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::LeadData::Pipeline ModelData::Pipeline::getLead() { + return ::cereal::ModelData::LeadData::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setLead( ::cereal::ModelData::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::LeadData::Builder ModelData::Builder::initLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::init( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptLead( + ::capnp::Orphan< ::cereal::ModelData::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::adopt( + _builder.getPointerField(3 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::LeadData> ModelData::Builder::disownLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::disown( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasSettings() const { + return !_reader.getPointerField(4 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasSettings() { + return !_builder.getPointerField(4 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::ModelSettings::Reader ModelData::Reader::getSettings() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::get( + _reader.getPointerField(4 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::ModelSettings::Builder ModelData::Builder::getSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::get( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::ModelSettings::Pipeline ModelData::Pipeline::getSettings() { + return ::cereal::ModelData::ModelSettings::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setSettings( ::cereal::ModelData::ModelSettings::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::set( + _builder.getPointerField(4 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::ModelSettings::Builder ModelData::Builder::initSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::init( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptSettings( + ::capnp::Orphan< ::cereal::ModelData::ModelSettings>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::adopt( + _builder.getPointerField(4 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::ModelSettings> ModelData::Builder::disownSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::disown( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} + +inline bool ModelData::PathData::Reader::hasPoints() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::PathData::Builder::hasPoints() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::PathData::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::PathData::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::PathData::Builder::setPoints( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void ModelData::PathData::Builder::setPoints(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::PathData::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void ModelData::PathData::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::PathData::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float ModelData::PathData::Reader::getProb() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float ModelData::PathData::Builder::getProb() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::PathData::Builder::setProb(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::PathData::Reader::getStd() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float ModelData::PathData::Builder::getStd() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::PathData::Builder::setStd(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getDist() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getDist() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setDist(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getProb() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getProb() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setProb(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getStd() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getStd() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setStd(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxX() const { + return _reader.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxX() { + return _builder.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxX( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxY() const { + return _reader.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxY() { + return _builder.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxY( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxWidth() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxWidth() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxWidth( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxHeight() const { + return _reader.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxHeight() { + return _builder.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxHeight( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline bool ModelData::ModelSettings::Reader::hasBoxProjection() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::ModelSettings::Builder::hasBoxProjection() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::ModelSettings::Reader::getBoxProjection() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::getBoxProjection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::ModelSettings::Builder::setBoxProjection( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void ModelData::ModelSettings::Builder::setBoxProjection(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::initBoxProjection(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void ModelData::ModelSettings::Builder::adoptBoxProjection( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::ModelSettings::Builder::disownBoxProjection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool ModelData::ModelSettings::Reader::hasYuvCorrection() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::ModelSettings::Builder::hasYuvCorrection() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::ModelSettings::Reader::getYuvCorrection() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::getYuvCorrection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void ModelData::ModelSettings::Builder::setYuvCorrection( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline void ModelData::ModelSettings::Builder::setYuvCorrection(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::initYuvCorrection(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void ModelData::ModelSettings::Builder::adoptYuvCorrection( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::ModelSettings::Builder::disownYuvCorrection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline ::uint32_t CalibrationFeatures::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t CalibrationFeatures::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void CalibrationFeatures::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool CalibrationFeatures::Reader::hasP0() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasP0() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CalibrationFeatures::Reader::getP0() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::getP0() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setP0( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setP0(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::initP0(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptP0( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CalibrationFeatures::Builder::disownP0() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool CalibrationFeatures::Reader::hasP1() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasP1() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CalibrationFeatures::Reader::getP1() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::getP1() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setP1( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setP1(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::initP1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptP1( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CalibrationFeatures::Builder::disownP1() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool CalibrationFeatures::Reader::hasStatus() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasStatus() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int8_t>::Reader CalibrationFeatures::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int8_t>::Builder CalibrationFeatures::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setStatus( ::capnp::List< ::int8_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setStatus(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int8_t>::Builder CalibrationFeatures::Builder::initStatus(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptStatus( + ::capnp::Orphan< ::capnp::List< ::int8_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int8_t>> CalibrationFeatures::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline ::uint32_t EncodeIndex::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::cereal::EncodeIndex::Type EncodeIndex::Reader::getType() const { + return _reader.getDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS); +} + +inline ::cereal::EncodeIndex::Type EncodeIndex::Builder::getType() { + return _builder.getDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setType( ::cereal::EncodeIndex::Type value) { + _builder.setDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t EncodeIndex::Reader::getEncodeId() const { + return _reader.getDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getEncodeId() { + return _builder.getDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setEncodeId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t EncodeIndex::Reader::getSegmentNum() const { + return _reader.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::int32_t EncodeIndex::Builder::getSegmentNum() { + return _builder.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setSegmentNum( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t EncodeIndex::Reader::getSegmentId() const { + return _reader.getDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getSegmentId() { + return _builder.getDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setSegmentId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t AndroidLogEntry::Reader::getId() const { + return _reader.getDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint8_t AndroidLogEntry::Builder::getId() { + return _builder.getDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setId( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t AndroidLogEntry::Reader::getTs() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t AndroidLogEntry::Builder::getTs() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setTs( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t AndroidLogEntry::Reader::getPriority() const { + return _reader.getDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint8_t AndroidLogEntry::Builder::getPriority() { + return _builder.getDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setPriority( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t AndroidLogEntry::Reader::getPid() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t AndroidLogEntry::Builder::getPid() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setPid( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t AndroidLogEntry::Reader::getTid() const { + return _reader.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int32_t AndroidLogEntry::Builder::getTid() { + return _builder.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setTid( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline bool AndroidLogEntry::Reader::hasTag() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool AndroidLogEntry::Builder::hasTag() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader AndroidLogEntry::Reader::getTag() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::getTag() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void AndroidLogEntry::Builder::setTag( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::initTag(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void AndroidLogEntry::Builder::adoptTag( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> AndroidLogEntry::Builder::disownTag() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool AndroidLogEntry::Reader::hasMessage() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool AndroidLogEntry::Builder::hasMessage() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader AndroidLogEntry::Reader::getMessage() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::getMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void AndroidLogEntry::Builder::setMessage( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::initMessage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void AndroidLogEntry::Builder::adoptMessage( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> AndroidLogEntry::Builder::disownMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline ::int32_t LogRotate::Reader::getSegmentNum() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LogRotate::Builder::getSegmentNum() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LogRotate::Builder::setSegmentNum( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool LogRotate::Reader::hasPath() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LogRotate::Builder::hasPath() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LogRotate::Reader::getPath() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LogRotate::Builder::getPath() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LogRotate::Builder::setPath( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LogRotate::Builder::initPath(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LogRotate::Builder::adoptPath( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LogRotate::Builder::disownPath() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::cereal::Event::Which Event::Reader::which() const { + return _reader.getDataField(4 * ::capnp::ELEMENTS); +} +inline ::cereal::Event::Which Event::Builder::which() { + return _builder.getDataField(4 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Event::Reader::getLogMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Event::Builder::getLogMonoTime() { + return _builder.getDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS); +} +inline void Event::Builder::setLogMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool Event::Reader::isInitData() const { + return which() == Event::INIT_DATA; +} +inline bool Event::Builder::isInitData() { + return which() == Event::INIT_DATA; +} +inline bool Event::Reader::hasInitData() const { + if (which() != Event::INIT_DATA) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasInitData() { + if (which() != Event::INIT_DATA) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::InitData::Reader Event::Reader::getInitData() const { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::InitData::Builder Event::Builder::getInitData() { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setInitData( ::cereal::InitData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + ::capnp::_::PointerHelpers< ::cereal::InitData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::InitData::Builder Event::Builder::initInitData() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptInitData( + ::capnp::Orphan< ::cereal::InitData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + ::capnp::_::PointerHelpers< ::cereal::InitData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::InitData> Event::Builder::disownInitData() { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isFrame() const { + return which() == Event::FRAME; +} +inline bool Event::Builder::isFrame() { + return which() == Event::FRAME; +} +inline bool Event::Reader::hasFrame() const { + if (which() != Event::FRAME) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasFrame() { + if (which() != Event::FRAME) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::FrameData::Reader Event::Reader::getFrame() const { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::FrameData::Builder Event::Builder::getFrame() { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setFrame( ::cereal::FrameData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + ::capnp::_::PointerHelpers< ::cereal::FrameData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::FrameData::Builder Event::Builder::initFrame() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptFrame( + ::capnp::Orphan< ::cereal::FrameData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + ::capnp::_::PointerHelpers< ::cereal::FrameData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::FrameData> Event::Builder::disownFrame() { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isGpsNMEA() const { + return which() == Event::GPS_N_M_E_A; +} +inline bool Event::Builder::isGpsNMEA() { + return which() == Event::GPS_N_M_E_A; +} +inline bool Event::Reader::hasGpsNMEA() const { + if (which() != Event::GPS_N_M_E_A) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasGpsNMEA() { + if (which() != Event::GPS_N_M_E_A) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::GPSNMEAData::Reader Event::Reader::getGpsNMEA() const { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::GPSNMEAData::Builder Event::Builder::getGpsNMEA() { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setGpsNMEA( ::cereal::GPSNMEAData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::GPSNMEAData::Builder Event::Builder::initGpsNMEA() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptGpsNMEA( + ::capnp::Orphan< ::cereal::GPSNMEAData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::GPSNMEAData> Event::Builder::disownGpsNMEA() { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSensorEventDEPRECATED() const { + return which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isSensorEventDEPRECATED() { + return which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasSensorEventDEPRECATED() const { + if (which() != Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSensorEventDEPRECATED() { + if (which() != Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::Reader Event::Reader::getSensorEventDEPRECATED() const { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::Builder Event::Builder::getSensorEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSensorEventDEPRECATED( ::cereal::SensorEventData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::Builder Event::Builder::initSensorEventDEPRECATED() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptSensorEventDEPRECATED( + ::capnp::Orphan< ::cereal::SensorEventData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData> Event::Builder::disownSensorEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isCan() const { + return which() == Event::CAN; +} +inline bool Event::Builder::isCan() { + return which() == Event::CAN; +} +inline bool Event::Reader::hasCan() const { + if (which() != Event::CAN) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasCan() { + if (which() != Event::CAN) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::CanData>::Reader Event::Reader::getCan() const { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::getCan() { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setCan( ::capnp::List< ::cereal::CanData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::initCan(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptCan( + ::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> Event::Builder::disownCan() { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isThermal() const { + return which() == Event::THERMAL; +} +inline bool Event::Builder::isThermal() { + return which() == Event::THERMAL; +} +inline bool Event::Reader::hasThermal() const { + if (which() != Event::THERMAL) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasThermal() { + if (which() != Event::THERMAL) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ThermalData::Reader Event::Reader::getThermal() const { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ThermalData::Builder Event::Builder::getThermal() { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setThermal( ::cereal::ThermalData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + ::capnp::_::PointerHelpers< ::cereal::ThermalData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ThermalData::Builder Event::Builder::initThermal() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptThermal( + ::capnp::Orphan< ::cereal::ThermalData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + ::capnp::_::PointerHelpers< ::cereal::ThermalData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ThermalData> Event::Builder::disownThermal() { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLive100() const { + return which() == Event::LIVE100; +} +inline bool Event::Builder::isLive100() { + return which() == Event::LIVE100; +} +inline bool Event::Reader::hasLive100() const { + if (which() != Event::LIVE100) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLive100() { + if (which() != Event::LIVE100) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live100Data::Reader Event::Reader::getLive100() const { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::Live100Data::Builder Event::Builder::getLive100() { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLive100( ::cereal::Live100Data::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + ::capnp::_::PointerHelpers< ::cereal::Live100Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::Live100Data::Builder Event::Builder::initLive100() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLive100( + ::capnp::Orphan< ::cereal::Live100Data>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + ::capnp::_::PointerHelpers< ::cereal::Live100Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live100Data> Event::Builder::disownLive100() { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveEventDEPRECATED() const { + return which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isLiveEventDEPRECATED() { + return which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasLiveEventDEPRECATED() const { + if (which() != Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveEventDEPRECATED() { + if (which() != Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::LiveEventData>::Reader Event::Reader::getLiveEventDEPRECATED() const { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::LiveEventData>::Builder Event::Builder::getLiveEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveEventDEPRECATED( ::capnp::List< ::cereal::LiveEventData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::LiveEventData>::Builder Event::Builder::initLiveEventDEPRECATED(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLiveEventDEPRECATED( + ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>> Event::Builder::disownLiveEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isModel() const { + return which() == Event::MODEL; +} +inline bool Event::Builder::isModel() { + return which() == Event::MODEL; +} +inline bool Event::Reader::hasModel() const { + if (which() != Event::MODEL) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasModel() { + if (which() != Event::MODEL) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::Reader Event::Reader::getModel() const { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::Builder Event::Builder::getModel() { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setModel( ::cereal::ModelData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + ::capnp::_::PointerHelpers< ::cereal::ModelData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::Builder Event::Builder::initModel() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptModel( + ::capnp::Orphan< ::cereal::ModelData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + ::capnp::_::PointerHelpers< ::cereal::ModelData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData> Event::Builder::disownModel() { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isFeatures() const { + return which() == Event::FEATURES; +} +inline bool Event::Builder::isFeatures() { + return which() == Event::FEATURES; +} +inline bool Event::Reader::hasFeatures() const { + if (which() != Event::FEATURES) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasFeatures() { + if (which() != Event::FEATURES) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::CalibrationFeatures::Reader Event::Reader::getFeatures() const { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::CalibrationFeatures::Builder Event::Builder::getFeatures() { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setFeatures( ::cereal::CalibrationFeatures::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::CalibrationFeatures::Builder Event::Builder::initFeatures() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptFeatures( + ::capnp::Orphan< ::cereal::CalibrationFeatures>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::CalibrationFeatures> Event::Builder::disownFeatures() { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSensorEvents() const { + return which() == Event::SENSOR_EVENTS; +} +inline bool Event::Builder::isSensorEvents() { + return which() == Event::SENSOR_EVENTS; +} +inline bool Event::Reader::hasSensorEvents() const { + if (which() != Event::SENSOR_EVENTS) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSensorEvents() { + if (which() != Event::SENSOR_EVENTS) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::SensorEventData>::Reader Event::Reader::getSensorEvents() const { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::SensorEventData>::Builder Event::Builder::getSensorEvents() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSensorEvents( ::capnp::List< ::cereal::SensorEventData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::SensorEventData>::Builder Event::Builder::initSensorEvents(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptSensorEvents( + ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>> Event::Builder::disownSensorEvents() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isHealth() const { + return which() == Event::HEALTH; +} +inline bool Event::Builder::isHealth() { + return which() == Event::HEALTH; +} +inline bool Event::Reader::hasHealth() const { + if (which() != Event::HEALTH) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasHealth() { + if (which() != Event::HEALTH) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::HealthData::Reader Event::Reader::getHealth() const { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::HealthData::Builder Event::Builder::getHealth() { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setHealth( ::cereal::HealthData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + ::capnp::_::PointerHelpers< ::cereal::HealthData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::HealthData::Builder Event::Builder::initHealth() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptHealth( + ::capnp::Orphan< ::cereal::HealthData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + ::capnp::_::PointerHelpers< ::cereal::HealthData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::HealthData> Event::Builder::disownHealth() { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLive20() const { + return which() == Event::LIVE20; +} +inline bool Event::Builder::isLive20() { + return which() == Event::LIVE20; +} +inline bool Event::Reader::hasLive20() const { + if (which() != Event::LIVE20) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLive20() { + if (which() != Event::LIVE20) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::Reader Event::Reader::getLive20() const { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::Builder Event::Builder::getLive20() { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLive20( ::cereal::Live20Data::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + ::capnp::_::PointerHelpers< ::cereal::Live20Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::Builder Event::Builder::initLive20() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLive20( + ::capnp::Orphan< ::cereal::Live20Data>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + ::capnp::_::PointerHelpers< ::cereal::Live20Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data> Event::Builder::disownLive20() { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveUIDEPRECATED() const { + return which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isLiveUIDEPRECATED() { + return which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasLiveUIDEPRECATED() const { + if (which() != Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveUIDEPRECATED() { + if (which() != Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::LiveUI::Reader Event::Reader::getLiveUIDEPRECATED() const { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::LiveUI::Builder Event::Builder::getLiveUIDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveUIDEPRECATED( ::cereal::LiveUI::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::LiveUI>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::LiveUI::Builder Event::Builder::initLiveUIDEPRECATED() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLiveUIDEPRECATED( + ::capnp::Orphan< ::cereal::LiveUI>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::LiveUI>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::LiveUI> Event::Builder::disownLiveUIDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isEncodeIdx() const { + return which() == Event::ENCODE_IDX; +} +inline bool Event::Builder::isEncodeIdx() { + return which() == Event::ENCODE_IDX; +} +inline bool Event::Reader::hasEncodeIdx() const { + if (which() != Event::ENCODE_IDX) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasEncodeIdx() { + if (which() != Event::ENCODE_IDX) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::EncodeIndex::Reader Event::Reader::getEncodeIdx() const { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::EncodeIndex::Builder Event::Builder::getEncodeIdx() { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setEncodeIdx( ::cereal::EncodeIndex::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::EncodeIndex::Builder Event::Builder::initEncodeIdx() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptEncodeIdx( + ::capnp::Orphan< ::cereal::EncodeIndex>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::EncodeIndex> Event::Builder::disownEncodeIdx() { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveTracks() const { + return which() == Event::LIVE_TRACKS; +} +inline bool Event::Builder::isLiveTracks() { + return which() == Event::LIVE_TRACKS; +} +inline bool Event::Reader::hasLiveTracks() const { + if (which() != Event::LIVE_TRACKS) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveTracks() { + if (which() != Event::LIVE_TRACKS) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::LiveTracks>::Reader Event::Reader::getLiveTracks() const { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::LiveTracks>::Builder Event::Builder::getLiveTracks() { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveTracks( ::capnp::List< ::cereal::LiveTracks>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::LiveTracks>::Builder Event::Builder::initLiveTracks(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLiveTracks( + ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>> Event::Builder::disownLiveTracks() { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSendcan() const { + return which() == Event::SENDCAN; +} +inline bool Event::Builder::isSendcan() { + return which() == Event::SENDCAN; +} +inline bool Event::Reader::hasSendcan() const { + if (which() != Event::SENDCAN) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSendcan() { + if (which() != Event::SENDCAN) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::CanData>::Reader Event::Reader::getSendcan() const { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::getSendcan() { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSendcan( ::capnp::List< ::cereal::CanData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::initSendcan(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptSendcan( + ::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> Event::Builder::disownSendcan() { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLogMessage() const { + return which() == Event::LOG_MESSAGE; +} +inline bool Event::Builder::isLogMessage() { + return which() == Event::LOG_MESSAGE; +} +inline bool Event::Reader::hasLogMessage() const { + if (which() != Event::LOG_MESSAGE) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLogMessage() { + if (which() != Event::LOG_MESSAGE) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Event::Reader::getLogMessage() const { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Event::Builder::getLogMessage() { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLogMessage( ::capnp::Text::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Event::Builder::initLogMessage(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLogMessage( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Event::Builder::disownLogMessage() { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveCalibration() const { + return which() == Event::LIVE_CALIBRATION; +} +inline bool Event::Builder::isLiveCalibration() { + return which() == Event::LIVE_CALIBRATION; +} +inline bool Event::Reader::hasLiveCalibration() const { + if (which() != Event::LIVE_CALIBRATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveCalibration() { + if (which() != Event::LIVE_CALIBRATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::LiveCalibrationData::Reader Event::Reader::getLiveCalibration() const { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::LiveCalibrationData::Builder Event::Builder::getLiveCalibration() { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveCalibration( ::cereal::LiveCalibrationData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::LiveCalibrationData::Builder Event::Builder::initLiveCalibration() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLiveCalibration( + ::capnp::Orphan< ::cereal::LiveCalibrationData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::LiveCalibrationData> Event::Builder::disownLiveCalibration() { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isAndroidLogEntry() const { + return which() == Event::ANDROID_LOG_ENTRY; +} +inline bool Event::Builder::isAndroidLogEntry() { + return which() == Event::ANDROID_LOG_ENTRY; +} +inline bool Event::Reader::hasAndroidLogEntry() const { + if (which() != Event::ANDROID_LOG_ENTRY) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasAndroidLogEntry() { + if (which() != Event::ANDROID_LOG_ENTRY) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::AndroidLogEntry::Reader Event::Reader::getAndroidLogEntry() const { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::AndroidLogEntry::Builder Event::Builder::getAndroidLogEntry() { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setAndroidLogEntry( ::cereal::AndroidLogEntry::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::AndroidLogEntry::Builder Event::Builder::initAndroidLogEntry() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptAndroidLogEntry( + ::capnp::Orphan< ::cereal::AndroidLogEntry>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::AndroidLogEntry> Event::Builder::disownAndroidLogEntry() { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +} // namespace + +#endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ diff --git a/cereal/log.capnp b/cereal/log.capnp new file mode 100644 index 0000000000..166b2b558d --- /dev/null +++ b/cereal/log.capnp @@ -0,0 +1,272 @@ +using Cxx = import "c++.capnp"; +$Cxx.namespace("cereal"); + +@0xf3b1f17e25a4285b; + +const logVersion :Int32 = 1; + +struct InitData { + kernelArgs @0 :List(Text); + gctx @1 :Text; + dongleId @2 :Text; +} + +struct FrameData { + frameId @0 :UInt32; + encodeId @1 :UInt32; # DEPRECATED + timestampEof @2 :UInt64; + frameLength @3 :Int32; + integLines @4 :Int32; + globalGain @5 :Int32; + image @6 :Data; +} + +struct GPSNMEAData { + timestamp @0 :Int64; + localWallTime @1 :UInt64; + nmea @2 :Text; +} + +# android sensor_event_t +struct SensorEventData { + version @0 :Int32; + sensor @1 :Int32; + type @2 :Int32; + timestamp @3 :Int64; + union { + acceleration @4 :SensorVec; + magnetic @5 :SensorVec; + orientation @6 :SensorVec; + gyro @7 :SensorVec; + } + + struct SensorVec { + v @0 :List(Float32); + status @1 :Int8; + } +} + +struct CanData { + address @0 :UInt32; + busTime @1 :UInt16; + dat @2 :Data; + src @3 :Int8; +} + +struct ThermalData { + cpu0 @0 :UInt16; + cpu1 @1 :UInt16; + cpu2 @2 :UInt16; + cpu3 @3 :UInt16; + mem @4 :UInt16; + gpu @5 :UInt16; + bat @6 :UInt32; +} + +struct HealthData { + # from can health + voltage @0 :UInt32; + current @1 :UInt32; + started @2 :Bool; + controlsAllowed @3 :Bool; + gasInterceptorDetected @4 :Bool; +} + +struct LiveUI { + rearViewCam @0 :Bool; + alertText1 @1 :Text; + alertText2 @2 :Text; + awarenessStatus @3 :Float32; +} + +struct Live20Data { + canMonoTimes @10 :List(UInt64); + mdMonoTime @6 :UInt64; + ftMonoTime @7 :UInt64; + + # all deprecated + warpMatrix @0 :List(Float32); + angleOffset @1 :Float32; + calStatus @2 :Int8; + calCycle @8 :Int32; + calPerc @9 :Int8; + + leadOne @3 :LeadData; + leadTwo @4 :LeadData; + cumLagMs @5 :Float32; + + struct LeadData { + dRel @0 :Float32; + yRel @1 :Float32; + vRel @2 :Float32; + aRel @3 :Float32; + vLead @4 :Float32; + aLead @5 :Float32; + dPath @6 :Float32; + vLat @7 :Float32; + vLeadK @8 :Float32; + aLeadK @9 :Float32; + fcw @10 :Bool; + status @11 :Bool; + } +} + +struct LiveCalibrationData { + warpMatrix @0 :List(Float32); + calStatus @1 :Int8; + calCycle @2 :Int32; + calPerc @3 :Int8; +} + +struct LiveTracks { + trackId @0 :Int32; + dRel @1 :Float32; + yRel @2 :Float32; + vRel @3 :Float32; + aRel @4 :Float32; + timeStamp @5 :Float32; + status @6 :Float32; + currentTime @7 :Float32; + stationary @8 :Bool; + oncoming @9 :Bool; +} + +struct Live100Data { + canMonoTime @16 :UInt64; + canMonoTimes @21 :List(UInt64); + l20MonoTime @17 :UInt64; + mdMonoTime @18 :UInt64; + + vEgo @0 :Float32; + aEgo @1 :Float32; + vPid @2 :Float32; + vTargetLead @3 :Float32; + upAccelCmd @4 :Float32; + uiAccelCmd @5 :Float32; + yActual @6 :Float32; + yDes @7 :Float32; + upSteer @8 :Float32; + uiSteer @9 :Float32; + aTargetMin @10 :Float32; + aTargetMax @11 :Float32; + jerkFactor @12 :Float32; + angleSteers @13 :Float32; + hudLead @14 :Int32; + cumLagMs @15 :Float32; + + enabled @19: Bool; + steerOverride @20: Bool; + + vCruise @22: Float32; + + rearViewCam @23 :Bool; + alertText1 @24 :Text; + alertText2 @25 :Text; + awarenessStatus @26 :Float32; +} + +struct LiveEventData { + name @0 :Text; + value @1 :Int32; +} + +struct ModelData { + frameId @0 :UInt32; + + path @1 :PathData; + leftLane @2 :PathData; + rightLane @3 :PathData; + lead @4 :LeadData; + + settings @5 :ModelSettings; + + struct PathData { + points @0 :List(Float32); + prob @1 :Float32; + std @2 :Float32; + } + + struct LeadData { + dist @0 :Float32; + prob @1 :Float32; + std @2 :Float32; + } + + struct ModelSettings { + bigBoxX @0 :UInt16; + bigBoxY @1 :UInt16; + bigBoxWidth @2 :UInt16; + bigBoxHeight @3 :UInt16; + boxProjection @4 :List(Float32); + yuvCorrection @5 :List(Float32); + } +} + +struct CalibrationFeatures { + frameId @0 :UInt32; + + p0 @1 :List(Float32); + p1 @2 :List(Float32); + status @3 :List(Int8); +} + +struct EncodeIndex { + # picture from camera + frameId @0 :UInt32; + type @1 :Type; + # index of encoder from start of route + encodeId @2 :UInt32; + # minute long segment this frame is in + segmentNum @3 :Int32; + # index into camera file in segment from 0 + segmentId @4 :UInt32; + + enum Type { + bigBoxLossless @0; # rcamera.mkv + fullHEVC @1; # fcamera.hevc + bigBoxHEVC @2; # bcamera.hevc + } +} + +struct AndroidLogEntry { + id @0 :UInt8; + ts @1 :UInt64; + priority @2 :UInt8; + pid @3 :Int32; + tid @4 :Int32; + tag @5 :Text; + message @6 :Text; +} + +struct LogRotate { + segmentNum @0 :Int32; + path @1 :Text; +} + + +struct Event { + logMonoTime @0 :UInt64; + + union { + initData @1 :InitData; + frame @2 :FrameData; + gpsNMEA @3 :GPSNMEAData; + sensorEventDEPRECATED @4 :SensorEventData; + can @5 :List(CanData); + thermal @6 :ThermalData; + live100 @7 :Live100Data; + liveEventDEPRECATED @8 :List(LiveEventData); + model @9 :ModelData; + features @10 :CalibrationFeatures; + sensorEvents @11 :List(SensorEventData); + health @12 : HealthData; + live20 @13 :Live20Data; + liveUIDEPRECATED @14 :LiveUI; + encodeIdx @15 :EncodeIndex; + liveTracks @16 :List(LiveTracks); + sendcan @17 :List(CanData); + logMessage @18 :Text; + liveCalibration @19 :LiveCalibrationData; + androidLogEntry @20 :AndroidLogEntry; + } +} diff --git a/common/__init__.py b/common/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/common/api/__init__.py b/common/api/__init__.py new file mode 100644 index 0000000000..daf21cd4a3 --- /dev/null +++ b/common/api/__init__.py @@ -0,0 +1,8 @@ +import requests + +def api_get(endpoint, method='GET', timeout=None, **params): + backend = "https://api.commadotai.com/" + + params['_version'] = "OPENPILOTv0.0" + + return requests.request(method, backend+endpoint, timeout=timeout, params=params) diff --git a/common/crash.py b/common/crash.py new file mode 100644 index 0000000000..e886758184 --- /dev/null +++ b/common/crash.py @@ -0,0 +1,26 @@ +"""Install exception handler for process crash.""" +import os +import sys + +if os.getenv("NOLOG"): + def capture_exception(*exc_info): + pass + def install(): + pass +else: + from raven import Client + from raven.transport.http import HTTPTransport + + client = Client('https://1994756b5e6f41cf939a4c65de45f4f2:cefebaf3a8aa40d182609785f7189bd7@app.getsentry.com/77924', + install_sys_hook=False, transport=HTTPTransport) + + capture_exception = client.captureException + + def install(): + # installs a sys.excepthook + __excepthook__ = sys.excepthook + def handle_exception(*exc_info): + if exc_info[0] not in (KeyboardInterrupt, SystemExit): + client.captureException(exc_info=exc_info) + __excepthook__(*exc_info) + sys.excepthook = handle_exception diff --git a/common/dbc.py b/common/dbc.py new file mode 100755 index 0000000000..bc9dab3bac --- /dev/null +++ b/common/dbc.py @@ -0,0 +1,182 @@ +import re +from collections import namedtuple +import bitstring + +def int_or_float(s): + # return number, trying to maintain int format + try: + return int(s) + except ValueError: + return float(s) + +DBCSignal = namedtuple( + "DBCSignal", ["name", "start_bit", "size", "is_little_endian", "is_signed", + "factor", "offset", "tmin", "tmax", "units"]) + +class dbc(object): + def __init__(self, fn): + self.txt = open(fn).read().split("\n") + self._warned_addresses = set() + + # regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py + bo_regexp = re.compile("^BO\_ (\w+) (\w+) *: (\w+) (\w+)") + sg_regexp = re.compile("^SG\_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + sgm_regexp = re.compile("^SG\_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + + # A dictionary which maps message ids to tuples ((name, size), signals). + # name is the ASCII name of the message. + # size is the size of the message in bytes. + # signals is a list signals contained in the message. + # signals is a list of DBCSignal in order of increasing start_bit. + self.msgs = {} + + self.bits = [] + for i in range(0, 64, 8): + for j in range(7, -1, -1): + self.bits.append(i+j) + + for l in self.txt: + l = l.strip() + + if l.startswith("BO_ "): + # new group + dat = bo_regexp.match(l) + + if dat is None: + print "bad BO", l + name = dat.group(2) + size = int(dat.group(3)) + ids = int(dat.group(1), 0) # could be hex + + self.msgs[ids] = ((name, size), []) + + if l.startswith("SG_ "): + # new signal + dat = sg_regexp.match(l) + go = 0 + if dat is None: + dat = sgm_regexp.match(l) + go = 1 + if dat is None: + print "bad SG", l + + sgname = dat.group(1) + start_bit = int(dat.group(go+2)) + signal_size = int(dat.group(go+3)) + is_little_endian = int(dat.group(go+4))==1 + is_signed = dat.group(go+5)=='-' + factor = int_or_float(dat.group(go+6)) + offset = int_or_float(dat.group(go+7)) + tmin = int_or_float(dat.group(go+8)) + tmax = int_or_float(dat.group(go+9)) + units = dat.group(go+10) + + self.msgs[ids][1].append( + DBCSignal(sgname, start_bit, signal_size, is_little_endian, + is_signed, factor, offset, tmin, tmax, units)) + + for msg in self.msgs.viewvalues(): + msg[1].sort(key=lambda x: x.start_bit) + + def encode(self, msg_id, dd): + """Encode a CAN message using the dbc. + + Inputs: + msg_id: The message ID. + dd: A dictionary mapping signal name to signal data. + """ + # TODO: Stop using bitstring, which is super slow. + msg_def = self.msgs[msg_id] + size = msg_def[0][1] + + bsf = bitstring.Bits(hex="00"*size) + for s in msg_def[1]: + ival = dd.get(s.name) + if ival is not None: + ival = (ival / s.factor) - s.offset + ival = int(round(ival)) + + # should pack this + if s.is_little_endian: + ss = s.start_bit + else: + ss = self.bits.index(s.start_bit) + + + if s.is_signed: + tbs = bitstring.Bits(int=ival, length=s.size) + else: + tbs = bitstring.Bits(uint=ival, length=s.size) + + lpad = bitstring.Bits(bin="0b"+"0"*ss) + rpad = bitstring.Bits(bin="0b"+"0"*(8*size-(ss+s.size))) + tbs = lpad+tbs+rpad + + bsf |= tbs + return bsf.tobytes() + + def decode(self, x, arr=None, debug=False): + """Decode a CAN message using the dbc. + + Inputs: + x: A collection with elements (address, time, data), where address is + the CAN address, time is the bus time, and data is the CAN data as a + hex string. + arr: Optional list of signals which should be decoded and returned. + debug: True to print debugging statements. + + Returns: + A tuple (name, data), where name is the name of the CAN message and data + is the decoded result. If arr is None, data is a dict of properties. + Otherwise data is a list of the same length as arr. + + Returns (None, None) if the message could not be decoded. + """ + if arr is None: + out = {} + else: + out = [None]*len(arr) + + msg = self.msgs.get(x[0]) + if msg is None: + if x[0] not in self._warned_addresses: + print("WARNING: Unknown message address {}".format(x[0])) + self._warned_addresses.add(x[0]) + return None, None + + name = msg[0][0] + if debug: + print name + + blen = (len(x[2])/2)*8 + x2_int = int(x[2], 16) + + for s in msg[1]: + if arr is not None and s[0] not in arr: + continue + + # big or little endian? + # see http://vi-firmware.openxcplatform.com/en/master/config/bit-numbering.html + if s[3] is False: + ss = self.bits.index(s[1]) + else: + ss = s[1] + + data_bit_pos = (blen - (ss + s[2])) + if data_bit_pos < 0: + continue + ival = (x2_int >> data_bit_pos) & ((1 << (s[2])) - 1) + + if s[4] and (ival & (1<<(s[2]-1))): # signed + ival -= (1< +CLOCK_BOOTTIME = 7 + +class timespec(ctypes.Structure): + _fields_ = [ + ('tv_sec', ctypes.c_long), + ('tv_nsec', ctypes.c_long), + ] + + +try: + libc = ctypes.CDLL('libc.so', use_errno=True) +except OSError: + try: + libc = ctypes.CDLL('libc.so.6', use_errno=True) + except OSError: + libc = None + +if libc is not None: + libc.clock_gettime.argtypes = [ctypes.c_int, ctypes.POINTER(timespec)] + +def clock_gettime(clk_id): + if platform.system() == "darwin": + # TODO: fix this + return time.time() + else: + t = timespec() + if libc.clock_gettime(clk_id, ctypes.pointer(t)) != 0: + errno_ = ctypes.get_errno() + raise OSError(errno_, os.strerror(errno_)) + return t.tv_sec + t.tv_nsec * 1e-9 + +def monotonic_time(): + return clock_gettime(CLOCK_MONOTONIC_RAW) + +def sec_since_boot(): + return clock_gettime(CLOCK_BOOTTIME) + + +def set_realtime_priority(level): + if os.getuid() != 0: + print "not setting priority, not root" + return + if platform.machine() == "x86_64": + NR_gettid = 186 + elif platform.machine() == "aarch64": + NR_gettid = 178 + else: + raise NotImplementedError + + tid = libc.syscall(NR_gettid) + subprocess.check_call(['chrt', '-f', '-p', str(level), str(tid)]) + + +class Ratekeeper(object): + def __init__(self, rate, print_delay_threshold=0.): + """Rate in Hz for ratekeeping. print_delay_threshold must be nonnegative.""" + self._interval = 1. / rate + self._next_frame_time = sec_since_boot() + self._interval + self._print_delay_threshold = print_delay_threshold + self._frame = 0 + self._remaining = 0 + self._process_name = multiprocessing.current_process().name + + @property + def frame(self): + return self._frame + + @property + def remaining(self): + return self._remaining + + # Maintain loop rate by calling this at the end of each loop + def keep_time(self): + self.monitor_time() + if self._remaining > 0: + time.sleep(self._remaining) + + # this only monitor the cumulative lag, but does not enforce a rate + def monitor_time(self): + remaining = self._next_frame_time - sec_since_boot() + self._next_frame_time += self._interval + if remaining < -self._print_delay_threshold: + print self._process_name, "lagging by", round(-remaining * 1000, 2), "ms" + self._frame += 1 + self._remaining = remaining diff --git a/common/services.py b/common/services.py new file mode 100644 index 0000000000..6a2cd948c7 --- /dev/null +++ b/common/services.py @@ -0,0 +1,82 @@ +# TODO: these port numbers are hardcoded in c, fix this + +# LogRotate: 8001 is a PUSH PULL socket between loggerd and visiond + +class Service(object): + def __init__(self, port, should_log): + self.port = port + self.should_log = should_log + +# all ZMQ pub sub +service_list = { + # frame syncing packet + "frame": Service(8002, True), + # accel, gyro, and compass + "sensorEvents": Service(8003, True), + # GPS data, also global timestamp + "gpsNMEA": Service(8004, True), + # CPU+MEM+GPU+BAT temps + "thermal": Service(8005, True), + # List(CanData), list of can messages + "can": Service(8006, True), + "live100": Service(8007, True), + # random events we want to log + #"liveEvent": Service(8008, True), + "model": Service(8009, True), + "features": Service(8010, True), + "health": Service(8011, True), + "live20": Service(8012, True), + #"liveUI": Service(8014, True), + "encodeIdx": Service(8015, True), + "liveTracks": Service(8016, True), + "sendcan": Service(8017, True), + "logMessage": Service(8018, True), + "liveCalibration": Service(8019, True), + "androidLog": Service(8020, True), +} + +# manager -- base process to manage starting and stopping of all others +# subscribes: health +# publishes: thermal + +# boardd -- communicates with the car +# subscribes: sendcan +# publishes: can, health + +# visiond -- talks to the cameras, runs the model, saves the videos +# subscribes: liveCalibration, sensorEvents +# publishes: frame, encodeIdx, model, features + +# controlsd -- actually drives the car +# subscribes: can, thermal, model, live20 +# publishes: sendcan, live100 + +# radard -- processes the radar data +# subscribes: can, live100, model +# publishes: live20, liveTracks + +# sensord -- publishes the IMU and GPS +# publishes: sensorEvents, gpsNMEA + +# calibrationd -- places the camera box +# subscribes: features, live100 +# publishes: liveCalibration + +# **** LOGGING SERVICE **** + +# loggerd +# subscribes: EVERYTHING + +# **** NON VITAL SERVICES **** + +# ui +# subscribes: live100, live20, liveCalibration, model, (raw frames) + +# uploader +# communicates through file system with loggerd + +# logmessaged -- central logging service, can log to cloud +# publishes: logMessage + +# logcatd -- fetches logcat info from android +# publishes: androidLog diff --git a/dbcs/__init__.py b/dbcs/__init__.py new file mode 100644 index 0000000000..a74a06029f --- /dev/null +++ b/dbcs/__init__.py @@ -0,0 +1,2 @@ +import os +DBC_PATH = os.path.dirname(os.path.abspath(__file__)) diff --git a/dbcs/acura_ilx_2016_can.dbc b/dbcs/acura_ilx_2016_can.dbc new file mode 100644 index 0000000000..87c201d117 --- /dev/null +++ b/dbcs/acura_ilx_2016_can.dbc @@ -0,0 +1,295 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BO_ 0x039 XXX: 3 XXX + +BO_ 0x091 XXX: 8 XXX + SG_ LAT_ACCEL : 0|10@1+ (0.02,-512) [-20|20] "m/s2" Vector__XXX + +BO_ 0x0E4 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 0|16@1- (1,0) [-3840|3840] "" Vector__XXX + SG_ STEER_TORQUE_REQUEST : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X00 : 17|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ SET_ME_X00 : 24|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x130 GAS_PEDAL2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 0|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ ENGINE_TORQUE_REQUEST : 16|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x13C GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x156 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 0|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ STEER_ANGLE_RATE : 16|16@1- (1,0) [-3000|3000] "deg/s" Vector__XXX + SG_ COUNTER : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 44|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x158 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 0|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ XMISSION_SPEED2 : 32|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x17C POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ GAS_PRESSED : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_STATUS : 33|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH_17C : 34|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_LIGHTS_ON : 39|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH2_17C : 40|10@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_PRESSED : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH3_17C : 51|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x18E XXX: 3 XXX + +BO_ 0x18F STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 0|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_TORQUE_MOTOR : 16|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_STATUS : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ STEER_CONTROL_ACTIVE : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A3 GEARBOX: 8 PCM + SG_ GEAR : 0|8@1+ (1,0) [0|256] "" Vector__XXX + SG_ GEAR_SHIFTER : 36|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A4 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 0|16@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ ESP_DISABLED : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A6 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 0|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ LIGHTS_SETTING : 6|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ MAIN_ON : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_SETTING : 44|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1AC XXX: 8 XXX + +BO_ 0x1B0 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_1 : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_2 : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D0 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 0|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_FR : 15|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RL : 30|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RR : 45|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1DC XXX: 4 XXX + +BO_ 0x1EA VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 16|16@1- (0.0015384,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x1FA BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 0|10@1+ (0.003906248,0) [0|1] "" Vector__XXX + SG_ ZEROS_BOH : 10|5@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH2 : 16|3@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_OVERRIDE : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH3 : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_FAULT_CMD : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_CANCEL_CMD : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST_2 : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH4 : 24|8@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_LIGHTS : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH5 : 33|7@1+ (1,0) [0|1] "" Vector__XXX + SG_ CHIME : 40|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ CRUISE_BOH6 : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCW : 44|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_BOH7 : 46|10@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x200 GAS_COMMAND: 3 ADAS + SG_ GAS_COMMAND : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ COUNTER : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 20|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x201 GAS_SENSOR: 5 ADAS + SG_ INTERCEPTOR_GAS : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ INTERCEPTOR_GAS2 : 16|16@1+ (0.126992032,-656) [0|1] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x21E XXX: 7 XXX +BO_ 0x221 XXX: 4 XXX + +BO_ 0x255 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 0|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_FR : 8|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RL : 16|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RR : 24|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ SET_TO_X55 : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SET_TO_X55 : 40|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x294 SCM_COMMANDS: 8 SCM + SG_ RIGHT_BLINKER : 1|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LEFT_BLINKER : 2|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ WIPERS_SPEED : 3|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x305 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SEATBELT_DRIVER_LATCHED : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x309 XXX: 8 XXX + +BO_ 0x30C ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 0|16@1+ (0.002763889,0) [0|100] "m/s" Vector__XXX + SG_ PCM_GAS : 16|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ ZEROS_BOH : 23|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ DTC_MODE : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_PROBLEM : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_OFF : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH_2 : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_PROBLEM : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RADAR_OBSTRUCTED : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ENABLE_MINI_CAR : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X03 : 40|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_LEAD : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_3 : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_4 : 45|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_5 : 46|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_CONTROL_LABEL : 47|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_DISTANCE_3 : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x320 XXX: 8 XXX + +BO_ 0x324 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 8|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ TRIP_FUEL_CONSUMED : 16|16@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED_PCM : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH2 : 40|8@1- (1,0) [0|255] "" Vector__XXX + SG_ BOH3 : 48|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x328 XXX: 8 XXX +BO_ 0x333 XXX: 7 XXX +BO_ 0x335 XXX: 5 XXX + +BO_ 0x33D LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 0|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 1|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ DASHED_LANES : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DTC : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_PROBLEM : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_OFF : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SOLID_LANES : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_RIGHT : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STEERING_REQUIRED : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 16|2@1+ (1,0) [0|4] "" Vector__XXX + SG_ LDW_PROBLEM : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BEEP : 22|2@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_OFF : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CLEAN_WINDSHIELD : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X48 : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + + +BO_ 0x372 XXX: 2 XXX + +BO_ 0x374 XXX: 7 XXX +BO_ 0x377 XXX: 8 XXX +BO_ 0x378 XXX: 8 XXX +BO_ 0x37C XXX: 8 XXX +BO_ 0x39B XXX: 2 XXX +BO_ 0x3A1 XXX: 4 XXX +BO_ 0x3D7 XXX: 8 XXX +BO_ 0x3D9 XXX: 3 XXX +BO_ 0x400 XXX: 5 XXX +BO_ 0x403 XXX: 5 XXX + +BO_ 0x405 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RL : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RR : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x406 XXX: 5 VSA +BO_ 0x40A XXX: 5 XXX +BO_ 0x40C XXX: 8 XXX +BO_ 0x40F XXX: 8 XXX +BO_ 0x421 XXX: 5 EPS +BO_ 0x428 XXX: 7 XXX +BO_ 0x454 XXX: 8 XXX +BO_ 0x555 XXX: 5 XXX +BO_ 0x640 XXX: 5 XXX +BO_ 0x641 XXX: 8 XXX + +VAL_ 0x1A6 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 0x1A6 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 0x30C HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 0x1A6 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights"; +VAL_ 0x18F STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal"; +VAL_ 0x1A3 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P"; +VAL_ 0x33D BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 0x1FA CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 0x1FA FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; + +CM_ SG_ 0x1A3 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 0x324 CRUISE_SPEED_ECHO "255 = no speed"; +CM_ SG_ 0x33D CRUISE_SPEED "255 = no speed"; +CM_ SG_ 0x1EA LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 0x33D BEEP "beeps are pleasant, chimes are for warnngs etc..."; diff --git a/dbcs/acura_ilx_2016_nidec.dbc b/dbcs/acura_ilx_2016_nidec.dbc new file mode 100644 index 0000000000..70105e38e2 --- /dev/null +++ b/dbcs/acura_ilx_2016_nidec.dbc @@ -0,0 +1,175 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + + +BO_ 0x300 VEHICLE_STATE: 8 ADAS + SG_ SET_ME_XF9 : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ VEHICLE_SPEED : 8|8@1+ (1,0) [0|255] "kph" Vector__XXX + +BO_ 0x301 VEHICLE_STATE2: 8 ADAS + SG_ SET_ME_0F18510 : 0|28@1+ (1,0) [0|268435455] "" Vector__XXX + SG_ SET_ME_25A0000 : 28|28@1+ (1,0) [0|268435455] "" Vector__XXX + +BO_ 0x400 XXX: 8 RADAR + +BO_ 0x410 XXX: 8 RADAR + +BO_ 0x411 XXX: 8 RADAR + +BO_ 0x412 XXX: 8 RADAR + +BO_ 0x413 XXX: 8 RADAR + +BO_ 0x414 XXX: 8 RADAR + +BO_ 0x415 XXX: 8 RADAR + +BO_ 0x416 XXX: 8 RADAR + +BO_ 0x417 XXX: 8 RADAR + +BO_ 0x420 XXX: 8 RADAR + +BO_ 0x421 XXX: 8 RADAR + +BO_ 0x422 XXX: 8 RADAR + +BO_ 0x423 XXX: 8 RADAR + +BO_ 0x424 XXX: 8 RADAR + +BO_ 0x430 TRACK_0: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x431 TRACK_1: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x432 TRACK_2: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x433 TRACK_3: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x434 TRACK_4: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x435 TRACK_5: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x436 TRACK_6: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x437 TRACK_7: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x438 TRACK_8: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x439 TRACK_9: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x440 TRACK_10: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x441 TRACK_11: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x442 TRACK_12: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x443 TRACK_13: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x444 TRACK_14: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x445 TRACK_15: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x4FF XXX: 8 RADAR + +BO_ 0x500 XXX: 8 RADAR + +BO_ 0x510 XXX: 8 RADAR + +BO_ 0x511 XXX: 8 RADAR diff --git a/dbcs/honda_civic_touring_2016_can.dbc b/dbcs/honda_civic_touring_2016_can.dbc new file mode 100644 index 0000000000..3ba510c44b --- /dev/null +++ b/dbcs/honda_civic_touring_2016_can.dbc @@ -0,0 +1,319 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BO_ 0x039 XXX: 3 XXX + +BO_ 0x94 XXX: 8 XXX + SG_ LAT_ACCEL : 0|10@1+ (0.02,-512) [-20|20] "m/s2" Vector__XXX + SG_ LONG_ACCEL : 31|9@1- (-0.02,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x0E4 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 0|16@1- (1,0) [-3840|3840] "" Vector__XXX + SG_ STEER_TORQUE_REQUEST : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X00 : 17|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ SET_ME_X00_2 : 24|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ CHECKSUM : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 38|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x130 GAS_PEDAL2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 0|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ ENGINE_TORQUE_REQUEST : 16|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x14A STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 0|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ STEER_ANGLE_RATE : 16|16@1- (-1,0) [-3000|3000] "deg/s" Vector__XXX + SG_ STEER_ANGLE_OFFSET : 32|8@1- (-0.1,0) [-128|127] "deg" Vector__XXX + SG_ STEER_WHEEL_ANGLE : 40|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x158 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 0|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ XMISSION_SPEED2 : 32|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x17C POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ GAS_PRESSED : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_STATUS : 33|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH_17C : 34|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_LIGHTS_ON : 39|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH2_17C : 40|10@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_PRESSED : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH3_17C : 51|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x18F STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 0|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_TORQUE_MOTOR : 16|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_STATUS : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ STEER_CONTROL_ACTIVE : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x191 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 2|6@1+ (1,0) [0|63] "" Vector__XXX + SG_ GEAR : 36|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A4 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 0|16@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ ESP_DISABLED : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1AB XXX: 3 VSA + +BO_ 0x1AC XXX: 8 XXX + +BO_ 0x1B0 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_1 : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_2 : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1C2 XXX: 8 EPB + SG_ EPB_ACTIVE : 4|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_STATE : 26|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D0 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 0|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_FR : 15|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RL : 30|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RR : 45|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D6 XXX: 2 VSA + +BO_ 0x1DC XXX: 7 XXX + +BO_ 0x1E7 XXX: 4 VSA + SG_ BRAKE_PRESSURE1 : 0|10@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ BRAKE_PRESSURE2 : 14|10@1+ (0.015625,-103) [0|1000] "" Vector__XXX + +BO_ 0x1EA VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 16|16@1- (0.0015384,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x1ED XXX: 5 VSA + +BO_ 0x1FA BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 0|10@1+ (0.003906248,0) [0|1.0] "" Vector__XXX + SG_ ZEROS_BOH : 10|5@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH2 : 16|3@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_OVERRIDE : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH3 : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_FAULT_CMD : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_CANCEL_CMD : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST_2 : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_0X80 : 24|8@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_LIGHTS : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_STATES : 33|7@1+ (1,0) [0|1] "" Vector__XXX + SG_ CHIME : 40|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ ZEROS_BOH6 : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCW : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ ZEROS_BOH3 : 45|2@1+ (1,0) [0|0] "" Vector__XXX + SG_ FCW2 : 47|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ ZEROS_BOH4 : 48|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x200 GAS_COMMAND: 3 ADAS + SG_ GAS_COMMAND : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ COUNTER : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 20|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x201 GAS_SENSOR: 5 ADAS + SG_ INTERCEPTOR_GAS : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ INTERCEPTOR_GAS2 : 16|16@1+ (0.126992032,-656) [0|1] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x221 XXX: 6 XXX + +BO_ 0x255 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 0|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_FR : 8|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RL : 16|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RR : 24|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ SET_TO_X55 : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SET_TO_X55 : 40|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x296 CRUISE_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 0|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ CRUISE_SETTING : 4|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x305 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SEATBELT_DRIVER_LATCHED : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x309 XXX: 8 XXX + +BO_ 0x30C ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 0|16@1+ (0.002763889,0) [0|100] "m/s" Vector__XXX + SG_ PCM_GAS : 16|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ ZEROS_BOH : 23|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ DTC_MODE : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_PROBLEM : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_OFF : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH_2 : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_PROBLEM : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RADAR_OBSTRUCTED : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ENABLE_MINI_CAR : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HUD_DISTANCE : 40|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_LEAD : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_3 : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_4 : 45|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_5 : 46|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_CONTROL_LABEL : 47|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x31B XXX: 8 XXX + +BO_ 0x320 XXX: 8 XXX + +BO_ 0x324 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 8|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ TRIP_FUEL_CONSUMED : 16|16@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED_PCM : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH2 : 40|8@1- (1,0) [0|255] "" Vector__XXX + SG_ BOH3 : 48|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x326 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 17|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ MAIN_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RIGHT_BLINKER : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LEFT_BLINKER : 29|1@1+ (1,0) [0|1] "" Vector__XXX + + +BO_ 0x328 XXX: 8 XXX + +BO_ 0x33D LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 0|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 1|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ DASHED_LANES : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DTC : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_PROBLEM : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_OFF : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SOLID_LANES : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_RIGHT : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STEERING_REQUIRED : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 16|2@1+ (1,0) [0|4] "" Vector__XXX + SG_ LDW_PROBLEM : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BEEP : 22|2@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_OFF : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CLEAN_WINDSHIELD : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X48 : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x35E XXX: 8 ADAS + SG_ UI_ALERTS : 0|56@1+ (1,0) [0|127] "" Vector__XXX + +BO_ 0x374 XXX: 8 XXX +BO_ 0x37B XXX: 8 XXX +BO_ 0x37C XXX: 8 XXX + +BO_ 0x39F XXX: 8 ADAS + SG_ ZEROS_BOH : 0|17@1+ (1,0) [0|127] "" Vector__XXX + SG_ APPLY_BRAKES_FOR_CANC : 16|1@1+ (1,0) [0|15] "" Vector__XXX + SG_ ZEROS_BOH2 : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RESUME_INSTRUCTION : 18|1@1+ (1,0) [0|15] "" Vector__XXX + SG_ ACC_ALERTS : 19|5@1+ (1,0) [0|15] "" Vector__XXX + SG_ ZEROS_BOH2 : 24|8@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_SPEED : 32|9@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_STATE : 41|3@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_DISTANCE : 44|5@1+ (1,0) [0|31] "" Vector__XXX + SG_ ZEROS_BOH3 : 49|7@1+ (1,0) [0|127] "" Vector__XXX + +BO_ 0x3A1 XXX: 8 XXX +BO_ 0x3D9 XXX: 3 XXX +BO_ 0x400 XXX: 5 XXX +BO_ 0x403 XXX: 5 XXX + +BO_ 0x405 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RL : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RR : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x40C XXX: 8 XXX +BO_ 0x40F XXX: 8 XXX +BO_ 0x454 XXX: 8 XXX +BO_ 0x516 XXX: 8 XXX +BO_ 0x52A XXX: 5 XXX +BO_ 0x551 XXX: 5 XXX +BO_ 0x555 XXX: 5 XXX +BO_ 0x590 XXX: 5 XXX +BO_ 0x640 XXX: 5 XXX +BO_ 0x641 XXX: 8 XXX +BO_ 0x661 XXX: 8 XXX + +VAL_ 0x296 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 0x296 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 0x33D HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 0x1A6 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights"; +VAL_ 0x18F STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal"; +VAL_ 0x191 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P"; +VAL_ 0x33D BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 0x1FA CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 0x1C2 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged"; +VAL_ 0x326 CMBS_BUTTON 3 "pressed" 0 "released"; +VAL_ 0x39F ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead"; +VAL_ 0x30C CRUISE_SPEED 255 "no_speed" 252 "stopped"; + +CM_ SG_ 0x1A3 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 0x324 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 0x30C CRUISE_SPEED "255 = no speed"; +CM_ SG_ 0x1EA LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 0x33D BEEP "beeps are pleasant, chimes are for warnngs etc..."; diff --git a/installation/files/continue.sh b/installation/files/continue.sh new file mode 100755 index 0000000000..2030d907a9 --- /dev/null +++ b/installation/files/continue.sh @@ -0,0 +1,28 @@ +#!/usr/bin/bash + +# enable wifi access point for debugging only! +#service call wifi 37 i32 0 i32 1 # WifiService.setWifiApEnabled(null, true) + +# use the openpilot ro key +export GIT_SSH_COMMAND="ssh -i /data/data/com.termux/files/id_rsa_openpilot_ro" + +# check out the openpilot repo +# TODO: release branch only +if [ ! -d /data/openpilot ]; then + cd /tmp + git clone git@github.com:commaai/openpilot.git + mv /tmp/openpilot /data/openpilot +fi + +# update the openpilot repo +cd /data/openpilot +git pull + +# start manager +cd selfdrive +mkdir -p /sdcard/realdata +PYTHONPATH=/data/openpilot ./manager.py + +# if broken, keep on screen error +while true; do sleep 1; done + diff --git a/installation/files/id_rsa_openpilot_ro b/installation/files/id_rsa_openpilot_ro new file mode 100644 index 0000000000..de98cabe17 --- /dev/null +++ b/installation/files/id_rsa_openpilot_ro @@ -0,0 +1,27 @@ +-----BEGIN RSA PRIVATE KEY----- +MIIEpAIBAAKCAQEAy/ZlYE/iHHjhbSvCnBm5Zsq5GPpVugLXFHai/doqyfRxErop +/g1TIRhzK3mkHRYRN7H0L9whogwoIVr5CldoxU49FDnNbVHNimScNrL4LprRWjq6 +dRmCVoxMpLHZTyX1jIkcHsMr7klcUnssyeQO2pWvZv0ZC67wM7G20r7+ZLdEa0Ck +MBh8JYhDaZx2xvYtTnt6vKMmFVE5+zW/+wDVma3a4r9pG9s0+r0wCl8CUuJ+yDhR +mzNkPJ5mJCMx99AI6k4Gq9Vsng8/35b6Azh3TucPaXOLK7yPnL3YBKUa0PpR7IRH ++OKkVCH+LL7tcPFSqPPVy/pUTBdEUROjJdSHxwIDAQABAoIBAQCxBgUM56h3T89Q +AoghFg6dkdu/Ox8GmAp231UuAJncuMUfHObvcj8xXVgwZp4zBIEjFte6ZlPmoqh9 +8sht2lm7zeEjWdvbQwGjWRlgPEs9n++OYaSNl/tRBOpMk3Ppxydst1/prznE0nVH +vVKtU7w0qXAYchm30zj1lQv5s/12CTGmnpQatbo5X488RfCfv2zFX1h+lEWF8ycL +eZRi8z6l8h2Y+JLyEwPCmR+gR6XtosZ/ECQcTknavqLqdr7NbYYfOo3JfHCUtpJa +8s7m0VFhMuxFFCl1sV0eMzAynJYNVz45DyaKpr2b/2YAGY8fn96FxaWv1xw1xTkK +c5+wStwJAoGBAOjQpLZ1qGa4GwXzeHoDsGFpGgY9ug6af0M23c8O42fJHAwYkk7r +Qeo4SSBddoSfo3jdchFLo59+m3qyTKpjkph7NBBCEwaCvX3heStDIMZEWX0IOV5y +iJD/D6EXSqFmXCUUaudX2OxlaHguA0yOEx9s/5uUJrvaIHbBAOpYyar1AoGBAOBG +MJp+EA3e1Zx/VszD2Tdxn8V0DAwvy9WIEqZuG689S/Sk5GnA4m2L8Txv0xAHFvLv +JpF7Zn9AoFXGpjf9P0FF53cpjEYn9f+uK84j1HOL/6R7Nj9rcS5yL2PCP1ZHymw6 +xOXl3oZa1YtYE6jfvXUaOb8Z7y8gaStP763sXmpLAoGBAM1WSBANUcvXES58gIPN +ASHJGwTqKFF8/kV//L4EuZjuDWi1u0UTxX0Yy5ZaGI/8ZKfTWCnc9qFTfzoGTAvz +6nXGJDM6s6EIaqy90qrPd/amje7y8/ZTOhP4ggZojpAvwZGKoocMOey1vCBTJOG+ +ZStQbVkAn/EK/5r9uxr12FiJAoGAH9UWlPcLpExamWnhkhLCRAJWoRoFk708+0Pj +EchTGZ5jp4e3++KqwM26Ic/lb0LyWOzk1oVjWPB9UW9urEe/sK4RWnKFPHfzjKTW +Bt5DC1t1n4z1eC7x05vVah1qC/8IljAJPnBQE1XVNX/82l1XcMWWKK+vqUq6YrFn +3ZHNHN0CgYA3uUVWqW37vfJuk0MJBkQSqMo5Y5TPlCt4b1ebkdhlM4v/N+iuiPiC +PBhjP1MLeudkJvzllt4YvNWLerCKpMWuw7Zvy5uzFEsqOrVlzfnyWqqqYbYjHe9f +Ef0/yXKuGJajs54Ts6Xrm0+elVUu//pEuf6NI96Ehctqz8/BqGqAtw== +-----END RSA PRIVATE KEY----- diff --git a/installation/install.sh b/installation/install.sh new file mode 100755 index 0000000000..011e2c187f --- /dev/null +++ b/installation/install.sh @@ -0,0 +1,11 @@ +#!/bin/bash +set -e + +# move files into place +adb push files/id_rsa_openpilot_ro /tmp/id_rsa_openpilot_ro +adb shell mv /tmp/id_rsa_openpilot_ro /data/data/com.termux/files/ + +# moving continue into place runs the continue script +adb push files/continue.sh /tmp/continue.sh +adb shell mv /tmp/continue.sh /data/data/com.termux/files/ + diff --git a/phonelibs/hierarchy/lib/_hierarchy.so b/phonelibs/hierarchy/lib/_hierarchy.so new file mode 100755 index 0000000000..d4d2d17889 --- /dev/null +++ b/phonelibs/hierarchy/lib/_hierarchy.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:bb7a23963ff80018961778bc2946da9a027ba3ed15658af91cfd9fdadad7e384 +size 772536 diff --git a/phonelibs/nanovg/fontstash.h b/phonelibs/nanovg/fontstash.h new file mode 100644 index 0000000000..ea07a71556 --- /dev/null +++ b/phonelibs/nanovg/fontstash.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b41c3a15854c04c566e4306f96ecc7b67a8d299ec78b52ae002786b955a59f04 +size 47001 diff --git a/phonelibs/nanovg/nanovg.c b/phonelibs/nanovg/nanovg.c new file mode 100644 index 0000000000..9589b27c09 --- /dev/null +++ b/phonelibs/nanovg/nanovg.c @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8905156d392d6f296e4ace097fd4ae81346fd007447a8dbbd593f27bc3395cb7 +size 75203 diff --git a/phonelibs/nanovg/nanovg.h b/phonelibs/nanovg/nanovg.h new file mode 100644 index 0000000000..92fd6c1ceb --- /dev/null +++ b/phonelibs/nanovg/nanovg.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d7e279756b2a87a99641125f9eb169ce0efc40ec197a633db5969c9b0c3d5312 +size 27692 diff --git a/phonelibs/nanovg/nanovg_gl.h b/phonelibs/nanovg/nanovg_gl.h new file mode 100644 index 0000000000..fdf5b66cf9 --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:4fb9a04f0e678418ad15f0ea013fbb02be50b75f0b3d59ab3f150a440869bd67 +size 44596 diff --git a/phonelibs/nanovg/nanovg_gl_utils.h b/phonelibs/nanovg/nanovg_gl_utils.h new file mode 100644 index 0000000000..317133bfea --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl_utils.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fce2de44fb1d6304105f24a995f92593ebb778a43db85174f5e6c12a30c4f23f +size 4255 diff --git a/phonelibs/nanovg/stb_image.h b/phonelibs/nanovg/stb_image.h new file mode 100644 index 0000000000..9837bc16aa --- /dev/null +++ b/phonelibs/nanovg/stb_image.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:19e32991baf7fc7e29bad10e83aef9afbbd41b56115b04fed69d3e57d69b383a +size 227413 diff --git a/phonelibs/nanovg/stb_truetype.h b/phonelibs/nanovg/stb_truetype.h new file mode 100644 index 0000000000..7d7473949f --- /dev/null +++ b/phonelibs/nanovg/stb_truetype.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aed9de6af844809b66449fc112937a72e1f9a7b9e3f8c7df7d4be8e098d6960f +size 127284 diff --git a/selfdrive/__init__.py b/selfdrive/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/assets/Roboto-Bold.ttf b/selfdrive/assets/Roboto-Bold.ttf new file mode 100644 index 0000000000..5ff22906a6 --- /dev/null +++ b/selfdrive/assets/Roboto-Bold.ttf @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ef2ab0e402d5cb9de893e263a2c44e57f57fec3974b0d981bfe84dec3dae83a1 +size 162464 diff --git a/selfdrive/assets/courbd.ttf b/selfdrive/assets/courbd.ttf new file mode 100644 index 0000000000..437654f3d6 --- /dev/null +++ b/selfdrive/assets/courbd.ttf @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:89cff1ff9e59a661ba947500e9c242506e2dbf36c0417783dea8b762e13da704 +size 710192 diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile new file mode 100644 index 0000000000..4e0c00c6c7 --- /dev/null +++ b/selfdrive/boardd/Makefile @@ -0,0 +1,73 @@ +CC = clang +CXX = clang++ + +ARCH := $(shell uname -m) + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +EXTRA_LIBS = -lusb + +ifeq ($(ARCH),x86_64) +ZMQ_LIBS = -L$(HOME)/drive/external/zmq/lib/ \ + -l:libczmq.a -l:libzmq.a +CEREAL_LIBS = -L$(HOME)/drive/external/capnp/lib/ \ + -l:libcapnp.a -l:libkj.a +EXTRA_LIBS = -lusb-1.0 -lpthread +endif + + +OBJS = boardd.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: boardd + +boardd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + $(EXTRA_LIBS) + +boardd.o: boardd.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + + +.PHONY: clean +clean: + rm -f boardd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/boardd/__init__.py b/selfdrive/boardd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc new file mode 100644 index 0000000000..da3b458943 --- /dev/null +++ b/selfdrive/boardd/boardd.cc @@ -0,0 +1,322 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/timing.h" + +int do_exit = 0; + +libusb_context *ctx = NULL; +libusb_device_handle *dev_handle; +pthread_mutex_t usb_lock; + +// double the FIFO size +#define RECV_SIZE (0x1000) +#define TIMEOUT 0 + +#define DEBUG_BOARDD +#ifdef DEBUG_BOARDD +#define DPRINTF(fmt, ...) printf("boardd: " fmt, ## __VA_ARGS__) +#else +#define DPRINTF(fmt, ...) +#endif + +bool usb_connect() { + int err; + + dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); + if (dev_handle == NULL) { return false; } + + err = libusb_set_configuration(dev_handle, 1); + if (err != 0) { return false; } + + err = libusb_claim_interface(dev_handle, 0); + if (err != 0) { return false; } + + return true; +} + + +void handle_usb_issue(int err, const char func[]) { + DPRINTF("usb error %d \"%s\" in %s\n", err, libusb_strerror((enum libusb_error)err), func); + if (err == -4) { + while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } + } + // TODO: check other errors, is simply retrying okay? +} + +void can_recv(void *s) { + int err; + uint32_t data[RECV_SIZE/4]; + int recv; + uint32_t f1, f2; + + // do recv + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); + if (err != 0) { handle_usb_issue(err, __func__); } + if (err == -8) { DPRINTF("overflow got 0x%x\n", recv); }; + + // timeout is okay to exit, recv still happened + if (err == -7) { break; } + } while(err != 0); + + pthread_mutex_unlock(&usb_lock); + + // return if length is 0 + if (recv <= 0) { + return; + } + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto canData = event.initCan(recv/0x10); + + // populate message + for (int i = 0; i<(recv/0x10); i++) { + if (data[i*4] & 4) { + // extended + canData[i].setAddress(data[i*4] >> 3); + //printf("got extended: %x\n", data[i*4] >> 3); + } else { + // normal + canData[i].setAddress(data[i*4] >> 21); + } + canData[i].setBusTime(data[i*4+1] >> 16); + int len = data[i*4+1]&0xF; + canData[i].setDat(kj::arrayPtr((uint8_t*)&data[i*4+2], len)); + canData[i].setSrc((data[i*4+1] >> 4) & 3); + } + + // send to can + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + +void can_health(void *s) { + int cnt; + + // copied from board/main.c + struct health { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + } health; + + // recv from board + pthread_mutex_lock(&usb_lock); + + do { + cnt = libusb_control_transfer(dev_handle, 0xc0, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), TIMEOUT); + if (cnt != sizeof(health)) { handle_usb_issue(cnt, __func__); } + } while(cnt != sizeof(health)); + + pthread_mutex_unlock(&usb_lock); + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto healthData = event.initHealth(); + + // set fields + healthData.setVoltage(health.voltage); + healthData.setCurrent(health.current); + healthData.setStarted(health.started); + healthData.setControlsAllowed(health.controls_allowed); + healthData.setGasInterceptorDetected(health.gas_interceptor_detected); + + // send to health + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + + +void can_send(void *s) { + int err; + + // recv from sendcan + zmq_msg_t msg; + zmq_msg_init(&msg); + err = zmq_msg_recv(&msg, s, 0); + assert(err >= 0); + + // format for board + auto amsg = kj::arrayPtr((const capnp::word*)zmq_msg_data(&msg), zmq_msg_size(&msg)); + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + int msg_count = event.getCan().size(); + + uint32_t *send = (uint32_t*)malloc(msg_count*0x10); + memset(send, 0, msg_count*0x10); + + for (int i = 0; i < msg_count; i++) { + auto cmsg = event.getCan()[i]; + if (cmsg.getAddress() >= 0x800) { + // extended + send[i*4] = (cmsg.getAddress() << 3) | 5; + } else { + // normal + send[i*4] = (cmsg.getAddress() << 21) | 1; + } + assert(cmsg.getDat().size() <= 8); + send[i*4+1] = cmsg.getDat().size() | (cmsg.getSrc() << 4); + memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); + } + + //DPRINTF("got send message: %d\n", msg_count); + + // release msg + zmq_msg_close(&msg); + + // send to board + int sent; + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); + if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); } + } while(err != 0); + + pthread_mutex_unlock(&usb_lock); + + // done + free(send); +} + + +// **** threads **** + +void *can_send_thread(void *crap) { + DPRINTF("start send thread\n"); + + // sendcan = 8017 + void *context = zmq_ctx_new(); + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8017"); + + // run as fast as messages come in + while (!do_exit) { + can_send(subscriber); + } + return NULL; +} + +void *can_recv_thread(void *crap) { + DPRINTF("start recv thread\n"); + + // can = 8006 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8006"); + + // run at ~200hz + while (!do_exit) { + can_recv(publisher); + // 5ms + usleep(5*1000); + } + return NULL; +} + +void *can_health_thread(void *crap) { + DPRINTF("start health thread\n"); + + // health = 8011 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8011"); + + // run at 1hz + while (!do_exit) { + can_health(publisher); + usleep(1000*1000); + } + return NULL; +} + +int main() { + int err; + printf("boardd: starting boardd\n"); + + // set process priority + err = setpriority(PRIO_PROCESS, 0, -4); + printf("boardd: setpriority returns %d\n", err); + + // connect to the board + err = libusb_init(&ctx); + assert(err == 0); + libusb_set_debug(ctx, 3); + + // TODO: duplicate code from error handling + while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } + + /*int config; + err = libusb_get_configuration(dev_handle, &config); + assert(err == 0); + DPRINTF("configuration is %d\n", config);*/ + + /*err = libusb_set_interface_alt_setting(dev_handle, 0, 0); + assert(err == 0);*/ + + // create threads + + pthread_t can_health_thread_handle; + err = pthread_create(&can_health_thread_handle, NULL, + can_health_thread, NULL); + assert(err == 0); + + pthread_t can_send_thread_handle; + err = pthread_create(&can_send_thread_handle, NULL, + can_send_thread, NULL); + assert(err == 0); + + pthread_t can_recv_thread_handle; + err = pthread_create(&can_recv_thread_handle, NULL, + can_recv_thread, NULL); + assert(err == 0); + + // join threads + + err = pthread_join(can_recv_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_send_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_health_thread_handle, NULL); + assert(err == 0); + + // destruct libusb + + libusb_close(dev_handle); + libusb_exit(ctx); +} + diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py new file mode 100755 index 0000000000..50d4aacc6e --- /dev/null +++ b/selfdrive/boardd/boardd.py @@ -0,0 +1,179 @@ +#!/usr/bin/env python +import os +import struct +import zmq + +import selfdrive.messaging as messaging +from common.realtime import Ratekeeper +from common.services import service_list +from selfdrive.swaglog import cloudlog + +# USB is optional +try: + import usb1 + from usb1 import USBErrorIO, USBErrorOverflow +except Exception: + pass + +# TODO: rewrite in C to save CPU + +# *** serialization functions *** +def can_list_to_can_capnp(can_msgs): + dat = messaging.new_message() + dat.init('can', len(can_msgs)) + for i, can_msg in enumerate(can_msgs): + dat.can[i].address = can_msg[0] + dat.can[i].busTime = can_msg[1] + dat.can[i].dat = can_msg[2] + dat.can[i].src = can_msg[3] + return dat + +def can_capnp_to_can_list_old(dat, src_filter=[]): + ret = [] + for msg in dat.can: + if msg.src in src_filter: + ret.append([msg.address, msg.busTime, msg.dat.encode("hex")]) + return ret + +def can_capnp_to_can_list(dat): + ret = [] + for msg in dat.can: + ret.append([msg.address, msg.busTime, msg.dat, msg.src]) + return ret + +# *** can driver *** +def can_health(): + while 1: + try: + dat = handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd2, 0, 0, 0x10) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD HEALTH, RETRYING") + v, i, started = struct.unpack("IIB", dat[0:9]) + # TODO: units + return {"voltage": v, "current": i, "started": bool(started)} + +def __parse_can_buffer(dat): + ret = [] + for j in range(0, len(dat), 0x10): + ddat = dat[j:j+0x10] + f1, f2 = struct.unpack("II", ddat[0:8]) + ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&3)) + return ret + +def can_send_many(arr): + snds = [] + for addr, _, dat, alt in arr: + snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat + snd = snd.ljust(0x10, '\x00') + snds.append(snd) + while 1: + try: + handle.bulkWrite(3, ''.join(snds)) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD SEND MANY, RETRYING") + +def can_recv(): + dat = "" + while 1: + try: + dat = handle.bulkRead(1, 0x10*256) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD RECV, RETRYING") + return __parse_can_buffer(dat) + +def can_init(): + global handle, context + cloudlog.info("attempting can init") + + context = usb1.USBContext() + #context.setDebug(9) + + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: + handle = device.open() + handle.claimInterface(0) + + if handle is None: + print "CAN NOT FOUND" + exit(-1) + + print "got handle" + cloudlog.info("can init done") + +def boardd_mock_loop(): + context = zmq.Context() + can_init() + + logcan = messaging.sub_sock(context, service_list['can'].port) + + while 1: + tsc = messaging.drain_sock(logcan, wait_for_one=True) + snds = map(can_capnp_to_can_list, tsc) + snd = [] + for s in snds: + snd += s + snd = filter(lambda x: x[-1] <= 1, snd) + can_send_many(snd) + + # recv @ 100hz + can_msgs = can_recv() + print "sent %d got %d" % (len(snd), len(can_msgs)) + + #print can_msgs + +# *** main loop *** +def boardd_loop(rate=200): + rk = Ratekeeper(rate) + context = zmq.Context() + + can_init() + + # *** publishes can and health + logcan = messaging.pub_sock(context, service_list['can'].port) + health_sock = messaging.pub_sock(context, service_list['health'].port) + + # *** subscribes to can send + sendcan = messaging.sub_sock(context, service_list['sendcan'].port) + + while 1: + # health packet @ 1hz + if (rk.frame%rate) == 0: + health = can_health() + msg = messaging.new_message() + msg.init('health') + + # store the health to be logged + msg.health.voltage = health['voltage'] + msg.health.current = health['current'] + msg.health.started = health['started'] + + health_sock.send(msg.to_bytes()) + + # recv @ 100hz + can_msgs = can_recv() + + # publish to logger + # TODO: refactor for speed + if len(can_msgs) > 0: + dat = can_list_to_can_capnp(can_msgs) + logcan.send(dat.to_bytes()) + + # send can if we have a packet + tsc = messaging.recv_sock(sendcan) + if tsc is not None: + can_send_many(can_capnp_to_can_list(tsc)) + + rk.keep_time() + +def main(gctx=None): + if os.getenv("MOCK") is not None: + boardd_mock_loop() + else: + boardd_loop() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/calibrationd/__init__.py b/selfdrive/calibrationd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/calibrationd/calibration.py b/selfdrive/calibrationd/calibration.py new file mode 100644 index 0000000000..cd5daa6ff4 --- /dev/null +++ b/selfdrive/calibrationd/calibration.py @@ -0,0 +1,208 @@ +import numpy as np + +import common.filters as filters +from selfdrive.controls.lib.latcontrol import calc_curvature + + +# Calibration Status +class CalibStatus(object): + INCOMPLETE = 0 + VALID = 1 + INVALID = 2 + + +def line_intersection(line1, line2, no_int_sub = [0,0]): + xdiff = (line1[0][0] - line1[1][0], line2[0][0] - line2[1][0]) + ydiff = (line1[0][1] - line1[1][1], line2[0][1] - line2[1][1]) + + def det(a, b): + return a[0] * b[1] - a[1] * b[0] + + div = det(xdiff, ydiff) + if div == 0: + # since we are in float domain, this should really never happen + return no_int_sub + + d = (det(*line1), det(*line2)) + x = det(d, xdiff) / div + y = det(d, ydiff) / div + return [x, y] + +def points_inside_hit_box(pts, box): + """Determine which points lie inside a box. + + Inputs: + pts: An nx2 array of points to hit test. + box: An array [[x_left, y_top], [x_right, y_bottom]] describing a box to + use for hit testing. + Returns: + A logical array with true for every member of pts inside box. + """ + hits = np.all(np.logical_and(pts > box[0, :], pts < box[1, :]), axis=1) + return hits + +def warp_points(pt_s, warp_matrix): + # pt_s are the source points, nx2 array. + pt_d = np.dot(warp_matrix[:, :2], pt_s.T) + warp_matrix[:, 2][:, np.newaxis] + + # divide by third dimension for representation in image space. + return (pt_d[:2, :] / pt_d[2, :]).T + +class ViewCalibrator(object): + def __init__(self, box_size, big_box_size, vp_r, warp_matrix_start, vp_f=None, cal_cycle=0, cal_status=0): + self.calibration_threshold = 3000 + self.box_size = box_size + self.big_box_size = big_box_size + + self.warp_matrix_start = warp_matrix_start + self.vp_r = list(vp_r) + + if vp_f is None: + self.vp_f = list(vp_r) + else: + self.vp_f = list(vp_f) + + # slow filter fot the vanishing point + vp_fr = 0.005 # Hz, slow filter + self.dt = 0.05 # camera runs at 20Hz + + self.update_warp_matrix() + + self.vp_x_filter = filters.FirstOrderLowpassFilter(vp_fr, self.dt, self.vp_f[0]) + self.vp_y_filter = filters.FirstOrderLowpassFilter(vp_fr, self.dt, self.vp_f[1]) + + self.cal_cycle = cal_cycle + self.cal_status = cal_status + self.cal_perc = int(np.minimum(self.cal_cycle*100./self.calibration_threshold, 100)) + + def vanishing_point_process(self, old_ps, new_ps, v_ego, steer_angle, VP): + # correct diffs by yaw rate + cam_fov = 23.06*np.pi/180. # deg + curvature = calc_curvature(v_ego, steer_angle, VP) + yaw_rate = curvature * v_ego + hor_angle_shift = yaw_rate * self.dt * self.box_size[0] / cam_fov + old_ps += [hor_angle_shift, 0] # old points have moved in the image due to yaw rate + + pos_ps = [None]*len(new_ps) + for ii in range(len(old_ps)): + xo = old_ps[ii][0] + yo = old_ps[ii][1] + yn = new_ps[ii][1] + + # don't consider points with low flow in y + if abs(yn - yo) > 1: + if xo > (self.vp_f[0] + 20): + pos_ps[ii] = 'r' # right lane point + elif xo < (self.vp_f[0] - 20): + pos_ps[ii] = 'l' # left lane point + + # intersect all the right lines with the left lines + idxs_l = [i for i, x in enumerate(pos_ps) if x == 'l'] + idxs_r = [i for i, x in enumerate(pos_ps) if x == 'r'] + + old_ps_l, new_ps_l = old_ps[idxs_l], new_ps[idxs_l] + old_ps_r, new_ps_r = old_ps[idxs_r], new_ps[idxs_r] + # return None if there is one side with no lines, the speed is low or the steer angle is high + if len(old_ps_l) == 0 or len(old_ps_r) == 0 or v_ego < 20 or abs(steer_angle) > 5: + return None + + int_ps = [[None] * len(old_ps_r)] * len(old_ps_l) + for ll in range(len(old_ps_l)): + for rr in range(len(old_ps_r)): + old_p_l, old_p_r, new_p_l, new_p_r = old_ps_l[ll], old_ps_r[ + rr], new_ps_l[ll], new_ps_r[rr] + line_l = [[old_p_l[0], old_p_l[1]], [new_p_l[0], new_p_l[1]]] + line_r = [[old_p_r[0], old_p_r[1]], [new_p_r[0], new_p_r[1]]] + int_ps[ll][rr] = line_intersection( + line_l, line_r, no_int_sub=self.vp_f) + # saturate outliers that are too far from the estimated vp + int_ps[ll][rr][0] = np.clip(int_ps[ll][rr][0], self.vp_f[0] - 20, self.vp_f[0] + 20) + int_ps[ll][rr][1] = np.clip(int_ps[ll][rr][1], self.vp_f[1] - 30, self.vp_f[1] + 30) + vp = np.mean(np.mean(np.array(int_ps), axis=0), axis=0) + + return vp + + def calibration_validity(self): + # this function sanity checks that the small box is contained in the big box. + # otherwise the warp function will generate black spots on the small box + cp = np.asarray([[0, 0], + [self.box_size[0], 0], + [self.box_size[0], self.box_size[1]], + [0, self.box_size[1]]]) + + cpw = warp_points(cp, self.warp_matrix) + + # pixel margin for validity hysteresys: + # - if calibration is good, keep it good until small box is inside the big box + # - if calibration isn't good, then make it good again if small box is in big box with margin + margin_px = 0 if self.cal_status == CalibStatus.VALID else 5 + big_hit_box = np.asarray( + [[margin_px, margin_px], + [self.big_box_size[0], self.big_box_size[1] - margin_px]]) + + cpw_outside_big_box = np.logical_not(points_inside_hit_box(cpw, big_hit_box)) + return not np.any(cpw_outside_big_box) + + + def get_calibration_hit_box(self): + """Returns an axis-aligned hit box in canonical image space. + Points which do not fall within this box should not be used for + calibration. + + Returns: + An array [[x_left, y_top], [x_right, y_bottom]] describing a box inside + which all calibration points should lie. + """ + # We mainly care about feature from lanes, so removed points from sky. + y_filter = 50. + return np.asarray([[0, y_filter], [self.box_size[0], self.box_size[1]]]) + + + def update_warp_matrix(self): + translation_matrix = np.asarray( + [[1, 0, self.vp_f[0] - self.vp_r[0]], + [0, 1, self.vp_f[1] - self.vp_r[1]], + [0, 0, 1]]) + self.warp_matrix = np.dot(translation_matrix, self.warp_matrix_start) + self.warp_matrix_inv = np.linalg.inv(self.warp_matrix) + + def calibration(self, p0, p1, st, v_ego, steer_angle, VP): + # convert to np array first thing + p0 = np.asarray(p0) + p1 = np.asarray(p1) + st = np.asarray(st) + + p0 = p0.reshape((-1,2)) + p1 = p1.reshape((-1,2)) + + # filter out pts with bad status + p0 = p0[st==1] + p1 = p1[st==1] + + calib_hit_box = self.get_calibration_hit_box() + # remove all the points outside the small box and above the horizon line + good_idxs = points_inside_hit_box( + warp_points(p0, self.warp_matrix_inv), calib_hit_box) + p0 = p0[good_idxs] + p1 = p1[good_idxs] + + # print("unwarped points: {}".format(warp_points(p0, self.warp_matrix_inv))) + # print("good_idxs {}:".format(good_idxs)) + + # get instantaneous vp + vp = self.vanishing_point_process(p0, p1, v_ego, steer_angle, VP) + + if vp is not None: + # filter the vanishing point + self.vp_f = [self.vp_x_filter(vp[0]), self.vp_y_filter(vp[1])] + self.cal_cycle += 1 + + if not self.calibration_validity(): + self.cal_status = CalibStatus.INVALID + else: + # 10 minutes @5Hz TODO: make this threshold function of convergency speed + self.cal_status = CalibStatus.VALID + #self.cal_status = CalibStatus.VALID if self.cal_cycle > self.calibration_threshold else CalibStatus.INCOMPLETE + self.cal_perc = int(np.minimum(self.cal_cycle*100./self.calibration_threshold, 100)) + + self.update_warp_matrix() diff --git a/selfdrive/calibrationd/calibrationd.py b/selfdrive/calibrationd/calibrationd.py new file mode 100755 index 0000000000..779cb4723f --- /dev/null +++ b/selfdrive/calibrationd/calibrationd.py @@ -0,0 +1,116 @@ +#!/usr/bin/env python +import os +import numpy as np +import zmq + +from common.services import service_list +import selfdrive.messaging as messaging +from selfdrive.config import ImageParams, VehicleParams +from selfdrive.calibrationd.calibration import ViewCalibrator, CalibStatus + +CALIBRATION_FILE = "/sdcard/calibration_param" + +def load_calibration(gctx): + # calibration initialization + I = ImageParams() + vp_guess = None + + if gctx is not None: + warp_matrix_start = np.array( + gctx['calibration']["initial_homography"]).reshape(3, 3) + big_box_size = [560, 304] + else: + warp_matrix_start = np.array([[1., 0., I.SX_R], + [0., 1., I.SY_R], + [0., 0., 1.]]) + big_box_size = [640, 480] + + # translate the vanishing point into phone image space + vp_box = (I.VPX_R-I.SX_R, I.VPY_R-I.SY_R) + vp_trans = np.dot(warp_matrix_start, vp_box+(1.,)) + vp_img = (vp_trans[0]/vp_trans[2], vp_trans[1]/vp_trans[2]) + + # load calibration data + if os.path.isfile(CALIBRATION_FILE): + # if the calibration file exist, start from the last cal values + with open(CALIBRATION_FILE, "r") as cal_file: + data = [float(l.strip()) for l in cal_file.readlines()] + calib = ViewCalibrator((I.X, I.Y), + big_box_size, + vp_img, + warp_matrix_start, + vp_f=[data[2], data[3]], + cal_cycle=data[0], + cal_status=data[1]) + + if calib.cal_status == CalibStatus.INCOMPLETE: + print "CALIBRATION IN PROGRESS", calib.cal_cycle + else: + print "NO CALIBRATION FILE" + calib = ViewCalibrator((I.X, I.Y), + big_box_size, + vp_img, + warp_matrix_start, + vp_f=vp_guess) + + return calib + +def calibrationd_thread(gctx): + context = zmq.Context() + + features = messaging.sub_sock(context, service_list['features'].port) + live100 = messaging.sub_sock(context, service_list['live100'].port) + + livecalibration = messaging.pub_sock(context, service_list['liveCalibration'].port) + + # subscribe to stats about the car + VP = VehicleParams(False) + + v_ego = None + + calib = load_calibration(gctx) + last_cal_cycle = calib.cal_cycle + + while 1: + # calibration at the end so it does not delay radar processing above + ft = messaging.recv_sock(features, wait=True) + + # get latest here + l100 = messaging.recv_sock(live100) + if l100 is not None: + v_ego = l100.live100.vEgo + steer_angle = l100.live100.angleSteers + + if v_ego is None: + continue + + p0 = ft.features.p0 + p1 = ft.features.p1 + st = ft.features.status + + calib.calibration(p0, p1, st, v_ego, steer_angle, VP) + + # write a new calibration every 100 cal cycle + if calib.cal_cycle - last_cal_cycle >= 100: + print "writing cal", calib.cal_cycle + with open(CALIBRATION_FILE, "w") as cal_file: + cal_file.write(str(calib.cal_cycle)+'\n') + cal_file.write(str(calib.cal_status)+'\n') + cal_file.write(str(calib.vp_f[0])+'\n') + cal_file.write(str(calib.vp_f[1])+'\n') + last_cal_cycle = calib.cal_cycle + + warp_matrix = map(float, calib.warp_matrix.reshape(9).tolist()) + dat = messaging.new_message() + dat.init('liveCalibration') + dat.liveCalibration.warpMatrix = warp_matrix + dat.liveCalibration.calStatus = calib.cal_status + dat.liveCalibration.calCycle = calib.cal_cycle + dat.liveCalibration.calPerc = calib.cal_perc + livecalibration.send(dat.to_bytes()) + +def main(gctx=None): + calibrationd_thread(gctx) + +if __name__ == "__main__": + main() diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc new file mode 100644 index 0000000000..4b13b644d4 --- /dev/null +++ b/selfdrive/common/framebuffer.cc @@ -0,0 +1,135 @@ + +#include +#include +#include + +#include + +#include +#include +#include + + +#include +#include + +#define BACKLIGHT_CONTROL "/sys/class/leds/lcd-backlight/brightness" +#define BACKLIGHT_LEVEL "205" + +using namespace android; + +struct FramebufferState { + sp session; + sp dtoken; + DisplayInfo dinfo; + sp control; + + sp s; + EGLDisplay display; + + EGLint egl_major, egl_minor; + EGLConfig config; + EGLSurface surface; + EGLContext context; +}; + +extern "C" FramebufferState* framebuffer_init( + const char* name, int32_t layer, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h) { + status_t status; + int success; + + FramebufferState *s = new FramebufferState; + + s->session = new SurfaceComposerClient(); + assert(s->session != NULL); + + s->dtoken = SurfaceComposerClient::getBuiltInDisplay( + ISurfaceComposer::eDisplayIdMain); + assert(s->dtoken != NULL); + + status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo); + assert(status == 0); + + int orientation = 3; // rotate framebuffer 270 degrees + if(orientation == 1 || orientation == 3) { + int temp = s->dinfo.h; + s->dinfo.h = s->dinfo.w; + s->dinfo.w = temp; + } + + printf("dinfo %dx%d\n", s->dinfo.w, s->dinfo.h); + + Rect destRect(s->dinfo.w, s->dinfo.h); + s->session->setDisplayProjection(s->dtoken, orientation, destRect, destRect); + + s->control = s->session->createSurface(String8(name), + s->dinfo.w, s->dinfo.h, PIXEL_FORMAT_RGBX_8888); + assert(s->control != NULL); + + SurfaceComposerClient::openGlobalTransaction(); + status = s->control->setLayer(layer); + SurfaceComposerClient::closeGlobalTransaction(); + assert(status == 0); + + s->s = s->control->getSurface(); + assert(s->s != NULL); + + // init opengl and egl + const EGLint attribs[] = { + EGL_RED_SIZE, 8, + EGL_GREEN_SIZE, 8, + EGL_BLUE_SIZE, 8, + EGL_DEPTH_SIZE, 0, + EGL_STENCIL_SIZE, 8, + EGL_RENDERABLE_TYPE, EGL_OPENGL_ES3_BIT_KHR, + EGL_NONE, + }; + + s->display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(s->display != EGL_NO_DISPLAY); + + success = eglInitialize(s->display, &s->egl_major, &s->egl_minor); + assert(success); + + printf("egl version %d.%d\n", s->egl_major, s->egl_minor); + + EGLint num_configs; + success = eglChooseConfig(s->display, attribs, &s->config, 1, &num_configs); + assert(success); + + s->surface = eglCreateWindowSurface(s->display, s->config, s->s.get(), NULL); + assert(s->surface != EGL_NO_SURFACE); + + const EGLint context_attribs[] = { + EGL_CONTEXT_CLIENT_VERSION, 3, + EGL_NONE, + }; + s->context = eglCreateContext(s->display, s->config, NULL, context_attribs); + assert(s->context != EGL_NO_CONTEXT); + + EGLint w, h; + eglQuerySurface(s->display, s->surface, EGL_WIDTH, &w); + eglQuerySurface(s->display, s->surface, EGL_HEIGHT, &h); + printf("egl w %d h %d\n", w, h); + + success = eglMakeCurrent(s->display, s->surface, s->surface, s->context); + assert(success); + + printf("gl version %s\n", glGetString(GL_VERSION)); + + + // set brightness + int brightness_fd = open(BACKLIGHT_CONTROL, O_RDWR); + const char brightness_level[] = BACKLIGHT_LEVEL; + write(brightness_fd, brightness_level, strlen(brightness_level)); + + + if (out_display) *out_display = s->display; + if (out_surface) *out_surface = s->surface; + if (out_w) *out_w = w; + if (out_h) *out_h = h; + + return s; +} diff --git a/selfdrive/common/framebuffer.h b/selfdrive/common/framebuffer.h new file mode 100644 index 0000000000..cac8590398 --- /dev/null +++ b/selfdrive/common/framebuffer.h @@ -0,0 +1,21 @@ +#ifndef FRAMEBUFFER_H +#define FRAMEBUFFER_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct FramebufferState FramebufferState; + +FramebufferState* framebuffer_init( + const char* name, int32_t layer, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h); + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/mat.h b/selfdrive/common/mat.h new file mode 100644 index 0000000000..f429b0c5d3 --- /dev/null +++ b/selfdrive/common/mat.h @@ -0,0 +1,68 @@ +#ifndef COMMON_MAT_H +#define COMMON_MAT_H + +typedef struct vec3 { + float v[3]; +} vec3; + +typedef struct vec4 { + float v[4]; +} vec4; + +typedef struct mat3 { + float v[3*3]; +} mat3; + +typedef struct mat4 { + float v[4*4]; +} mat4; + +static inline mat3 matmul3(const mat3 a, const mat3 b) { + mat3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + float v = 0.0; + for (int k=0; k<3; k++) { + v += a.v[r*3+k] * b.v[k*3+c]; + } + ret.v[r*3+c] = v; + } + } + return ret; +} + +static inline vec3 matvecmul3(const mat3 a, const vec3 b) { + vec3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + ret.v[r] += a.v[r*3+c] * b.v[c]; + } + } + return ret; +} + +static inline mat4 matmul(const mat4 a, const mat4 b) { + mat4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + float v = 0.0; + for (int k=0; k<4; k++) { + v += a.v[r*4+k] * b.v[k*4+c]; + } + ret.v[r*4+c] = v; + } + } + return ret; +} + +static inline vec4 matvecmul(const mat4 a, const vec4 b) { + vec4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + ret.v[r] += a.v[r*4+c] * b.v[c]; + } + } + return ret; +} + +#endif diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h new file mode 100644 index 0000000000..521767775f --- /dev/null +++ b/selfdrive/common/modeldata.h @@ -0,0 +1,23 @@ +#ifndef MODELDATA_H +#define MODELDATA_H + +typedef struct PathData { + float points[50]; + float prob; + float std; +} PathData; + +typedef struct LeadData { + float dist; + float prob; + float std; +} LeadData; + +typedef struct ModelData { + PathData path; + PathData left_lane; + PathData right_lane; + LeadData lead; +} ModelData; + +#endif diff --git a/selfdrive/common/mutex.h b/selfdrive/common/mutex.h new file mode 100644 index 0000000000..ef01359357 --- /dev/null +++ b/selfdrive/common/mutex.h @@ -0,0 +1,13 @@ +#ifndef COMMON_MUTEX_H +#define COMMON_MUTEX_H + +#include + +static inline void mutex_init_reentrant(pthread_mutex_t *mutex) { + pthread_mutexattr_t attr; + pthread_mutexattr_init(&attr); + pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE); + pthread_mutex_init(mutex, &attr); +} + +#endif diff --git a/selfdrive/common/swaglog.c b/selfdrive/common/swaglog.c new file mode 100644 index 0000000000..8fc64aed8e --- /dev/null +++ b/selfdrive/common/swaglog.c @@ -0,0 +1,90 @@ +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "common/timing.h" + +#include "swaglog.h" + +typedef struct LogState { + pthread_mutex_t lock; + bool inited; + JsonNode *ctx_j; + void *zctx; + void *sock; +} LogState; + +static LogState s = { + .lock = PTHREAD_MUTEX_INITIALIZER, +}; + +static void cloudlog_init() { + if (s.inited) return; + s.ctx_j = json_mkobject(); + s.zctx = zmq_ctx_new(); + s.sock = zmq_socket(s.zctx, ZMQ_PUSH); + zmq_connect(s.sock, "ipc:///tmp/logmessage"); + s.inited = true; +} + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, + const char* fmt, ...) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + + char* msg_buf = NULL; + va_list args; + va_start(args, fmt); + vasprintf(&msg_buf, fmt, args); + va_end(args); + + if (!msg_buf) { + pthread_mutex_unlock(&s.lock); + return; + } + + if (levelnum >= CLOUDLOG_PRINT_LEVEL) { + printf("%s: %s\n", filename, msg_buf); + } + + JsonNode *log_j = json_mkobject(); + assert(log_j); + + json_append_member(log_j, "msg", json_mkstring(msg_buf)); + json_append_member(log_j, "ctx", s.ctx_j); + json_append_member(log_j, "levelnum", json_mknumber(levelnum)); + json_append_member(log_j, "filename", json_mkstring(filename)); + json_append_member(log_j, "lineno", json_mknumber(lineno)); + json_append_member(log_j, "funcname", json_mkstring(func)); + json_append_member(log_j, "srctime", json_mkstring(srctime)); + json_append_member(log_j, "created", json_mknumber(seconds_since_epoch())); + + char* log_s = json_encode(log_j); + assert(log_s); + + json_remove_from_parent(s.ctx_j); + + json_delete(log_j); + free(msg_buf); + + char levelnum_c = levelnum; + zmq_send(s.sock, &levelnum_c, 1, ZMQ_NOBLOCK | ZMQ_SNDMORE); + zmq_send(s.sock, log_s, strlen(log_s), ZMQ_NOBLOCK); + free(log_s); + + pthread_mutex_unlock(&s.lock); +} + +void cloudlog_bind(const char* k, const char* v) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + json_append_member(s.ctx_j, k, json_mkstring(v)); + pthread_mutex_unlock(&s.lock); +} diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h new file mode 100644 index 0000000000..50b01da66f --- /dev/null +++ b/selfdrive/common/swaglog.h @@ -0,0 +1,26 @@ +#ifndef SWAGLOG_H +#define SWAGLOG_H + +#define CLOUDLOG_DEBUG 10 +#define CLOUDLOG_INFO 20 +#define CLOUDLOG_WARNING 30 +#define CLOUDLOG_ERROR 40 +#define CLOUDLOG_CRITICAL 50 + +#define CLOUDLOG_PRINT_LEVEL CLOUDLOG_WARNING + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, + const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; + +void cloudlog_bind(const char* k, const char* v); + +#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ + __func__, __DATE__ " " __TIME__, \ + fmt, ## __VA_ARGS__) + +#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#endif diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h new file mode 100644 index 0000000000..f682c35dee --- /dev/null +++ b/selfdrive/common/timing.h @@ -0,0 +1,31 @@ +#ifndef COMMON_TIMING_H +#define COMMON_TIMING_H + +#include +#include + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double millis_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000.0 + t.tv_nsec / 1000000.0; +} + +static inline uint64_t nanos_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double seconds_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return (double)t.tv_sec + t.tv_nsec / 1000000000.0; +} + +#endif diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h new file mode 100644 index 0000000000..3bf3e9e387 --- /dev/null +++ b/selfdrive/common/util.h @@ -0,0 +1,22 @@ +#ifndef COMMON_UTIL_H +#define COMMON_UTIL_H + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#define clamp(a,b,c) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + __typeof__ (c) _c = (c); \ + _a < _b ? _b : (_a > _c ? _c : _a); }) + +#define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) + +#endif diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c new file mode 100644 index 0000000000..44463b4c94 --- /dev/null +++ b/selfdrive/common/visionipc.c @@ -0,0 +1,127 @@ +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "visionipc.h" + +typedef struct VisionPacketWire { + int type; + VisionPacketData d; +} VisionPacketWire; + +int vipc_connect() { + int err; + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + assert(sock >= 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + .sun_path = VIPC_SOCKET_PATH, + }; + err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (err != 0) { + close(sock); + return -1; + } + + return sock; +} + +static int sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds) { + int err; + + char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; + memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); + + struct iovec iov = { + .iov_base = buf, + .iov_len = buf_size, + }; + struct msghdr msg = { + .msg_iov = &iov, + .msg_iovlen = 1, + }; + + if (num_fds > 0) { + assert(fds); + + msg.msg_control = control_buf; + msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); + } + + if (send) { + if (num_fds) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + cmsg->cmsg_level = SOL_SOCKET; + cmsg->cmsg_type = SCM_RIGHTS; + cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); + memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); + // printf("send clen %d -> %d\n", num_fds, cmsg->cmsg_len); + } + return sendmsg(fd, &msg, 0); + } else { + int r = recvmsg(fd, &msg, 0); + if (r < 0) return r; + + int recv_fds = 0; + if (msg.msg_controllen > 0) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); + recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); + assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); + recv_fds /= sizeof(int); + // printf("recv clen %d -> %d\n", cmsg->cmsg_len, recv_fds); + // assert(cmsg->cmsg_len == CMSG_LEN(sizeof(int) * num_fds)); + + assert(fds && recv_fds <= num_fds); + memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); + } + + if (msg.msg_flags) { + for (int i=0; i 950 for t in cpu_temps) + + # *** getting model logic *** + PP.update(cur_time, CS.v_ego) + + if rk.frame % 5 == 2: + # *** run this at 20hz again *** + angle_offset = learn_angle_offset(enabled, CS.v_ego, angle_offset, np.asarray(PP.d_poly), LaC.y_des, CS.steer_override) + + # to avoid race conditions, check if control has been disabled for at least 0.2s + mismatch_ctrl = not CC.controls_allowed and enabled + mismatch_pcm = (not CS.pcm_acc_status and (not apply_brake or CS.v_ego < 0.1)) and enabled + + # keep resetting start timer if mismatch isn't true + if not mismatch_ctrl: + no_mismatch_ctrl_last = cur_time + if not mismatch_pcm or not CS.brake_only: + no_mismatch_pcm_last = cur_time + + #*** v_cruise logic *** + if CS.brake_only: + v_cruise = int(CS.v_cruise_pcm) # TODO: why sometimes v_cruise_pcm is long type? + else: + if CS.prev_cruise_buttons == 0 and CS.cruise_buttons == CruiseButtons.RES_ACCEL and enabled: + v_cruise = v_cruise - (v_cruise % v_cruise_delta) + v_cruise_delta + elif CS.prev_cruise_buttons == 0 and CS.cruise_buttons == CruiseButtons.DECEL_SET and enabled: + v_cruise = v_cruise + (v_cruise % v_cruise_delta) - v_cruise_delta + + # *** enabling/disabling logic *** + enable_pressed = (CS.prev_cruise_buttons == CruiseButtons.DECEL_SET or CS.prev_cruise_buttons == CruiseButtons.RES_ACCEL) \ + and CS.cruise_buttons == 0 + + if enable_pressed: + print "enabled pressed at", cur_time + last_enable_pressed = cur_time + + # if pcm does speed control than we need to wait on pcm to enable + if CS.brake_only: + enable_condition = (cur_time - last_enable_pressed) < 0.2 and CS.pcm_acc_status + else: + enable_condition = enable_pressed + + # always clear the alert at every cycle + alert_id = [] + + # check for PCM not enabling + if CS.brake_only and (cur_time - last_enable_pressed) < 0.2 and not CS.pcm_acc_status: + print "waiting for PCM to enable" + + # check for denied enabling + if enable_pressed and not enabled: + deny_enable = \ + [(AI.SEATBELT, not CS.seatbelt), + (AI.DOOR_OPEN, not CS.door_all_closed), + (AI.ESP_OFF, CS.esp_disabled), + (AI.STEER_ERROR, CS.steer_error), + (AI.BRAKE_ERROR, CS.brake_error), + (AI.GEAR_NOT_D, not CS.gear_shifter_valid), + (AI.MAIN_OFF, not CS.main_on), + (AI.PEDAL_PRESSED, CS.user_gas_pressed or CS.brake_pressed or (CS.pedal_gas > 0 and CS.brake_only)), + (AI.HIGH_SPEED, CS.v_ego > max_enable_speed), + (AI.OVERHEAT, overtemp), + (AI.COMM_ISSUE, PP.dead or AC.dead), + (AI.CONTROLSD_LAG, rk.remaining < -0.2)] + for alertn, cond in deny_enable: + if cond: + alert_id += [alertn] + + # check for soft disables + if enabled: + soft_disable = \ + [(AI.SEATBELT_SD, not CS.seatbelt), + (AI.DOOR_OPEN_SD, not CS.door_all_closed), + (AI.ESP_OFF_SD, CS.esp_disabled), + (AI.OVERHEAT_SD, overtemp), + (AI.COMM_ISSUE_SD, PP.dead or AC.dead), + (AI.CONTROLSD_LAG_SD, rk.remaining < -0.2)] + sounding = False + for alertn, cond in soft_disable: + if cond: + alert_id += [alertn] + sounding = True + # soft disengagement expired, user need to take control + if (cur_time - soft_disable_start) > 3.: + enabled = False + v_cruise = 255 + if not sounding: + soft_disable_start = cur_time + + # check for immediate disables + if enabled: + immediate_disable = \ + [(AI.PCM_LOW_SPEED, (cur_time > no_mismatch_pcm_last > 0.2) and CS.v_ego < pcm_threshold), + (AI.STEER_ERROR_ID, CS.steer_error), + (AI.BRAKE_ERROR_ID, CS.brake_error), + (AI.CTRL_MISMATCH_ID, (cur_time - no_mismatch_ctrl_last) > 0.2), + (AI.PCM_MISMATCH_ID, (cur_time - no_mismatch_pcm_last) > 0.2)] + for alertn, cond in immediate_disable: + if cond: + alert_id += [alertn] + # immediate turn off control + enabled = False + v_cruise = 255 + + # user disabling + if enabled and (CS.user_gas_pressed or CS.brake_pressed or not CS.gear_shifter_valid or \ + (CS.cruise_buttons == CruiseButtons.CANCEL and CS.prev_cruise_buttons == 0) or \ + not CS.main_on or (CS.pedal_gas > 0 and CS.brake_only)): + enabled = False + v_cruise = 255 + alert_id += [AI.DISABLE] + + # enabling + if enable_condition and not enabled and len(alert_id) == 0: + print "*** enabling controls" + + #enable both lateral and longitudinal controls + enabled = True + counter_pcm_enabled = CS.counter_pcm + # on activation, let's always set v_cruise from where we are, even if PCM ACC is active + # what we want to be displayed in mph + v_cruise_mph = round(CS.v_ego * CV.MS_TO_MPH * CS.ui_speed_fudge) + # what we need to send to have that displayed + v_cruise = int(round(np.maximum(v_cruise_mph * CV.MPH_TO_KPH, v_cruise_enable_min))) + + # 6 minutes driver you're on + awareness_status = 1.0 + + # reset the PID loops + LaC.reset() + # start long control at actual speed + LoC.reset(v_pid = CS.v_ego) + + alert_id += [AI.ENABLE] + + if v_cruise != 255 and not CS.brake_only: + v_cruise = np.clip(v_cruise, v_cruise_min, v_cruise_max) + + # **** awareness status manager **** + if enabled: + # gives the user 6 minutes + awareness_status -= 1.0/(100*60*6) + # reset on steering, blinker, or cruise buttons + if CS.steer_override or CS.blinker_on or CS.cruise_buttons or CS.cruise_setting: + awareness_status = 1.0 + if awareness_status <= 0.: + alert_id += [AI.DRIVER_DISTRACTED] + + # ****** initial actuators commands *** + # *** gas/brake PID loop *** + AC.update(cur_time, CS.v_ego, CS.angle_steers, LoC.v_pid, awareness_status, CS.VP) + final_gas, final_brake = LoC.update(enabled, CS, v_cruise, AC.v_target_lead, AC.a_target, AC.jerk_factor) + pcm_accel = int(np.clip(AC.a_pcm/1.4,0,1)*0xc6) # TODO: perc of max accel in ACC? + + # *** steering PID loop *** + final_steer, sat_flag = LaC.update(enabled, CS, PP.d_poly, angle_offset) + + # this needs to stay before hysteresis logic to avoid pcm staying on control during brake hysteresis + pcm_override = True # this is always True + pcm_cancel_cmd = False + if CS.brake_only and final_brake == 0.: + pcm_speed = LoC.v_pid - .3 # FIXME: just for exp + else: + pcm_speed = 0 + + # ***** handle alerts **** + # send a "steering required alert" if saturation count has reached the limit + if sat_flag: + alert_id += [AI.STEER_SATURATED] + + # process the alert, based on id + alert, chime, beep, hud_alert, alert_text, sound_exp, hud_exp, text_exp, alert_p = \ + process_alert(alert_id, alert, cur_time, sound_exp, hud_exp, text_exp, alert_p) + + # alerts pub + if len(alert_id) != 0: + print alert_id, alert_text + + # *** process for hud display *** + if not enabled or (hud_v_cruise == 255 and CS.counter_pcm == counter_pcm_enabled): + hud_v_cruise = 255 + else: + hud_v_cruise = v_cruise + + # *** actually do can sends *** + CC.update(sendcan, enabled, CS, rk.frame, \ + final_gas, final_brake, final_steer, \ + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + hud_v_cruise, hud_show_lanes = enabled, \ + hud_show_car = AC.has_lead, \ + hud_alert = hud_alert, \ + snd_beep = beep, snd_chime = chime) + + # ***** publish state to logger ***** + + # publish controls state at 100Hz + dat = messaging.new_message() + dat.init('live100') + + # move liveUI into live100 + dat.live100.rearViewCam = bool(rear_view_cam) + dat.live100.alertText1 = alert_text[0] + dat.live100.alertText2 = alert_text[1] + dat.live100.awarenessStatus = max(awareness_status, 0.0) if enabled else 0.0 + + # what packets were used to process + dat.live100.canMonoTimes = canMonoTimes + dat.live100.mdMonoTime = PP.logMonoTime + dat.live100.l20MonoTime = AC.logMonoTime + + # if controls is enabled + dat.live100.enabled = enabled + + # car state + dat.live100.vEgo = float(CS.v_ego) + dat.live100.aEgo = float(CS.a_ego) + dat.live100.angleSteers = float(CS.angle_steers) + dat.live100.hudLead = CS.hud_lead + dat.live100.steerOverride = CS.steer_override + + # longitudinal control state + dat.live100.vPid = float(LoC.v_pid) + dat.live100.vCruise = float(v_cruise) + dat.live100.upAccelCmd = float(LoC.Up_accel_cmd) + dat.live100.uiAccelCmd = float(LoC.Ui_accel_cmd) + + # lateral control state + dat.live100.yActual = float(LaC.y_actual) + dat.live100.yDes = float(LaC.y_des) + dat.live100.upSteer = float(LaC.Up_steer) + dat.live100.uiSteer = float(LaC.Ui_steer) + + # processed radar state, should add a_pcm? + dat.live100.vTargetLead = float(AC.v_target_lead) + dat.live100.aTargetMin = float(AC.a_target[0]) + dat.live100.aTargetMax = float(AC.a_target[1]) + dat.live100.jerkFactor = float(AC.jerk_factor) + + # lag + dat.live100.cumLagMs = -rk.remaining*1000. + + live100.send(dat.to_bytes()) + + # *** run loop at fixed rate *** + rk.keep_time() + +def main(gctx=None): + controlsd_thread(gctx, 100) + +if __name__ == "__main__": + main() diff --git a/selfdrive/controls/lib/__init__.py b/selfdrive/controls/lib/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/controls/lib/adaptivecruise.py b/selfdrive/controls/lib/adaptivecruise.py new file mode 100644 index 0000000000..bf940e0e1b --- /dev/null +++ b/selfdrive/controls/lib/adaptivecruise.py @@ -0,0 +1,332 @@ +import selfdrive.messaging as messaging +import numpy as np + +# lookup tables VS speed to determine min and max accels in cruise +_A_CRUISE_MIN_V = np.asarray([-1.0, -.8, -.67, -.5, -.30]) +_A_CRUISE_MIN_BP = np.asarray([ 0., 5., 10., 20., 40.]) + +# need fast accel at very low speed for stop and go +_A_CRUISE_MAX_V = np.asarray([1., 1., .8, .5, .30]) +_A_CRUISE_MAX_BP = np.asarray([0., 5., 10., 20., 40.]) + +def calc_cruise_accel_limits(v_ego): + a_cruise_min = np.interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) + a_cruise_max = np.interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V) + + a_pcm = 1. # always 1 for now + return np.vstack([a_cruise_min, a_cruise_max]), a_pcm + +_A_TOTAL_MAX_V = np.asarray([1.5, 1.9, 3.2]) +_A_TOTAL_MAX_BP = np.asarray([0., 20., 40.]) + +def limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP): + #*** this function returns a limited long acceleration allowed, depending on the existing lateral acceleration + # this should avoid accelerating when losing the target in turns + deg_to_rad = np.pi / 180. # from can reading to rad + + a_total_max = np.interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) + a_y = v_ego**2 * angle_steers * deg_to_rad / (VP.steer_ratio * VP.wheelbase) + a_x_allowed = np.sqrt(np.maximum(a_total_max**2 - a_y**2, 0.)) + + a_target[1] = np.minimum(a_target[1], a_x_allowed) + a_pcm = np.minimum(a_pcm, a_x_allowed) + return a_target, a_pcm + +def process_a_lead(a_lead): + # soft threshold of 0.5m/s^2 applied to a_lead to reject noise, also not considered positive a_lead + a_lead_threshold = 0.5 + a_lead = np.minimum(a_lead + a_lead_threshold, 0) + return a_lead + +def calc_desired_distance(v_lead): + #*** compute desired distance *** + t_gap = 1.7 # good to be far away + d_offset = 4 # distance when at zero speed + return d_offset + v_lead * t_gap + + +#linear slope +_L_SLOPE_V = np.asarray([0.40, 0.10]) +_L_SLOPE_BP = np.asarray([0., 40]) + +# parabola slope +_P_SLOPE_V = np.asarray([1.0, 0.25]) +_P_SLOPE_BP = np.asarray([0., 40]) + +def calc_desired_speed(d_lead, d_des, v_lead, a_lead): + #*** compute desired speed *** + # the desired speed curve is divided in 4 portions: + # 1-constant + # 2-linear to regain distance + # 3-linear to shorten distance + # 4-parabolic (constant decel) + + max_runaway_speed = -2. # no slower than 2m/s over the lead + + # interpolate the lookups to find the slopes for a give lead speed + l_slope = np.interp(v_lead, _L_SLOPE_BP, _L_SLOPE_V) + p_slope = np.interp(v_lead, _P_SLOPE_BP, _P_SLOPE_V) + + # this is where parabola and linear curves are tangents + x_linear_to_parabola = p_slope / l_slope**2 + + # parabola offset to have the parabola being tangent to the linear curve + x_parabola_offset = p_slope / (2 * l_slope**2) + + if d_lead < d_des: + # calculate v_rel_des on the line that connects 0m at max_runaway_speed to d_des + v_rel_des_1 = (- max_runaway_speed) / d_des * (d_lead - d_des) + # calculate v_rel_des on one third of the linear slope + v_rel_des_2 = (d_lead - d_des) * l_slope / 3. + # take the min of the 2 above + v_rel_des = np.minimum(v_rel_des_1, v_rel_des_2) + v_rel_des = np.maximum(v_rel_des, max_runaway_speed) + elif d_lead < d_des + x_linear_to_parabola: + v_rel_des = (d_lead - d_des) * l_slope + v_rel_des = np.maximum(v_rel_des, max_runaway_speed) + else: + v_rel_des = np.sqrt(2 * (d_lead - d_des - x_parabola_offset) * p_slope) + + # compute desired speed + v_target = v_rel_des + v_lead + + # compute v_coast: above this speed we want to coast + t_lookahead = 1. # how far in time we consider a_lead to anticipate the coast region + v_coast_shift = np.maximum(a_lead * t_lookahead, - v_lead) # don't consider projections that would make v_lead<0 + v_coast = (v_lead + v_target)/2 + v_coast_shift # no accel allowed above this line + v_coast = np.minimum(v_coast, v_target) + + return v_target, v_coast + +def calc_critical_decel(d_lead, v_rel, d_offset, v_offset): + # this function computes the required decel to avoid crashing, given safety offsets + a_critical = - np.maximum(0., v_rel + v_offset)**2/np.maximum(2*(d_lead - d_offset), 0.5) + return a_critical + + +# maximum acceleration adjustment +_A_CORR_BY_SPEED_V = np.asarray([0.4, 0.4, 0]) +# speeds +_A_CORR_BY_SPEED_BP = np.asarray([0., 5., 20.]) + +def calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_ref, v_rel_ref, v_coast, v_target, a_lead_contr, a_max): + a_coast_min = -1.0 # never coast faster then -1m/s^2 + # coasting behavior above v_coast. Forcing a_max to be negative will force the pid_speed to decrease, + # regardless v_target + if v_ref > np.minimum(v_coast, v_target): + # for smooth coast we can be agrressive and target a point where car would actually crash + v_offset_coast = 0. + d_offset_coast = d_des/2. - 4. + + # acceleration value to smoothly coast until we hit v_target + if d_lead > d_offset_coast + 0.1: + a_coast = calc_critical_decel(d_lead, v_rel_ref, d_offset_coast, v_offset_coast) + # if lead is decelerating, then offset the coast decel + a_coast += a_lead_contr + a_max = np.maximum(a_coast, a_coast_min) + else: + a_max = a_coast_min + else: + # same as cruise accel, but add a small correction based on lead acceleration at low speeds + # when lead car accelerates faster, we can do the same, and vice versa + + a_max = a_max + np.interp(v_ego, _A_CORR_BY_SPEED_BP, _A_CORR_BY_SPEED_V) \ + * np.clip(-v_rel / 4., -.5, 1) + return a_max + +# arbitrary limits to avoid too high accel being computed +_A_SAT = np.asarray([-10., 5.]) + +# do not consider a_lead at 0m/s, fully consider it at 10m/s +_A_LEAD_LOW_SPEED_V = np.asarray([0., 1.]) + +# speed break points +_A_LEAD_LOW_SPEED_BP = np.asarray([0., 10.]) + +# add a small offset to the desired decel, just for safety margin +_DECEL_OFFSET_V = np.asarray([-0.3, -0.5, -0.5, -0.4, -0.3]) + +# speed bp: different offset based on the likelyhood that lead decels abruptly +_DECEL_OFFSET_BP = np.asarray([0., 4., 15., 30, 40.]) + + +def calc_acc_accel_limits(d_lead, d_des, v_ego, v_pid, v_lead, v_rel, a_lead, + v_target, v_coast, a_target, a_pcm): + #*** compute max accel *** + # v_rel is now your velocity in lead car frame + v_rel = -v_rel # this simplifiess things when thinking in d_rel-v_rel diagram + + v_rel_pid = v_pid - v_lead + + # this is how much lead accel we consider in assigning the desired decel + a_lead_contr = a_lead * np.interp(v_lead, _A_LEAD_LOW_SPEED_BP, + _A_LEAD_LOW_SPEED_V) * 0.8 + + # first call of calc_positive_accel_limit is used to shape v_pid + a_target[1] = calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_pid, + v_rel_pid, v_coast, v_target, + a_lead_contr, a_target[1]) + # second call of calc_positive_accel_limit is used to limit the pcm throttle + # control (only useful when we don't control throttle directly) + a_pcm = calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_ego, v_rel, + v_coast, v_target, a_lead_contr, a_pcm) + + #*** compute max decel *** + v_offset = 1. # assume the car is 1m/s slower + d_offset = 1. # assume the distance is 1m lower + if v_target - v_ego > 0.5: + pass # acc target speed is above vehicle speed, so we can use the cruise limits + elif d_lead > d_offset + 0.01: # add small value to avoid by zero divisions + # compute needed accel to get to 1m distance with -1m/s rel speed + decel_offset = np.interp(v_lead, _DECEL_OFFSET_BP, _DECEL_OFFSET_V) + + critical_decel = calc_critical_decel(d_lead, v_rel, d_offset, v_offset) + a_target[0] = np.minimum(decel_offset + critical_decel + a_lead_contr, + a_target[0]) + else: + a_target[0] = _A_SAT[0] + # a_min can't be higher than a_max + a_target[0] = np.minimum(a_target[0], a_target[1]) + # final check on limits + a_target = np.clip(a_target, _A_SAT[0], _A_SAT[1]) + a_target = a_target.tolist() + return a_target, a_pcm + +def calc_jerk_factor(d_lead, v_rel): + # we don't have an explicit jerk limit, so this function calculates a factor + # that is used by the PID controller to scale the gains. Not the cleanest solution + # but we need this for the demo. + # TODO: Calculate Kp and Ki directly in this function. + + # the higher is the decel required to avoid a crash, the higher is the PI factor scaling + d_offset = 0.5 + v_offset = 2. + a_offset = 1. + jerk_factor_max = 1.0 # can't increase Kp and Ki more than double. + if d_lead < d_offset + 0.1: # add small value to avoid by zero divisions + jerk_factor = jerk_factor_max + else: + a_critical = - calc_critical_decel(d_lead, -v_rel, d_offset, v_offset) + # increase Kp and Ki by 20% for every 1m/s2 of decel required above 1m/s2 + jerk_factor = np.maximum(a_critical - a_offset, 0.)/5. + jerk_factor = np.minimum(jerk_factor, jerk_factor_max) + return jerk_factor + + +def calc_ttc(d_rel, v_rel, a_rel, v_lead): + # this function returns the time to collision (ttc), assuming that a_rel will stay constant + # TODO: Review these assumptions. + # change sign to rel quantities as it's going to be easier for calculations + v_rel = -v_rel + a_rel = -a_rel + + # assuming that closing gap a_rel comes from lead vehicle decel, then limit a_rel so that v_lead will get to zero in no sooner than t_decel + # this helps overweighting a_rel when v_lead is close to zero. + t_decel = 2. + a_rel = np.minimum(a_rel, v_lead/t_decel) + + delta = v_rel**2 + 2 * d_rel * a_rel + # assign an arbitrary high ttc value if there is no solution to ttc + if delta < 0.1: + ttc = 5. + elif np.sqrt(delta) + v_rel < 0.1: + ttc = 5. + else: + ttc = 2 * d_rel / (np.sqrt(delta) + v_rel) + return ttc + + +def limit_accel_driver_awareness(v_ego, a_target, a_pcm, awareness_status): + decel_bp = [0. , 40.] + decel_v = [-0.3, -0.2] + decel = np.interp(v_ego, decel_bp, decel_v) + # gives 18 seconds before decel begins (w 6 minute timeout) + if awareness_status < -0.05: + a_target[1] = np.minimum(a_target[1], decel) + a_target[0] = np.minimum(a_target[1], a_target[0]) + a_pcm = 0. + return a_target, a_pcm + +MAX_SPEED_POSSIBLE = 55. + +def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, awareness_status, VP): + # drive limits + # TODO: Make lims function of speed (more aggressive at low speed). + a_lim = [-3., 1.5] + + #*** set target speed pretty high, as lead hasn't been considered yet + v_target_lead = MAX_SPEED_POSSIBLE + + #*** set accel limits as cruise accel/decel limits *** + a_target, a_pcm = calc_cruise_accel_limits(v_ego) + #*** limit max accel in sharp turns + a_target, a_pcm = limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP) + jerk_factor = 0. + + if l1 is not None and l1.status: + #*** process noisy a_lead signal from radar processing *** + a_lead_p = process_a_lead(l1.aLeadK) + + #*** compute desired distance *** + d_des = calc_desired_distance(l1.vLead) + + #*** compute desired speed *** + v_target_lead, v_coast = calc_desired_speed(l1.dRel, d_des, l1.vLead, a_lead_p) + + if l2 is not None and l2.status: + #*** process noisy a_lead signal from radar processing *** + a_lead_p2 = process_a_lead(l2.aLeadK) + + #*** compute desired distance *** + d_des2 = calc_desired_distance(l2.vLead) + + #*** compute desired speed *** + v_target_lead2, v_coast2 = calc_desired_speed(l2.dRel, d_des2, l2.vLead, a_lead_p2) + + # listen to lead that makes you go slower + if v_target_lead2 < v_target_lead: + l1 = l2 + d_des, a_lead_p, v_target_lead, v_coast = d_des2, a_lead_p2, v_target_lead2, v_coast2 + + # l1 is the main lead now + + #*** compute accel limits *** + a_target1, a_pcm1 = calc_acc_accel_limits(l1.dRel, d_des, v_ego, v_pid, l1.vLead, + l1.vRel, a_lead_p, v_target_lead, v_coast, a_target, a_pcm) + + # we can now limit a_target to a_lim + a_target = np.clip(a_target1, a_lim[0], a_lim[1]) + a_pcm = np.clip(a_pcm1, a_lim[0], a_lim[1]).tolist() + + #*** compute max factor *** + jerk_factor = calc_jerk_factor(l1.dRel, l1.vRel) + + # force coasting decel if driver hasn't been controlling car in a while + a_target, a_pcm = limit_accel_driver_awareness(v_ego, a_target, a_pcm, awareness_status) + + return v_target_lead, a_target, a_pcm, jerk_factor + + +class AdaptiveCruise(object): + def __init__(self, live20): + self.live20 = live20 + self.last_cal = 0. + self.l1, self.l2 = None, None + self.logMonoTime = 0 + self.dead = True + def update(self, cur_time, v_ego, angle_steers, v_pid, awareness_status, VP): + l20 = messaging.recv_sock(self.live20) + if l20 is not None: + self.l1 = l20.live20.leadOne + self.l2 = l20.live20.leadTwo + self.logMonoTime = l20.logMonoTime + + # TODO: no longer has anything to do with calibration + self.last_cal = cur_time + self.dead = False + elif cur_time - self.last_cal > 0.5: + self.dead = True + + self.v_target_lead, self.a_target, self.a_pcm, self.jerk_factor = \ + compute_speed_with_leads(v_ego, angle_steers, v_pid, self.l1, self.l2, awareness_status, VP) + self.has_lead = self.v_target_lead != MAX_SPEED_POSSIBLE diff --git a/selfdrive/controls/lib/alert_database.py b/selfdrive/controls/lib/alert_database.py new file mode 100644 index 0000000000..7b74afb641 --- /dev/null +++ b/selfdrive/controls/lib/alert_database.py @@ -0,0 +1,178 @@ +alerts = [] +keys = ["id", + "chime", + "beep", + "hud_alert", + "screen_chime", + "priority", + "text_line_1", + "text_line_2", + "duration_sound", + "duration_hud_alert", + "duration_text"] + + +#car chimes: enumeration from dbc file. Chimes are for alerts and warnings +class CM: + MUTE = 0 + SINGLE = 3 + DOUBLE = 4 + REPEATED = 1 + CONTINUOUS = 2 + + +#car beepss: enumeration from dbc file. Beeps are for activ and deactiv +class BP: + MUTE = 0 + SINGLE = 3 + TRIPLE = 2 + REPEATED = 1 + + +# lert ids +class AI: + ENABLE = 0 + DISABLE = 1 + SEATBELT = 2 + DOOR_OPEN = 3 + PEDAL_PRESSED = 4 + COMM_ISSUE = 5 + ESP_OFF = 6 + FCW = 7 + STEER_ERROR = 8 + BRAKE_ERROR = 9 + CALIB_INCOMPLETE = 10 + CALIB_INVALID = 11 + GEAR_NOT_D = 12 + MAIN_OFF = 13 + STEER_SATURATED = 14 + PCM_LOW_SPEED = 15 + THERMAL_DEAD = 16 + OVERHEAT = 17 + HIGH_SPEED = 18 + CONTROLSD_LAG = 19 + STEER_ERROR_ID = 100 + BRAKE_ERROR_ID = 101 + PCM_MISMATCH_ID = 102 + CTRL_MISMATCH_ID = 103 + SEATBELT_SD = 200 + DOOR_OPEN_SD = 201 + COMM_ISSUE_SD = 202 + ESP_OFF_SD = 203 + THERMAL_DEAD_SD = 204 + OVERHEAT_SD = 205 + CONTROLSD_LAG_SD = 206 + CALIB_INCOMPLETE_SD = 207 + CALIB_INVALID_SD = 208 + DRIVER_DISTRACTED = 300 + +class AH: + #[alert_idx, value] + # See dbc files for info on values" + NONE = [0, 0] + FCW = [1, 0x8] + STEER = [2, 1] + BRAKE_PRESSED = [3, 10] + GEAR_NOT_D = [4, 6] + SEATBELT = [5, 5] + SPEED_TOO_HIGH = [6, 8] + +class ET: + ENABLE = 0 + NO_ENTRY = 1 + WARNING = 2 + SOFT_DISABLE = 3 + IMMEDIATE_DISABLE = 4 + USER_DISABLE = 5 + +def process_alert(alert_id, alert, cur_time, sound_exp, hud_exp, text_exp, alert_p): + # INPUTS: + # alert_id is mapped to the alert properties in alert_database + # cur_time is current time + # sound_exp is when the alert beep/chime is supposed to end + # hud_exp is when the hud visual is supposed to end + # text_exp is when the alert text is supposed to disappear + # alert_p is the priority of the current alert + # CM, BP, AH are classes defined in alert_database and they respresents chimes, beeps and hud_alerts + if len(alert_id) > 0: + # take the alert with higher priority + alerts_present = filter(lambda a_id: a_id['id'] in alert_id, alerts) + alert = sorted(alerts_present, key=lambda k: k['priority'])[-1] + # check if we have a more important alert + if alert['priority'] > alert_p: + alert_p = alert['priority'] + sound_exp = cur_time + alert['duration_sound'] + hud_exp = cur_time + alert['duration_hud_alert'] + text_exp = cur_time + alert['duration_text'] + + chime = CM.MUTE + beep = BP.MUTE + if cur_time < sound_exp: + chime = alert['chime'] + beep = alert['beep'] + + hud_alert = AH.NONE + if cur_time < hud_exp: + hud_alert = alert['hud_alert'] + + alert_text = ["", ""] + if cur_time < text_exp: + alert_text = [alert['text_line_1'], alert['text_line_2']] + + if chime == CM.MUTE and beep == BP.MUTE and hud_alert == AH.NONE: #and alert_text[0] is None and alert_text[1] is None: + alert_p = 0 + return alert, chime, beep, hud_alert, alert_text, sound_exp, hud_exp, text_exp, alert_p + +def process_hud_alert(hud_alert): + # initialize to no alert + fcw_display = 0 + steer_required = 0 + acc_alert = 0 + if hud_alert == AH.NONE: # no alert + pass + elif hud_alert == AH.FCW: # FCW + fcw_display = hud_alert[1] + elif hud_alert == AH.STEER: # STEER + steer_required = hud_alert[1] + else: # any other ACC alert + acc_alert = hud_alert[1] + + return fcw_display, steer_required, acc_alert + +def app_alert(alert_add): + alerts.append(dict(zip(keys, alert_add))) + +app_alert([AI.ENABLE, CM.MUTE, BP.SINGLE, AH.NONE, ET.ENABLE, 2, "", "", .2, 0., 0.]) +app_alert([AI.DISABLE, CM.MUTE, BP.SINGLE, AH.NONE, ET.USER_DISABLE, 2, "", "", .2, 0., 0.]) +app_alert([AI.SEATBELT, CM.DOUBLE, BP.MUTE, AH.SEATBELT, ET.NO_ENTRY, 1, "Comma Unavailable", "Seatbelt Unlatched", .4, 2., 3.]) +app_alert([AI.DOOR_OPEN, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Door Open", .4, 0., 3.]) +app_alert([AI.PEDAL_PRESSED, CM.DOUBLE, BP.MUTE, AH.BRAKE_PRESSED, ET.NO_ENTRY, 1, "Comma Unavailable", "Pedal Pressed", .4, 2., 3.]) +app_alert([AI.COMM_ISSUE, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Communcation Issues", .4, 0., 3.]) +app_alert([AI.ESP_OFF, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "ESP Off", .4, 0., 3.]) +app_alert([AI.FCW, CM.REPEATED, BP.MUTE, AH.FCW, ET.WARNING, 3, "Risk of Collision", "", 1., 2., 3.]) +app_alert([AI.STEER_ERROR, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Steer Error", .4, 0., 3.]) +app_alert([AI.BRAKE_ERROR, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Brake Error", .4, 0., 3.]) +app_alert([AI.CALIB_INCOMPLETE, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Calibration in Progress", .4, 0., 3.]) +app_alert([AI.CALIB_INVALID, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Calibration Error", .4, 0., 3.]) +app_alert([AI.GEAR_NOT_D, CM.DOUBLE, BP.MUTE, AH.GEAR_NOT_D, ET.NO_ENTRY, 1, "Comma Unavailable", "Gear not in D", .4, 2., 3.]) +app_alert([AI.MAIN_OFF, CM.MUTE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Main Switch Off", .4, 0., 3.]) +app_alert([AI.STEER_SATURATED, CM.SINGLE, BP.MUTE, AH.STEER, ET.WARNING, 2, "Take Control", "Steer Control Saturated", 1., 2., 3.]) +app_alert([AI.PCM_LOW_SPEED, CM.MUTE, BP.SINGLE, AH.STEER, ET.WARNING, 2, "Comma disengaged", "Speed too low", .2, 2., 3.]) +app_alert([AI.THERMAL_DEAD, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Thermal Unavailable", .4, 0., 3.]) +app_alert([AI.OVERHEAT, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "System Overheated", .4, 0., 3.]) +app_alert([AI.HIGH_SPEED, CM.DOUBLE, BP.MUTE, AH.SPEED_TOO_HIGH, ET.NO_ENTRY, 1, "Comma Unavailable", "Speed Too High", .4, 2., 3.]) +app_alert([AI.CONTROLSD_LAG, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Controls Lagging", .4, 0., 3.]) +app_alert([AI.STEER_ERROR_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Steer Error", 1., 3., 3.]) +app_alert([AI.BRAKE_ERROR_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Brake Error", 1., 3., 3.]) +app_alert([AI.PCM_MISMATCH_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Pcm Mismatch", 1., 3., 3.]) +app_alert([AI.CTRL_MISMATCH_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Ctrl Mismatch", 1., 3., 3.]) +app_alert([AI.SEATBELT_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Seatbelt Unlatched", 1., 3., 3.]) +app_alert([AI.DOOR_OPEN_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Door Open", 1., 3., 3.]) +app_alert([AI.COMM_ISSUE_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Technical Issues", 1., 3., 3.]) +app_alert([AI.ESP_OFF_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "ESP Off", 1., 3., 3.]) +app_alert([AI.THERMAL_DEAD_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Thermal Unavailable", 1., 3., 3.]) +app_alert([AI.OVERHEAT_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "System Overheated", 1., 3., 3.]) +app_alert([AI.CONTROLSD_LAG_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Controls Lagging", 1., 3., 3.]) +app_alert([AI.CALIB_INCOMPLETE_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Calibration in Progress", 1., 3., 3.]) +app_alert([AI.CALIB_INVALID_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Calibration Error", 1., 3., 3.]) +app_alert([AI.DRIVER_DISTRACTED, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 2, "Take Control to Regain Speed", "User Distracted", 1., 1., 1.]) diff --git a/selfdrive/controls/lib/can_parser.py b/selfdrive/controls/lib/can_parser.py new file mode 100644 index 0000000000..7bd8dd54ee --- /dev/null +++ b/selfdrive/controls/lib/can_parser.py @@ -0,0 +1,123 @@ +import os +import dbcs +from collections import defaultdict + +from selfdrive.controls.lib.hondacan import fix +from common.realtime import sec_since_boot +from common.dbc import dbc + +class CANParser(object): + def __init__(self, dbc_f, signals, checks=[]): + ### input: + # dbc_f : dbc file + # signals : List of tuples (name, address, ival) where + # - name is the signal name. + # - address is the corresponding message address. + # - ival is the initial value. + # checks : List of pairs (address, frequency) where + # - address is the message address of a message for which health should be + # monitored. + # - frequency is the frequency at which health should be monitored. + + self.msgs_ck = [check[0] for check in checks] + self.frqs = [check[1] for check in checks] + self.can_valid = False # start with False CAN assumption + self.msgs_upd = [] # list of updated messages + # list of received msg we want to monitor counter and checksum for + # read dbc file + self.can_dbc = dbc(os.path.join(dbcs.DBC_PATH, dbc_f)) + # initialize variables to initial values + self.vl = {} # signal values + self.ts = {} # time stamp recorded in log + self.ct = {} # current time stamp + self.ok = {} # valid message? + self.cn = {} # message counter + self.cn_vl = {} # message counter mismatch value + self.ck = {} # message checksum status + + for _, addr, _ in signals: + self.vl[addr] = {} + self.ts[addr] = 0 + self.ct[addr] = sec_since_boot() + self.ok[addr] = False + self.cn[addr] = 0 + self.cn_vl[addr] = 0 + self.ck[addr] = False + + for name, addr, ival in signals: + self.vl[addr][name] = ival + + self._msgs = [s[1] for s in signals] + self._sgs = [s[0] for s in signals] + + self._message_indices = defaultdict(list) + for i, x in enumerate(self._msgs): + self._message_indices[x].append(i) + + def update_can(self, can_recv): + self.msgs_upd = [] + cn_vl_max = 5 # no more than 5 wrong counter checks + + # we are subscribing to PID_XXX, else data from USB + for msg, ts, cdat in can_recv: + idxs = self._message_indices[msg] + if idxs: + self.msgs_upd += [msg] + # read the entire message + out = self.can_dbc.decode([msg, 0, cdat])[1] + # checksum check + self.ck[msg] = True + if "CHECKSUM" in out.keys() and msg in self.msgs_ck: + # remove checksum (half byte) + ck_portion = (''.join((cdat[:-1], '0'))).decode('hex') + # recalculate checksum + msg_vl = fix(ck_portion, msg) + # compare recalculated vs received checksum + if msg_vl != cdat.decode('hex'): + print hex(msg), "CHECKSUM FAIL" + self.ck[msg] = False + self.ok[msg] = False + # counter check + cn = 0 + if "COUNTER" in out.keys(): + cn = out["COUNTER"] + # check counter validity if it's a relevant message + if cn != ((self.cn[msg] + 1) % 4) and msg in self.msgs_ck and "COUNTER" in out.keys(): + #print hex(msg), "FAILED COUNTER!" + self.cn_vl[msg] += 1 # counter check failed + else: + self.cn_vl[msg] -= 1 # counter check passed + # message status is invalid if we received too many wrong counter values + if self.cn_vl[msg] >= cn_vl_max: + self.ok[msg] = False + + # update msg time stamps and counter value + self.ts[msg] = ts + self.ct[msg] = sec_since_boot() + self.cn[msg] = cn + self.cn_vl[msg] = min(max(self.cn_vl[msg], 0), cn_vl_max) + + # set msg valid status if checksum is good and wrong counter counter is zero + if self.ck[msg] and self.cn_vl[msg] == 0: + self.ok[msg] = True + + # update value of signals in the + for ii in idxs: + sg = self._sgs[ii] + self.vl[msg][sg] = out[sg] + + # for each message, check if it's too long since last time we received it + self._check_dead_msgs() + + # assess overall can validity: if there is one relevant message invalid, then set can validity flag to False + self.can_valid = True + if False in self.ok.values(): + print "CAN INVALID!" + self.can_valid = False + + def _check_dead_msgs(self): + ### input: + ## simple stuff for now: msg is not valid if a message isn't received for 10 consecutive steps + for msg in set(self._msgs): + if msg in self.msgs_ck and sec_since_boot() - self.ct[msg] > 10./self.frqs[self.msgs_ck.index(msg)]: + self.ok[msg] = False diff --git a/selfdrive/controls/lib/carcontroller.py b/selfdrive/controls/lib/carcontroller.py new file mode 100644 index 0000000000..6c3766d387 --- /dev/null +++ b/selfdrive/controls/lib/carcontroller.py @@ -0,0 +1,185 @@ +from collections import namedtuple + +import common.numpy_fast as np +import selfdrive.controls.lib.hondacan as hondacan +from common.realtime import sec_since_boot +from selfdrive.config import CruiseButtons +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.controls.lib.alert_database import process_hud_alert +from selfdrive.controls.lib.drive_helpers import actuator_hystereses, rate_limit + +HUDData = namedtuple("HUDData", + ["pcm_accel", "v_cruise", "X2", "car", "X4", "X5", + "lanes", "beep", "X8", "chime", "acc_alert"]) + +class CarController(object): + def __init__(self): + self.controls_allowed = False + self.mismatch_start, self.pcm_mismatch_start = 0, 0 + self.braking = False + self.brake_steady = 0. + self.final_brake_last = 0. + + def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_steer, \ + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \ + snd_beep, snd_chime): + """ Controls thread """ + + # *** apply brake hysteresis *** + final_brake, self.braking, self.brake_steady = actuator_hystereses(final_brake, self.braking, self.brake_steady, CS.v_ego, CS.civic) + + # *** no output if not enabled *** + if not enabled: + final_gas = 0. + final_brake = 0. + final_steer = 0. + # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated + if CS.pcm_acc_status: + pcm_cancel_cmd = True + + # *** rate limit after the enable check *** + final_brake = rate_limit(final_brake, self.final_brake_last, -2., 1./100) + self.final_brake_last = final_brake + + # vehicle hud display, wait for one update from 10Hz 0x304 msg + #TODO: use enum!! + if hud_show_lanes: + hud_lanes = 0x04 + else: + hud_lanes = 0x00 + + # TODO: factor this out better + if enabled: + if hud_show_car: + hud_car = 0xe0 + else: + hud_car = 0xd0 + else: + hud_car = 0xc0 + + #print chime, alert_id, hud_alert + fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) + + hud = HUDData(pcm_accel, hud_v_cruise, 0x41, hud_car, + 0xc1, 0x41, hud_lanes + steer_required, + snd_beep, 0x48, (snd_chime << 5) + fcw_display, acc_alert) + + if not all(isinstance(x, int) and 0 <= x < 256 for x in hud): + print "INVALID HUD", hud + hud = HUDData(0xc6, 255, 64, 0xc0, 209, 0x41, 0x40, 0, 0x48, 0, 0) + + # **** process the car messages **** + + user_brake_ctrl = CS.user_brake/0.015625 # FIXME: factor needed to convert to old scale + + # *** compute control surfaces *** + tt = sec_since_boot() + GAS_MAX = 1004 + BRAKE_MAX = 1024/4 + #STEER_MAX = 0xF00 if not CS.torque_mod else 0xF00/4 # ilx has 8x steering torque limit, used as a 2x + STEER_MAX = 0xF00 # ilx has 8x steering torque limit, used as a 2x + GAS_OFFSET = 328 + + # steer torque is converted back to CAN reference (positive when steering right) + apply_gas = int(np.clip(final_gas*GAS_MAX, 0, GAS_MAX-1)) + apply_brake = int(np.clip(final_brake*BRAKE_MAX, 0, BRAKE_MAX-1)) + apply_steer = int(np.clip(-final_steer*STEER_MAX, -STEER_MAX, STEER_MAX)) + + # no gas if you are hitting the brake or the user is + if apply_gas > 0 and (apply_brake != 0 or user_brake_ctrl > 10): + print "CANCELLING GAS", apply_brake, user_brake_ctrl + apply_gas = 0 + + # no computer brake if the user is hitting the gas + # if the computer is trying to brake, it can't be hitting the gas + # TODO: car_gas can override brakes without canceling... this is bad + if CS.car_gas > 0 and apply_brake != 0: + apply_brake = 0 + + if (CS.prev_cruise_buttons == CruiseButtons.DECEL_SET or CS.prev_cruise_buttons == CruiseButtons.RES_ACCEL) and \ + CS.cruise_buttons == 0 and not self.controls_allowed: + print "CONTROLS ARE LIVE" + self.controls_allowed = True + + # to avoid race conditions, check if control has been disabled for at least 0.2s + # keep resetting start timer if mismatch isn't true + if not (self.controls_allowed and not enabled): + self.mismatch_start = tt + + # to avoid race conditions, check if control is disabled but pcm control is on for at least 0.2s + if not (not self.controls_allowed and CS.pcm_acc_status): + self.pcm_mismatch_start = tt + + # something is very wrong, since pcm control is active but controls should not be allowed; TODO: send pcm fault cmd? + if (tt - self.pcm_mismatch_start) > 0.2: + pcm_cancel_cmd = True + + # TODO: clean up gear condition, ideally only D (and P for debug) shall be valid gears + if (CS.cruise_buttons == CruiseButtons.CANCEL or CS.brake_pressed or + CS.user_gas_pressed or (tt - self.mismatch_start) > 0.2 or + not CS.main_on or not CS.gear_shifter_valid or + (CS.pedal_gas > 0 and CS.brake_only)) and self.controls_allowed: + self.controls_allowed = False + + # 5 is a permanent fault, no torque request will be fullfilled + if CS.steer_error: + print "STEER ERROR" + self.controls_allowed = False + + # any other cp.vl[0x18F]['STEER_STATUS'] is common and can happen during user override. sending 0 torque to avoid EPS sending error 5 + elif CS.steer_not_allowed: + print "STEER ALERT, TORQUE INHIBITED" + apply_steer = 0 + + if CS.brake_error: + print "BRAKE ERROR" + self.controls_allowed = False + + if not CS.can_valid and self.controls_allowed: # 200 ms + print "CAN INVALID" + self.controls_allowed = False + + if not self.controls_allowed: + apply_steer = 0 + apply_gas = 0 + apply_brake = 0 + pcm_speed = 0 # make sure you send 0 target speed to pcm + #pcm_cancel_cmd = 1 # prevent pcm control from turning on. FIXME: we can't just do this + + # Send CAN commands. + can_sends = [] + + # Send steering command. + idx = frame % 4 + can_sends.append(hondacan.create_steering_control(apply_steer, idx)) + + # Send gas and brake commands. + if (frame % 2) == 0: + idx = (frame / 2) % 4 + can_sends.append( + hondacan.create_brake_command(apply_brake, pcm_override, + pcm_cancel_cmd, hud.chime, idx)) + + if not CS.brake_only: + # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. + # This prevents unexpected pedal range rescaling + gas_amount = (apply_gas + GAS_OFFSET) * (apply_gas > 0) + can_sends.append(hondacan.create_gas_command(gas_amount, idx)) + + # Send dashboard UI commands. + if (frame % 10) == 0: + idx = (frame/10) % 4 + can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.civic, idx)) + + # radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug) + if CS.civic: + radar_send_step = 5 + else: + radar_send_step = 2 + + if (frame % radar_send_step) == 0: + idx = (frame/radar_send_step) % 4 + can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.civic, idx)) + + sendcan.send(can_list_to_can_capnp(can_sends).to_bytes()) diff --git a/selfdrive/controls/lib/carstate.py b/selfdrive/controls/lib/carstate.py new file mode 100644 index 0000000000..5ac3b138ef --- /dev/null +++ b/selfdrive/controls/lib/carstate.py @@ -0,0 +1,275 @@ +import numpy as np + +import selfdrive.messaging as messaging +from selfdrive.boardd.boardd import can_capnp_to_can_list_old, can_capnp_to_can_list +from selfdrive.controls.lib.can_parser import CANParser +from selfdrive.controls.lib.fingerprints import fingerprints +from selfdrive.config import VehicleParams +from common.realtime import sec_since_boot + + +def get_can_parser(civic, brake_only): + # this function generates lists for signal, messages and initial values + if civic: + dbc_f = 'honda_civic_touring_2016_can.dbc' + signals = [ + ("XMISSION_SPEED", 0x158, 0), + ("WHEEL_SPEED_FL", 0x1d0, 0), + ("WHEEL_SPEED_FR", 0x1d0, 0), + ("WHEEL_SPEED_RL", 0x1d0, 0), + ("STEER_ANGLE", 0x14a, 0), + ("STEER_TORQUE_SENSOR", 0x18f, 0), + ("GEAR", 0x191, 0), + ("WHEELS_MOVING", 0x1b0, 1), + ("DOOR_OPEN_FL", 0x405, 1), + ("DOOR_OPEN_FR", 0x405, 1), + ("DOOR_OPEN_RL", 0x405, 1), + ("DOOR_OPEN_RR", 0x405, 1), + ("CRUISE_SPEED_PCM", 0x324, 0), + ("SEATBELT_DRIVER_LAMP", 0x305, 1), + ("SEATBELT_DRIVER_LATCHED", 0x305, 0), + ("BRAKE_PRESSED", 0x17c, 0), + ("CAR_GAS", 0x130, 0), + ("CRUISE_BUTTONS", 0x296, 0), + ("ESP_DISABLED", 0x1a4, 1), + ("HUD_LEAD", 0x30c, 0), + ("USER_BRAKE", 0x1a4, 0), + ("STEER_STATUS", 0x18f, 5), + ("WHEEL_SPEED_RR", 0x1d0, 0), + ("BRAKE_ERROR_1", 0x1b0, 1), + ("BRAKE_ERROR_2", 0x1b0, 1), + ("GEAR_SHIFTER", 0x191, 0), + ("MAIN_ON", 0x326, 0), + ("ACC_STATUS", 0x17c, 0), + ("PEDAL_GAS", 0x17c, 0), + ("CRUISE_SETTING", 0x296, 0), + ("LEFT_BLINKER", 0x326, 0), + ("RIGHT_BLINKER", 0x326, 0), + ("COUNTER", 0x324, 0), + ] + checks = [ + (0x14a, 100), + (0x158, 100), + (0x17c, 100), + (0x191, 100), + (0x1a4, 50), + (0x326, 10), + (0x1b0, 50), + (0x1d0, 50), + (0x305, 10), + (0x324, 10), + (0x405, 3), + ] + + else: + dbc_f = 'acura_ilx_2016_can.dbc' + signals = [ + ("XMISSION_SPEED", 0x158, 0), + ("WHEEL_SPEED_FL", 0x1d0, 0), + ("WHEEL_SPEED_FR", 0x1d0, 0), + ("WHEEL_SPEED_RL", 0x1d0, 0), + ("STEER_ANGLE", 0x156, 0), + ("STEER_TORQUE_SENSOR", 0x18f, 0), + ("GEAR", 0x1a3, 0), + ("WHEELS_MOVING", 0x1b0, 1), + ("DOOR_OPEN_FL", 0x405, 1), + ("DOOR_OPEN_FR", 0x405, 1), + ("DOOR_OPEN_RL", 0x405, 1), + ("DOOR_OPEN_RR", 0x405, 1), + ("CRUISE_SPEED_PCM", 0x324, 0), + ("SEATBELT_DRIVER_LAMP", 0x305, 1), + ("SEATBELT_DRIVER_LATCHED", 0x305, 0), + ("BRAKE_PRESSED", 0x17c, 0), + ("CAR_GAS", 0x130, 0), + ("CRUISE_BUTTONS", 0x1a6, 0), + ("ESP_DISABLED", 0x1a4, 1), + ("HUD_LEAD", 0x30c, 0), + ("USER_BRAKE", 0x1a4, 0), + ("STEER_STATUS", 0x18f, 5), + ("WHEEL_SPEED_RR", 0x1d0, 0), + ("BRAKE_ERROR_1", 0x1b0, 1), + ("BRAKE_ERROR_2", 0x1b0, 1), + ("GEAR_SHIFTER", 0x1a3, 0), + ("MAIN_ON", 0x1a6, 0), + ("ACC_STATUS", 0x17c, 0), + ("PEDAL_GAS", 0x17c, 0), + ("CRUISE_SETTING", 0x1a6, 0), + ("LEFT_BLINKER", 0x294, 0), + ("RIGHT_BLINKER", 0x294, 0), + ("COUNTER", 0x324, 0), + ] + checks = [ + (0x156, 100), + (0x158, 100), + (0x17c, 100), + (0x1a3, 50), + (0x1a4, 50), + (0x1a6, 50), + (0x1b0, 50), + (0x1d0, 50), + (0x305, 10), + (0x324, 10), + (0x405, 3), + ] + + # add gas interceptor reading if we are using it + if not brake_only: + signals.append(("INTERCEPTOR_GAS", 0x201, 0)) + checks.append((0x201, 50)) + + return CANParser(dbc_f, signals, checks) + +def fingerprint(logcan): + print "waiting for fingerprint..." + brake_only = True + + finger = {} + st = None + while 1: + possible_cars = [] + for a in messaging.drain_sock(logcan, wait_for_one=True): + if st is None: + st = sec_since_boot() + for adr, _, msg, idx in can_capnp_to_can_list(a): + # pedal + if adr == 0x201 and idx == 0: + brake_only = False + if idx == 0: + finger[adr] = len(msg) + + # check for a single match + for f in fingerprints: + is_possible = True + for adr in finger: + # confirm all messages we have seen match + if adr not in fingerprints[f] or fingerprints[f][adr] != finger[adr]: + #print "mismatch", f, adr + is_possible = False + break + if is_possible: + possible_cars.append(f) + + # if we only have one car choice and it's been 100ms since we got our first message, exit + if len(possible_cars) == 1 and st is not None and (sec_since_boot()-st) > 0.1: + break + elif len(possible_cars) == 0: + raise Exception("car doesn't match any fingerprints") + + print "fingerprinted", possible_cars[0] + return brake_only, possible_cars[0] + +class CarState(object): + def __init__(self, logcan): + self.torque_mod = False + self.brake_only, self.car_type = fingerprint(logcan) + + # assuming if you have a pedal interceptor you also have a torque mod + if not self.brake_only: + self.torque_mod = True + + if self.car_type == "HONDA CIVIC 2016 TOURING": + self.civic = True + elif self.car_type == "ACURA ILX 2016 ACURAWATCH PLUS": + self.civic = False + else: + raise ValueError("unsupported car %s" % self.car_type) + + # initialize can parser + self.cp = get_can_parser(self.civic, self.brake_only) + + self.user_gas, self.user_gas_pressed = 0., 0 + + self.cruise_buttons = 0 + self.cruise_setting = 0 + self.blinker_on = 0 + + # TODO: actually make this work + self.a_ego = 0. + + # speed in UI is shown as few % higher + self.ui_speed_fudge = 1.01 if self.civic else 1.025 + + # load vehicle params + self.VP = VehicleParams(self.civic) + + def update(self, logcan): + # ******************* do can recv ******************* + can_pub_main = [] + canMonoTimes = [] + for a in messaging.drain_sock(logcan): + canMonoTimes.append(a.logMonoTime) + can_pub_main.extend(can_capnp_to_can_list_old(a, [0,2])) + + cp = self.cp + cp.update_can(can_pub_main) + + # copy can_valid + self.can_valid = cp.can_valid + + # car params + v_weight_v = [0., 1. ] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero + + # update prevs, update must run once per loop + self.prev_cruise_buttons = self.cruise_buttons + self.prev_cruise_setting = self.cruise_setting + self.prev_blinker_on = self.blinker_on + + # ******************* parse out can ******************* + self.door_all_closed = not any([cp.vl[0x405]['DOOR_OPEN_FL'], cp.vl[0x405]['DOOR_OPEN_FR'], + cp.vl[0x405]['DOOR_OPEN_RL'], cp.vl[0x405]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl[0x305]['SEATBELT_DRIVER_LAMP'] and cp.vl[0x305]['SEATBELT_DRIVER_LATCHED'] + # error 2 = temporary + # error 4 = temporary, hit a bump + # error 5 (permanent) + # error 6 = temporary + # error 7 (permanent) + #self.steer_error = cp.vl[0x18F]['STEER_STATUS'] in [5,7] + # whitelist instead of blacklist, safer at the expense of disengages + self.steer_error = cp.vl[0x18F]['STEER_STATUS'] not in [0,2,4,6] + self.steer_not_allowed = cp.vl[0x18F]['STEER_STATUS'] != 0 + if cp.vl[0x18F]['STEER_STATUS'] != 0: + print cp.vl[0x18F]['STEER_STATUS'] + self.brake_error = cp.vl[0x1B0]['BRAKE_ERROR_1'] or cp.vl[0x1B0]['BRAKE_ERROR_2'] + self.esp_disabled = cp.vl[0x1A4]['ESP_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel = ( + cp.vl[0x1D0]['WHEEL_SPEED_FL'] + cp.vl[0x1D0]['WHEEL_SPEED_FR'] + + cp.vl[0x1D0]['WHEEL_SPEED_RL'] + cp.vl[0x1D0]['WHEEL_SPEED_RR']) / 4. + # blend in transmission speed at low speed, since it has more low speed accuracy + self.v_weight = np.interp(self.v_wheel, v_weight_bp, v_weight_v) + self.v_ego = (1. - self.v_weight) * cp.vl[0x158]['XMISSION_SPEED'] + self.v_weight * self.v_wheel + if not self.brake_only: + self.user_gas = cp.vl[0x201]['INTERCEPTOR_GAS'] + self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change + #print user_gas, user_gas_pressed + if self.civic: + self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] + self.gear = 0 # TODO: civic has CVT... needs rev engineering + self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] + self.main_on = cp.vl[0x326]['MAIN_ON'] + self.gear_shifter_valid = self.gear_shifter in [1,8] # TODO: 1/P allowed for debug + self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] + else: + self.gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] + self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] + self.gear = cp.vl[0x1A3]['GEAR'] + self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] + self.main_on = cp.vl[0x1A6]['MAIN_ON'] + self.gear_shifter_valid = self.gear_shifter in [1,4] # TODO: 1/P allowed for debug + self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] + self.car_gas = cp.vl[0x130]['CAR_GAS'] + self.brake_pressed = cp.vl[0x17C]['BRAKE_PRESSED'] + self.user_brake = cp.vl[0x1A4]['USER_BRAKE'] + self.standstill = not cp.vl[0x1B0]['WHEELS_MOVING'] + self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 + self.v_cruise_pcm = cp.vl[0x324]['CRUISE_SPEED_PCM'] + self.pcm_acc_status = cp.vl[0x17C]['ACC_STATUS'] + self.pedal_gas = cp.vl[0x17C]['PEDAL_GAS'] + self.hud_lead = cp.vl[0x30C]['HUD_LEAD'] + self.counter_pcm = cp.vl[0x324]['COUNTER'] + + return canMonoTimes diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py new file mode 100644 index 0000000000..a2c4917dc1 --- /dev/null +++ b/selfdrive/controls/lib/drive_helpers.py @@ -0,0 +1,52 @@ +import numpy as np + +def rate_limit(new_value, last_value, dw_step, up_step): + return np.clip(new_value, last_value + dw_step, last_value + up_step) + +def learn_angle_offset(lateral_control, v_ego, angle_offset, d_poly, y_des, steer_override): + # simple integral controller that learns how much steering offset to put to have the car going straight + min_offset = -1. # deg + max_offset = 1. # deg + alpha = 1./36000. # correct by 1 deg in 2 mins, at 30m/s, with 50cm of error, at 20Hz + min_learn_speed = 1. + + # learn less at low speed or when turning + alpha_v = alpha*(np.maximum(v_ego - min_learn_speed, 0.))/(1. + 0.5*abs(y_des)) + + # only learn if lateral control is active and if driver is not overriding: + if lateral_control and not steer_override: + angle_offset += d_poly[3] * alpha_v + angle_offset = np.clip(angle_offset, min_offset, max_offset) + + return angle_offset + +def actuator_hystereses(final_brake, braking, brake_steady, v_ego, civic): + # hyst params... TODO: move these to VehicleParams + brake_hyst_on = 0.055 if civic else 0.1 # to activate brakes exceed this value + brake_hyst_off = 0.005 # to deactivate brakes below this value + brake_hyst_gap = 0.01 # don't change brake command for small ocilalitons within this value + + #*** histeresys logic to avoid brake blinking. go above 0.1 to trigger + if (final_brake < brake_hyst_on and not braking) or final_brake < brake_hyst_off: + final_brake = 0. + braking = final_brake > 0. + + # for small brake oscillations within brake_hyst_gap, don't change the brake command + if final_brake == 0.: + brake_steady = 0. + elif final_brake > brake_steady + brake_hyst_gap: + brake_steady = final_brake - brake_hyst_gap + elif final_brake < brake_steady - brake_hyst_gap: + brake_steady = final_brake + brake_hyst_gap + final_brake = brake_steady + + if not civic: + brake_on_offset_v = [.25, .15] # min brake command on brake activation. below this no decel is perceived + brake_on_offset_bp = [15., 30.] # offset changes VS speed to not have too abrupt decels at high speeds + # offset the brake command for threshold in the brake system. no brake torque perceived below it + brake_on_offset = np.interp(v_ego, brake_on_offset_bp, brake_on_offset_v) + brake_offset = brake_on_offset - brake_hyst_on + if final_brake > 0.0: + final_brake += brake_offset + + return final_brake, braking, brake_steady diff --git a/selfdrive/controls/lib/fingerprints.py b/selfdrive/controls/lib/fingerprints.py new file mode 100644 index 0000000000..f3363c2d89 --- /dev/null +++ b/selfdrive/controls/lib/fingerprints.py @@ -0,0 +1,8 @@ +fingerprints = { + "ACURA ILX 2016 ACURAWATCH PLUS": { + 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5 + }, + "HONDA CIVIC 2016 TOURING": { + 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5 + } +} diff --git a/selfdrive/controls/lib/hondacan.py b/selfdrive/controls/lib/hondacan.py new file mode 100644 index 0000000000..fe6d9e79d9 --- /dev/null +++ b/selfdrive/controls/lib/hondacan.py @@ -0,0 +1,88 @@ +import struct + +import common.numpy_fast as np +from selfdrive.config import Conversions as CV + + +# *** Honda specific *** +def can_cksum(mm): + s = 0 + for c in mm: + c = ord(c) + s += (c>>4) + s += c & 0xF + s = 8-s + s %= 0x10 + return s + +def fix(msg, addr): + msg2 = msg[0:-1] + chr(ord(msg[-1]) | can_cksum(struct.pack("I", addr)+msg)) + return msg2 + +def make_can_msg(addr, dat, idx, alt): + if idx is not None: + dat += chr(idx << 4) + dat = fix(dat, addr) + return [addr, 0, dat, alt] + +def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx): + """Creates a CAN message for the Honda DBC BRAKE_COMMAND.""" + pump_on = apply_brake > 0 + brakelights = apply_brake > 0 + brake_rq = apply_brake > 0 + + pcm_fault_cmd = False + amount = struct.pack("!H", (apply_brake << 6) + pump_on) + msg = amount + struct.pack("BBB", (pcm_override << 4) | + (pcm_fault_cmd << 2) | + (pcm_cancel_cmd << 1) | brake_rq, 0x80, + brakelights << 7) + chr(chime) + "\x00" + return make_can_msg(0x1fa, msg, idx, 0) + +def create_gas_command(gas_amount, idx): + """Creates a CAN message for the Honda DBC GAS_COMMAND.""" + msg = struct.pack("!H", gas_amount) + return make_can_msg(0x200, msg, idx, 0) + +def create_steering_control(apply_steer, idx): + """Creates a CAN message for the Honda DBC STEERING_CONTROL.""" + msg = struct.pack("!h", apply_steer) + ("\x80\x00" if apply_steer != 0 else "\x00\x00") + return make_can_msg(0xe4, msg, idx, 0) + +def create_ui_commands(pcm_speed, hud, civic, idx): + """Creates an iterable of CAN messages for the UIs.""" + commands = [] + pcm_speed_real = np.clip(int(round(pcm_speed / 0.002763889)), 0, + 64000) # conversion factor from dbc file + msg_0x30c = struct.pack("!HBBBBB", pcm_speed_real, hud.pcm_accel, + hud.v_cruise, hud.X2, hud.car, hud.X4) + commands.append(make_can_msg(0x30c, msg_0x30c, idx, 0)) + + msg_0x33d = chr(hud.X5) + chr(hud.lanes) + chr(hud.beep) + chr(hud.X8) + commands.append(make_can_msg(0x33d, msg_0x33d, idx, 0)) + if civic: # 2 more msgs + msg_0x35e = chr(0) * 7 + commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0)) + msg_0x39f = ( + chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0) + ) + commands.append(make_can_msg(0x39f, msg_0x39f, idx, 0)) + return commands + +def create_radar_commands(v_ego, civic, idx): + """Creates an iterable of CAN messages for the radar system.""" + commands = [] + v_ego_kph = np.clip(int(round(v_ego * CV.MS_TO_KPH)), 0, 255) + speed = struct.pack('!B', v_ego_kph) + msg_0x300 = ("\xf9" + speed + "\x8a\xd0" +\ + ("\x20" if idx == 0 or idx == 3 else "\x00") +\ + "\x00\x00") + if civic: + msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" + # add 8 on idx. + commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) + else: + msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00" + commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) + commands.append(make_can_msg(0x301, msg_0x301, idx, 1)) + return commands diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py new file mode 100644 index 0000000000..3a77a16cdd --- /dev/null +++ b/selfdrive/controls/lib/latcontrol.py @@ -0,0 +1,120 @@ +import numpy as np + +def calc_curvature(v_ego, angle_steers, VP, angle_offset=0): + deg_to_rad = np.pi/180. + angle_steers_rad = (angle_steers - angle_offset) * deg_to_rad + curvature = angle_steers_rad/(VP.steer_ratio * VP.wheelbase * (1. + VP.slip_factor * v_ego**2)) + return curvature + +def calc_d_lookahead(v_ego): + #*** this function computes how far too look for lateral control + # howfar we look ahead is function of speed + offset_lookahead = 1. + coeff_lookahead = 4.4 + # sqrt on speed is needed to keep, for a given curvature, the y_offset + # proportional to speed. Indeed, y_offset is prop to d_lookahead^2 + # 26m at 25m/s + d_lookahead = offset_lookahead + np.sqrt(np.maximum(v_ego, 0)) * coeff_lookahead + return d_lookahead + +def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VP, angle_offset): + #*** this function return teh lateral offset given the steering angle, speed and the lookahead distance + curvature = calc_curvature(v_ego, angle_steers, VP, angle_offset) + + # clip is to avoid arcsin NaNs due to too sharp turns + y_actual = d_lookahead * np.tan(np.arcsin(np.clip(d_lookahead * curvature, -0.999, 0.999))/2.) + return y_actual, curvature + +def pid_lateral_control(v_ego, y_actual, y_des, Ui_steer, steer_max, + steer_override, sat_count, enabled, half_pid, rate): + + sat_count_rate = 1./rate + sat_count_limit = 0.8 # after 0.8s of continuous saturation, an alert will be sent + + error_steer = y_des - y_actual + Ui_unwind_speed = 0.3/rate #.3 per second + if not half_pid: + Kp, Ki = 12.0, 1.0 + else: + Kp, Ki = 6.0, .5 # 2x limit in ILX + Up_steer = error_steer*Kp + Ui_steer_new = Ui_steer + error_steer*Ki * 1./rate + output_steer_new = Ui_steer_new + Up_steer + + # Anti-wind up for integrator: do not integrate if we are against the steer limits + if ( + (error_steer >= 0. and (output_steer_new < steer_max or Ui_steer < 0)) or + (error_steer <= 0. and + (output_steer_new > -steer_max or Ui_steer > 0))) and not steer_override: + #update integrator + Ui_steer = Ui_steer_new + # unwind integrator if driver is maneuvering the steering wheel + elif steer_override: + Ui_steer -= Ui_unwind_speed * np.sign(Ui_steer) + + # still, intergral term should not be bigger then limits + Ui_steer = np.clip(Ui_steer, -steer_max, steer_max) + + output_steer = Up_steer + Ui_steer + + # don't run steer control if at very low speed + if v_ego < 0.3 or not enabled: + output_steer = 0. + Ui_steer = 0. + + # useful to know if control is against the limit + lateral_control_sat = False + if abs(output_steer) > steer_max: + lateral_control_sat = True + + output_steer = np.clip(output_steer, -steer_max, steer_max) + + # if lateral control is saturated for a certain period of time, send an alert for taking control of the car + # wind + if lateral_control_sat and not steer_override and v_ego > 10 and abs(error_steer) > 0.1: + sat_count += sat_count_rate + # unwind + else: + sat_count -= sat_count_rate + + sat_flag = False + if sat_count >= sat_count_limit: + sat_flag = True + + sat_count = np.clip(sat_count, 0, 1) + + return output_steer, Up_steer, Ui_steer, lateral_control_sat, sat_count, sat_flag + +class LatControl(object): + def __init__(self): + self.Up_steer = 0. + self.sat_count = 0 + self.y_des = 0.0 + self.lateral_control_sat = False + self.Ui_steer = 0. + self.reset() + + def reset(self): + self.Ui_steer = 0. + + def update(self, enabled, CS, d_poly, angle_offset): + rate = 100 + + steer_max = 1.0 + + # how far we look ahead is function of speed + d_lookahead = calc_d_lookahead(CS.v_ego) + + # calculate actual offset at the lookahead point + self.y_actual, _ = calc_lookahead_offset(CS.v_ego, CS.angle_steers, + d_lookahead, CS.VP, angle_offset) + + # desired lookahead offset + self.y_des = np.polyval(d_poly, d_lookahead) + + output_steer, self.Up_steer, self.Ui_steer, self.lateral_control_sat, self.sat_count, sat_flag = pid_lateral_control( + CS.v_ego, self.y_actual, self.y_des, self.Ui_steer, steer_max, + CS.steer_override, self.sat_count, enabled, CS.torque_mod, rate) + + final_steer = np.clip(output_steer, -steer_max, steer_max) + return final_steer, sat_flag diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py new file mode 100644 index 0000000000..819d4807a4 --- /dev/null +++ b/selfdrive/controls/lib/longcontrol.py @@ -0,0 +1,232 @@ +import numpy as np +from selfdrive.config import Conversions as CV + +class LongCtrlState: + #*** this function handles the long control state transitions + # long_control_state labels: + off = 0 # Off + pid = 1 # moving and tracking targets, with PID control running + stopping = 2 # stopping and changing controls to almost open loop as PID does not fit well at such a low speed + starting = 3 # starting and releasing brakes in open loop before giving back to PID + +def long_control_state_trans(enabled, long_control_state, v_ego, v_target, v_pid, output_gb): + + stopping_speed = 0.5 + stopping_target_speed = 0.3 + starting_target_speed = 0.5 + brake_threshold_to_pid = 0.2 + + stopping_condition = ((v_ego < stopping_speed) and (v_pid < stopping_target_speed) and (v_target < stopping_target_speed)) + + if not enabled: + long_control_state = LongCtrlState.off + else: + if long_control_state == LongCtrlState.off: + if enabled: + long_control_state = LongCtrlState.pid + elif long_control_state == LongCtrlState.pid: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif long_control_state == LongCtrlState.stopping: + if (v_target > starting_target_speed): + long_control_state = LongCtrlState.starting + elif long_control_state == LongCtrlState.starting: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif output_gb >= -brake_threshold_to_pid: + long_control_state = LongCtrlState.pid + + return long_control_state + +def get_compute_gb(): + # see debug/dump_accel_from_fiber.py + w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], + [ 1.03691769, 0.78210306, -0.41343188]]) + b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) + w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], + [ 0.79973811, 0.13178682, 0.08550351], + [-0.15651935, -0.44360259, 0.76910877]]) + b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) + w4 = np.array([[-0.31521443], + [-0.38626176], + [ 0.52667892]]) + b4 = np.array([-0.02922216]) + + def compute_output(dat, w0, b0, w2, b2, w4, b4): + m0 = np.dot(dat, w0) + b0 + m0 = leakyrelu(m0, 0.1) + m2 = np.dot(m0, w2) + b2 + m2 = leakyrelu(m2, 0.1) + m4 = np.dot(m2, w4) + b4 + return m4 + + def leakyrelu(x, alpha): + return np.maximum(x, alpha * x) + + def _compute_gb(dat): + #linearly extrap below v1 using v1 and v2 data + v1 = 5. + v2 = 10. + vx = dat[1] + if vx > 5.: + m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) + else: + dat[1] = v1 + m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) + dat[1] = v2 + m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) + m4 = (vx - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 + return m4 + return _compute_gb + +# takes in [desired_accel, current_speed] -> [-1.0, 1.0] where -1.0 is max brake and 1.0 is max gas +compute_gb = get_compute_gb() + +def pid_long_control(v_ego, v_pid, Ui_accel_cmd, gas_max, brake_max, jerk_factor, gear, rate): + #*** This function compute the gb pedal positions in order to track the desired speed + # proportional and integral terms. More precision at low speed + Kp_v = [1.2, 0.8, 0.5] + Kp_bp = [0., 5., 35.] + Kp = np.interp(v_ego, Kp_bp, Kp_v) + Ki_v = [0.18, 0.12] + Ki_bp = [0., 35.] + Ki = np.interp(v_ego, Ki_bp, Ki_v) + + # scle Kp and Ki by jerk factor drom drive_thread + Kp = (1. + jerk_factor)*Kp + Ki = (1. + jerk_factor)*Ki + + # this is ugly but can speed reports 0 when speed<0.3m/s and we can't have that jump + v_ego_min = 0.3 + v_ego = np.maximum(v_ego, v_ego_min) + + v_error = v_pid - v_ego + + Up_accel_cmd = v_error*Kp + Ui_accel_cmd_new = Ui_accel_cmd + v_error*Ki*1.0/rate + accel_cmd_new = Ui_accel_cmd_new + Up_accel_cmd + output_gb_new = compute_gb([accel_cmd_new, v_ego]) + + # Anti-wind up for integrator: only update integrator if we not against the thottle and brake limits + # do not wind up if we are changing gear and we are on the gas pedal + if (((v_error >= 0. and (output_gb_new < gas_max or Ui_accel_cmd < 0)) or + (v_error <= 0. and (output_gb_new > - brake_max or Ui_accel_cmd > 0))) and + not (v_error >= 0. and gear == 11 and output_gb_new > 0)): + #update integrator + Ui_accel_cmd = Ui_accel_cmd_new + + accel_cmd = Ui_accel_cmd + Up_accel_cmd + + # go from accel to pedals + output_gb = compute_gb([accel_cmd, v_ego]) + output_gb = output_gb[0] + + # useful to know if control is against the limit + long_control_sat = False + if output_gb > gas_max or output_gb < -brake_max: + long_control_sat = True + + output_gb = np.clip(output_gb, -brake_max, gas_max) + + return output_gb, Up_accel_cmd, Ui_accel_cmd, long_control_sat + + +stopping_brake_rate = 0.2 # brake_travel/s while trying to stop +starting_brake_rate = 0.6 # brake_travel/s while releasing on restart +starting_Ui = 0.5 # Since we don't have much info about acceleration at this point, be conservative +brake_stopping_target = 0.5 # apply at least this amount of brake to maintain the vehicle stationary + +max_speed_error_v = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp +max_speed_error_bp = [0., 30.] # speed breakpoints + +class LongControl(object): + def __init__(self): + self.long_control_state = LongCtrlState.off # initialized to off + self.long_control_sat = False + self.Up_accel_cmd = 0. + self.last_output_gb = 0. + self.reset(0.) + + def reset(self, v_pid): + self.Ui_accel_cmd = 0. + self.v_pid = v_pid + + def update(self, enabled, CS, v_cruise, v_target_lead, a_target, jerk_factor): + # TODO: not every time + if CS.brake_only: + gas_max_v = [0, 0] # values + else: + gas_max_v = [0.6, 0.6] # values + gas_max_bp = [0., 100.] # speeds + brake_max_v = [1.0, 1.0, 0.8, 0.8] # values + brake_max_bp = [0., 5., 20., 100.] # speeds + + # brake and gas limits + brake_max = np.interp(CS.v_ego, brake_max_bp, brake_max_v) + gas_max = np.interp(CS.v_ego, gas_max_bp, gas_max_v) + + overshoot_allowance = 2.0 # overshoot allowed when changing accel sign + + output_gb = self.last_output_gb + rate = 100 + + # limit max target speed based on cruise setting: + v_cruise_mph = round(v_cruise * CV.KPH_TO_MPH) # what's displayed in mph on the IC + v_target = np.minimum(v_target_lead, v_cruise_mph * CV.MPH_TO_MS / CS.ui_speed_fudge) + + max_speed_delta_up = a_target[1]*1.0/rate + max_speed_delta_down = a_target[0]*1.0/rate + + # *** long control substate transitions + self.long_control_state = long_control_state_trans(enabled, self.long_control_state, CS.v_ego, v_target, self.v_pid, output_gb) + + # *** long control behavior based on state + # TODO: move this to drive_helpers + # disabled + if self.long_control_state == LongCtrlState.off: + self.v_pid = CS.v_ego # do nothing + output_gb = 0. + self.Ui_accel_cmd = 0. + # tracking objects and driving + elif self.long_control_state == LongCtrlState.pid: + #reset v_pid close to v_ego if it was too far and new v_target is closer to v_ego + if ((self.v_pid > CS.v_ego + overshoot_allowance) and + (v_target < self.v_pid)): + self.v_pid = np.maximum(v_target, CS.v_ego + overshoot_allowance) + elif ((self.v_pid < CS.v_ego - overshoot_allowance) and + (v_target > self.v_pid)): + self.v_pid = np.minimum(v_target, CS.v_ego - overshoot_allowance) + + # move v_pid no faster than allowed accel limits + if (v_target > self.v_pid + max_speed_delta_up): + self.v_pid += max_speed_delta_up + elif (v_target < self.v_pid + max_speed_delta_down): + self.v_pid += max_speed_delta_down + else: + self.v_pid = v_target + + # to avoid too much wind up on acceleration, limit positive speed error + if not CS.brake_only: + max_speed_error = np.interp(CS.v_ego, max_speed_error_bp, max_speed_error_v) + self.v_pid = np.minimum(self.v_pid, CS.v_ego + max_speed_error) + + output_gb, self.Up_accel_cmd, self.Ui_accel_cmd, self.long_control_sat = pid_long_control(CS.v_ego, self.v_pid, \ + self.Ui_accel_cmd, gas_max, brake_max, jerk_factor, CS.gear, rate) + # intention is to stop, switch to a different brake control until we stop + elif self.long_control_state == LongCtrlState.stopping: + if CS.v_ego > 0. or output_gb > -brake_stopping_target or not CS.standstill: + output_gb -= stopping_brake_rate/rate + output_gb = np.clip(output_gb, -brake_max, gas_max) + self.v_pid = CS.v_ego + self.Ui_accel_cmd = 0. + # intention is to move again, release brake fast before handling control to PID + elif self.long_control_state == LongCtrlState.starting: + if output_gb < -0.2: + output_gb += starting_brake_rate/rate + self.v_pid = CS.v_ego + self.Ui_accel_cmd = starting_Ui + + self.last_output_gb = output_gb + final_gas = np.clip(output_gb, 0., gas_max) + final_brake = -np.clip(output_gb, -brake_max, 0.) + return final_gas, final_brake diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py new file mode 100644 index 0000000000..49e5eb2e3e --- /dev/null +++ b/selfdrive/controls/lib/pathplanner.py @@ -0,0 +1,63 @@ +import selfdrive.messaging as messaging +import numpy as np +X_PATH = np.arange(0.0, 50.0) + +def model_polyfit(points): + return np.polyfit(X_PATH, map(float, points), 3) + +# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm +_LANE_WIDTH_V = np.asarray([3., 3.8]) + +# break points of speed +_LANE_WIDTH_BP = np.asarray([0., 31.]) + +def calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, speed): + #*** this function computes the poly for the center of the lane, averaging left and right polys + lane_width = np.interp(speed, _LANE_WIDTH_BP, _LANE_WIDTH_V) + + # lanes in US are ~3.6m wide + half_lane_poly = np.array([0., 0., 0., lane_width / 2.]) + if l_prob + r_prob > 0.01: + c_poly = ((l_poly - half_lane_poly) * l_prob + + (r_poly + half_lane_poly) * r_prob) / (l_prob + r_prob) + c_prob = np.sqrt((l_prob**2 + r_prob**2) / 2.) + else: + c_poly = np.zeros(4) + c_prob = 0. + + p_weight = 1. # predicted path weight relatively to the center of the lane + d_poly = list((c_poly*c_prob + p_poly*p_prob*p_weight ) / (c_prob + p_prob*p_weight)) + return d_poly, c_poly, c_prob + +class PathPlanner(object): + def __init__(self, model): + self.model = model + self.dead = True + self.d_poly = [0., 0., 0., 0.] + self.last_model = 0. + self.logMonoTime = 0 + self.lead_dist, self.lead_prob, self.lead_var = 0, 0, 1 + + def update(self, cur_time, v_ego): + md = messaging.recv_sock(self.model) + + if md is not None: + self.logMonoTime = md.logMonoTime + p_poly = model_polyfit(md.model.path.points) # predicted path + p_prob = 1. # model does not tell this probability yet, so set to 1 for now + l_poly = model_polyfit(md.model.leftLane.points) # left line + l_prob = md.model.leftLane.prob # left line prob + r_poly = model_polyfit(md.model.rightLane.points) # right line + r_prob = md.model.rightLane.prob # right line prob + + self.lead_dist = md.model.lead.dist + self.lead_prob = md.model.lead.prob + self.lead_var = md.model.lead.std**2 + + #*** compute target path *** + self.d_poly, _, _ = calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, v_ego) + + self.last_model = cur_time + self.dead = False + elif cur_time - self.last_model > 0.5: + self.dead = True diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py new file mode 100644 index 0000000000..f7759a4d4d --- /dev/null +++ b/selfdrive/controls/lib/radar_helpers.py @@ -0,0 +1,256 @@ +import numpy as np +import platform +import os +import sys + +from common.kalman.ekf import FastEKF1D, SimpleSensor + +# radar tracks +SPEED, ACCEL = 0, 1 # Kalman filter states enum + +rate, ratev = 20., 20. # model and radar are both at 20Hz +ts = 1./rate +freq_v_lat = 0.2 # Hz +k_v_lat = 2*np.pi*freq_v_lat*ts / (1 + 2*np.pi*freq_v_lat*ts) + +freq_a_lead = .5 # Hz +k_a_lead = 2*np.pi*freq_a_lead*ts / (1 + 2*np.pi*freq_a_lead*ts) + +# stationary qualification parameters +v_stationary_thr = 4. # objects moving below this speed are classified as stationary +v_oncoming_thr = -3.9 # needs to be a bit lower in abs value than v_stationary_thr to not leave "holes" +v_ego_stationary = 4. # no stationary object flag below this speed + +class Track(object): + def __init__(self): + self.ekf = None + self.stationary = True + self.initted = False + + def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned): + if self.initted: + self.dPathPrev = self.dPath + self.vLeadPrev = self.vLead + self.vRelPrev = self.vRel + + # relative values, copy + self.dRel = d_rel # LONG_DIST + self.yRel = y_rel # -LAT_DIST + self.vRel = v_rel # REL_SPEED + + # compute distance to path + self.dPath = d_path + + # computed velocity and accelerations + self.vLead = self.vRel + v_ego_t_aligned + + if not self.initted: + self.aRel = 0. # nidec gives no information about this + self.vLat = 0. + self.aLead = 0. + else: + # estimate acceleration + a_rel_unfilt = (self.vRel - self.vRelPrev) / ts + a_rel_unfilt = np.clip(a_rel_unfilt, -10., 10.) + self.aRel = k_a_lead * a_rel_unfilt + (1 - k_a_lead) * self.aRel + + v_lat_unfilt = (self.dPath - self.dPathPrev) / ts + self.vLat = k_v_lat * v_lat_unfilt + (1 - k_v_lat) * self.vLat + + a_lead_unfilt = (self.vLead - self.vLeadPrev) / ts + a_lead_unfilt = np.clip(a_lead_unfilt, -10., 10.) + self.aLead = k_a_lead * a_lead_unfilt + (1 - k_a_lead) * self.aLead + + if self.stationary: + # stationary objects can become non stationary, but not the other way around + self.stationary = v_ego_t_aligned > v_ego_stationary and abs(self.vLead) < v_stationary_thr + self.oncoming = self.vLead < v_oncoming_thr + + if self.ekf is None: + self.ekf = FastEKF1D(ts, 1e3, [0.1, 1]) + self.ekf.state[SPEED] = self.vLead + self.ekf.state[ACCEL] = 0 + self.lead_sensor = SimpleSensor(SPEED, 1, 2) + + self.vLeadK = self.vLead + self.aLeadK = self.aLead + else: + self.ekf.update_scalar(self.lead_sensor.read(self.vLead)) + self.ekf.predict(ts) + self.vLeadK = float(self.ekf.state[SPEED]) + self.aLeadK = float(self.ekf.state[ACCEL]) + + if not self.initted: + self.cnt = 1 + self.vision_cnt = 0 + else: + self.cnt += 1 + + self.initted = True + self.vision = False + + def mix_vision(self, dist_to_vision, rel_speed_diff): + # rel speed is very hard to estimate from vision + if dist_to_vision < 4.0 and rel_speed_diff < 10.: + # vision point is never stationary + self.stationary = False + self.vision = True + self.vision_cnt += 1 + + def get_key_for_cluster(self): + # Weigh y higher since radar is inaccurate in this dimension + return [self.dRel, self.dPath*2, self.vRel] + +# ******************* Cluster ******************* + +if platform.machine() == 'aarch64': + for x in sys.path: + pp = os.path.join(x, "phonelibs/hierarchy/lib") + if os.path.isfile(os.path.join(pp, "_hierarchy.so")): + sys.path.append(pp) + break + import _hierarchy +else: + from scipy.cluster import _hierarchy + +def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None): + # supersimplified function to get fast clustering. Got it from scipy + Z = np.asarray(Z, order='c') + n = Z.shape[0] + 1 + T = np.zeros((n,), dtype='i') + _hierarchy.cluster_dist(Z, T, float(t), int(n)) + return T + +RDR_TO_LDR = 2.7 + +def mean(l): + return sum(l)/len(l) + +class Cluster(object): + def __init__(self): + self.tracks = set() + + def add(self, t): + # add the first track + self.tracks.add(t) + + # TODO: make generic + @property + def dRel(self): + return mean([t.dRel for t in self.tracks]) + + @property + def yRel(self): + return mean([t.yRel for t in self.tracks]) + + @property + def vRel(self): + return mean([t.vRel for t in self.tracks]) + + @property + def aRel(self): + return mean([t.aRel for t in self.tracks]) + + @property + def vLead(self): + return mean([t.vLead for t in self.tracks]) + + @property + def aLead(self): + return mean([t.aLead for t in self.tracks]) + + @property + def dPath(self): + return mean([t.dPath for t in self.tracks]) + + @property + def vLat(self): + return mean([t.vLat for t in self.tracks]) + + @property + def vLeadK(self): + return mean([t.vLeadK for t in self.tracks]) + + @property + def aLeadK(self): + return mean([t.aLeadK for t in self.tracks]) + + @property + def vision(self): + return any([t.vision for t in self.tracks]) + + @property + def vision_cnt(self): + return max([t.vision_cnt for t in self.tracks]) + + @property + def stationary(self): + return all([t.stationary for t in self.tracks]) + + @property + def oncoming(self): + return all([t.oncoming for t in self.tracks]) + + def toLive20(self, lead): + lead.dRel = float(self.dRel) - RDR_TO_LDR + lead.yRel = float(self.yRel) + lead.vRel = float(self.vRel) + lead.aRel = float(self.aRel) + lead.vLead = float(self.vLead) + lead.aLead = float(self.aLead) + lead.dPath = float(self.dPath) + lead.vLat = float(self.vLat) + lead.vLeadK = float(self.vLeadK) + lead.aLeadK = float(self.aLeadK) + lead.status = True + lead.fcw = False + + def __str__(self): + ret = "x: %7.2f y: %7.2f v: %7.2f a: %7.2f" % (self.dRel, self.yRel, self.vRel, self.aRel) + if self.stationary: + ret += " stationary" + if self.vision: + ret += " vision" + if self.oncoming: + ret += " oncoming" + if self.vision_cnt > 0: + ret += " vision_cnt: %6.0f" % self.vision_cnt + return ret + + def is_potential_lead(self, v_ego, enabled): + # predict cut-ins by extrapolating lateral speed by a lookahead time + # lookahead time depends on cut-in distance. more attentive for close cut-ins + # also, above 50 meters the predicted path isn't very reliable + + # the distance at which v_lat matters is higher at higher speed + lookahead_dist = 40. + v_ego/1.2 #40m at 0mph, ~70m at 80mph + + t_lookahead_v = [1., 0.] + t_lookahead_bp = [10., lookahead_dist] + + # average dist + d_path = self.dPath + + if enabled: + t_lookahead = np.interp(self.dRel, t_lookahead_bp, t_lookahead_v) + # correct d_path for lookahead time, considering only cut-ins and no more than 1m impact + lat_corr = np.clip(t_lookahead * self.vLat, -1, 0) + else: + lat_corr = 0. + d_path = np.maximum(d_path + lat_corr, 0) + + if d_path < 1.5 and not self.stationary and not self.oncoming: + return True + else: + return False + + def is_potential_lead2(self, lead_clusters): + if len(lead_clusters) > 0: + lead_cluster = lead_clusters[0] + # check if the new lead is too close and roughly at the same speed of the first lead: it might just be the second axle of the same vehicle + if (self.dRel - lead_cluster.dRel) < 8. and abs(self.vRel - lead_cluster.vRel) < 1.: + return False + else: + return True + else: + return False diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py new file mode 100755 index 0000000000..2ee244d3cd --- /dev/null +++ b/selfdrive/controls/radard.py @@ -0,0 +1,268 @@ +#!/usr/bin/env python +import zmq +import numpy as np +import numpy.matlib +from collections import defaultdict + +from fastcluster import linkage_vector + +import selfdrive.messaging as messaging +from selfdrive.boardd.boardd import can_capnp_to_can_list_old +from selfdrive.controls.lib.latcontrol import calc_lookahead_offset +from selfdrive.controls.lib.can_parser import CANParser +from selfdrive.controls.lib.pathplanner import PathPlanner +from selfdrive.config import VehicleParams +from selfdrive.controls.lib.radar_helpers import Track, Cluster, fcluster, RDR_TO_LDR + +from common.services import service_list +from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper +from common.kalman.ekf import EKF, SimpleSensor + +#vision point +DIMSV = 2 +XV, SPEEDV = 0, 1 +VISION_POINT = 1 + +class EKFV1D(EKF): + def __init__(self): + super(EKFV1D, self).__init__(False) + self.identity = np.matlib.identity(DIMSV) + self.state = np.matlib.zeros((DIMSV, 1)) + self.var_init = 1e2 # ~ model variance when probability is 70%, so good starting point + self.covar = self.identity * self.var_init + + # self.process_noise = np.asmatrix(np.diag([100, 10])) + self.process_noise = np.matlib.diag([0.5, 1]) + + def calc_transfer_fun(self, dt): + tf = np.matlib.identity(DIMSV) + tf[XV, SPEEDV] = dt + tfj = tf + return tf, tfj + + +# nidec radar decoding +def nidec_decode(cp, ar_pts): + for ii in cp.msgs_upd: + # filter points with very big distance, as fff (~255) is invalid. FIXME: use VAL tables from dbc + if cp.vl[ii]['LONG_DIST'] < 255: + ar_pts[ii] = [cp.vl[ii]['LONG_DIST'] + RDR_TO_LDR, + -cp.vl[ii]['LAT_DIST'], cp.vl[ii]['REL_SPEED'], np.nan, + cp.ts[ii], cp.vl[ii]['NEW_TRACK'], cp.ct[ii]] + elif ii in ar_pts: + del ar_pts[ii] + return ar_pts + + +def _create_radard_can_parser(): + dbc_f = 'acura_ilx_2016_nidec.dbc' + radar_messages = range(0x430, 0x43A) + range(0x440, 0x446) + signals = zip(['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + ['REL_SPEED'] * 16, radar_messages * 4, + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) + checks = zip(radar_messages, [20]*16) + + return CANParser(dbc_f, signals, checks) + + +# fuses camera and radar data for best lead detection +def radard_thread(gctx=None): + set_realtime_priority(1) + + context = zmq.Context() + + # *** subscribe to features and model from visiond + model = messaging.sub_sock(context, service_list['model'].port) + logcan = messaging.sub_sock(context, service_list['can'].port) + live100 = messaging.sub_sock(context, service_list['live100'].port) + + PP = PathPlanner(model) + + # *** publish live20 and liveTracks + live20 = messaging.pub_sock(context, service_list['live20'].port) + liveTracks = messaging.pub_sock(context, service_list['liveTracks'].port) + + # subscribe to stats about the car + # TODO: move this to new style packet + VP = VehicleParams(False) # same for ILX and civic + + ar_pts = {} + path_x = np.arange(0.0, 140.0, 0.1) # 140 meters is max + + # Time-alignment + rate = 20. # model and radar are both at 20Hz + tsv = 1./rate + rdr_delay = 0.10 # radar data delay in s + v_len = 20 # how many speed data points to remember for t alignment with rdr data + + enabled = 0 + steer_angle = 0. + + tracks = defaultdict(dict) + + # Nidec + cp = _create_radard_can_parser() + + # Kalman filter stuff: + ekfv = EKFV1D() + speedSensorV = SimpleSensor(XV, 1, 2) + + # v_ego + v_ego = None + v_ego_array = np.zeros([2, v_len]) + v_ego_t_aligned = 0. + + rk = Ratekeeper(rate, print_delay_threshold=np.inf) + while 1: + canMonoTimes = [] + can_pub_radar = [] + for a in messaging.drain_sock(logcan, wait_for_one=True): + canMonoTimes.append(a.logMonoTime) + can_pub_radar.extend(can_capnp_to_can_list_old(a, [1, 3])) + + # only run on the 0x445 packets, used for timing + if not any(x[0] == 0x445 for x in can_pub_radar): + continue + + cp.update_can(can_pub_radar) + + if not cp.can_valid: + # TODO: handle this + pass + + ar_pts = nidec_decode(cp, ar_pts) + + # receive the live100s + l100 = messaging.recv_sock(live100) + if l100 is not None: + enabled = l100.live100.enabled + v_ego = l100.live100.vEgo + steer_angle = l100.live100.angleSteers + + v_ego_array = np.append(v_ego_array, [[v_ego], [float(rk.frame)/rate]], 1) + v_ego_array = v_ego_array[:, 1:] + + if v_ego is None: + continue + + # *** get path prediction from the model *** + PP.update(sec_since_boot(), v_ego) + + # run kalman filter only if prob is high enough + if PP.lead_prob > 0.7: + ekfv.update(speedSensorV.read(PP.lead_dist, covar=PP.lead_var)) + ekfv.predict(tsv) + ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])), + float(ekfv.state[SPEEDV]), np.nan, PP.logMonoTime, np.nan, sec_since_boot()) + else: + ekfv.state[XV] = PP.lead_dist + ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) + ekfv.state[SPEEDV] = 0. + if VISION_POINT in ar_pts: + del ar_pts[VISION_POINT] + + # *** compute the likely path_y *** + if enabled: # use path from model path_poly + path_y = np.polyval(PP.d_poly, path_x) + else: # use path from steer, set angle_offset to 0 since calibration does not exactly report the physical offset + path_y = calc_lookahead_offset(v_ego, steer_angle, path_x, VP, angle_offset=0)[0] + + # *** remove missing points from meta data *** + for ids in tracks.keys(): + if ids not in ar_pts: + tracks.pop(ids, None) + + # *** compute the tracks *** + for ids in ar_pts: + # ignore the vision point for now + if ids == VISION_POINT: + continue + rpt = ar_pts[ids] + + # align v_ego by a fixed time to align it with the radar measurement + cur_time = float(rk.frame)/rate + v_ego_t_aligned = np.interp(cur_time - rdr_delay, v_ego_array[1], v_ego_array[0]) + d_path = np.sqrt(np.amin((path_x - rpt[0]) ** 2 + (path_y - rpt[1]) ** 2)) + + # create the track + if ids not in tracks or rpt[5] == 1: + tracks[ids] = Track() + tracks[ids].update(rpt[0], rpt[1], rpt[2], d_path, v_ego_t_aligned) + + # allow the vision model to remove the stationary flag if distance and rel speed roughly match + if VISION_POINT in ar_pts: + dist_to_vision = np.sqrt((0.5*(ar_pts[VISION_POINT][0] - rpt[0])) ** 2 + (2*(ar_pts[VISION_POINT][1] - rpt[1])) ** 2) + rel_speed_diff = abs(ar_pts[VISION_POINT][2] - rpt[2]) + tracks[ids].mix_vision(dist_to_vision, rel_speed_diff) + + # publish tracks (debugging) + dat = messaging.new_message() + dat.init('liveTracks', len(tracks)) + for cnt, ids in enumerate(tracks.keys()): + dat.liveTracks[cnt].trackId = ids + dat.liveTracks[cnt].dRel = float(tracks[ids].dRel) + dat.liveTracks[cnt].yRel = float(tracks[ids].yRel) + dat.liveTracks[cnt].vRel = float(tracks[ids].vRel) + dat.liveTracks[cnt].aRel = float(tracks[ids].aRel) + dat.liveTracks[cnt].stationary = tracks[ids].stationary + dat.liveTracks[cnt].oncoming = tracks[ids].oncoming + liveTracks.send(dat.to_bytes()) + + idens = tracks.keys() + track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens]) + + # If we have multiple points, cluster them + if len(track_pts) > 1: + link = linkage_vector(track_pts, method='centroid') + cluster_idxs = fcluster(link, 2.5, criterion='distance') + clusters = [None]*max(cluster_idxs) + + for idx in xrange(len(track_pts)): + cluster_i = cluster_idxs[idx]-1 + + if clusters[cluster_i] == None: + clusters[cluster_i] = Cluster() + clusters[cluster_i].add(tracks[idens[idx]]) + elif len(track_pts) == 1: + # TODO: why do we need this? + clusters = [Cluster()] + clusters[0].add(tracks[idens[0]]) + else: + clusters = [] + + # *** extract the lead car *** + lead_clusters = [c for c in clusters + if c.is_potential_lead(v_ego, enabled)] + lead_clusters.sort(key=lambda x: x.dRel) + lead_len = len(lead_clusters) + + # *** extract the second lead from the whole set of leads *** + lead2_clusters = [c for c in lead_clusters + if c.is_potential_lead2(lead_clusters)] + lead2_clusters.sort(key=lambda x: x.dRel) + lead2_len = len(lead2_clusters) + + # *** publish live20 *** + dat = messaging.new_message() + dat.init('live20') + dat.live20.mdMonoTime = PP.logMonoTime + dat.live20.canMonoTimes = canMonoTimes + if lead_len > 0: + lead_clusters[0].toLive20(dat.live20.leadOne) + if lead2_len > 0: + lead2_clusters[0].toLive20(dat.live20.leadTwo) + else: + dat.live20.leadTwo.status = False + else: + dat.live20.leadOne.status = False + + dat.live20.cumLagMs = -rk.remaining*1000. + live20.send(dat.to_bytes()) + + rk.monitor_time() + +def main(gctx=None): + radard_thread(gctx) + +if __name__ == "__main__": + main() diff --git a/selfdrive/logcatd/Makefile b/selfdrive/logcatd/Makefile new file mode 100644 index 0000000000..610ca25676 --- /dev/null +++ b/selfdrive/logcatd/Makefile @@ -0,0 +1,58 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +OBJS = logcatd.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: logcatd + +logcatd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -llog + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f logcatd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/logcatd/logcatd.cc b/selfdrive/logcatd/logcatd.cc new file mode 100644 index 0000000000..c2f688fd59 --- /dev/null +++ b/selfdrive/logcatd/logcatd.cc @@ -0,0 +1,68 @@ +#include +#include +#include + +#include +#include +#include + +#include +#include +#include "common/timing.h" +#include "cereal/gen/cpp/log.capnp.h" + +int main() { + int err; + + struct logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0); + assert(logger_list); + struct logger *main_logger = android_logger_open(logger_list, LOG_ID_MAIN); + assert(main_logger); + struct logger *radio_logger = android_logger_open(logger_list, LOG_ID_RADIO); + assert(radio_logger); + struct logger *system_logger = android_logger_open(logger_list, LOG_ID_SYSTEM); + assert(system_logger); + struct logger *crash_logger = android_logger_open(logger_list, LOG_ID_CRASH); + assert(crash_logger); + struct logger *kernel_logger = android_logger_open(logger_list, LOG_ID_KERNEL); + assert(kernel_logger); + + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + err = zmq_bind(publisher, "tcp://*:8020"); + assert(err == 0); + + while (1) { + log_msg log_msg; + err = android_logger_list_read(logger_list, &log_msg); + if (err <= 0) { + break; + } + + AndroidLogEntry entry; + err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); + if (err < 0) { + continue; + } + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto androidEntry = event.initAndroidLogEntry(); + androidEntry.setId(log_msg.id()); + androidEntry.setTs(entry.tv_sec * 1000000000ULL + entry.tv_nsec); + androidEntry.setPriority(entry.priority); + androidEntry.setPid(entry.pid); + androidEntry.setTid(entry.tid); + androidEntry.setTag(entry.tag); + androidEntry.setMessage(entry.message); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + } + + android_logger_list_close(logger_list); + + return 0; +} \ No newline at end of file diff --git a/selfdrive/loggerd/__init__.py b/selfdrive/loggerd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py new file mode 100644 index 0000000000..ffba77d078 --- /dev/null +++ b/selfdrive/loggerd/config.py @@ -0,0 +1,9 @@ +import os + +# fetch from environment +DONGLE_ID = os.getenv("DONGLE_ID") +DONGLE_SECRET = os.getenv("DONGLE_SECRET") + +ROOT = '/sdcard/realdata/' + +SEGMENT_LENGTH = 60 diff --git a/selfdrive/loggerd/logger.py b/selfdrive/loggerd/logger.py new file mode 100644 index 0000000000..78af9d4740 --- /dev/null +++ b/selfdrive/loggerd/logger.py @@ -0,0 +1,65 @@ +import os +import time + + +class Logger(object): + def __init__(self, root, init_data): + self.root = root + self.init_data = init_data + + self.part = None + self.data_dir = None + self.cur_dir = None + self.log_file = None + self.started = False + self.log_path = None + self.lock_path = None + self.log_file = None + + def open(self): + self.data_dir = self.cur_dir + "--" + str(self.part) + + try: + os.makedirs(self.data_dir) + except OSError: + pass + + self.log_path = os.path.join(self.data_dir, "rlog") + self.lock_path = self.log_path + ".lock" + + open(self.lock_path, "wb").close() + self.log_file = open(self.log_path, "wb") + self.log_file.write(self.init_data) + + def start(self): + self.part = 0 + self.cur_dir = self.root + time.strftime("%Y-%m-%d--%H-%M-%S") + + self.open() + + self.started = True + + return self.data_dir, self.part + + def stop(self): + if not self.started: + return + self.log_file.close() + os.unlink(self.lock_path) + self.started = False + + def rotate(self): + old_lock_path = self.lock_path + old_log_file = self.log_file + self.part += 1 + self.open() + + old_log_file.close() + os.unlink(old_lock_path) + + return self.data_dir, self.part + + def log_data(self, d): + if not self.started: + return + self.log_file.write(d) diff --git a/selfdrive/loggerd/loggerd.py b/selfdrive/loggerd/loggerd.py new file mode 100755 index 0000000000..2e7985ba0d --- /dev/null +++ b/selfdrive/loggerd/loggerd.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python +import os +import json +import zmq + +import common.realtime as realtime +from common.services import service_list +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging + +import uploader +from logger import Logger + +from selfdrive.loggerd.config import ROOT, SEGMENT_LENGTH + + +def gen_init_data(gctx): + msg = messaging.new_message() + + kernel_args = open("/proc/cmdline", "r").read().strip().split(" ") + msg.initData.kernelArgs = kernel_args + + msg.initData.gctx = json.dumps(gctx) + if os.getenv('DONGLE_ID'): + msg.initData.dongleId = os.getenv('DONGLE_ID') + + return msg.to_bytes() + +def main(gctx=None): + logger = Logger(ROOT, gen_init_data(gctx)) + + context = zmq.Context() + poller = zmq.Poller() + + # we push messages to visiond to rotate image recordings + vision_control_sock = context.socket(zmq.PUSH) + vision_control_sock.connect("tcp://127.0.0.1:8001") + + # register listeners for all services + for service in service_list.itervalues(): + if service.should_log and service.port is not None: + messaging.sub_sock(context, service.port, poller) + + uploader.clear_locks(ROOT) + + cur_dir, cur_part = logger.start() + try: + cloudlog.info("starting in dir %r", cur_dir) + + rotate_msg = messaging.log.LogRotate.new_message() + rotate_msg.segmentNum = cur_part + rotate_msg.path = cur_dir + vision_control_sock.send(rotate_msg.to_bytes()) + + last_rotate = realtime.sec_since_boot() + while True: + polld = poller.poll(timeout=1000) + for sock, mode in polld: + if mode != zmq.POLLIN: + continue + dat = sock.recv() + + # print "got", len(dat), realtime.sec_since_boot() + # logevent = log_capnp.Event.from_bytes(dat) + # print str(logevent) + logger.log_data(dat) + + t = realtime.sec_since_boot() + if (t - last_rotate) > SEGMENT_LENGTH: + last_rotate += SEGMENT_LENGTH + + cur_dir, cur_part = logger.rotate() + cloudlog.info("rotated to %r", cur_dir) + + rotate_msg = messaging.log.LogRotate.new_message() + rotate_msg.segmentNum = cur_part + rotate_msg.path = cur_dir + + vision_control_sock.send(rotate_msg.to_bytes()) + + finally: + logger.stop() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py new file mode 100755 index 0000000000..246d45342c --- /dev/null +++ b/selfdrive/loggerd/uploader.py @@ -0,0 +1,238 @@ +#!/usr/bin/env python +import os +import time +import stat +import random +import ctypes +import inspect +import requests +import traceback +import threading + +from selfdrive.swaglog import cloudlog +from selfdrive.loggerd.config import DONGLE_ID, DONGLE_SECRET, ROOT + +from common.api import api_get + +def raise_on_thread(t, exctype): + for ctid, tobj in threading._active.items(): + if tobj is t: + tid = ctid + break + else: + raise Exception("Could not find thread") + + '''Raises an exception in the threads with id tid''' + if not inspect.isclass(exctype): + raise TypeError("Only types can be raised (not instances)") + + res = ctypes.pythonapi.PyThreadState_SetAsyncExc(ctypes.c_long(tid), + ctypes.py_object(exctype)) + if res == 0: + raise ValueError("invalid thread id") + elif res != 1: + # "if it returns a number greater than one, you're in trouble, + # and you should call it again with exc=NULL to revert the effect" + ctypes.pythonapi.PyThreadState_SetAsyncExc(tid, 0) + raise SystemError("PyThreadState_SetAsyncExc failed") + +def listdir_with_creation_date(d): + lst = os.listdir(d) + for fn in lst: + try: + st = os.stat(os.path.join(d, fn)) + ctime = st[stat.ST_CTIME] + yield (ctime, fn) + except OSError: + cloudlog.exception("listdir_with_creation_date: stat failed?") + yield (None, fn) + +def listdir_by_creation_date(d): + times_and_paths = list(listdir_with_creation_date(d)) + return [path for _, path in sorted(times_and_paths)] + +def clear_locks(root): + for logname in os.listdir(root): + path = os.path.join(root, logname) + try: + for fname in os.listdir(path): + if fname.endswith(".lock"): + os.unlink(os.path.join(path, fname)) + except OSError: + cloudlog.exception("clear_locks failed") + + +class Uploader(object): + def __init__(self, dongle_id, dongle_secret, root): + self.dongle_id = dongle_id + self.dongle_secret = dongle_secret + self.root = root + + self.upload_thread = None + + self.last_resp = None + self.last_exc = None + + def clean_dirs(self): + try: + for logname in os.listdir(self.root): + path = os.path.join(self.root, logname) + # remove empty directories + if not os.listdir(path): + os.rmdir(path) + except OSError: + cloudlog.exception("clean_dirs failed") + + def gen_upload_files(self): + for logname in listdir_by_creation_date(self.root): + path = os.path.join(self.root, logname) + names = os.listdir(path) + if any(name.endswith(".lock") for name in names): + continue + + for name in names: + key = os.path.join(logname, name) + fn = os.path.join(path, name) + + yield (name, key, fn) + + def next_file_to_upload(self): + # try to upload log files first + for name, key, fn in self.gen_upload_files(): + if name in ["rlog", "rlog.bz2"]: + return (key, fn, 0) + + # then upload camera files no not on wifi + for name, key, fn in self.gen_upload_files(): + if not name.endswith('.lock') and not name.endswith(".tmp"): + return (key, fn, 1) + + return None + + + def do_upload(self, key, fn): + try: + url_resp = api_get("upload_url", timeout=2, + id=self.dongle_id, secret=self.dongle_secret, + path=key) + url = url_resp.text + cloudlog.info({"upload_url", url}) + + with open(fn, "rb") as f: + self.last_resp = requests.put(url, data=f) + except Exception as e: + self.last_exc = (e, traceback.format_exc()) + raise + + def normal_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + try: + self.do_upload(key, fn) + except Exception: + pass + + return self.last_resp + + def killable_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + self.upload_thread = threading.Thread(target=lambda: self.do_upload(key, fn)) + self.upload_thread.start() + self.upload_thread.join() + self.upload_thread = None + + return self.last_resp + + def abort_upload(self): + thread = self.upload_thread + if thread is None: + return + if not thread.is_alive(): + return + raise_on_thread(thread, SystemExit) + thread.join() + + def upload(self, key, fn): + # write out the bz2 compress + if fn.endswith("log"): + ext = ".bz2" + cloudlog.info("compressing %r to %r", fn, fn+ext) + if os.system("nice -n 19 bzip2 -c %s > %s.tmp && mv %s.tmp %s%s && rm %s" % (fn, fn, fn, fn, ext, fn)) != 0: + cloudlog.exception("upload: bzip2 compression failed") + return False + + # assuming file is named properly + key += ext + fn += ext + + try: + sz = os.path.getsize(fn) + except OSError: + cloudlog.exception("upload: getsize failed") + return False + + cloudlog.event("upload", key=key, fn=fn, sz=sz) + + cloudlog.info("checking %r with size %r", key, sz) + + if sz == 0: + # can't upload files of 0 size + os.unlink(fn) # delete the file + success = True + else: + cloudlog.info("uploading %r", fn) + # stat = self.killable_upload(key, fn) + stat = self.normal_upload(key, fn) + if stat is not None and stat.status_code == 200: + cloudlog.event("upload_success", key=key, fn=fn, sz=sz) + os.unlink(fn) # delete the file + success = True + else: + cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz) + success = False + + self.clean_dirs() + + return success + + + +def uploader_fn(exit_event): + cloudlog.info("uploader_fn") + + uploader = Uploader(DONGLE_ID, DONGLE_SECRET, ROOT) + + while True: + backoff = 0.1 + while True: + + if exit_event.is_set(): + return + + d = uploader.next_file_to_upload() + if d is None: + break + + key, fn, _ = d + + cloudlog.info("to upload %r", d) + success = uploader.upload(key, fn) + if success: + backoff = 0.1 + else: + cloudlog.info("backoff %r", backoff) + time.sleep(backoff + random.uniform(0, backoff)) + backoff *= 2 + cloudlog.info("upload done, success=%r", success) + + time.sleep(5) + +def main(gctx=None): + uploader_fn(threading.Event()) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/logmessaged.py b/selfdrive/logmessaged.py new file mode 100755 index 0000000000..2e49df417c --- /dev/null +++ b/selfdrive/logmessaged.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python +import zmq +from logentries import LogentriesHandler +from common.services import service_list +import selfdrive.messaging as messaging + +def main(gctx): + # setup logentries. we forward log messages to it + le_token = "bc65354a-b887-4ef4-8525-15dd51230e8c" + le_handler = LogentriesHandler(le_token, use_tls=False) + + le_level = 20 #logging.INFO + + ctx = zmq.Context() + sock = ctx.socket(zmq.PULL) + sock.bind("ipc:///tmp/logmessage") + + # and we publish them + pub_sock = messaging.pub_sock(ctx, service_list['logMessage'].port) + + while True: + dat = ''.join(sock.recv_multipart()) + + # print "RECV", repr(dat) + + levelnum = ord(dat[0]) + dat = dat[1:] + + if levelnum >= le_level: + # push to logentries + le_handler.emit_raw(dat) + + # then we publish them + msg = messaging.new_message() + msg.logMessage = dat + pub_sock.send(msg.to_bytes()) + +if __name__ == "__main__": + main(None) diff --git a/selfdrive/manager.py b/selfdrive/manager.py new file mode 100755 index 0000000000..93eae5be2c --- /dev/null +++ b/selfdrive/manager.py @@ -0,0 +1,278 @@ +#!/usr/bin/env python +import os +import sys +import time +import importlib +import subprocess +import signal +import traceback +import usb1 +from multiprocessing import Process +from common.services import service_list + +import zmq + +from setproctitle import setproctitle + +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging +from selfdrive.thermal import read_thermal +from selfdrive.registration import register + +import common.crash + +# comment out anything you don't want to run +managed_processes = { + "uploader": "selfdrive.loggerd.uploader", + "controlsd": "selfdrive.controls.controlsd", + "radard": "selfdrive.controls.radard", + "calibrationd": "selfdrive.calibrationd.calibrationd", + "loggerd": "selfdrive.loggerd.loggerd", + "logmessaged": "selfdrive.logmessaged", + #"boardd": "selfdrive.boardd.boardd", + "logcatd": ("logcatd", ["./logcatd"]), + "boardd": ("boardd", ["./boardd"]), # switch to c++ boardd + "ui": ("ui", ["./ui"]), + "visiond": ("visiond", ["./visiond"]), + "sensord": ("sensord", ["./sensord"]), } + +running = {} + +car_started_processes = ['controlsd', 'loggerd', 'visiond', 'sensord', 'radard', 'calibrationd'] + + +# ****************** process management functions ****************** +def launcher(proc, gctx): + try: + # unset the signals + signal.signal(signal.SIGINT, signal.SIG_DFL) + signal.signal(signal.SIGTERM, signal.SIG_DFL) + + # import the process + mod = importlib.import_module(proc) + + # rename the process + setproctitle(proc) + + # exec the process + mod.main(gctx) + except Exception: + # can't install the crash handler becuase sys.excepthook doesn't play nice + # with threads, so catch it here. + common.crash.capture_exception() + raise + +def nativelauncher(pargs, cwd): + # exec the process + os.chdir(cwd) + + # because when extracted from pex zips permissions get lost -_- + os.chmod(pargs[0], 0o700) + + os.execvp(pargs[0], pargs) + +def start_managed_process(name): + if name in running or name not in managed_processes: + return + proc = managed_processes[name] + if isinstance(proc, basestring): + cloudlog.info("starting python %s" % proc) + running[name] = Process(name=name, target=launcher, args=(proc, gctx)) + else: + pdir, pargs = proc + cwd = os.path.dirname(os.path.realpath(__file__)) + if pdir is not None: + cwd = os.path.join(cwd, pdir) + cloudlog.info("starting process %s" % name) + running[name] = Process(name=name, target=nativelauncher, args=(pargs, cwd)) + running[name].start() + +def kill_managed_process(name): + if name not in running or name not in managed_processes: + return + cloudlog.info("killing %s" % name) + running[name].terminate() + running[name].join(5.0) + if running[name].exitcode is None: + cloudlog.info("killing %s with SIGKILL" % name) + os.kill(running[name].pid, signal.SIGKILL) + running[name].join() + cloudlog.info("%s is finally dead" % name) + else: + cloudlog.info("%s is dead with %d" % (name, running[name].exitcode)) + del running[name] + +def cleanup_all_processes(signal, frame): + cloudlog.info("caught ctrl-c %s %s" % (signal, frame)) + for name in running.keys(): + kill_managed_process(name) + sys.exit(0) + +# ****************** run loop ****************** + +def manager_init(): + global gctx + + reg_res = register() + if reg_res: + dongle_id, dongle_secret = reg_res + else: + raise Exception("server registration failed") + + # set dongle id + cloudlog.info("dongle id is " + dongle_id) + os.environ['DONGLE_ID'] = dongle_id + os.environ['DONGLE_SECRET'] = dongle_secret + + cloudlog.bind_global(dongle_id=dongle_id) + + # set gctx + gctx = { + "calibration": { + "initial_homography": [1.15728010e+00, -4.69379619e-02, 7.46450623e+01, + 7.99253014e-02, 1.06372458e+00, 5.77762553e+01, + 9.35543519e-05, -1.65429898e-04, 9.98062699e-01] + } + } + + # hook to kill all processes + signal.signal(signal.SIGINT, cleanup_all_processes) + signal.signal(signal.SIGTERM, cleanup_all_processes) + +def manager_thread(): + # now loop + context = zmq.Context() + thermal_sock = messaging.pub_sock(context, service_list['thermal'].port) + health_sock = messaging.sub_sock(context, service_list['health'].port) + + cloudlog.info("manager start") + + start_managed_process("logmessaged") + start_managed_process("logcatd") + start_managed_process("uploader") + start_managed_process("ui") + + # *** wait for the board *** + wait_for_device() + + # flash the device + if os.getenv("NOPROG") is None: + boarddir = os.path.dirname(os.path.abspath(__file__))+"/../board/" + os.system("cd %s && make" % boarddir) + + start_managed_process("boardd") + + if os.getenv("STARTALL") is not None: + for p in car_started_processes: + start_managed_process(p) + + while 1: + # get health of board, log this in "thermal" + td = messaging.recv_sock(health_sock, wait=True) + print td + + # replace thermald + msg = read_thermal() + thermal_sock.send(msg.to_bytes()) + print msg + + # TODO: add car battery voltage check + max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, + msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + + # uploader is gated based on the phone temperature + if max_temp > 85.0: + cloudlog.info("over temp: %r", max_temp) + kill_managed_process("uploader") + elif max_temp < 70.0: + start_managed_process("uploader") + + # start constellation of processes when the car starts + if td.health.started: + for p in car_started_processes: + start_managed_process(p) + else: + for p in car_started_processes: + kill_managed_process(p) + + # check the status of all processes, did any of them die? + for p in running: + cloudlog.info(" running %s %s" % (p, running[p])) + + +# optional, build the c++ binaries and preimport the python for speed +def manager_prepare(): + for p in managed_processes: + proc = managed_processes[p] + if isinstance(proc, basestring): + # import this python + cloudlog.info("preimporting %s" % proc) + importlib.import_module(proc) + else: + # build this process + cloudlog.info("building %s" % (proc,)) + try: + subprocess.check_call(["make", "-j4"], cwd=proc[0]) + except subprocess.CalledProcessError: + # make clean if the build failed + cloudlog.info("building %s failed, make clean" % (proc, )) + subprocess.check_call(["make", "clean"], cwd=proc[0]) + subprocess.check_call(["make", "-j4"], cwd=proc[0]) + +def manager_test(): + global managed_processes + managed_processes = {} + managed_processes["test1"] = ("test", ["./test.py"]) + managed_processes["test2"] = ("test", ["./test.py"]) + managed_processes["test3"] = "selfdrive.test.test" + manager_prepare() + start_managed_process("test1") + start_managed_process("test2") + start_managed_process("test3") + print running + time.sleep(3) + kill_managed_process("test1") + kill_managed_process("test2") + kill_managed_process("test3") + print running + time.sleep(10) + +def wait_for_device(): + while 1: + try: + context = usb1.USBContext() + for device in context.getDeviceList(skip_on_error=True): + if (device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc) or \ + (device.getVendorID() == 0x0483 and device.getProductID() == 0xdf11): + handle = device.open() + handle.claimInterface(0) + cloudlog.info("found board") + handle.close() + return + except Exception as e: + print "exception", e, + print "waiting..." + time.sleep(1) + +def main(): + if os.getenv("NOLOG") is not None: + del managed_processes['loggerd'] + if os.getenv("NOBOARD") is not None: + del managed_processes['boardd'] + + manager_init() + + if len(sys.argv) > 1 and sys.argv[1] == "test": + manager_test() + else: + manager_prepare() + try: + manager_thread() + except Exception: + traceback.print_exc() + common.crash.capture_exception() + finally: + cleanup_all_processes(None, None) + +if __name__ == "__main__": + main() diff --git a/selfdrive/messaging.py b/selfdrive/messaging.py new file mode 100644 index 0000000000..cb5c27b891 --- /dev/null +++ b/selfdrive/messaging.py @@ -0,0 +1,52 @@ +import zmq + +from cereal import log +from common import realtime + +def new_message(): + dat = log.Event.new_message() + dat.logMonoTime = int(realtime.sec_since_boot() * 1e9) + return dat + +def pub_sock(context, port, addr="*"): + sock = context.socket(zmq.PUB) + sock.bind("tcp://%s:%d" % (addr, port)) + return sock + +def sub_sock(context, port, poller=None, addr="127.0.0.1"): + sock = context.socket(zmq.SUB) + sock.connect("tcp://%s:%d" % (addr, port)) + sock.setsockopt(zmq.SUBSCRIBE, "") + if poller is not None: + poller.register(sock, zmq.POLLIN) + return sock + +def drain_sock(sock, wait_for_one=False): + ret = [] + while 1: + try: + if wait_for_one and len(ret) == 0: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + dat = log.Event.from_bytes(dat) + ret.append(dat) + except zmq.error.Again: + break + return ret + + +# TODO: print when we drop packets? +def recv_sock(sock, wait=False): + dat = None + while 1: + try: + if wait and dat is None: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + except zmq.error.Again: + break + if dat is not None: + dat = log.Event.from_bytes(dat) + return dat diff --git a/selfdrive/registration.py b/selfdrive/registration.py new file mode 100644 index 0000000000..b2dc5d0146 --- /dev/null +++ b/selfdrive/registration.py @@ -0,0 +1,38 @@ +import os +import json +import subprocess + +from selfdrive.swaglog import cloudlog +from common.api import api_get + +DONGLEAUTH_PATH = "/sdcard/dongleauth" + +def get_imei(): + # Telephony.getDeviceId() + result = subprocess.check_output(["service", "call", "phone", "130"]).strip().split("\n") + hex_data = ''.join(l[14:49] for l in result[1:]).replace(" ", "") + data = hex_data.decode("hex") + + imei_str = data[8:-4].replace("\x00", "") + return imei_str + +def get_serial(): + return subprocess.check_output(["getprop", "ro.serialno"]).strip() + +def register(): + try: + if os.path.exists(DONGLEAUTH_PATH): + dongleauth = json.load(open(DONGLEAUTH_PATH)) + else: + resp = api_get("pilot_auth", method='POST', imei=get_imei(), serial=get_serial()) + resp = resp.text + dongleauth = json.loads(resp) + open(DONGLEAUTH_PATH, "w").write(resp) + return dongleauth["dongle_id"], dongleauth["dongle_secret"] + except Exception: + cloudlog.exception("failed to authenticate") + return None + +if __name__ == "__main__": + print api_get("").text + print register() diff --git a/selfdrive/sensord/Makefile b/selfdrive/sensord/Makefile new file mode 100644 index 0000000000..e6ad07817e --- /dev/null +++ b/selfdrive/sensord/Makefile @@ -0,0 +1,60 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +OBJS = sensors.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: sensord + +sensord: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -lhardware + +sensors.o: sensors.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + + +.PHONY: clean +clean: + rm -f sensord $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors.cc new file mode 100644 index 0000000000..774b9afc26 --- /dev/null +++ b/selfdrive/sensord/sensors.cc @@ -0,0 +1,227 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +#include + +#include "common/timing.h" + +#include "cereal/gen/cpp/log.capnp.h" + +// zmq output +static void *gps_publisher; + +#define SENSOR_ACCELEROMETER 1 +#define SENSOR_MAGNETOMETER 2 +#define SENSOR_GYRO 4 + +void sensor_loop() { + printf("*** sensor loop\n"); + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // required + struct sensor_t const* list; + int count = module->get_sensors_list(module, &list); + printf("%d sensors found\n", count); + + device->activate(device, SENSOR_ACCELEROMETER, 0); + device->activate(device, SENSOR_MAGNETOMETER, 0); + device->activate(device, SENSOR_GYRO, 0); + + device->activate(device, SENSOR_ACCELEROMETER, 1); + device->activate(device, SENSOR_MAGNETOMETER, 1); + device->activate(device, SENSOR_GYRO, 1); + + device->setDelay(device, SENSOR_ACCELEROMETER, ms2ns(10)); + device->setDelay(device, SENSOR_GYRO, ms2ns(10)); + device->setDelay(device, SENSOR_MAGNETOMETER, ms2ns(100)); + + static const size_t numEvents = 16; + sensors_event_t buffer[numEvents]; + + // zmq output + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8003"); + + while (1) { + int n = device->poll(device, buffer, numEvents); + if (n == 0) continue; + if (n < 0) { + printf("sensor_loop poll failed: %d\n", n); + continue; + } + + uint64_t log_time = nanos_since_boot(); + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(log_time); + + auto sensorEvents = event.initSensorEvents(n); + + for (int i = 0; i < n; i++) { + + const sensors_event_t& data = buffer[i]; + + sensorEvents[i].setVersion(data.version); + sensorEvents[i].setSensor(data.sensor); + sensorEvents[i].setType(data.type); + sensorEvents[i].setTimestamp(data.timestamp); + + switch (data.type) { + case SENSOR_TYPE_ACCELEROMETER: { + auto svec = sensorEvents[i].initAcceleration(); + kj::ArrayPtr vs(&data.acceleration.v[0], 3); + svec.setV(vs); + svec.setStatus(data.acceleration.status); + break; + } + case SENSOR_TYPE_MAGNETIC_FIELD: { + auto svec = sensorEvents[i].initMagnetic(); + kj::ArrayPtr vs(&data.magnetic.v[0], 3); + svec.setV(vs); + svec.setStatus(data.magnetic.status); + break; + } + case SENSOR_TYPE_GYROSCOPE: { + auto svec = sensorEvents[i].initGyro(); + kj::ArrayPtr vs(&data.gyro.v[0], 3); + svec.setV(vs); + svec.setStatus(data.gyro.status); + break; + } + default: + continue; + } + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + // printf("send %d\n", bytes.size()); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + + } +} + +static const GpsInterface* gGpsInterface = NULL; +static const AGpsInterface* gAGpsInterface = NULL; +static const GpsMeasurementInterface* gGpsMeasurementInterface = NULL; + +static void nmea_callback(GpsUtcTime timestamp, const char* nmea, int length) { + + uint64_t log_time = nanos_since_boot(); + uint64_t log_time_wall = nanos_since_epoch(); + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(log_time); + + auto nmeaData = event.initGpsNMEA(); + nmeaData.setTimestamp(timestamp); + nmeaData.setLocalWallTime(log_time_wall); + nmeaData.setNmea(nmea); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + // printf("gps send %d\n", bytes.size()); + zmq_send(gps_publisher, bytes.begin(), bytes.size(), 0); +} + +static pthread_t create_thread_callback(const char* name, void (*start)(void *), void* arg) { + printf("creating thread: %s\n", name); + pthread_t thread; + pthread_attr_t attr; + int err; + + err = pthread_attr_init(&attr); + err = pthread_create(&thread, &attr, (void*(*)(void*))start, arg); + + return thread; +} + +static GpsCallbacks gps_callbacks = { + sizeof(GpsCallbacks), + NULL, + NULL, + NULL, + nmea_callback, + NULL, + NULL, + NULL, + create_thread_callback, +}; + +static void agps_status_cb(AGpsStatus *status) { + switch (status->status) { + case GPS_REQUEST_AGPS_DATA_CONN: + fprintf(stdout, "*** data_conn_open\n"); + gAGpsInterface->data_conn_open("internet"); + break; + case GPS_RELEASE_AGPS_DATA_CONN: + fprintf(stdout, "*** data_conn_closed\n"); + gAGpsInterface->data_conn_closed(); + break; + } +} + +static AGpsCallbacks agps_callbacks = { + agps_status_cb, + create_thread_callback, +}; + + + +static void gps_init() { + printf("*** init GPS\n"); + hw_module_t* module; + hw_get_module(GPS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + + hw_device_t* device; + module->methods->open(module, GPS_HARDWARE_MODULE_ID, &device); + + // ** get gps interface ** + gps_device_t* gps_device = (gps_device_t *)device; + gGpsInterface = gps_device->get_gps_interface(gps_device); + gAGpsInterface = (const AGpsInterface*)gGpsInterface->get_extension(AGPS_INTERFACE); + + + + gGpsInterface->init(&gps_callbacks); + gAGpsInterface->init(&agps_callbacks); + gAGpsInterface->set_server(AGPS_TYPE_SUPL, "supl.google.com", 7276); + + gGpsInterface->delete_aiding_data(GPS_DELETE_ALL); + gGpsInterface->start(); + gGpsInterface->set_position_mode(GPS_POSITION_MODE_MS_BASED, + GPS_POSITION_RECURRENCE_PERIODIC, + 1000, 0, 0); + void *gps_context = zmq_ctx_new(); + gps_publisher = zmq_socket(gps_context, ZMQ_PUB); + zmq_bind(gps_publisher, "tcp://*:8004"); +} + +int main(int argc, char *argv[]) { + gps_init(); + sensor_loop(); +} + diff --git a/selfdrive/swaglog.py b/selfdrive/swaglog.py new file mode 100644 index 0000000000..012bb93806 --- /dev/null +++ b/selfdrive/swaglog.py @@ -0,0 +1,38 @@ +import os +import logging + +import zmq + +from common.logging_extra import SwagLogger, SwagFormatter + +class LogMessageHandler(logging.Handler): + def __init__(self, formatter): + logging.Handler.__init__(self) + self.setFormatter(formatter) + self.pid = None + + def connect(self): + self.zctx = zmq.Context() + self.sock = self.zctx.socket(zmq.PUSH) + self.sock.connect("ipc:///tmp/logmessage") + self.pid = os.getpid() + + def emit(self, record): + if os.getpid() != self.pid: + self.connect() + + msg = self.format(record).rstrip('\n') + # print "SEND", repr(msg) + try: + self.sock.send(chr(record.levelno)+msg, zmq.NOBLOCK) + except zmq.error.Again: + # drop :/ + pass + +cloudlog = log = SwagLogger() +log.setLevel(logging.DEBUG) + +outhandler = logging.StreamHandler() +log.addHandler(outhandler) + +log.addHandler(LogMessageHandler(SwagFormatter(log))) diff --git a/selfdrive/thermal.py b/selfdrive/thermal.py new file mode 100644 index 0000000000..f89f358d48 --- /dev/null +++ b/selfdrive/thermal.py @@ -0,0 +1,19 @@ +"""Methods for reading system thermal information.""" +import selfdrive.messaging as messaging + +def read_tz(x): + with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: + ret = int(f.read()) + return ret + +def read_thermal(): + dat = messaging.new_message() + dat.init('thermal') + dat.thermal.cpu0 = read_tz(5) + dat.thermal.cpu1 = read_tz(7) + dat.thermal.cpu2 = read_tz(10) + dat.thermal.cpu3 = read_tz(12) + dat.thermal.mem = read_tz(2) + dat.thermal.gpu = read_tz(16) + dat.thermal.bat = read_tz(29) + return dat diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile new file mode 100644 index 0000000000..e4549e1183 --- /dev/null +++ b/selfdrive/ui/Makefile @@ -0,0 +1,73 @@ +CC = clang +CXX = clang++ + + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-c/aarch64/lib -l:libcapn.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +NANOVG_FLAGS = -I$(PHONELIBS)/nanovg + +OPENGL_LIBS = -lGLESv3 + +FRAMEBUFFER_LIBS = -lutils -lgui -lEGL + +OBJS = ui.o \ + touch.o \ + ../common/visionipc.o \ + ../common/framebuffer.o \ + $(PHONELIBS)/nanovg/nanovg.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +all: ui + +ui: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(FRAMEBUFFER_LIBS) \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -L/system/vendor/lib64 \ + $(OPENGL_LIBS) \ + -lcutils -lm -llog + +../common/framebuffer.o: ../common/framebuffer.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -I$(PHONELIBS)/android_frameworks_native/include \ + -I$(PHONELIBS)/android_system_core/include \ + -I$(PHONELIBS)/android_hardware_libhardware/include \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I.. -I../.. \ + $(NANOVG_FLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CFLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f ui $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/ui/touch.c b/selfdrive/ui/touch.c new file mode 100644 index 0000000000..a1b6a683af --- /dev/null +++ b/selfdrive/ui/touch.c @@ -0,0 +1,63 @@ +#include +#include +#include +#include +#include +#include + +#include "touch.h" + +void touch_init(TouchState *s) { + // synaptics touch screen on oneplus 3 + s->fd = open("/dev/input/event4", O_RDONLY); + assert(s->fd >= 0); +} + +int touch_poll(TouchState *s, int* out_x, int* out_y) { + assert(out_x && out_y); + bool up = false; + while (true) { + struct pollfd polls[] = {{ + .fd = s->fd, + .events = POLLIN, + }}; + int err = poll(polls, 1, 0); + if (err < 0) { + return -1; + } + if (!(polls[0].revents & POLLIN)) { + break; + } + + struct input_event event; + err = read(polls[0].fd, &event, sizeof(event)); + if (err < sizeof(event)) { + return -1; + } + + switch (event.type) { + case EV_ABS: + if (event.code == ABS_MT_POSITION_X) { + s->last_x = event.value; + } else if (event.code == ABS_MT_POSITION_Y) { + s->last_y = event.value; + } + break; + case EV_KEY: + if (event.code == BTN_TOOL_FINGER && event.value == 0) { + // finger up + up = true; + } + break; + default: + break; + } + } + if (up) { + // adjust for landscape + *out_x = 1920 - s->last_y; + *out_y = s->last_x; + } + return up; +} + diff --git a/selfdrive/ui/touch.h b/selfdrive/ui/touch.h new file mode 100644 index 0000000000..de89a71c5f --- /dev/null +++ b/selfdrive/ui/touch.h @@ -0,0 +1,12 @@ +#ifndef TOUCH_H +#define TOUCH_H + +typedef struct TouchState { + int fd; + int last_x, last_y; +} TouchState; + +void touch_init(TouchState *s); +int touch_poll(TouchState *s, int *out_x, int *out_y); + +#endif diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c new file mode 100644 index 0000000000..a5b9e63cde --- /dev/null +++ b/selfdrive/ui/ui.c @@ -0,0 +1,1325 @@ +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include + +#include "nanovg.h" +#define NANOVG_GLES3_IMPLEMENTATION +#include "nanovg_gl.h" +#include "nanovg_gl_utils.h" + +#include "common/timing.h" +#include "common/util.h" +#include "common/mat.h" + +#include "common/framebuffer.h" +#include "common/visionipc.h" +#include "common/modeldata.h" + +#include "cereal/gen/c/log.capnp.h" + +#include "touch.h" + +#define UI_BUF_COUNT 4 +typedef struct UIBuf { + int fd; + size_t len; + void* addr; +} UIBuf; + +typedef struct UIScene { + + int frontview; + + uint8_t *bgr_ptr; + int big_box_x, big_box_y, big_box_width, big_box_height; + + int transformed_width, transformed_height; + + uint64_t model_ts; + ModelData model; + + mat3 big_box_transform; // transformed box -> big box + + float v_cruise; + float v_ego; + float angle_steers; + int engaged; + + int lead_status; + float lead_d_rel, lead_y_rel, lead_v_rel; + + uint8_t *bgr_front_ptr; + int front_box_x, front_box_y, front_box_width, front_box_height; + + char alert_text1[1024]; + char alert_text2[1024]; + + float awareness_status; +} UIScene; + + +typedef struct UIState { + pthread_mutex_t lock; + + TouchState touch; + + FramebufferState *fb; + + int fb_w, fb_h; + EGLDisplay display; + EGLSurface surface; + + NVGcontext *vg; + int font; + + + + zsock_t *model_sock; + void* model_sock_raw; + zsock_t *live100_sock; + void* live100_sock_raw; + zsock_t *livecalibration_sock; + void* livecalibration_sock_raw; + zsock_t *live20_sock; + void* live20_sock_raw; + + // base ui + uint64_t last_base_update; + uint64_t last_rx_bytes; + uint64_t last_tx_bytes; + char serial[4096]; + const char* dongle_id; + char base_text[4096]; + int wifi_enabled; + int ap_enabled; + int board_connected; + + // vision state + + bool vision_connected; + bool vision_connect_firstrun; + int ipc_fd; + + VisionUIBufs vision_bufs; + UIBuf bufs[UI_BUF_COUNT]; + UIBuf front_bufs[UI_BUF_COUNT]; + int cur_vision_idx; + int cur_vision_front_idx; + + GLuint frame_program; + + GLuint frame_tex; + GLint frame_pos_loc, frame_texcoord_loc; + GLint frame_texture_loc, frame_transform_loc; + + GLuint line_program; + GLint line_pos_loc, line_color_loc; + GLint line_transform_loc; + + unsigned int rgb_width, rgb_height; + mat4 rgb_transform; + + unsigned int rgb_front_width, rgb_front_height; + GLuint frame_front_tex; + + UIScene scene; + + +} UIState; + + +static bool activity_running() { + return system("dumpsys activity activities | grep mFocusedActivity > /dev/null") == 0; +} + +static void start_settings_activity(const char* name) { + char launch_cmd[1024]; + snprintf(launch_cmd, sizeof(launch_cmd), + "am start -W --ez :settings:show_fragment_as_subsetting true -n 'com.android.settings/.%s'", name); + system(launch_cmd); +} + +static void wifi_pressed() { + start_settings_activity("Settings$WifiSettingsActivity"); +} +static void ap_pressed() { + start_settings_activity("Settings$TetherSettingsActivity"); +} + +static int wifi_enabled(UIState *s) { + return s->wifi_enabled; +} + +static int ap_enabled(UIState *s) { + return s->ap_enabled; +} + +typedef struct Button { + const char* label; + int x, y, w, h; + void (*pressed)(void); + int (*enabled)(UIState *); +} Button; +static const Button buttons[] = { + { + .label = "wifi", + .x = 400, .y = 700, .w = 250, .h = 250, + .pressed = wifi_pressed, + .enabled = wifi_enabled, + }, + { + .label = "ap", + .x = 1300, .y = 700, .w = 250, .h = 250, + .pressed = ap_pressed, + .enabled = ap_enabled, + } +}; + +// transform from road space into little-box (used for drawing path) +static const mat3 path_transform = {{ + 1.29149378e+00, -2.30320967e-01, -3.02391994e+01, + -1.72449331e-15, -2.12045399e-02, 5.03539175e+01, + -3.24378996e-17, -1.38821089e-03, 1.06663412e+00, +}}; + +static const char frame_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aTexCoord;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vTexCoord = aTexCoord;\n" + "}\n"; + +static const char frame_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_FragColor = texture2D(uTexture, vTexCoord.xy);\n" + "}\n"; + +static const char line_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aColor;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vColor = aColor;\n" + "}\n"; + +static const char line_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_FragColor = vColor;\n" + "}\n"; + +static GLuint load_shader(GLenum shaderType, const char *src) { + GLint status = 0, len = 0; + GLuint shader; + + if (!(shader = glCreateShader(shaderType))) + return 0; + + glShaderSource(shader, 1, &src, NULL); + glCompileShader(shader); + glGetShaderiv(shader, GL_COMPILE_STATUS, &status); + + if (status) + return shader; + + glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *msg = malloc(len); + if (msg) { + glGetShaderInfoLog(shader, len, NULL, msg); + msg[len-1] = 0; + fprintf(stderr, "error compiling shader:\n%s\n", msg); + free(msg); + } + } + glDeleteShader(shader); + return 0; +} + +static GLuint load_program(const char *vert_src, const char *frag_src) { + GLuint vert, frag, prog; + GLint status = 0, len = 0; + + if (!(vert = load_shader(GL_VERTEX_SHADER, vert_src))) + return 0; + if (!(frag = load_shader(GL_FRAGMENT_SHADER, frag_src))) + goto fail_frag; + if (!(prog = glCreateProgram())) + goto fail_prog; + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + glLinkProgram(prog); + + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status) + return prog; + + glGetProgramiv(prog, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *buf = (char*) malloc(len); + if (buf) { + glGetProgramInfoLog(prog, len, NULL, buf); + buf[len-1] = 0; + fprintf(stderr, "error linking program:\n%s\n", buf); + free(buf); + } + } + glDeleteProgram(prog); +fail_prog: + glDeleteShader(frag); +fail_frag: + glDeleteShader(vert); + return 0; +} + +static const mat4 device_transform = {{ + 1.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +// frame from 4/3 to 16/9 with a 2x zoon +static const mat4 frame_transform = {{ + 2*(4./3.)/(16./9.), 0.0, 0.0, 0.0, + 0.0, 2.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + + + +static void ui_init(UIState *s) { + memset(s, 0, sizeof(UIState)); + + pthread_mutex_init(&s->lock, NULL); + + // init connections + s->model_sock = zsock_new_sub(">tcp://127.0.0.1:8009", ""); + assert(s->model_sock); + s->model_sock_raw = zsock_resolve(s->model_sock); + + s->live100_sock = zsock_new_sub(">tcp://127.0.0.1:8007", ""); + assert(s->live100_sock); + s->live100_sock_raw = zsock_resolve(s->live100_sock); + + s->livecalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", ""); + assert(s->livecalibration_sock); + s->livecalibration_sock_raw = zsock_resolve(s->livecalibration_sock); + + s->live20_sock = zsock_new_sub(">tcp://127.0.0.1:8012", ""); + assert(s->live20_sock); + s->live20_sock_raw = zsock_resolve(s->live20_sock); + + s->ipc_fd = -1; + + touch_init(&s->touch); + + // init display + s->fb = framebuffer_init("ui", 0x00001000, + &s->display, &s->surface, &s->fb_w, &s->fb_h); + assert(s->fb); + + + // init base + property_get("ro.serialno", s->serial, ""); + + s->dongle_id = getenv("DONGLE_ID"); + if (!s->dongle_id) s->dongle_id = "(null)"; + + + // init drawing + s->vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG); + assert(s->vg); + //s->font = nvgCreateFont(s->vg, "sans-bold", "../assets/Roboto-Bold.ttf"); + s->font = nvgCreateFont(s->vg, "Bold", "../assets/courbd.ttf"); + assert(s->font >= 0); + + // init gl + + s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader); + assert(s->frame_program); + + s->frame_pos_loc = glGetAttribLocation(s->frame_program, "aPosition"); + s->frame_texcoord_loc = glGetAttribLocation(s->frame_program, "aTexCoord"); + + s->frame_texture_loc = glGetUniformLocation(s->frame_program, "uTexture"); + s->frame_transform_loc = glGetUniformLocation(s->frame_program, "uTransform"); + + + s->line_program = load_program(line_vertex_shader, line_fragment_shader); + assert(s->line_program); + + s->line_pos_loc = glGetAttribLocation(s->line_program, "aPosition"); + s->line_color_loc = glGetAttribLocation(s->line_program, "aColor"); + s->line_transform_loc = glGetUniformLocation(s->line_program, "uTransform"); + + glViewport(0, 0, s->fb_w, s->fb_h); + + glDisable(GL_DEPTH_TEST); + + assert(glGetError() == GL_NO_ERROR); +} + + +static void ui_init_vision(UIState *s, const VisionUIBufs vision_bufs, const int* fds) { + assert(vision_bufs.num_bufs == UI_BUF_COUNT); + assert(vision_bufs.num_front_bufs == UI_BUF_COUNT); + + for (int i=0; ibufs[i].addr) { + munmap(s->bufs[i].addr, vision_bufs.buf_len); + s->bufs[i].addr = NULL; + close(s->bufs[i].fd); + } + s->bufs[i].fd = fds[i]; + s->bufs[i].len = vision_bufs.buf_len; + s->bufs[i].addr = mmap(NULL, s->bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, s->bufs[i].fd, 0); + // printf("b %d %p\n", bufs[i].fd, bufs[i].addr); + assert(s->bufs[i].addr != MAP_FAILED); + } + for (int i=0; ifront_bufs[i].addr) { + munmap(s->front_bufs[i].addr, vision_bufs.buf_len); + s->front_bufs[i].addr = NULL; + close(s->front_bufs[i].fd); + } + s->front_bufs[i].fd = fds[vision_bufs.num_bufs + i]; + s->front_bufs[i].len = vision_bufs.front_buf_len; + s->front_bufs[i].addr = mmap(NULL, s->front_bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, s->front_bufs[i].fd, 0); + // printf("f %d %p\n", front_bufs[i].fd, front_bufs[i].addr); + assert(s->front_bufs[i].addr != MAP_FAILED); + } + + s->cur_vision_idx = -1; + s->cur_vision_front_idx = -1; + + s->scene = (UIScene){ + .frontview = 0, + .big_box_x = vision_bufs.big_box_x, + .big_box_y = vision_bufs.big_box_y, + .big_box_width = vision_bufs.big_box_width, + .big_box_height = vision_bufs.big_box_height, + .transformed_width = vision_bufs.transformed_width, + .transformed_height = vision_bufs.transformed_height, + .front_box_x = vision_bufs.front_box_x, + .front_box_y = vision_bufs.front_box_y, + .front_box_width = vision_bufs.front_box_width, + .front_box_height = vision_bufs.front_box_height, + + // only used when ran without controls. overwridden by liveCalibration messages. + .big_box_transform = (mat3){{ + 1.16809241e+00, -3.18601797e-02, 7.42513711e+01, + 7.97437780e-02, 1.09117765e+00, 5.71824220e+01, + 8.67937981e-05, -7.68221181e-05, 1.00196836e+00, + }}, + }; + + s->vision_bufs = vision_bufs; + + s->rgb_width = vision_bufs.width; + s->rgb_height = vision_bufs.height; + + s->rgb_front_width = vision_bufs.front_width; + s->rgb_front_height = vision_bufs.front_height; + + s->rgb_transform = (mat4){{ + 2.0/s->rgb_width, 0.0, 0.0, -1.0, + 0.0, 2.0/s->rgb_height, 0.0, -1.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; +} + +static void ui_update_frame(UIState *s) { + assert(glGetError() == GL_NO_ERROR); + + UIScene *scene = &s->scene; + + if (scene->frontview && scene->bgr_front_ptr) { + // load front frame texture + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, + s->rgb_front_width, s->rgb_front_height, + GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_front_ptr); + } else if (!scene->frontview && scene->bgr_ptr) { + // load frame texture + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, + s->rgb_width, s->rgb_height, + GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_ptr); + } + + assert(glGetError() == GL_NO_ERROR); +} + +static void draw_rgb_box(UIState *s, int x, int y, int w, int h, uint32_t color) { + const struct { + uint32_t x, y, color; + } verts[] = { + {x, y, color}, + {x+w, y, color}, + {x+w, y+h, color}, + {x, y+h, color}, + {x, y, color}, + }; + + glUseProgram(s->line_program); + + mat4 out_mat = matmul(device_transform, + matmul(frame_transform, s->rgb_transform)); + glUniformMatrix4fv(s->line_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->line_pos_loc); + glVertexAttribPointer(s->line_pos_loc, 2, GL_UNSIGNED_INT, GL_FALSE, sizeof(verts[0]), &verts[0].x); + + glEnableVertexAttribArray(s->line_color_loc); + glVertexAttribPointer(s->line_color_loc, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(verts[0]), &verts[0].color); + + assert(glGetError() == GL_NO_ERROR); + glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); +} + +static void ui_draw_transformed_box(UIState *s, uint32_t color) { + const UIScene *scene = &s->scene; + + const mat3 bbt = scene->big_box_transform; + + struct { + vec3 pos; + uint32_t color; + } verts[] = { + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + }; + + for (int i=0; ibig_box_x + verts[i].pos.v[0] / verts[i].pos.v[2]; + verts[i].pos.v[1] = scene->big_box_y + verts[i].pos.v[1] / verts[i].pos.v[2]; + verts[i].pos.v[1] = s->rgb_height - verts[i].pos.v[1]; + } + + glUseProgram(s->line_program); + + mat4 out_mat = matmul(device_transform, + matmul(frame_transform, s->rgb_transform)); + glUniformMatrix4fv(s->line_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->line_pos_loc); + glVertexAttribPointer(s->line_pos_loc, 2, GL_FLOAT, GL_FALSE, sizeof(verts[0]), &verts[0].pos.v[0]); + + glEnableVertexAttribArray(s->line_color_loc); + glVertexAttribPointer(s->line_color_loc, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(verts[0]), &verts[0].color); + + assert(glGetError() == GL_NO_ERROR); + glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); +} + +// TODO: refactor with draw_path +static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor color) { + const UIScene *scene = &s->scene; + + const float meter_width = 20; + const float car_x = 160; + const float car_y = 570 + meter_width * 8; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, color); + nvgStrokeWidth(s->vg, 5); + + float px = -y_in * meter_width + car_x; + float py = x_in * -meter_width + car_y; + + vec3 dxy = matvecmul3(path_transform, (vec3){{px, py, 1.0}}); + dxy.v[0] /= dxy.v[2]; dxy.v[1] /= dxy.v[2]; dxy.v[2] = 1.0f; //paranoia + vec3 bbpos = matvecmul3(scene->big_box_transform, dxy); + + float x = scene->big_box_x + bbpos.v[0]/bbpos.v[2]; + float y = scene->big_box_y + bbpos.v[1]/bbpos.v[2]; + + nvgMoveTo(s->vg, x-sz, y); + nvgLineTo(s->vg, x+sz, y); + + nvgMoveTo(s->vg, x, y-sz); + nvgLineTo(s->vg, x, y+sz); + + nvgStroke(s->vg); + + nvgRestore(s->vg); +} + +static void draw_path(UIState *s, const float* points, float off, NVGcolor color) { + const UIScene *scene = &s->scene; + + const float meter_width = 20; + const float car_x = 160; + const float car_y = 570 + meter_width * 8; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, color); + nvgStrokeWidth(s->vg, 5); + + for (int i=0; i<50; i++) { + float px = (-points[i] + off) * meter_width + car_x; + float py = (float)i * -meter_width + car_y; + + vec3 dxy = matvecmul3(path_transform, (vec3){{px, py, 1.0}}); + dxy.v[0] /= dxy.v[2]; dxy.v[1] /= dxy.v[2]; dxy.v[2] = 1.0f; //paranoia + vec3 bbpos = matvecmul3(scene->big_box_transform, dxy); + + float x = scene->big_box_x + bbpos.v[0]/bbpos.v[2]; + float y = scene->big_box_y + bbpos.v[1]/bbpos.v[2]; + + if (i == 0) { + nvgMoveTo(s->vg, x, y); + } else { + nvgLineTo(s->vg, x, y); + } + } + + nvgStroke(s->vg); + + nvgRestore(s->vg); +} + +static void draw_model_path(UIState *s, const PathData path, NVGcolor color) { + float var = min(path.std, 0.7); + draw_path(s, path.points, 0.0, color); + color.a /= 4; + draw_path(s, path.points, -var, color); + draw_path(s, path.points, var, color); +} + +static double calc_curvature(float v_ego, float angle_steers) { + const double deg_to_rad = M_PI / 180.0f; + const double slip_fator = 0.0014; + const double steer_ratio = 15.3; + const double wheel_base = 2.67; + + const double angle_offset = 0.0; + + double angle_steers_rad = (angle_steers - angle_offset) * deg_to_rad; + double curvature = angle_steers_rad/(steer_ratio * wheel_base * (1. + slip_fator * v_ego*v_ego)); + return curvature; +} + +static void draw_steering(UIState *s, float v_ego, float angle_steers) { + double curvature = calc_curvature(v_ego, angle_steers); + + float points[50]; + for (int i=0; i<50; i++) { + float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999))/2.); + points[i] = y_actual; + } + + draw_path(s, points, 0.0, nvgRGBA(0, 0, 255, 128)); +} + +static void draw_frame(UIState *s) { + // draw frame texture + const UIScene *scene = &s->scene; + + mat4 out_mat; + float x1, x2, y1, y2; + if (s->scene.frontview) { + out_mat = device_transform; // full 16/9 + + // flip horizontally so it looks like a mirror + x2 = (float)scene->front_box_x / s->rgb_front_width; + x1 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width; + + y1 = (float)scene->front_box_y / s->rgb_front_height; + y2 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height; + } else { + out_mat = matmul(device_transform, frame_transform); + + x1 = 0.0; + x2 = 1.0; + y1 = 0.0; + y2 = 1.0; + } + + const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; + const float frame_coords[4][4] = { + {-1.0, -1.0, x2, y1}, //bl + {-1.0, 1.0, x2, y2}, //tl + { 1.0, 1.0, x1, y2}, //tr + { 1.0, -1.0, x1, y1}, //br + }; + + glActiveTexture(GL_TEXTURE0); + if (s->scene.frontview) { + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + } else { + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + } + + glUseProgram(s->frame_program); + + glUniform1i(s->frame_texture_loc, 0); + glUniformMatrix4fv(s->frame_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->frame_pos_loc); + glVertexAttribPointer(s->frame_pos_loc, 2, GL_FLOAT, GL_FALSE, sizeof(frame_coords[0]), frame_coords); + + glEnableVertexAttribArray(s->frame_texcoord_loc); + glVertexAttribPointer(s->frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, sizeof(frame_coords[0]), &frame_coords[0][2]); + + assert(glGetError() == GL_NO_ERROR); + glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, &frame_indicies[0]); +} + +static void ui_draw_vision(UIState *s) { + const UIScene *scene = &s->scene; + + if (scene->engaged) { + glClearColor(1.0, 0.5, 0.0, 1.0); + } else { + glClearColor(0.1, 0.1, 0.1, 1.0); + } + glClear(GL_COLOR_BUFFER_BIT); + + draw_frame(s); + + if (!scene->frontview) { + draw_rgb_box(s, scene->big_box_x, s->rgb_height-scene->big_box_height-scene->big_box_y, + scene->big_box_width, scene->big_box_height, + 0xFF0000FF); + + ui_draw_transformed_box(s, 0xFF00FF00); + + // nvg drawings + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + // glEnable(GL_CULL_FACE); + + + glClear(GL_STENCIL_BUFFER_BIT); + + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + + draw_steering(s, scene->v_ego, scene->angle_steers); + + // draw paths + + if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) { + draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(128, 0, 255, 255)); + + draw_model_path(s, scene->model.left_lane, nvgRGBA(0, (int)(255 * scene->model.left_lane.prob), 0, 128)); + draw_model_path(s, scene->model.right_lane, nvgRGBA(0, (int)(255 * scene->model.right_lane.prob), 0, 128)); + } + + // draw speed + char speed_str[16]; + nvgFontSize(s->vg, 128.0f); + + if (scene->engaged) { + nvgFillColor(s->vg, nvgRGBA(255,128,0,192)); + } else { + nvgFillColor(s->vg, nvgRGBA(64,64,64,192)); + } + + if (scene->v_cruise != 255 && scene->v_cruise != 0) { + // Convert KPH to MPH. + snprintf(speed_str, sizeof(speed_str), "%3d MPH", (int)(scene->v_cruise * 0.621371 + 0.5)); + nvgTextAlign(s->vg, NVG_ALIGN_RIGHT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 500, 150, speed_str, NULL); + } + + nvgFillColor(s->vg, nvgRGBA(255,255,255,192)); + snprintf(speed_str, sizeof(speed_str), "%3d MPH", (int)(scene->v_ego * 2.237 + 0.5)); + nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 1920-500, 150, speed_str, NULL); + + /*nvgFontSize(s->vg, 64.0f); + nvgTextAlign(s->vg, NVG_ALIGN_RIGHT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 100+450-20, 1080-100, "mph", NULL);*/ + + if (scene->lead_status) { + char radar_str[16]; + int lead_v_rel = (int)(2.236 * scene->lead_v_rel); + snprintf(radar_str, sizeof(radar_str), "%3d m %+d mph", (int)(scene->lead_d_rel), lead_v_rel); + nvgFontSize(s->vg, 96.0f); + nvgFillColor(s->vg, nvgRGBA(128,128,0,192)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); + nvgText(s->vg, 1920/2, 150, radar_str, NULL); + + // 2.7 m fudge factor + draw_cross(s, scene->lead_d_rel + 2.7, scene->lead_y_rel, 15, nvgRGBA(255, 0, 0, 128)); + } + + + // draw alert text + if (strlen(scene->alert_text1) > 0) { + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, 100, 200, 1700, 800, 40); + nvgFillColor(s->vg, nvgRGBA(10,10,10,220)); + nvgFill(s->vg); + + nvgFontSize(s->vg, 200.0f); + nvgFillColor(s->vg, nvgRGBA(255,0,0,255)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); + nvgTextBox(s->vg, 100+50, 200+50, 1700-50, scene->alert_text1, NULL); + + if (strlen(scene->alert_text2) > 0) { + nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); + nvgFontSize(s->vg, 100.0f); + nvgText(s->vg, 100+1700/2, 200+500, scene->alert_text2, NULL); + } + } + + if (scene->awareness_status > 0) { + nvgBeginPath(s->vg); + int bar_height = scene->awareness_status*700; + nvgRect(s->vg, 100, 300+(700-bar_height), 50, bar_height); + nvgFillColor(s->vg, nvgRGBA(255*(1-scene->awareness_status),255*scene->awareness_status,0,128)); + nvgFill(s->vg); + } + + nvgEndFrame(s->vg); + + glDisable(GL_BLEND); + glDisable(GL_CULL_FACE); + } +} + +static void ui_draw_base(UIState *s) { + glClearColor(0.1, 0.1, 0.1, 1.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + + nvgFontSize(s->vg, 96.0f); + nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); + nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE); + nvgTextBox(s->vg, 50, 100, s->fb_w, s->base_text, NULL); + + // draw buttons + for (int i=0; ivg); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + nvgRoundedRect(s->vg, b->x, b->y, b->w, b->h, 20); + nvgFill(s->vg); + + if (b->label) { + if (b->enabled && b->enabled(s)) { + nvgFillColor(s->vg, nvgRGBA(0, 255, 0, 255)); + } else { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE); + nvgText(s->vg, b->x+b->w/2, b->y+b->h/2, b->label, NULL); + } + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgStrokeWidth(s->vg, 5); + nvgRoundedRect(s->vg, b->x, b->y, b->w, b->h, 20); + nvgStroke(s->vg); + } + + nvgEndFrame(s->vg); + + glDisable(GL_BLEND); +} + +static void ui_draw(UIState *s) { + + if (s->vision_connected) { + ui_draw_vision(s); + } else { + ui_draw_base(s); + } + + eglSwapBuffers(s->display, s->surface); + assert(glGetError() == GL_NO_ERROR); +} + + +static PathData read_path(cereal_ModelData_PathData_ptr pathp) { + PathData ret = {0}; + + struct cereal_ModelData_PathData pathd; + cereal_read_ModelData_PathData(&pathd, pathp); + + ret.prob = pathd.prob; + ret.std = pathd.std; + + capn_list32 pointl = pathd.points; + capn_resolve(&pointl.p); + for (int i=0; i<50; i++) { + ret.points[i] = capn_to_f32(capn_get32(pointl, i)); + } + + return ret; +} + +static ModelData read_model(cereal_ModelData_ptr modelp) { + struct cereal_ModelData modeld; + cereal_read_ModelData(&modeld, modelp); + + ModelData d = {0}; + + d.path = read_path(modeld.path); + d.left_lane = read_path(modeld.leftLane); + d.right_lane = read_path(modeld.rightLane); + + struct cereal_ModelData_LeadData leadd; + cereal_read_ModelData_LeadData(&leadd, modeld.lead); + d.lead = (LeadData){ + .dist = leadd.dist, + .prob = leadd.prob, + .std = leadd.std, + }; + + return d; +} + +static char* read_file(const char* path) { + FILE* f = fopen(path, "r"); + if (!f) { + return NULL; + } + fseek(f, 0, SEEK_END); + long f_len = ftell(f); + rewind(f); + + char* buf = (char *)malloc(f_len+1); + assert(buf); + memset(buf, 0, f_len+1); + fread(buf, f_len, 1, f); + fclose(f); + + for (int i=f_len; i>=0; i--) { + if (buf[i] == '\n') buf[i] = 0; + else if (buf[i] != 0) break; + } + + return buf; +} + +static int pending_uploads() { + DIR *dirp = opendir("/sdcard/realdata"); + if (!dirp) return -1; + int cnt = 0; + struct dirent *entry = NULL; + while ((entry = readdir(dirp))) { + if (entry->d_name[0] != '.') { + cnt++; + } + } + closedir(dirp); + return cnt; +} + + +static void ui_update(UIState *s) { + int err; + + if (s->vision_connect_firstrun) { + // cant run this in connector thread because opengl. + // do this here for now in lieu of a run_on_main_thread event + + // setup frame texture + glDeleteTextures(1, &s->frame_tex); //silently ignores a 0 texture + glGenTextures(1, &s->frame_tex); + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_width, s->rgb_height); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + + // front + glDeleteTextures(1, &s->frame_front_tex); + glGenTextures(1, &s->frame_front_tex); + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_front_width, s->rgb_front_height); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + + assert(glGetError() == GL_NO_ERROR); + + s->vision_connect_firstrun = false; + } + + // poll for events + while (true) { + + zmq_pollitem_t polls[5] = {{0}}; + polls[0].socket = s->live100_sock_raw; + polls[0].events = ZMQ_POLLIN; + polls[1].socket = s->livecalibration_sock_raw; + polls[1].events = ZMQ_POLLIN; + polls[2].socket = s->model_sock_raw; + polls[2].events = ZMQ_POLLIN; + polls[3].socket = s->live20_sock_raw; + polls[3].events = ZMQ_POLLIN; + + int num_polls = 4; + if (s->vision_connected) { + assert(s->ipc_fd >= 0); + polls[4].fd = s->ipc_fd; + polls[4].events = ZMQ_POLLIN; + num_polls++; + } + + int ret = zmq_poll(polls, num_polls, 0); + if (ret < 0) { + printf("poll failed (%d)\n", ret); + break; + } + if (ret == 0) { + break; + } + + if (s->vision_connected && polls[4].revents) { + // vision ipc event + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + printf("vision disconnected\n"); + close(s->ipc_fd); + s->ipc_fd = -1; + s->vision_connected = false; + continue; + } + if (rp.type == VISION_UI_ACQUIRE) { + bool front = rp.d.ui_acq.front; + int idx = rp.d.ui_acq.idx; + int release_idx; + if (front) { + release_idx = s->cur_vision_front_idx; + } else { + release_idx = s->cur_vision_idx; + } + if (release_idx >= 0) { + VisionPacket rep = { + .type = VISION_UI_RELEASE, + .d = { .ui_rel = { + .front = front, + .idx = release_idx, + }}, + }; + vipc_send(s->ipc_fd, rep); + } + + if (front) { + assert(idx < s->vision_bufs.num_front_bufs); + s->cur_vision_front_idx = idx; + s->scene.bgr_front_ptr = s->front_bufs[idx].addr; + } else { + assert(idx < s->vision_bufs.num_bufs); + s->cur_vision_idx = idx; + s->scene.bgr_ptr = s->bufs[idx].addr; + // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); + } + if (front == s->scene.frontview) { + ui_update_frame(s); + } + + } else { + assert(false); + } + } else { + // zmq messages + void* which = NULL; + for (int i=0; i<4; i++) { + if (polls[i].revents) { + which = polls[i].socket; + break; + } + } + if (which == NULL) { + continue; + } + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + err = zmq_msg_recv(&msg, which, 0); + assert(err >= 0); + + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + if (eventd.which == cereal_Event_live100) { + struct cereal_Live100Data datad; + cereal_read_Live100Data(&datad, eventd.live100); + + s->scene.v_cruise = datad.vCruise; + s->scene.v_ego = datad.vEgo; + s->scene.angle_steers = datad.angleSteers; + s->scene.engaged = (datad.hudLead == 1) || (datad.hudLead == 2); + // printf("recv %f\n", datad.vEgo); + + s->scene.frontview = datad.rearViewCam; + if (datad.alertText1.str) { + snprintf(s->scene.alert_text1, sizeof(s->scene.alert_text1), "%s", datad.alertText1.str); + } else { + s->scene.alert_text1[0] = '\0'; + } + if (datad.alertText2.str) { + snprintf(s->scene.alert_text2, sizeof(s->scene.alert_text2), "%s", datad.alertText2.str); + } else { + s->scene.alert_text2[0] = '\0'; + } + s->scene.awareness_status = datad.awarenessStatus; + } else if (eventd.which == cereal_Event_live20) { + struct cereal_Live20Data datad; + cereal_read_Live20Data(&datad, eventd.live20); + struct cereal_Live20Data_LeadData leaddatad; + cereal_read_Live20Data_LeadData(&leaddatad, datad.leadOne); + s->scene.lead_status = leaddatad.status; + s->scene.lead_d_rel = leaddatad.dRel; + s->scene.lead_y_rel = leaddatad.yRel; + s->scene.lead_v_rel = leaddatad.vRel; + } else if (eventd.which == cereal_Event_liveCalibration) { + struct cereal_LiveCalibrationData datad; + cereal_read_LiveCalibrationData(&datad, eventd.liveCalibration); + + // should we still even have this? + + capn_list32 warpl = datad.warpMatrix; + capn_resolve(&warpl.p); //is this a bug? + // pthread_mutex_lock(&s->transform_lock); + for (int i=0; i<3*3; i++) { + s->scene.big_box_transform.v[i] = capn_to_f32(capn_get32(warpl, i)); + } + // pthread_mutex_unlock(&s->transform_lock); + + // printf("recv %f\n", datad.vEgo); + } else if (eventd.which == cereal_Event_model) { + s->scene.model_ts = eventd.logMonoTime; + s->scene.model = read_model(eventd.model); + } + + capn_free(&ctx); + + zmq_msg_close(&msg); + + } + + } + + // update base ui + uint64_t ts = nanos_since_boot(); + if (!s->vision_connected && ts - s->last_base_update > 1000000000ULL) { + char* bat_cap = read_file("/sys/class/power_supply/battery/capacity"); + char* bat_stat = read_file("/sys/class/power_supply/battery/status"); + + int tx_rate = 0; + int rx_rate = 0; + char* rx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/rx_bytes"); + char* tx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/tx_bytes"); + if (rx_bytes && tx_bytes) { + uint64_t rx_bytes_n = atoll(rx_bytes); + rx_rate = rx_bytes_n - s->last_rx_bytes; + s->last_rx_bytes = rx_bytes_n; + + uint64_t tx_bytes_n = atoll(tx_bytes); + tx_rate = tx_bytes_n - s->last_tx_bytes; + s->last_tx_bytes = tx_bytes_n; + } + if (rx_bytes) free(rx_bytes); + if (tx_bytes) free(tx_bytes); + + int pending = pending_uploads(); + + // service call wifi 20 # getWifiEnabledState + // Result: Parcel(00000000 00000003 '........') = enabled + s->wifi_enabled = !system("service call wifi 20 | grep 00000003 > /dev/null"); + + // service call wifi 38 # getWifiApEnabledState + // Result: Parcel(00000000 0000000d '........') = enabled + s->ap_enabled = !system("service call wifi 38 | grep 0000000d > /dev/null"); + + s->board_connected = !system("lsusb | grep bbaa > /dev/null"); + + snprintf(s->base_text, sizeof(s->base_text), + "serial: %s\n dongle id: %s\n battery: %s %s\npending: %d\nrx %.1fkiB/s tx %.1fkiB/s\nboard: %s", + s->serial, s->dongle_id, bat_cap ? bat_cap : "(null)", bat_stat ? bat_stat : "(null)", + pending, rx_rate / 1024.0, tx_rate / 1024.0, s->board_connected ? "found" : "NOT FOUND"); + + if (bat_cap) free(bat_cap); + if (bat_stat) free(bat_stat); + + s->last_base_update = ts; + } + + if (!s->vision_connected) { + // baseui interaction + + int touch_x = -1, touch_y = -1; + err = touch_poll(&s->touch, &touch_x, &touch_y); + if (err == 1) { + // press buttons + for (int i=0; i= b->x && touch_x < b->x+b->w + && touch_y >= b->y && touch_y < b->y+b->h) { + if (b->pressed && !activity_running()) { + b->pressed(); + break; + } + } + } + } + } + +} + +volatile int do_exit = 0; +static void set_do_exit(int sig) { + do_exit = 1; +} + + +static void* vision_connect_thread(void *args) { + int err; + + UIState *s = args; + while (!do_exit) { + usleep(100000); + pthread_mutex_lock(&s->lock); + bool connected = s->vision_connected; + pthread_mutex_unlock(&s->lock); + if (connected) continue; + + int fd = vipc_connect(); + if (fd < 0) continue; + + VisionPacket p = { + .type = VISION_UI_SUBSCRIBE, + }; + err = vipc_send(fd, p); + if (err < 0) { + close(fd); + continue; + } + + // printf("init recv\n"); + VisionPacket rp; + err = vipc_recv(fd, &rp); + if (err <= 0) { + close(fd); + continue; + } + + assert(rp.type == VISION_UI_BUFS); + assert(rp.num_fds == rp.d.ui_bufs.num_bufs + rp.d.ui_bufs.num_front_bufs); + + pthread_mutex_lock(&s->lock); + assert(!s->vision_connected); + s->ipc_fd = fd; + ui_init_vision(s, rp.d.ui_bufs, rp.fds); + s->vision_connected = true; + s->vision_connect_firstrun = true; + pthread_mutex_unlock(&s->lock); + } + return NULL; +} + +int main() { + int err; + + zsys_handler_set(NULL); + signal(SIGINT, (sighandler_t)set_do_exit); + + UIState uistate; + UIState *s = &uistate; + ui_init(s); + + pthread_t connect_thread_handle; + err = pthread_create(&connect_thread_handle, NULL, + vision_connect_thread, s); + assert(err == 0); + + while (!do_exit) { + pthread_mutex_lock(&s->lock); + ui_update(s); + ui_draw(s); + pthread_mutex_unlock(&s->lock); + + // no simple way to do 30fps vsync with surfaceflinger... + usleep(30000); + } + + err = pthread_join(connect_thread_handle, NULL); + assert(err == 0); + + return 0; +} diff --git a/selfdrive/visiond/Makefile b/selfdrive/visiond/Makefile new file mode 100644 index 0000000000..753c5e41ca --- /dev/null +++ b/selfdrive/visiond/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "visiond: this is a release" diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README new file mode 100644 index 0000000000..488343bc1e --- /dev/null +++ b/selfdrive/visiond/README @@ -0,0 +1,3 @@ +visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs and video logs lives here. + +Contact us if you'd like features added or support for your platform. diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond new file mode 100755 index 0000000000..0bc0cff878 --- /dev/null +++ b/selfdrive/visiond/visiond @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7896f5e614b47ba86ccc37dd620df36d84a5cc1cec54c2e06e919718a65980c5 +size 14719536