From 5de48a766885e80d27c27395c78fff175cf1bc16 Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Thu, 11 May 2017 12:41:17 -0700 Subject: [PATCH] openpilot v0.3.0-devel release old-commit-hash: 4653a9aef031b0389d6b2440085c961bd2933cf8 --- .gitignore | 5 +- .gitmodules | 3 + .travis.yml | 1 - README.md | 7 +- RELEASES.md | 10 + apk/com.baseui.apk | 3 + board/Makefile | 43 - board/adc.h | 38 - board/can.h | 84 - 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/stm32f2xx_hal_def.h | 3 - board/inc/stm32f2xx_hal_gpio_ex.h | 3 - board/inc/system_stm32f2xx.h | 3 - board/libc.h | 231 - board/main.c | 592 -- board/spi.h | 23 - 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/.gitignore | 1 + cereal/Makefile | 4 + cereal/build_from_src.mk | 38 + cereal/car.capnp | 30 + cereal/gen/c/c++.capnp.h | 0 cereal/gen/c/car.capnp.c | 337 - cereal/gen/c/car.capnp.h | 287 - cereal/gen/c/log.capnp.c | 1075 --- cereal/gen/c/log.capnp.h | 712 -- cereal/gen/cpp/car.capnp.c++ | 1504 ----- cereal/gen/cpp/car.capnp.h | 2032 ------ cereal/gen/cpp/log.capnp.c++ | 4089 ----------- cereal/gen/cpp/log.capnp.h | 7814 ---------------------- cereal/java.capnp | 28 + cereal/log.capnp | 621 +- common/api/__init__.py | 11 +- common/crash.py | 5 + common/filters.py | 17 - common/fingerprints.py | 128 + common/params.py | 285 + common/realtime.py | 25 +- common/services.py | 90 - dbcs/acura_ilx_2016_can.dbc | 8 +- dbcs/honda_accord_touring_2016_can.dbc | 305 + dbcs/honda_civic_touring_2016_can.dbc | 4 +- dbcs/tesla_can.dbc | 405 ++ panda | 1 + phonelibs/capnp-c/include/capnp_c.h | 3 + requirements_openpilot.txt | 1 + selfdrive/boardd/Makefile | 17 +- selfdrive/boardd/boardd.cc | 18 +- selfdrive/boardd/boardd.py | 20 +- selfdrive/calibrationd/__init__.py | 0 selfdrive/calibrationd/calibration.py | 208 - selfdrive/calibrationd/calibrationd.py | 121 - selfdrive/car/fingerprints.py | 12 - selfdrive/car/honda/carcontroller.py | 54 +- selfdrive/car/honda/carstate.py | 171 +- selfdrive/car/honda/hondacan.py | 37 +- selfdrive/car/honda/interface.py | 53 +- selfdrive/common/cereal.mk | 12 +- selfdrive/common/framebuffer.cc | 4 + selfdrive/common/framebuffer.h | 31 +- selfdrive/common/mutex.h | 13 - selfdrive/common/params.c | 124 + selfdrive/common/params.h | 35 + selfdrive/common/swaglog.c | 5 +- selfdrive/common/swaglog.h | 4 +- selfdrive/common/timing.h | 10 +- selfdrive/{ui => common}/touch.c | 0 selfdrive/{ui => common}/touch.h | 8 + selfdrive/common/util.c | 27 + selfdrive/common/util.h | 4 + selfdrive/common/utilpp.h | 65 + selfdrive/common/version.h | 2 +- selfdrive/common/visionipc.c | 122 +- selfdrive/common/visionipc.h | 92 +- selfdrive/config.py | 18 +- selfdrive/controls/controlsd.py | 173 +- selfdrive/controls/lib/adaptivecruise.py | 30 +- selfdrive/controls/lib/alertmanager.py | 1 + selfdrive/controls/lib/drive_helpers.py | 32 +- selfdrive/controls/lib/latcontrol.py | 21 +- selfdrive/controls/lib/longcontrol.py | 14 +- selfdrive/controls/plannerd.py | 80 + selfdrive/controls/radard.py | 27 +- selfdrive/debug/can_printer.py | 36 + selfdrive/debug/dump.py | 8 +- selfdrive/debug/test_carcontroller.py | 94 + selfdrive/debug/test_carstate.py | 53 + selfdrive/logcatd/Makefile | 2 +- selfdrive/loggerd/Makefile | 4 + selfdrive/loggerd/config.py | 5 - selfdrive/loggerd/logger.py | 65 - selfdrive/loggerd/loggerd | 3 + selfdrive/loggerd/loggerd.py | 93 - selfdrive/loggerd/uploader.py | 31 +- selfdrive/logmessaged.py | 2 +- selfdrive/manager.py | 227 +- selfdrive/proclogd/Makefile | 50 + selfdrive/proclogd/proclogd.cc | 245 + selfdrive/radar/nidec/interface.py | 2 +- selfdrive/registration.py | 32 +- selfdrive/sensord/Makefile | 53 +- selfdrive/sensord/sensord | 3 + selfdrive/sensord/sensors.cc | 228 - selfdrive/service_list.yaml | 99 + selfdrive/services.py | 14 + selfdrive/test/plant/plant.py | 27 +- selfdrive/test/plant/runtest.sh | 4 +- selfdrive/tombstoned.py | 83 + selfdrive/ui/Makefile | 7 +- selfdrive/ui/ui.c | 821 +-- selfdrive/version.py | 3 + selfdrive/visiond/LICENSE.boringssl | 192 + selfdrive/visiond/LICENSE.libyuv | 29 + selfdrive/visiond/LICENSE.opencv | 41 + selfdrive/visiond/README | 2 +- selfdrive/visiond/visiond | 4 +- 127 files changed, 4390 insertions(+), 21994 deletions(-) create mode 100644 .gitmodules create mode 100644 apk/com.baseui.apk delete mode 100644 board/Makefile delete mode 100644 board/adc.h delete mode 100644 board/can.h delete mode 100644 board/dac.h delete mode 100644 board/inc/core_cm3.h delete mode 100644 board/inc/core_cmFunc.h delete mode 100644 board/inc/core_cmInstr.h delete mode 100644 board/inc/stm32f205xx.h delete mode 100644 board/inc/stm32f2xx.h delete mode 100644 board/inc/stm32f2xx_hal_def.h delete mode 100644 board/inc/stm32f2xx_hal_gpio_ex.h delete mode 100644 board/inc/system_stm32f2xx.h delete mode 100644 board/libc.h delete mode 100644 board/main.c delete mode 100644 board/spi.h delete mode 100644 board/startup_stm32f205xx.s delete mode 100644 board/stm32_flash.ld delete mode 100644 board/timer.h delete mode 100755 board/tools/dfu-util-aarch64 delete mode 100755 board/tools/dfu-util-x86_64 delete mode 100755 board/tools/enter_download_mode.py delete mode 100644 board/usb.h create mode 100644 cereal/.gitignore create mode 100644 cereal/Makefile create mode 100644 cereal/build_from_src.mk delete mode 100644 cereal/gen/c/c++.capnp.h delete mode 100644 cereal/gen/c/car.capnp.c delete mode 100644 cereal/gen/c/car.capnp.h delete mode 100644 cereal/gen/c/log.capnp.c delete mode 100644 cereal/gen/c/log.capnp.h delete mode 100644 cereal/gen/cpp/car.capnp.c++ delete mode 100644 cereal/gen/cpp/car.capnp.h delete mode 100644 cereal/gen/cpp/log.capnp.c++ delete mode 100644 cereal/gen/cpp/log.capnp.h create mode 100644 cereal/java.capnp delete mode 100644 common/filters.py create mode 100644 common/fingerprints.py create mode 100755 common/params.py delete mode 100644 common/services.py create mode 100644 dbcs/honda_accord_touring_2016_can.dbc create mode 100644 dbcs/tesla_can.dbc create mode 160000 panda create mode 100644 phonelibs/capnp-c/include/capnp_c.h delete mode 100644 selfdrive/calibrationd/__init__.py delete mode 100644 selfdrive/calibrationd/calibration.py delete mode 100755 selfdrive/calibrationd/calibrationd.py delete mode 100644 selfdrive/car/fingerprints.py delete mode 100644 selfdrive/common/mutex.h create mode 100644 selfdrive/common/params.c create mode 100644 selfdrive/common/params.h rename selfdrive/{ui => common}/touch.c (100%) rename selfdrive/{ui => common}/touch.h (74%) create mode 100644 selfdrive/common/util.c create mode 100644 selfdrive/common/utilpp.h create mode 100755 selfdrive/controls/plannerd.py create mode 100755 selfdrive/debug/can_printer.py create mode 100755 selfdrive/debug/test_carcontroller.py create mode 100755 selfdrive/debug/test_carstate.py create mode 100644 selfdrive/loggerd/Makefile delete mode 100644 selfdrive/loggerd/logger.py create mode 100755 selfdrive/loggerd/loggerd delete mode 100755 selfdrive/loggerd/loggerd.py create mode 100644 selfdrive/proclogd/Makefile create mode 100644 selfdrive/proclogd/proclogd.cc create mode 100755 selfdrive/sensord/sensord delete mode 100644 selfdrive/sensord/sensors.cc create mode 100644 selfdrive/service_list.yaml create mode 100644 selfdrive/services.py create mode 100644 selfdrive/tombstoned.py create mode 100644 selfdrive/version.py create mode 100644 selfdrive/visiond/LICENSE.boringssl create mode 100644 selfdrive/visiond/LICENSE.libyuv create mode 100644 selfdrive/visiond/LICENSE.opencv diff --git a/.gitignore b/.gitignore index 3731d8f749..aad9fecc55 100644 --- a/.gitignore +++ b/.gitignore @@ -1,6 +1,7 @@ .DS_Store .tags .ipynb_checkpoints +model2.png *.pyc .*.swp @@ -11,12 +12,14 @@ *.so *.a *.clb +*.class config.json clcache board/obj/ selfdrive/boardd/boardd selfdrive/logcatd/logcatd -selfdrive/sensord/sensord +selfdrive/proclogd/proclogd selfdrive/ui/ui +/src/ diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000..2bbbbd459d --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "panda"] + path = panda + url = git@github.com:commaai/panda.git diff --git a/.travis.yml b/.travis.yml index 6a97c00622..9c668d75d9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -10,4 +10,3 @@ script: - docker run --rm -v "$(pwd)"/selfdrive/test/plant/out:/tmp/openpilot/selfdrive/test/plant/out tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/plant && ./runtest.sh' - diff --git a/README.md b/README.md index 0e034f068e..ef63cfaacb 100644 --- a/README.md +++ b/README.md @@ -26,27 +26,28 @@ Supported Cars 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 +- panda -- Code used to communicate on CAN and LIN - 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 - car -- Code that talks to the car and implements CarInterface - common -- Shared C/C++ code for the daemons - controls -- Python controls (PID loops etc) for the car + - debug -- Tools to help you debug and do car ports - logcatd -- Android logcat as a service - loggerd -- Logger and uploader of car data + - proclogd -- Logs information from proc - radar -- Code that talks to the radar and implements RadarInterface - sensord -- IMU / GPS interface code - test/plant -- Car simulator running code through virtual maneuvers - ui -- The UI - visiond -- embedded vision pipeline -To understand how the services interact, see `common/services.py` +To understand how the services interact, see `selfdrive/service_list.yaml` Testing on PC ------ diff --git a/RELEASES.md b/RELEASES.md index f468226d98..6b636e0591 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,13 @@ +Version 0.3.0 (2017-03-xx) +=========================== + * Add CarParams struct to improve the abstraction layer + * Refactor visiond IPC to support multiple clients + * Add raw GPS and beginning support for navigation + * Improve model in visiond using crowdsourced data + * Add improved system logging to diagnose instability + * Rewrite baseui in React Native + * Moved calibration to the cloud + Version 0.2.9 (2017-03-01) =========================== * Retain compatibility with NEOS v1 diff --git a/apk/com.baseui.apk b/apk/com.baseui.apk new file mode 100644 index 0000000000..2c576252a4 --- /dev/null +++ b/apk/com.baseui.apk @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:24fcc5e7b728675f4fe5b4da4a13793d20ac66fc0eb37f8ffc294bcea03014d7 +size 8987137 diff --git a/board/Makefile b/board/Makefile deleted file mode 100644 index 4c0b6d38ac..0000000000 --- a/board/Makefile +++ /dev/null @@ -1,43 +0,0 @@ -# :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 deleted file mode 100644 index 3ac2fe4fe4..0000000000 --- a/board/adc.h +++ /dev/null @@ -1,38 +0,0 @@ -// 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 deleted file mode 100644 index 5cb5b7e5c2..0000000000 --- a/board/can.h +++ /dev/null @@ -1,84 +0,0 @@ -void can_init(CAN_TypeDef *CAN) { - // enable CAN busses - if (CAN == CAN1) { - // CAN1_EN - GPIOB->ODR |= (1 << 3); - } else if (CAN == CAN2) { - // CAN2_EN - GPIOB->ODR |= (1 << 4); - } - - 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 deleted file mode 100644 index b8833dc4a6..0000000000 --- a/board/dac.h +++ /dev/null @@ -1,16 +0,0 @@ -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 deleted file mode 100644 index 3230d27cb1..0000000000 --- a/board/inc/core_cm3.h +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100644 index 9d7dad3e84..0000000000 --- a/board/inc/core_cmFunc.h +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100644 index 6bb15f9f12..0000000000 --- a/board/inc/core_cmInstr.h +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100644 index a5221edd5d..0000000000 --- a/board/inc/stm32f205xx.h +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100644 index 3f80ca09a7..0000000000 --- a/board/inc/stm32f2xx.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:92af21aaac6645199edf6b5ca2130b172652a0c929ae6ab8faa0bc72b0df6288 -size 5993 diff --git a/board/inc/stm32f2xx_hal_def.h b/board/inc/stm32f2xx_hal_def.h deleted file mode 100644 index e6a98f7003..0000000000 --- a/board/inc/stm32f2xx_hal_def.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:740f87930e67d4288d9e89186a89ca71254acd3981dc7231157a3c41305152b2 -size 6017 diff --git a/board/inc/stm32f2xx_hal_gpio_ex.h b/board/inc/stm32f2xx_hal_gpio_ex.h deleted file mode 100644 index 3ebb7f815c..0000000000 --- a/board/inc/stm32f2xx_hal_gpio_ex.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:99bd10a191f12b66e5a58fee1176f419785cb3c0ced16fc8f9c879682912aa64 -size 11218 diff --git a/board/inc/system_stm32f2xx.h b/board/inc/system_stm32f2xx.h deleted file mode 100644 index 33d731a777..0000000000 --- a/board/inc/system_stm32f2xx.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:086226c6423159dc7856adb385add2f550dcb53459b6a1dd3d9647649646453e -size 2092 diff --git a/board/libc.h b/board/libc.h deleted file mode 100644 index 798de46c04..0000000000 --- a/board/libc.h +++ /dev/null @@ -1,231 +0,0 @@ -#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)) - -#include "stm32f2xx_hal_gpio_ex.h" - -// **** 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->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - - 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->APB1ENR |= RCC_APB1ENR_TIM4EN; - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; - RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - - // 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 | GPIO_MODER_MODER12_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; - - // setup SPI - GPIOA->MODER |= GPIO_MODER_MODER4_1 | GPIO_MODER_MODER5_1 | - GPIO_MODER_MODER6_1 | GPIO_MODER_MODER7_1; - GPIOA->AFR[0] |= GPIO_AF5_SPI1 << (4*4) | GPIO_AF5_SPI1 << (5*4) | - GPIO_AF5_SPI1 << (6*4) | GPIO_AF5_SPI1 << (7*4); - - // 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 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;iODR &= ~(1 << (10 + led_num)); - } else { - // turn off - GPIOB->ODR |= (1 << (10 + led_num)); - } -} - diff --git a/board/main.c b/board/main.c deleted file mode 100644 index 637fdf1c84..0000000000 --- a/board/main.c +++ /dev/null @@ -1,592 +0,0 @@ -//#define DEBUG -//#define CAN_LOOPBACK_MODE -//#define USE_INTERNAL_OSC -//#define OLD_BOARD -//#define ENABLE_CURRENT_SENSOR -//#define ENABLE_SPI - -// choose serial port for debugging -//#define USART USART2 -#define USART USART3 - -#define USB_VID 0xbbaa -#define USB_PID 0xddcc - -// *** end config *** - -#include "stm32f2xx.h" -#include "obj/gitversion.h" - -#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef -uint32_t enter_bootloader_mode; - -USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; - -#include "libc.h" -#include "adc.h" -#include "timer.h" -#include "usb.h" -#include "can.h" -#include "spi.h" - -// debug safety check: is controls allowed? -int controls_allowed = 0; -int started = 0; -int can_live = 0, pending_can_live = 0; - -// optional features -int gas_interceptor_detected = 0; -int started_signal_detected = 0; - -// ********************* instantiate queues ********************* - -#define FIFO_SIZE 0x100 -typedef struct { - uint8_t w_ptr; - uint8_t r_ptr; - CAN_FIFOMailBox_TypeDef elems[FIFO_SIZE]; -} can_ring; - -can_ring can_rx_q = { .w_ptr = 0, .r_ptr = 0 }; -can_ring can_tx1_q = { .w_ptr = 0, .r_ptr = 0 }; -can_ring can_tx2_q = { .w_ptr = 0, .r_ptr = 0 }; - -// ********************* interrupt safe queue ********************* - -inline int pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - if (q->w_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) { - // can is live - pending_can_live = 1; - - // 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; - uint8_t started_signal_detected; - } *health = dat; - health->voltage = adc_get(ADCCHAN_VOLTAGE); -#ifdef ENABLE_CURRENT_SENSOR - health->current = adc_get(ADCCHAN_CURRENT); -#else - health->current = 0; -#endif - health->started = started; - - health->controls_allowed = controls_allowed; - - health->gas_interceptor_detected = gas_interceptor_detected; - health->started_signal_detected = started_signal_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"); -} - -#ifdef ENABLE_SPI - -#define SPI_BUF_SIZE 128 -uint8_t spi_buf[SPI_BUF_SIZE]; -int spi_buf_count = 0; -uint8_t spi_tx_buf[0x10]; - -void DMA2_Stream3_IRQHandler(void) { - #ifdef DEBUG - puts("DMA2\n"); - #endif - DMA2->LIFCR = DMA_LIFCR_CTCIF3; - - pop(&can_rx_q, spi_tx_buf); - spi_tx_dma(spi_tx_buf, 0x10); -} - -void SPI1_IRQHandler(void) { - // status is 0x43 - if (SPI1->SR & SPI_SR_RXNE) { - uint8_t dat = SPI1->DR; - /*spi_buf[spi_buf_count] = dat; - if (spi_buf_count < SPI_BUF_SIZE-1) { - spi_buf_count += 1; - }*/ - } - - if (SPI1->SR & SPI_SR_TXE) { - // all i send is U U U no matter what - //SPI1->DR = 'U'; - } - - int stat = SPI1->SR; - if (stat & ((~SPI_SR_RXNE) & (~SPI_SR_TXE) & (~SPI_SR_BSY))) { - puts("SPI status: "); - puth(stat); - puts("\n"); - } -} - -#endif - -// ***************************** 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(); - - gpio_init(); - uart_init(); - usb_init(); - can_init(CAN1); - can_init(CAN2); - adc_init(); - -#ifdef ENABLE_SPI - spi_init(); - - // set up DMA - memset(spi_tx_buf, 0, 0x10); - spi_tx_dma(spi_tx_buf, 0x10); -#endif - - // 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); - -#ifdef ENABLE_SPI - NVIC_EnableIRQ(DMA2_Stream3_IRQn); - NVIC_EnableIRQ(SPI1_IRQn); -#endif - __enable_irq(); - - - // LED should keep on blinking all the time - int cnt; - for (cnt=0;;cnt++) { - can_live = pending_can_live; - - // reset this every 16th pass - if ((cnt&0xF) == 0) pending_can_live = 0; - - #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); - - #ifdef ENABLE_SPI - if (spi_buf_count > 0) { - hexdump(spi_buf, spi_buf_count); - spi_buf_count = 0; - } - #endif - - // started logic - int started_signal = (GPIOC->IDR & (1 << 13)) != 0; - if (started_signal) { started_signal_detected = 1; } - - if (started_signal || (!started_signal_detected && can_live)) { - started = 1; - - // turn on fan at half speed - set_fan_speed(32768); - } else { - started = 0; - - // turn off fan - set_fan_speed(0); - } - } - - return 0; -} - diff --git a/board/spi.h b/board/spi.h deleted file mode 100644 index e725790d06..0000000000 --- a/board/spi.h +++ /dev/null @@ -1,23 +0,0 @@ -void spi_init() { - puts("SPI init\n"); - SPI1->CR1 = SPI_CR1_SPE; - SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE; -} - -void spi_tx_dma(void *addr, int len) { - // disable DMA - SPI1->CR2 &= ~SPI_CR2_TXDMAEN; - DMA2_Stream3->CR &= ~DMA_SxCR_EN; - - // DMA2, stream 3, channel 3 - DMA2_Stream3->M0AR = addr; - DMA2_Stream3->NDTR = len; - DMA2_Stream3->PAR = &(SPI1->DR); - - // channel3, increment memory, memory -> periph, enable - DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN; - DMA2_Stream3->CR |= DMA_SxCR_TCIE; - - SPI1->CR2 |= SPI_CR2_TXDMAEN; -} - diff --git a/board/startup_stm32f205xx.s b/board/startup_stm32f205xx.s deleted file mode 100644 index 6fb1d22fbb..0000000000 --- a/board/startup_stm32f205xx.s +++ /dev/null @@ -1,511 +0,0 @@ -/** - ****************************************************************************** - * @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 deleted file mode 100644 index 3d3c4c4540..0000000000 --- a/board/stm32_flash.ld +++ /dev/null @@ -1,163 +0,0 @@ -/* -***************************************************************************** -** -** 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 deleted file mode 100644 index a14b619e4b..0000000000 --- a/board/timer.h +++ /dev/null @@ -1,7 +0,0 @@ -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 deleted file mode 100755 index 73836c3598..0000000000 --- a/board/tools/dfu-util-aarch64 +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100755 index 2167cdf686..0000000000 --- a/board/tools/dfu-util-x86_64 +++ /dev/null @@ -1,3 +0,0 @@ -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 deleted file mode 100755 index 2b3d906f6f..0000000000 --- a/board/tools/enter_download_mode.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/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 deleted file mode 100644 index 65799a7936..0000000000 --- a/board/usb.h +++ /dev/null @@ -1,510 +0,0 @@ -// **** 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/.gitignore b/cereal/.gitignore new file mode 100644 index 0000000000..4f62b849d5 --- /dev/null +++ b/cereal/.gitignore @@ -0,0 +1 @@ +gen diff --git a/cereal/Makefile b/cereal/Makefile new file mode 100644 index 0000000000..ead08bf5be --- /dev/null +++ b/cereal/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "cereal: this is a release" diff --git a/cereal/build_from_src.mk b/cereal/build_from_src.mk new file mode 100644 index 0000000000..6f523e77ea --- /dev/null +++ b/cereal/build_from_src.mk @@ -0,0 +1,38 @@ +SRCS := log.capnp car.capnp + +GENS := gen/c/car.capnp.c gen/c/log.capnp.c gen/c/c++.capnp.h gen/c/java.capnp.h \ + gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++ + +# Dont build java on the phone... +UNAME_M := $(shell uname -m) +ifeq ($(UNAME_M),x86_64) + GENS += gen/java/Car.java gen/java/Log.java +endif + +.PHONY: all +all: $(GENS) + +.PHONY: clean +clean: + rm -rf gen + +gen/c/%.capnp.c: %.capnp + @echo "[ CAPNPC C ] $@" + mkdir -p gen/c/ + capnpc '$<' -o c:gen/c/ + +gen/cpp/%.capnp.c++: %.capnp + @echo "[ CAPNPC C++ ] $@" + mkdir -p gen/cpp/ + capnpc '$<' -o c++:gen/cpp/ + +gen/java/Car.java gen/java/Log.java: $(SRCS) + @echo "[ CAPNPC java ] $@" + mkdir -p gen/java/ + capnpc $^ -o java:gen/java + +# c-capnproto needs some empty headers +gen/c/c++.capnp.h gen/c/java.capnp.h: + mkdir -p gen/c/ + touch '$@' + diff --git a/cereal/car.capnp b/cereal/car.capnp index a5dd2f802d..093e66b299 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -1,6 +1,10 @@ using Cxx = import "c++.capnp"; $Cxx.namespace("cereal"); +using Java = import "java.capnp"; +$Java.package("ai.comma.openpilot.cereal"); +$Java.outerClassname("Car"); + @0x8e2af1e708af8b8d; # ******* main car state @ 100hz ******* @@ -170,3 +174,29 @@ struct CarControl { } } +# ****** car param ****** + +struct CarParams { + carName @0: Text; + radarName @1: Text; + carFingerprint @11: Text; + + enableSteer @2: Bool; + enableGas @3: Bool; + enableBrake @4: Bool; + enableCruise @5: Bool; + + # things about the car in the manual + wheelBase @6: Float32; # in meters + steerRatio @7: Float32; + + # things we can derive + slipFactor @8: Float32; + + # Kp and Ki for the lateral control + steerKp @9: Float32; + steerKi @10: Float32; + + # TODO: Kp and Ki for long control, perhaps not needed? +} + diff --git a/cereal/gen/c/c++.capnp.h b/cereal/gen/c/c++.capnp.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cereal/gen/c/car.capnp.c b/cereal/gen/c/car.capnp.c deleted file mode 100644 index 9cf47c5fb7..0000000000 --- a/cereal/gen/c/car.capnp.c +++ /dev/null @@ -1,337 +0,0 @@ -#include "car.capnp.h" -/* AUTO GENERATED - DO NOT EDIT */ - -cereal_CarState_ptr cereal_new_CarState(struct capn_segment *s) { - cereal_CarState_ptr p; - p.p = capn_new_struct(s, 24, 5); - return p; -} -cereal_CarState_list cereal_new_CarState_list(struct capn_segment *s, int len) { - cereal_CarState_list p; - p.p = capn_new_list(s, len, 24, 5); - return p; -} -void cereal_read_CarState(struct cereal_CarState *s, cereal_CarState_ptr p) { - capn_resolve(&p.p); - s->errors.p = capn_getp(p.p, 0, 0); - s->vEgo = capn_to_f32(capn_read32(p.p, 0)); - s->wheelSpeeds.p = capn_getp(p.p, 1, 0); - s->gas = capn_to_f32(capn_read32(p.p, 4)); - s->gasPressed = (capn_read8(p.p, 8) & 1) != 0; - s->brake = capn_to_f32(capn_read32(p.p, 12)); - s->brakePressed = (capn_read8(p.p, 8) & 2) != 0; - s->steeringAngle = capn_to_f32(capn_read32(p.p, 16)); - s->steeringTorque = capn_to_f32(capn_read32(p.p, 20)); - s->steeringPressed = (capn_read8(p.p, 8) & 4) != 0; - s->cruiseState.p = capn_getp(p.p, 2, 0); - s->buttonEvents.p = capn_getp(p.p, 3, 0); - s->canMonoTimes.p = capn_getp(p.p, 4, 0); -} -void cereal_write_CarState(const struct cereal_CarState *s, cereal_CarState_ptr p) { - capn_resolve(&p.p); - capn_setp(p.p, 0, s->errors.p); - capn_write32(p.p, 0, capn_from_f32(s->vEgo)); - capn_setp(p.p, 1, s->wheelSpeeds.p); - capn_write32(p.p, 4, capn_from_f32(s->gas)); - capn_write1(p.p, 64, s->gasPressed != 0); - capn_write32(p.p, 12, capn_from_f32(s->brake)); - capn_write1(p.p, 65, s->brakePressed != 0); - capn_write32(p.p, 16, capn_from_f32(s->steeringAngle)); - capn_write32(p.p, 20, capn_from_f32(s->steeringTorque)); - capn_write1(p.p, 66, s->steeringPressed != 0); - capn_setp(p.p, 2, s->cruiseState.p); - capn_setp(p.p, 3, s->buttonEvents.p); - capn_setp(p.p, 4, s->canMonoTimes.p); -} -void cereal_get_CarState(struct cereal_CarState *s, cereal_CarState_list l, int i) { - cereal_CarState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarState(s, p); -} -void cereal_set_CarState(const struct cereal_CarState *s, cereal_CarState_list l, int i) { - cereal_CarState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarState(s, p); -} - -cereal_CarState_WheelSpeeds_ptr cereal_new_CarState_WheelSpeeds(struct capn_segment *s) { - cereal_CarState_WheelSpeeds_ptr p; - p.p = capn_new_struct(s, 16, 0); - return p; -} -cereal_CarState_WheelSpeeds_list cereal_new_CarState_WheelSpeeds_list(struct capn_segment *s, int len) { - cereal_CarState_WheelSpeeds_list p; - p.p = capn_new_list(s, len, 16, 0); - return p; -} -void cereal_read_CarState_WheelSpeeds(struct cereal_CarState_WheelSpeeds *s, cereal_CarState_WheelSpeeds_ptr p) { - capn_resolve(&p.p); - s->fl = capn_to_f32(capn_read32(p.p, 0)); - s->fr = capn_to_f32(capn_read32(p.p, 4)); - s->rl = capn_to_f32(capn_read32(p.p, 8)); - s->rr = capn_to_f32(capn_read32(p.p, 12)); -} -void cereal_write_CarState_WheelSpeeds(const struct cereal_CarState_WheelSpeeds *s, cereal_CarState_WheelSpeeds_ptr p) { - capn_resolve(&p.p); - capn_write32(p.p, 0, capn_from_f32(s->fl)); - capn_write32(p.p, 4, capn_from_f32(s->fr)); - capn_write32(p.p, 8, capn_from_f32(s->rl)); - capn_write32(p.p, 12, capn_from_f32(s->rr)); -} -void cereal_get_CarState_WheelSpeeds(struct cereal_CarState_WheelSpeeds *s, cereal_CarState_WheelSpeeds_list l, int i) { - cereal_CarState_WheelSpeeds_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarState_WheelSpeeds(s, p); -} -void cereal_set_CarState_WheelSpeeds(const struct cereal_CarState_WheelSpeeds *s, cereal_CarState_WheelSpeeds_list l, int i) { - cereal_CarState_WheelSpeeds_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarState_WheelSpeeds(s, p); -} - -cereal_CarState_CruiseState_ptr cereal_new_CarState_CruiseState(struct capn_segment *s) { - cereal_CarState_CruiseState_ptr p; - p.p = capn_new_struct(s, 8, 0); - return p; -} -cereal_CarState_CruiseState_list cereal_new_CarState_CruiseState_list(struct capn_segment *s, int len) { - cereal_CarState_CruiseState_list p; - p.p = capn_new_list(s, len, 8, 0); - return p; -} -void cereal_read_CarState_CruiseState(struct cereal_CarState_CruiseState *s, cereal_CarState_CruiseState_ptr p) { - capn_resolve(&p.p); - s->enabled = (capn_read8(p.p, 0) & 1) != 0; - s->speed = capn_to_f32(capn_read32(p.p, 4)); -} -void cereal_write_CarState_CruiseState(const struct cereal_CarState_CruiseState *s, cereal_CarState_CruiseState_ptr p) { - capn_resolve(&p.p); - capn_write1(p.p, 0, s->enabled != 0); - capn_write32(p.p, 4, capn_from_f32(s->speed)); -} -void cereal_get_CarState_CruiseState(struct cereal_CarState_CruiseState *s, cereal_CarState_CruiseState_list l, int i) { - cereal_CarState_CruiseState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarState_CruiseState(s, p); -} -void cereal_set_CarState_CruiseState(const struct cereal_CarState_CruiseState *s, cereal_CarState_CruiseState_list l, int i) { - cereal_CarState_CruiseState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarState_CruiseState(s, p); -} - -cereal_CarState_ButtonEvent_ptr cereal_new_CarState_ButtonEvent(struct capn_segment *s) { - cereal_CarState_ButtonEvent_ptr p; - p.p = capn_new_struct(s, 8, 0); - return p; -} -cereal_CarState_ButtonEvent_list cereal_new_CarState_ButtonEvent_list(struct capn_segment *s, int len) { - cereal_CarState_ButtonEvent_list p; - p.p = capn_new_list(s, len, 8, 0); - return p; -} -void cereal_read_CarState_ButtonEvent(struct cereal_CarState_ButtonEvent *s, cereal_CarState_ButtonEvent_ptr p) { - capn_resolve(&p.p); - s->pressed = (capn_read8(p.p, 0) & 1) != 0; - s->type = (enum cereal_CarState_ButtonEvent_Type)(int) capn_read16(p.p, 2); -} -void cereal_write_CarState_ButtonEvent(const struct cereal_CarState_ButtonEvent *s, cereal_CarState_ButtonEvent_ptr p) { - capn_resolve(&p.p); - capn_write1(p.p, 0, s->pressed != 0); - capn_write16(p.p, 2, (uint16_t) (s->type)); -} -void cereal_get_CarState_ButtonEvent(struct cereal_CarState_ButtonEvent *s, cereal_CarState_ButtonEvent_list l, int i) { - cereal_CarState_ButtonEvent_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarState_ButtonEvent(s, p); -} -void cereal_set_CarState_ButtonEvent(const struct cereal_CarState_ButtonEvent *s, cereal_CarState_ButtonEvent_list l, int i) { - cereal_CarState_ButtonEvent_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarState_ButtonEvent(s, p); -} - -cereal_RadarState_ptr cereal_new_RadarState(struct capn_segment *s) { - cereal_RadarState_ptr p; - p.p = capn_new_struct(s, 0, 3); - return p; -} -cereal_RadarState_list cereal_new_RadarState_list(struct capn_segment *s, int len) { - cereal_RadarState_list p; - p.p = capn_new_list(s, len, 0, 3); - return p; -} -void cereal_read_RadarState(struct cereal_RadarState *s, cereal_RadarState_ptr p) { - capn_resolve(&p.p); - s->errors.p = capn_getp(p.p, 0, 0); - s->points.p = capn_getp(p.p, 1, 0); - s->canMonoTimes.p = capn_getp(p.p, 2, 0); -} -void cereal_write_RadarState(const struct cereal_RadarState *s, cereal_RadarState_ptr p) { - capn_resolve(&p.p); - capn_setp(p.p, 0, s->errors.p); - capn_setp(p.p, 1, s->points.p); - capn_setp(p.p, 2, s->canMonoTimes.p); -} -void cereal_get_RadarState(struct cereal_RadarState *s, cereal_RadarState_list l, int i) { - cereal_RadarState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_RadarState(s, p); -} -void cereal_set_RadarState(const struct cereal_RadarState *s, cereal_RadarState_list l, int i) { - cereal_RadarState_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_RadarState(s, p); -} - -cereal_RadarState_RadarPoint_ptr cereal_new_RadarState_RadarPoint(struct capn_segment *s) { - cereal_RadarState_RadarPoint_ptr p; - p.p = capn_new_struct(s, 32, 0); - return p; -} -cereal_RadarState_RadarPoint_list cereal_new_RadarState_RadarPoint_list(struct capn_segment *s, int len) { - cereal_RadarState_RadarPoint_list p; - p.p = capn_new_list(s, len, 32, 0); - return p; -} -void cereal_read_RadarState_RadarPoint(struct cereal_RadarState_RadarPoint *s, cereal_RadarState_RadarPoint_ptr p) { - capn_resolve(&p.p); - s->trackId = capn_read64(p.p, 0); - s->dRel = capn_to_f32(capn_read32(p.p, 8)); - s->yRel = capn_to_f32(capn_read32(p.p, 12)); - s->vRel = capn_to_f32(capn_read32(p.p, 16)); - s->aRel = capn_to_f32(capn_read32(p.p, 20)); - s->yvRel = capn_to_f32(capn_read32(p.p, 24)); -} -void cereal_write_RadarState_RadarPoint(const struct cereal_RadarState_RadarPoint *s, cereal_RadarState_RadarPoint_ptr p) { - capn_resolve(&p.p); - capn_write64(p.p, 0, s->trackId); - capn_write32(p.p, 8, capn_from_f32(s->dRel)); - capn_write32(p.p, 12, capn_from_f32(s->yRel)); - capn_write32(p.p, 16, capn_from_f32(s->vRel)); - capn_write32(p.p, 20, capn_from_f32(s->aRel)); - capn_write32(p.p, 24, capn_from_f32(s->yvRel)); -} -void cereal_get_RadarState_RadarPoint(struct cereal_RadarState_RadarPoint *s, cereal_RadarState_RadarPoint_list l, int i) { - cereal_RadarState_RadarPoint_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_RadarState_RadarPoint(s, p); -} -void cereal_set_RadarState_RadarPoint(const struct cereal_RadarState_RadarPoint *s, cereal_RadarState_RadarPoint_list l, int i) { - cereal_RadarState_RadarPoint_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_RadarState_RadarPoint(s, p); -} - -cereal_CarControl_ptr cereal_new_CarControl(struct capn_segment *s) { - cereal_CarControl_ptr p; - p.p = capn_new_struct(s, 16, 2); - return p; -} -cereal_CarControl_list cereal_new_CarControl_list(struct capn_segment *s, int len) { - cereal_CarControl_list p; - p.p = capn_new_list(s, len, 16, 2); - return p; -} -void cereal_read_CarControl(struct cereal_CarControl *s, cereal_CarControl_ptr p) { - capn_resolve(&p.p); - s->enabled = (capn_read8(p.p, 0) & 1) != 0; - s->gas = capn_to_f32(capn_read32(p.p, 4)); - s->brake = capn_to_f32(capn_read32(p.p, 8)); - s->steeringTorque = capn_to_f32(capn_read32(p.p, 12)); - s->cruiseControl.p = capn_getp(p.p, 0, 0); - s->hudControl.p = capn_getp(p.p, 1, 0); -} -void cereal_write_CarControl(const struct cereal_CarControl *s, cereal_CarControl_ptr p) { - capn_resolve(&p.p); - capn_write1(p.p, 0, s->enabled != 0); - capn_write32(p.p, 4, capn_from_f32(s->gas)); - capn_write32(p.p, 8, capn_from_f32(s->brake)); - capn_write32(p.p, 12, capn_from_f32(s->steeringTorque)); - capn_setp(p.p, 0, s->cruiseControl.p); - capn_setp(p.p, 1, s->hudControl.p); -} -void cereal_get_CarControl(struct cereal_CarControl *s, cereal_CarControl_list l, int i) { - cereal_CarControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarControl(s, p); -} -void cereal_set_CarControl(const struct cereal_CarControl *s, cereal_CarControl_list l, int i) { - cereal_CarControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarControl(s, p); -} - -cereal_CarControl_CruiseControl_ptr cereal_new_CarControl_CruiseControl(struct capn_segment *s) { - cereal_CarControl_CruiseControl_ptr p; - p.p = capn_new_struct(s, 16, 0); - return p; -} -cereal_CarControl_CruiseControl_list cereal_new_CarControl_CruiseControl_list(struct capn_segment *s, int len) { - cereal_CarControl_CruiseControl_list p; - p.p = capn_new_list(s, len, 16, 0); - return p; -} -void cereal_read_CarControl_CruiseControl(struct cereal_CarControl_CruiseControl *s, cereal_CarControl_CruiseControl_ptr p) { - capn_resolve(&p.p); - s->cancel = (capn_read8(p.p, 0) & 1) != 0; - s->override = (capn_read8(p.p, 0) & 2) != 0; - s->speedOverride = capn_to_f32(capn_read32(p.p, 4)); - s->accelOverride = capn_to_f32(capn_read32(p.p, 8)); -} -void cereal_write_CarControl_CruiseControl(const struct cereal_CarControl_CruiseControl *s, cereal_CarControl_CruiseControl_ptr p) { - capn_resolve(&p.p); - capn_write1(p.p, 0, s->cancel != 0); - capn_write1(p.p, 1, s->override != 0); - capn_write32(p.p, 4, capn_from_f32(s->speedOverride)); - capn_write32(p.p, 8, capn_from_f32(s->accelOverride)); -} -void cereal_get_CarControl_CruiseControl(struct cereal_CarControl_CruiseControl *s, cereal_CarControl_CruiseControl_list l, int i) { - cereal_CarControl_CruiseControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarControl_CruiseControl(s, p); -} -void cereal_set_CarControl_CruiseControl(const struct cereal_CarControl_CruiseControl *s, cereal_CarControl_CruiseControl_list l, int i) { - cereal_CarControl_CruiseControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarControl_CruiseControl(s, p); -} - -cereal_CarControl_HUDControl_ptr cereal_new_CarControl_HUDControl(struct capn_segment *s) { - cereal_CarControl_HUDControl_ptr p; - p.p = capn_new_struct(s, 16, 0); - return p; -} -cereal_CarControl_HUDControl_list cereal_new_CarControl_HUDControl_list(struct capn_segment *s, int len) { - cereal_CarControl_HUDControl_list p; - p.p = capn_new_list(s, len, 16, 0); - return p; -} -void cereal_read_CarControl_HUDControl(struct cereal_CarControl_HUDControl *s, cereal_CarControl_HUDControl_ptr p) { - capn_resolve(&p.p); - s->speedVisible = (capn_read8(p.p, 0) & 1) != 0; - s->setSpeed = capn_to_f32(capn_read32(p.p, 4)); - s->lanesVisible = (capn_read8(p.p, 0) & 2) != 0; - s->leadVisible = (capn_read8(p.p, 0) & 4) != 0; - s->visualAlert = (enum cereal_CarControl_HUDControl_VisualAlert)(int) capn_read16(p.p, 2); - s->audibleAlert = (enum cereal_CarControl_HUDControl_AudibleAlert)(int) capn_read16(p.p, 8); -} -void cereal_write_CarControl_HUDControl(const struct cereal_CarControl_HUDControl *s, cereal_CarControl_HUDControl_ptr p) { - capn_resolve(&p.p); - capn_write1(p.p, 0, s->speedVisible != 0); - capn_write32(p.p, 4, capn_from_f32(s->setSpeed)); - capn_write1(p.p, 1, s->lanesVisible != 0); - capn_write1(p.p, 2, s->leadVisible != 0); - capn_write16(p.p, 2, (uint16_t) (s->visualAlert)); - capn_write16(p.p, 8, (uint16_t) (s->audibleAlert)); -} -void cereal_get_CarControl_HUDControl(struct cereal_CarControl_HUDControl *s, cereal_CarControl_HUDControl_list l, int i) { - cereal_CarControl_HUDControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_CarControl_HUDControl(s, p); -} -void cereal_set_CarControl_HUDControl(const struct cereal_CarControl_HUDControl *s, cereal_CarControl_HUDControl_list l, int i) { - cereal_CarControl_HUDControl_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_CarControl_HUDControl(s, p); -} diff --git a/cereal/gen/c/car.capnp.h b/cereal/gen/c/car.capnp.h deleted file mode 100644 index 0a9b010af0..0000000000 --- a/cereal/gen/c/car.capnp.h +++ /dev/null @@ -1,287 +0,0 @@ -#ifndef CAPN_8E2AF1E78AF8B8D -#define CAPN_8E2AF1E78AF8B8D -/* 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_CarState; -struct cereal_CarState_WheelSpeeds; -struct cereal_CarState_CruiseState; -struct cereal_CarState_ButtonEvent; -struct cereal_RadarState; -struct cereal_RadarState_RadarPoint; -struct cereal_CarControl; -struct cereal_CarControl_CruiseControl; -struct cereal_CarControl_HUDControl; - -typedef struct {capn_ptr p;} cereal_CarState_ptr; -typedef struct {capn_ptr p;} cereal_CarState_WheelSpeeds_ptr; -typedef struct {capn_ptr p;} cereal_CarState_CruiseState_ptr; -typedef struct {capn_ptr p;} cereal_CarState_ButtonEvent_ptr; -typedef struct {capn_ptr p;} cereal_RadarState_ptr; -typedef struct {capn_ptr p;} cereal_RadarState_RadarPoint_ptr; -typedef struct {capn_ptr p;} cereal_CarControl_ptr; -typedef struct {capn_ptr p;} cereal_CarControl_CruiseControl_ptr; -typedef struct {capn_ptr p;} cereal_CarControl_HUDControl_ptr; - -typedef struct {capn_ptr p;} cereal_CarState_list; -typedef struct {capn_ptr p;} cereal_CarState_WheelSpeeds_list; -typedef struct {capn_ptr p;} cereal_CarState_CruiseState_list; -typedef struct {capn_ptr p;} cereal_CarState_ButtonEvent_list; -typedef struct {capn_ptr p;} cereal_RadarState_list; -typedef struct {capn_ptr p;} cereal_RadarState_RadarPoint_list; -typedef struct {capn_ptr p;} cereal_CarControl_list; -typedef struct {capn_ptr p;} cereal_CarControl_CruiseControl_list; -typedef struct {capn_ptr p;} cereal_CarControl_HUDControl_list; - -enum cereal_CarState_Error { - cereal_CarState_Error_commIssue = 0, - cereal_CarState_Error_steerUnavailable = 1, - cereal_CarState_Error_brakeUnavailable = 2, - cereal_CarState_Error_gasUnavailable = 3, - cereal_CarState_Error_wrongGear = 4, - cereal_CarState_Error_doorOpen = 5, - cereal_CarState_Error_seatbeltNotLatched = 6, - cereal_CarState_Error_espDisabled = 7, - cereal_CarState_Error_wrongCarMode = 8, - cereal_CarState_Error_steerTemporarilyUnavailable = 9, - cereal_CarState_Error_reverseGear = 10 -}; - -enum cereal_CarState_ButtonEvent_Type { - cereal_CarState_ButtonEvent_Type_unknown = 0, - cereal_CarState_ButtonEvent_Type_leftBlinker = 1, - cereal_CarState_ButtonEvent_Type_rightBlinker = 2, - cereal_CarState_ButtonEvent_Type_accelCruise = 3, - cereal_CarState_ButtonEvent_Type_decelCruise = 4, - cereal_CarState_ButtonEvent_Type_cancel = 5, - cereal_CarState_ButtonEvent_Type_altButton1 = 6, - cereal_CarState_ButtonEvent_Type_altButton2 = 7, - cereal_CarState_ButtonEvent_Type_altButton3 = 8 -}; - -enum cereal_RadarState_Error { - cereal_RadarState_Error_notValid = 0 -}; - -enum cereal_CarControl_HUDControl_VisualAlert { - cereal_CarControl_HUDControl_VisualAlert_none = 0, - cereal_CarControl_HUDControl_VisualAlert_fcw = 1, - cereal_CarControl_HUDControl_VisualAlert_steerRequired = 2, - cereal_CarControl_HUDControl_VisualAlert_brakePressed = 3, - cereal_CarControl_HUDControl_VisualAlert_wrongGear = 4, - cereal_CarControl_HUDControl_VisualAlert_seatbeltUnbuckled = 5, - cereal_CarControl_HUDControl_VisualAlert_speedTooHigh = 6 -}; - -enum cereal_CarControl_HUDControl_AudibleAlert { - cereal_CarControl_HUDControl_AudibleAlert_none = 0, - cereal_CarControl_HUDControl_AudibleAlert_beepSingle = 1, - cereal_CarControl_HUDControl_AudibleAlert_beepTriple = 2, - cereal_CarControl_HUDControl_AudibleAlert_beepRepeated = 3, - cereal_CarControl_HUDControl_AudibleAlert_chimeSingle = 4, - cereal_CarControl_HUDControl_AudibleAlert_chimeDouble = 5, - cereal_CarControl_HUDControl_AudibleAlert_chimeRepeated = 6, - cereal_CarControl_HUDControl_AudibleAlert_chimeContinuous = 7 -}; - -struct cereal_CarState { - capn_list16 errors; - float vEgo; - cereal_CarState_WheelSpeeds_ptr wheelSpeeds; - float gas; - unsigned gasPressed : 1; - float brake; - unsigned brakePressed : 1; - float steeringAngle; - float steeringTorque; - unsigned steeringPressed : 1; - cereal_CarState_CruiseState_ptr cruiseState; - cereal_CarState_ButtonEvent_list buttonEvents; - capn_list64 canMonoTimes; -}; - -static const size_t cereal_CarState_word_count = 3; - -static const size_t cereal_CarState_pointer_count = 5; - -static const size_t cereal_CarState_struct_bytes_count = 64; - -struct cereal_CarState_WheelSpeeds { - float fl; - float fr; - float rl; - float rr; -}; - -static const size_t cereal_CarState_WheelSpeeds_word_count = 2; - -static const size_t cereal_CarState_WheelSpeeds_pointer_count = 0; - -static const size_t cereal_CarState_WheelSpeeds_struct_bytes_count = 16; - -struct cereal_CarState_CruiseState { - unsigned enabled : 1; - float speed; -}; - -static const size_t cereal_CarState_CruiseState_word_count = 1; - -static const size_t cereal_CarState_CruiseState_pointer_count = 0; - -static const size_t cereal_CarState_CruiseState_struct_bytes_count = 8; - -struct cereal_CarState_ButtonEvent { - unsigned pressed : 1; - enum cereal_CarState_ButtonEvent_Type type; -}; - -static const size_t cereal_CarState_ButtonEvent_word_count = 1; - -static const size_t cereal_CarState_ButtonEvent_pointer_count = 0; - -static const size_t cereal_CarState_ButtonEvent_struct_bytes_count = 8; - -struct cereal_RadarState { - capn_list16 errors; - cereal_RadarState_RadarPoint_list points; - capn_list64 canMonoTimes; -}; - -static const size_t cereal_RadarState_word_count = 0; - -static const size_t cereal_RadarState_pointer_count = 3; - -static const size_t cereal_RadarState_struct_bytes_count = 24; - -struct cereal_RadarState_RadarPoint { - uint64_t trackId; - float dRel; - float yRel; - float vRel; - float aRel; - float yvRel; -}; - -static const size_t cereal_RadarState_RadarPoint_word_count = 4; - -static const size_t cereal_RadarState_RadarPoint_pointer_count = 0; - -static const size_t cereal_RadarState_RadarPoint_struct_bytes_count = 32; - -struct cereal_CarControl { - unsigned enabled : 1; - float gas; - float brake; - float steeringTorque; - cereal_CarControl_CruiseControl_ptr cruiseControl; - cereal_CarControl_HUDControl_ptr hudControl; -}; - -static const size_t cereal_CarControl_word_count = 2; - -static const size_t cereal_CarControl_pointer_count = 2; - -static const size_t cereal_CarControl_struct_bytes_count = 32; - -struct cereal_CarControl_CruiseControl { - unsigned cancel : 1; - unsigned override : 1; - float speedOverride; - float accelOverride; -}; - -static const size_t cereal_CarControl_CruiseControl_word_count = 2; - -static const size_t cereal_CarControl_CruiseControl_pointer_count = 0; - -static const size_t cereal_CarControl_CruiseControl_struct_bytes_count = 16; - -struct cereal_CarControl_HUDControl { - unsigned speedVisible : 1; - float setSpeed; - unsigned lanesVisible : 1; - unsigned leadVisible : 1; - enum cereal_CarControl_HUDControl_VisualAlert visualAlert; - enum cereal_CarControl_HUDControl_AudibleAlert audibleAlert; -}; - -static const size_t cereal_CarControl_HUDControl_word_count = 2; - -static const size_t cereal_CarControl_HUDControl_pointer_count = 0; - -static const size_t cereal_CarControl_HUDControl_struct_bytes_count = 16; - -cereal_CarState_ptr cereal_new_CarState(struct capn_segment*); -cereal_CarState_WheelSpeeds_ptr cereal_new_CarState_WheelSpeeds(struct capn_segment*); -cereal_CarState_CruiseState_ptr cereal_new_CarState_CruiseState(struct capn_segment*); -cereal_CarState_ButtonEvent_ptr cereal_new_CarState_ButtonEvent(struct capn_segment*); -cereal_RadarState_ptr cereal_new_RadarState(struct capn_segment*); -cereal_RadarState_RadarPoint_ptr cereal_new_RadarState_RadarPoint(struct capn_segment*); -cereal_CarControl_ptr cereal_new_CarControl(struct capn_segment*); -cereal_CarControl_CruiseControl_ptr cereal_new_CarControl_CruiseControl(struct capn_segment*); -cereal_CarControl_HUDControl_ptr cereal_new_CarControl_HUDControl(struct capn_segment*); - -cereal_CarState_list cereal_new_CarState_list(struct capn_segment*, int len); -cereal_CarState_WheelSpeeds_list cereal_new_CarState_WheelSpeeds_list(struct capn_segment*, int len); -cereal_CarState_CruiseState_list cereal_new_CarState_CruiseState_list(struct capn_segment*, int len); -cereal_CarState_ButtonEvent_list cereal_new_CarState_ButtonEvent_list(struct capn_segment*, int len); -cereal_RadarState_list cereal_new_RadarState_list(struct capn_segment*, int len); -cereal_RadarState_RadarPoint_list cereal_new_RadarState_RadarPoint_list(struct capn_segment*, int len); -cereal_CarControl_list cereal_new_CarControl_list(struct capn_segment*, int len); -cereal_CarControl_CruiseControl_list cereal_new_CarControl_CruiseControl_list(struct capn_segment*, int len); -cereal_CarControl_HUDControl_list cereal_new_CarControl_HUDControl_list(struct capn_segment*, int len); - -void cereal_read_CarState(struct cereal_CarState*, cereal_CarState_ptr); -void cereal_read_CarState_WheelSpeeds(struct cereal_CarState_WheelSpeeds*, cereal_CarState_WheelSpeeds_ptr); -void cereal_read_CarState_CruiseState(struct cereal_CarState_CruiseState*, cereal_CarState_CruiseState_ptr); -void cereal_read_CarState_ButtonEvent(struct cereal_CarState_ButtonEvent*, cereal_CarState_ButtonEvent_ptr); -void cereal_read_RadarState(struct cereal_RadarState*, cereal_RadarState_ptr); -void cereal_read_RadarState_RadarPoint(struct cereal_RadarState_RadarPoint*, cereal_RadarState_RadarPoint_ptr); -void cereal_read_CarControl(struct cereal_CarControl*, cereal_CarControl_ptr); -void cereal_read_CarControl_CruiseControl(struct cereal_CarControl_CruiseControl*, cereal_CarControl_CruiseControl_ptr); -void cereal_read_CarControl_HUDControl(struct cereal_CarControl_HUDControl*, cereal_CarControl_HUDControl_ptr); - -void cereal_write_CarState(const struct cereal_CarState*, cereal_CarState_ptr); -void cereal_write_CarState_WheelSpeeds(const struct cereal_CarState_WheelSpeeds*, cereal_CarState_WheelSpeeds_ptr); -void cereal_write_CarState_CruiseState(const struct cereal_CarState_CruiseState*, cereal_CarState_CruiseState_ptr); -void cereal_write_CarState_ButtonEvent(const struct cereal_CarState_ButtonEvent*, cereal_CarState_ButtonEvent_ptr); -void cereal_write_RadarState(const struct cereal_RadarState*, cereal_RadarState_ptr); -void cereal_write_RadarState_RadarPoint(const struct cereal_RadarState_RadarPoint*, cereal_RadarState_RadarPoint_ptr); -void cereal_write_CarControl(const struct cereal_CarControl*, cereal_CarControl_ptr); -void cereal_write_CarControl_CruiseControl(const struct cereal_CarControl_CruiseControl*, cereal_CarControl_CruiseControl_ptr); -void cereal_write_CarControl_HUDControl(const struct cereal_CarControl_HUDControl*, cereal_CarControl_HUDControl_ptr); - -void cereal_get_CarState(struct cereal_CarState*, cereal_CarState_list, int i); -void cereal_get_CarState_WheelSpeeds(struct cereal_CarState_WheelSpeeds*, cereal_CarState_WheelSpeeds_list, int i); -void cereal_get_CarState_CruiseState(struct cereal_CarState_CruiseState*, cereal_CarState_CruiseState_list, int i); -void cereal_get_CarState_ButtonEvent(struct cereal_CarState_ButtonEvent*, cereal_CarState_ButtonEvent_list, int i); -void cereal_get_RadarState(struct cereal_RadarState*, cereal_RadarState_list, int i); -void cereal_get_RadarState_RadarPoint(struct cereal_RadarState_RadarPoint*, cereal_RadarState_RadarPoint_list, int i); -void cereal_get_CarControl(struct cereal_CarControl*, cereal_CarControl_list, int i); -void cereal_get_CarControl_CruiseControl(struct cereal_CarControl_CruiseControl*, cereal_CarControl_CruiseControl_list, int i); -void cereal_get_CarControl_HUDControl(struct cereal_CarControl_HUDControl*, cereal_CarControl_HUDControl_list, int i); - -void cereal_set_CarState(const struct cereal_CarState*, cereal_CarState_list, int i); -void cereal_set_CarState_WheelSpeeds(const struct cereal_CarState_WheelSpeeds*, cereal_CarState_WheelSpeeds_list, int i); -void cereal_set_CarState_CruiseState(const struct cereal_CarState_CruiseState*, cereal_CarState_CruiseState_list, int i); -void cereal_set_CarState_ButtonEvent(const struct cereal_CarState_ButtonEvent*, cereal_CarState_ButtonEvent_list, int i); -void cereal_set_RadarState(const struct cereal_RadarState*, cereal_RadarState_list, int i); -void cereal_set_RadarState_RadarPoint(const struct cereal_RadarState_RadarPoint*, cereal_RadarState_RadarPoint_list, int i); -void cereal_set_CarControl(const struct cereal_CarControl*, cereal_CarControl_list, int i); -void cereal_set_CarControl_CruiseControl(const struct cereal_CarControl_CruiseControl*, cereal_CarControl_CruiseControl_list, int i); -void cereal_set_CarControl_HUDControl(const struct cereal_CarControl_HUDControl*, cereal_CarControl_HUDControl_list, int i); - -#ifdef __cplusplus -} -#endif -#endif diff --git a/cereal/gen/c/log.capnp.c b/cereal/gen/c/log.capnp.c deleted file mode 100644 index 1ae7c2c567..0000000000 --- a/cereal/gen/c/log.capnp.c +++ /dev/null @@ -1,1075 +0,0 @@ -#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; - } - s->source = (enum cereal_SensorEventData_SensorSource)(int) capn_read16(p.p, 14); -} -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; - } - capn_write16(p.p, 14, (uint16_t) (s->source)); -} -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_GpsLocationData_ptr cereal_new_GpsLocationData(struct capn_segment *s) { - cereal_GpsLocationData_ptr p; - p.p = capn_new_struct(s, 48, 0); - return p; -} -cereal_GpsLocationData_list cereal_new_GpsLocationData_list(struct capn_segment *s, int len) { - cereal_GpsLocationData_list p; - p.p = capn_new_list(s, len, 48, 0); - return p; -} -void cereal_read_GpsLocationData(struct cereal_GpsLocationData *s, cereal_GpsLocationData_ptr p) { - capn_resolve(&p.p); - s->flags = capn_read16(p.p, 0); - s->latitude = capn_to_f64(capn_read64(p.p, 8)); - s->longitude = capn_to_f64(capn_read64(p.p, 16)); - s->altitude = capn_to_f64(capn_read64(p.p, 24)); - s->speed = capn_to_f32(capn_read32(p.p, 4)); - s->bearing = capn_to_f32(capn_read32(p.p, 32)); - s->accuracy = capn_to_f32(capn_read32(p.p, 36)); - s->timestamp = (int64_t) ((int64_t)(capn_read64(p.p, 40))); -} -void cereal_write_GpsLocationData(const struct cereal_GpsLocationData *s, cereal_GpsLocationData_ptr p) { - capn_resolve(&p.p); - capn_write16(p.p, 0, s->flags); - capn_write64(p.p, 8, capn_from_f64(s->latitude)); - capn_write64(p.p, 16, capn_from_f64(s->longitude)); - capn_write64(p.p, 24, capn_from_f64(s->altitude)); - capn_write32(p.p, 4, capn_from_f32(s->speed)); - capn_write32(p.p, 32, capn_from_f32(s->bearing)); - capn_write32(p.p, 36, capn_from_f32(s->accuracy)); - capn_write64(p.p, 40, (uint64_t) (s->timestamp)); -} -void cereal_get_GpsLocationData(struct cereal_GpsLocationData *s, cereal_GpsLocationData_list l, int i) { - cereal_GpsLocationData_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_read_GpsLocationData(s, p); -} -void cereal_set_GpsLocationData(const struct cereal_GpsLocationData *s, cereal_GpsLocationData_list l, int i) { - cereal_GpsLocationData_ptr p; - p.p = capn_getp(l.p, i, 0); - cereal_write_GpsLocationData(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, 24, 1); - 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, 24, 1); - 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); - s->freeSpace = capn_to_f32(capn_read32(p.p, 16)); - s->batteryPercent = (int16_t) ((int16_t)capn_read16(p.p, 20)); - s->batteryStatus = capn_get_text(p.p, 0, capn_val0); -} -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); - capn_write32(p.p, 16, capn_from_f32(s->freeSpace)); - capn_write16(p.p, 20, (uint16_t) (s->batteryPercent)); - capn_set_text(p.p, 0, s->batteryStatus); -} -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; - s->startedSignalDetected = (capn_read8(p.p, 8) & 8) != 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); - capn_write1(p.p, 67, s->startedSignalDetected != 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->warpMatrixDEPRECATED.p = capn_getp(p.p, 0, 0); - s->angleOffsetDEPRECATED = capn_to_f32(capn_read32(p.p, 0)); - s->calStatusDEPRECATED = (int8_t) ((int8_t)capn_read8(p.p, 4)); - s->calCycleDEPRECATED = (int32_t) ((int32_t)capn_read32(p.p, 12)); - s->calPercDEPRECATED = (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->warpMatrixDEPRECATED.p); - capn_write32(p.p, 0, capn_from_f32(s->angleOffsetDEPRECATED)); - capn_write8(p.p, 4, (uint8_t) (s->calStatusDEPRECATED)); - capn_write32(p.p, 12, (uint32_t) (s->calCycleDEPRECATED)); - capn_write8(p.p, 5, (uint8_t) (s->calPercDEPRECATED)); - 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->aEgoDEPRECATED = 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->hudLeadDEPRECATED = (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->aEgoDEPRECATED)); - 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->hudLeadDEPRECATED)); - 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: - case cereal_Event_gpsLocation: - case cereal_Event_carState: - case cereal_Event_carControl: - s->carControl.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: - case cereal_Event_gpsLocation: - case cereal_Event_carState: - case cereal_Event_carControl: - capn_setp(p.p, 0, s->carControl.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 deleted file mode 100644 index 9b365fdde1..0000000000 --- a/cereal/gen/c/log.capnp.h +++ /dev/null @@ -1,712 +0,0 @@ -#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" -#include "car.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_GpsLocationData; -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_GpsLocationData_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_GpsLocationData_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_SensorEventData_SensorSource { - cereal_SensorEventData_SensorSource_android = 0, - cereal_SensorEventData_SensorSource_iOS = 1, - cereal_SensorEventData_SensorSource_fiber = 2, - cereal_SensorEventData_SensorSource_velodyne = 3 -}; - -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; - }; - enum cereal_SensorEventData_SensorSource source; -}; - -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_GpsLocationData { - uint16_t flags; - double latitude; - double longitude; - double altitude; - float speed; - float bearing; - float accuracy; - int64_t timestamp; -}; - -static const size_t cereal_GpsLocationData_word_count = 6; - -static const size_t cereal_GpsLocationData_pointer_count = 0; - -static const size_t cereal_GpsLocationData_struct_bytes_count = 48; - -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; - float freeSpace; - int16_t batteryPercent; - capn_text batteryStatus; -}; - -static const size_t cereal_ThermalData_word_count = 3; - -static const size_t cereal_ThermalData_pointer_count = 1; - -static const size_t cereal_ThermalData_struct_bytes_count = 32; - -struct cereal_HealthData { - uint32_t voltage; - uint32_t current; - unsigned started : 1; - unsigned controlsAllowed : 1; - unsigned gasInterceptorDetected : 1; - unsigned startedSignalDetected : 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 warpMatrixDEPRECATED; - float angleOffsetDEPRECATED; - int8_t calStatusDEPRECATED; - int32_t calCycleDEPRECATED; - int8_t calPercDEPRECATED; - 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 aEgoDEPRECATED; - 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 hudLeadDEPRECATED; - 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, - cereal_Event_gpsLocation = 20, - cereal_Event_carState = 21, - cereal_Event_carControl = 22 -}; - -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; - cereal_GpsLocationData_ptr gpsLocation; - cereal_CarState_ptr carState; - cereal_CarControl_ptr carControl; - }; -}; - -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_GpsLocationData_ptr cereal_new_GpsLocationData(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_GpsLocationData_list cereal_new_GpsLocationData_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_GpsLocationData(struct cereal_GpsLocationData*, cereal_GpsLocationData_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_GpsLocationData(const struct cereal_GpsLocationData*, cereal_GpsLocationData_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_GpsLocationData(struct cereal_GpsLocationData*, cereal_GpsLocationData_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_GpsLocationData(const struct cereal_GpsLocationData*, cereal_GpsLocationData_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/car.capnp.c++ b/cereal/gen/cpp/car.capnp.c++ deleted file mode 100644 index 10ccef31af..0000000000 --- a/cereal/gen/cpp/car.capnp.c++ +++ /dev/null @@ -1,1504 +0,0 @@ -// Generated by Cap'n Proto compiler, DO NOT EDIT -// source: car.capnp - -#include "car.capnp.h" - -namespace capnp { -namespace schemas { -static const ::capnp::_::AlignedData<248> b_9da4fa09e052903c = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 60, 144, 82, 224, 9, 250, 164, 157, - 10, 0, 0, 0, 1, 0, 3, 0, - 141, 139, 175, 8, 231, 241, 42, 142, - 5, 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, 71, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 85, 0, 0, 0, 223, 2, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 1, 0, 1, 0, - 163, 53, 89, 21, 166, 55, 26, 153, - 25, 0, 0, 0, 98, 0, 0, 0, - 175, 96, 110, 142, 71, 129, 78, 230, - 25, 0, 0, 0, 98, 0, 0, 0, - 222, 39, 247, 5, 213, 197, 168, 186, - 25, 0, 0, 0, 50, 0, 0, 0, - 246, 206, 74, 91, 131, 166, 92, 255, - 21, 0, 0, 0, 98, 0, 0, 0, - 87, 104, 101, 101, 108, 83, 112, 101, - 101, 100, 115, 0, 0, 0, 0, 0, - 67, 114, 117, 105, 115, 101, 83, 116, - 97, 116, 101, 0, 0, 0, 0, 0, - 69, 114, 114, 111, 114, 0, 0, 0, - 66, 117, 116, 116, 111, 110, 69, 118, - 101, 110, 116, 0, 0, 0, 0, 0, - 52, 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, - 93, 1, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 88, 1, 0, 0, 3, 0, 1, 0, - 116, 1, 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, - 113, 1, 0, 0, 42, 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, - 2, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 117, 1, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 1, 0, 0, 3, 0, 1, 0, - 128, 1, 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, - 125, 1, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 1, 0, 0, 3, 0, 1, 0, - 132, 1, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 64, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 129, 1, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 1, 0, 0, 3, 0, 1, 0, - 140, 1, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 137, 1, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 1, 0, 0, 3, 0, 1, 0, - 144, 1, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 65, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 1, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 1, 0, 0, 3, 0, 1, 0, - 152, 1, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 1, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 148, 1, 0, 0, 3, 0, 1, 0, - 160, 1, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 1, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 1, 0, 0, 3, 0, 1, 0, - 168, 1, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 1, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 1, 0, 0, 3, 0, 1, 0, - 176, 1, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 1, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 1, 0, 0, 3, 0, 1, 0, - 184, 1, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 181, 1, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 180, 1, 0, 0, 3, 0, 1, 0, - 208, 1, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 205, 1, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 1, 0, 0, 3, 0, 1, 0, - 232, 1, 0, 0, 2, 0, 1, 0, - 101, 114, 114, 111, 114, 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, - 15, 0, 0, 0, 0, 0, 0, 0, - 222, 39, 247, 5, 213, 197, 168, 186, - 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, 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, - 119, 104, 101, 101, 108, 83, 112, 101, - 101, 100, 115, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 163, 53, 89, 21, 166, 55, 26, 153, - 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, 97, 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, - 103, 97, 115, 80, 114, 101, 115, 115, - 101, 100, 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, - 98, 114, 97, 107, 101, 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, - 98, 114, 97, 107, 101, 80, 114, 101, - 115, 115, 101, 100, 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, 101, 101, 114, 105, 110, 103, - 65, 110, 103, 108, 101, 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, 101, 101, 114, 105, 110, 103, - 84, 111, 114, 113, 117, 101, 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, 101, 101, 114, 105, 110, 103, - 80, 114, 101, 115, 115, 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, 114, 117, 105, 115, 101, 83, 116, - 97, 116, 101, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 175, 96, 110, 142, 71, 129, 78, 230, - 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, - 98, 117, 116, 116, 111, 110, 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, - 246, 206, 74, 91, 131, 166, 92, 255, - 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, 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_9da4fa09e052903c = b_9da4fa09e052903c.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_9da4fa09e052903c[] = { - &s_991a37a6155935a3, - &s_baa8c5d505f727de, - &s_e64e81478e6e60af, - &s_ff5ca6835b4acef6, -}; -static const uint16_t m_9da4fa09e052903c[] = {5, 6, 11, 12, 10, 0, 3, 4, 7, 9, 8, 1, 2}; -static const uint16_t i_9da4fa09e052903c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; -const ::capnp::_::RawSchema s_9da4fa09e052903c = { - 0x9da4fa09e052903c, b_9da4fa09e052903c.words, 248, d_9da4fa09e052903c, m_9da4fa09e052903c, - 4, 13, i_9da4fa09e052903c, nullptr, nullptr, { &s_9da4fa09e052903c, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<78> b_991a37a6155935a3 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 163, 53, 89, 21, 166, 55, 26, 153, - 19, 0, 0, 0, 1, 0, 2, 0, - 60, 144, 82, 224, 9, 250, 164, 157, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 250, 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, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 46, 87, 104, 101, 101, 108, - 83, 112, 101, 101, 100, 115, 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, 26, 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, 1, 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, - 108, 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, - 105, 0, 0, 0, 26, 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, 3, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 26, 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, - 102, 108, 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, - 102, 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, - 114, 108, 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, - 114, 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, } -}; -::capnp::word const* const bp_991a37a6155935a3 = b_991a37a6155935a3.words; -#if !CAPNP_LITE -static const uint16_t m_991a37a6155935a3[] = {0, 1, 2, 3}; -static const uint16_t i_991a37a6155935a3[] = {0, 1, 2, 3}; -const ::capnp::_::RawSchema s_991a37a6155935a3 = { - 0x991a37a6155935a3, b_991a37a6155935a3.words, 78, nullptr, m_991a37a6155935a3, - 0, 4, i_991a37a6155935a3, nullptr, nullptr, { &s_991a37a6155935a3, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<48> b_e64e81478e6e60af = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 175, 96, 110, 142, 71, 129, 78, 230, - 19, 0, 0, 0, 1, 0, 1, 0, - 60, 144, 82, 224, 9, 250, 164, 157, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 250, 0, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 119, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 46, 67, 114, 117, 105, 115, - 101, 83, 116, 97, 116, 101, 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, 66, 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, 1, 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, - 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, 112, 101, 101, 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, } -}; -::capnp::word const* const bp_e64e81478e6e60af = b_e64e81478e6e60af.words; -#if !CAPNP_LITE -static const uint16_t m_e64e81478e6e60af[] = {0, 1}; -static const uint16_t i_e64e81478e6e60af[] = {0, 1}; -const ::capnp::_::RawSchema s_e64e81478e6e60af = { - 0xe64e81478e6e60af, b_e64e81478e6e60af.words, 48, nullptr, m_e64e81478e6e60af, - 0, 2, i_e64e81478e6e60af, nullptr, nullptr, { &s_e64e81478e6e60af, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<78> b_baa8c5d505f727de = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 222, 39, 247, 5, 213, 197, 168, 186, - 19, 0, 0, 0, 2, 0, 0, 0, - 60, 144, 82, 224, 9, 250, 164, 157, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 202, 0, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 15, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 46, 69, 114, 114, 111, 114, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 44, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 0, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 121, 0, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 121, 0, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 121, 0, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 117, 0, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 113, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 7, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 0, 0, 0, 0, 0, 0, 0, - 105, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 9, 0, 0, 0, 0, 0, 0, 0, - 101, 0, 0, 0, 226, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 105, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 111, 109, 109, 73, 115, 115, 117, - 101, 0, 0, 0, 0, 0, 0, 0, - 115, 116, 101, 101, 114, 85, 110, 97, - 118, 97, 105, 108, 97, 98, 108, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 98, 114, 97, 107, 101, 85, 110, 97, - 118, 97, 105, 108, 97, 98, 108, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 103, 97, 115, 85, 110, 97, 118, 97, - 105, 108, 97, 98, 108, 101, 0, 0, - 119, 114, 111, 110, 103, 71, 101, 97, - 114, 0, 0, 0, 0, 0, 0, 0, - 100, 111, 111, 114, 79, 112, 101, 110, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 101, 97, 116, 98, 101, 108, 116, - 78, 111, 116, 76, 97, 116, 99, 104, - 101, 100, 0, 0, 0, 0, 0, 0, - 101, 115, 112, 68, 105, 115, 97, 98, - 108, 101, 100, 0, 0, 0, 0, 0, - 119, 114, 111, 110, 103, 67, 97, 114, - 77, 111, 100, 101, 0, 0, 0, 0, - 115, 116, 101, 101, 114, 84, 101, 109, - 112, 111, 114, 97, 114, 105, 108, 121, - 85, 110, 97, 118, 97, 105, 108, 97, - 98, 108, 101, 0, 0, 0, 0, 0, - 114, 101, 118, 101, 114, 115, 101, 71, - 101, 97, 114, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_baa8c5d505f727de = b_baa8c5d505f727de.words; -#if !CAPNP_LITE -static const uint16_t m_baa8c5d505f727de[] = {2, 0, 5, 7, 3, 10, 6, 9, 1, 8, 4}; -const ::capnp::_::RawSchema s_baa8c5d505f727de = { - 0xbaa8c5d505f727de, b_baa8c5d505f727de.words, 78, nullptr, m_baa8c5d505f727de, - 0, 11, nullptr, nullptr, nullptr, { &s_baa8c5d505f727de, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(Error_baa8c5d505f727de, baa8c5d505f727de); -static const ::capnp::_::AlignedData<51> b_ff5ca6835b4acef6 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 246, 206, 74, 91, 131, 166, 92, 255, - 19, 0, 0, 0, 1, 0, 1, 0, - 60, 144, 82, 224, 9, 250, 164, 157, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 250, 0, 0, 0, - 33, 0, 0, 0, 23, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 119, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 46, 66, 117, 116, 116, 111, - 110, 69, 118, 101, 110, 116, 0, 0, - 4, 0, 0, 0, 1, 0, 1, 0, - 124, 113, 20, 84, 32, 0, 97, 225, - 1, 0, 0, 0, 42, 0, 0, 0, - 84, 121, 112, 101, 0, 0, 0, 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, 66, 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, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 0, 0, 0, 42, 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, - 112, 114, 101, 115, 115, 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, - 116, 121, 112, 101, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 124, 113, 20, 84, 32, 0, 97, 225, - 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, } -}; -::capnp::word const* const bp_ff5ca6835b4acef6 = b_ff5ca6835b4acef6.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_ff5ca6835b4acef6[] = { - &s_e16100205414717c, -}; -static const uint16_t m_ff5ca6835b4acef6[] = {0, 1}; -static const uint16_t i_ff5ca6835b4acef6[] = {0, 1}; -const ::capnp::_::RawSchema s_ff5ca6835b4acef6 = { - 0xff5ca6835b4acef6, b_ff5ca6835b4acef6.words, 51, d_ff5ca6835b4acef6, m_ff5ca6835b4acef6, - 1, 2, i_ff5ca6835b4acef6, nullptr, nullptr, { &s_ff5ca6835b4acef6, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<62> b_e16100205414717c = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 124, 113, 20, 84, 32, 0, 97, 225, - 31, 0, 0, 0, 2, 0, 0, 0, - 246, 206, 74, 91, 131, 166, 92, 255, - 0, 0, 0, 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, 223, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 83, 116, 97, - 116, 101, 46, 66, 117, 116, 116, 111, - 110, 69, 118, 101, 110, 116, 46, 84, - 121, 112, 101, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 36, 0, 0, 0, 1, 0, 2, 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, - 1, 0, 0, 0, 0, 0, 0, 0, - 93, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 85, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 81, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 77, 0, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 69, 0, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 7, 0, 0, 0, 0, 0, 0, 0, - 65, 0, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 117, 110, 107, 110, 111, 119, 110, 0, - 108, 101, 102, 116, 66, 108, 105, 110, - 107, 101, 114, 0, 0, 0, 0, 0, - 114, 105, 103, 104, 116, 66, 108, 105, - 110, 107, 101, 114, 0, 0, 0, 0, - 97, 99, 99, 101, 108, 67, 114, 117, - 105, 115, 101, 0, 0, 0, 0, 0, - 100, 101, 99, 101, 108, 67, 114, 117, - 105, 115, 101, 0, 0, 0, 0, 0, - 99, 97, 110, 99, 101, 108, 0, 0, - 97, 108, 116, 66, 117, 116, 116, 111, - 110, 49, 0, 0, 0, 0, 0, 0, - 97, 108, 116, 66, 117, 116, 116, 111, - 110, 50, 0, 0, 0, 0, 0, 0, - 97, 108, 116, 66, 117, 116, 116, 111, - 110, 51, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_e16100205414717c = b_e16100205414717c.words; -#if !CAPNP_LITE -static const uint16_t m_e16100205414717c[] = {3, 6, 7, 8, 5, 4, 1, 2, 0}; -const ::capnp::_::RawSchema s_e16100205414717c = { - 0xe16100205414717c, b_e16100205414717c.words, 62, nullptr, m_e16100205414717c, - 0, 9, nullptr, nullptr, nullptr, { &s_e16100205414717c, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(Type_e16100205414717c, e16100205414717c); -static const ::capnp::_::AlignedData<82> b_888ad6581cf0aacb = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 203, 170, 240, 28, 88, 214, 138, 136, - 10, 0, 0, 0, 1, 0, 0, 0, - 141, 139, 175, 8, 231, 241, 42, 142, - 3, 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, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 0, 0, 0, 175, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 82, 97, 100, 97, 114, 83, - 116, 97, 116, 101, 0, 0, 0, 0, - 8, 0, 0, 0, 1, 0, 1, 0, - 173, 118, 186, 235, 121, 102, 168, 232, - 9, 0, 0, 0, 50, 0, 0, 0, - 54, 223, 31, 172, 235, 51, 243, 143, - 5, 0, 0, 0, 90, 0, 0, 0, - 69, 114, 114, 111, 114, 0, 0, 0, - 82, 97, 100, 97, 114, 80, 111, 105, - 110, 116, 0, 0, 0, 0, 0, 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, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 84, 0, 0, 0, 3, 0, 1, 0, - 112, 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, - 109, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 0, 0, 0, 3, 0, 1, 0, - 136, 0, 0, 0, 2, 0, 1, 0, - 101, 114, 114, 111, 114, 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, - 15, 0, 0, 0, 0, 0, 0, 0, - 173, 118, 186, 235, 121, 102, 168, 232, - 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, 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, - 16, 0, 0, 0, 0, 0, 0, 0, - 54, 223, 31, 172, 235, 51, 243, 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, - 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_888ad6581cf0aacb = b_888ad6581cf0aacb.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_888ad6581cf0aacb[] = { - &s_8ff333ebac1fdf36, - &s_e8a86679ebba76ad, -}; -static const uint16_t m_888ad6581cf0aacb[] = {2, 0, 1}; -static const uint16_t i_888ad6581cf0aacb[] = {0, 1, 2}; -const ::capnp::_::RawSchema s_888ad6581cf0aacb = { - 0x888ad6581cf0aacb, b_888ad6581cf0aacb.words, 82, d_888ad6581cf0aacb, m_888ad6581cf0aacb, - 2, 3, i_888ad6581cf0aacb, nullptr, nullptr, { &s_888ad6581cf0aacb, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<23> b_e8a86679ebba76ad = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 173, 118, 186, 235, 121, 102, 168, 232, - 21, 0, 0, 0, 2, 0, 0, 0, - 203, 170, 240, 28, 88, 214, 138, 136, - 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, 31, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 82, 97, 100, 97, 114, 83, - 116, 97, 116, 101, 46, 69, 114, 114, - 111, 114, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 4, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 110, 111, 116, 86, 97, 108, 105, 100, - 0, 0, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_e8a86679ebba76ad = b_e8a86679ebba76ad.words; -#if !CAPNP_LITE -static const uint16_t m_e8a86679ebba76ad[] = {0}; -const ::capnp::_::RawSchema s_e8a86679ebba76ad = { - 0xe8a86679ebba76ad, b_e8a86679ebba76ad.words, 23, nullptr, m_e8a86679ebba76ad, - 0, 1, nullptr, nullptr, nullptr, { &s_e8a86679ebba76ad, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(Error_e8a86679ebba76ad, e8a86679ebba76ad); -static const ::capnp::_::AlignedData<108> b_8ff333ebac1fdf36 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 54, 223, 31, 172, 235, 51, 243, 143, - 21, 0, 0, 0, 1, 0, 4, 0, - 203, 170, 240, 28, 88, 214, 138, 136, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 2, 1, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 87, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 82, 97, 100, 97, 114, 83, - 116, 97, 116, 101, 46, 82, 97, 100, - 97, 114, 80, 111, 105, 110, 116, 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, 2, 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, 3, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 161, 0, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 0, 0, 0, 3, 0, 1, 0, - 168, 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, - 165, 0, 0, 0, 42, 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, - 4, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 0, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 0, 0, 0, 3, 0, 1, 0, - 176, 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, - 173, 0, 0, 0, 50, 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, - 116, 114, 97, 99, 107, 73, 100, 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, - 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, - 121, 118, 82, 101, 108, 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_8ff333ebac1fdf36 = b_8ff333ebac1fdf36.words; -#if !CAPNP_LITE -static const uint16_t m_8ff333ebac1fdf36[] = {4, 1, 0, 3, 2, 5}; -static const uint16_t i_8ff333ebac1fdf36[] = {0, 1, 2, 3, 4, 5}; -const ::capnp::_::RawSchema s_8ff333ebac1fdf36 = { - 0x8ff333ebac1fdf36, b_8ff333ebac1fdf36.words, 108, nullptr, m_8ff333ebac1fdf36, - 0, 6, i_8ff333ebac1fdf36, nullptr, nullptr, { &s_8ff333ebac1fdf36, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<118> b_f78829049ab814af = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 175, 20, 184, 154, 4, 41, 136, 247, - 10, 0, 0, 0, 1, 0, 2, 0, - 141, 139, 175, 8, 231, 241, 42, 142, - 2, 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, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 57, 0, 0, 0, 87, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 67, 111, 110, - 116, 114, 111, 108, 0, 0, 0, 0, - 8, 0, 0, 0, 1, 0, 1, 0, - 211, 168, 11, 14, 110, 56, 14, 178, - 9, 0, 0, 0, 114, 0, 0, 0, - 56, 58, 176, 78, 124, 200, 149, 216, - 9, 0, 0, 0, 90, 0, 0, 0, - 67, 114, 117, 105, 115, 101, 67, 111, - 110, 116, 114, 111, 108, 0, 0, 0, - 72, 85, 68, 67, 111, 110, 116, 114, - 111, 108, 0, 0, 0, 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, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 0, 0, 0, 34, 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, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 0, 0, 0, 3, 0, 1, 0, - 168, 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, - 165, 0, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 0, 0, 0, 3, 0, 1, 0, - 176, 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, - 173, 0, 0, 0, 114, 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, 1, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 181, 0, 0, 0, 90, 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, - 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, - 103, 97, 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, - 98, 114, 97, 107, 101, 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, 101, 101, 114, 105, 110, 103, - 84, 111, 114, 113, 117, 101, 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, 114, 117, 105, 115, 101, 67, 111, - 110, 116, 114, 111, 108, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 211, 168, 11, 14, 110, 56, 14, 178, - 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, - 104, 117, 100, 67, 111, 110, 116, 114, - 111, 108, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 56, 58, 176, 78, 124, 200, 149, 216, - 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_f78829049ab814af = b_f78829049ab814af.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_f78829049ab814af[] = { - &s_b20e386e0e0ba8d3, - &s_d895c87c4eb03a38, -}; -static const uint16_t m_f78829049ab814af[] = {2, 4, 0, 1, 5, 3}; -static const uint16_t i_f78829049ab814af[] = {0, 1, 2, 3, 4, 5}; -const ::capnp::_::RawSchema s_f78829049ab814af = { - 0xf78829049ab814af, b_f78829049ab814af.words, 118, d_f78829049ab814af, m_f78829049ab814af, - 2, 6, i_f78829049ab814af, nullptr, nullptr, { &s_f78829049ab814af, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<82> b_b20e386e0e0ba8d3 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 211, 168, 11, 14, 110, 56, 14, 178, - 21, 0, 0, 0, 1, 0, 2, 0, - 175, 20, 184, 154, 4, 41, 136, 247, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 26, 1, 0, 0, - 37, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 231, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 67, 111, 110, - 116, 114, 111, 108, 46, 67, 114, 117, - 105, 115, 101, 67, 111, 110, 116, 114, - 111, 108, 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, 58, 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, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 0, 0, 0, 74, 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, - 2, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 0, 0, 0, 3, 0, 1, 0, - 120, 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, - 117, 0, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 0, 0, 0, 3, 0, 1, 0, - 128, 0, 0, 0, 2, 0, 1, 0, - 99, 97, 110, 99, 101, 108, 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, 118, 101, 114, 114, 105, 100, 101, - 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, - 115, 112, 101, 101, 100, 79, 118, 101, - 114, 114, 105, 100, 101, 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, 99, 99, 101, 108, 79, 118, 101, - 114, 114, 105, 100, 101, 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_b20e386e0e0ba8d3 = b_b20e386e0e0ba8d3.words; -#if !CAPNP_LITE -static const uint16_t m_b20e386e0e0ba8d3[] = {3, 0, 1, 2}; -static const uint16_t i_b20e386e0e0ba8d3[] = {0, 1, 2, 3}; -const ::capnp::_::RawSchema s_b20e386e0e0ba8d3 = { - 0xb20e386e0e0ba8d3, b_b20e386e0e0ba8d3.words, 82, nullptr, m_b20e386e0e0ba8d3, - 0, 4, i_b20e386e0e0ba8d3, nullptr, nullptr, { &s_b20e386e0e0ba8d3, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<122> b_d895c87c4eb03a38 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 56, 58, 176, 78, 124, 200, 149, 216, - 21, 0, 0, 0, 1, 0, 2, 0, - 175, 20, 184, 154, 4, 41, 136, 247, - 0, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 2, 1, 0, 0, - 33, 0, 0, 0, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 87, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 67, 111, 110, - 116, 114, 111, 108, 46, 72, 85, 68, - 67, 111, 110, 116, 114, 111, 108, 0, - 8, 0, 0, 0, 1, 0, 1, 0, - 212, 23, 110, 97, 132, 142, 215, 144, - 9, 0, 0, 0, 98, 0, 0, 0, - 158, 51, 78, 149, 108, 226, 165, 245, - 9, 0, 0, 0, 106, 0, 0, 0, - 86, 105, 115, 117, 97, 108, 65, 108, - 101, 114, 116, 0, 0, 0, 0, 0, - 65, 117, 100, 105, 98, 108, 101, 65, - 108, 101, 114, 116, 0, 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, 106, 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, - 1, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 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, - 2, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 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, - 3, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 177, 0, 0, 0, 98, 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, - 4, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 0, 0, 0, 98, 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, - 5, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 5, 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, - 115, 112, 101, 101, 100, 86, 105, 115, - 105, 98, 108, 101, 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, 101, 116, 83, 112, 101, 101, 100, - 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, - 108, 97, 110, 101, 115, 86, 105, 115, - 105, 98, 108, 101, 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, - 108, 101, 97, 100, 86, 105, 115, 105, - 98, 108, 101, 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, - 118, 105, 115, 117, 97, 108, 65, 108, - 101, 114, 116, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 212, 23, 110, 97, 132, 142, 215, 144, - 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, - 97, 117, 100, 105, 98, 108, 101, 65, - 108, 101, 114, 116, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 158, 51, 78, 149, 108, 226, 165, 245, - 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, } -}; -::capnp::word const* const bp_d895c87c4eb03a38 = b_d895c87c4eb03a38.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_d895c87c4eb03a38[] = { - &s_90d78e84616e17d4, - &s_f5a5e26c954e339e, -}; -static const uint16_t m_d895c87c4eb03a38[] = {5, 2, 3, 1, 0, 4}; -static const uint16_t i_d895c87c4eb03a38[] = {0, 1, 2, 3, 4, 5}; -const ::capnp::_::RawSchema s_d895c87c4eb03a38 = { - 0xd895c87c4eb03a38, b_d895c87c4eb03a38.words, 122, d_d895c87c4eb03a38, m_d895c87c4eb03a38, - 2, 6, i_d895c87c4eb03a38, nullptr, nullptr, { &s_d895c87c4eb03a38, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<54> b_90d78e84616e17d4 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 212, 23, 110, 97, 132, 142, 215, 144, - 32, 0, 0, 0, 2, 0, 0, 0, - 56, 58, 176, 78, 124, 200, 149, 216, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 98, 1, 0, 0, - 41, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 175, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 67, 111, 110, - 116, 114, 111, 108, 46, 72, 85, 68, - 67, 111, 110, 116, 114, 111, 108, 46, - 86, 105, 115, 117, 97, 108, 65, 108, - 101, 114, 116, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 28, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 0, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 69, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 57, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 53, 0, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 49, 0, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 49, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 110, 111, 110, 101, 0, 0, 0, 0, - 102, 99, 119, 0, 0, 0, 0, 0, - 115, 116, 101, 101, 114, 82, 101, 113, - 117, 105, 114, 101, 100, 0, 0, 0, - 98, 114, 97, 107, 101, 80, 114, 101, - 115, 115, 101, 100, 0, 0, 0, 0, - 119, 114, 111, 110, 103, 71, 101, 97, - 114, 0, 0, 0, 0, 0, 0, 0, - 115, 101, 97, 116, 98, 101, 108, 116, - 85, 110, 98, 117, 99, 107, 108, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 84, 111, 111, - 72, 105, 103, 104, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_90d78e84616e17d4 = b_90d78e84616e17d4.words; -#if !CAPNP_LITE -static const uint16_t m_90d78e84616e17d4[] = {3, 1, 0, 5, 6, 2, 4}; -const ::capnp::_::RawSchema s_90d78e84616e17d4 = { - 0x90d78e84616e17d4, b_90d78e84616e17d4.words, 54, nullptr, m_90d78e84616e17d4, - 0, 7, nullptr, nullptr, nullptr, { &s_90d78e84616e17d4, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(VisualAlert_90d78e84616e17d4, 90d78e84616e17d4); -static const ::capnp::_::AlignedData<59> b_f5a5e26c954e339e = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 158, 51, 78, 149, 108, 226, 165, 245, - 32, 0, 0, 0, 2, 0, 0, 0, - 56, 58, 176, 78, 124, 200, 149, 216, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 106, 1, 0, 0, - 41, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 199, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 67, 111, 110, - 116, 114, 111, 108, 46, 72, 85, 68, - 67, 111, 110, 116, 114, 111, 108, 46, - 65, 117, 100, 105, 98, 108, 101, 65, - 108, 101, 114, 116, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 32, 0, 0, 0, 1, 0, 2, 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, - 1, 0, 0, 0, 0, 0, 0, 0, - 81, 0, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 77, 0, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 73, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 69, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 65, 0, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 7, 0, 0, 0, 0, 0, 0, 0, - 57, 0, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 110, 111, 110, 101, 0, 0, 0, 0, - 98, 101, 101, 112, 83, 105, 110, 103, - 108, 101, 0, 0, 0, 0, 0, 0, - 98, 101, 101, 112, 84, 114, 105, 112, - 108, 101, 0, 0, 0, 0, 0, 0, - 98, 101, 101, 112, 82, 101, 112, 101, - 97, 116, 101, 100, 0, 0, 0, 0, - 99, 104, 105, 109, 101, 83, 105, 110, - 103, 108, 101, 0, 0, 0, 0, 0, - 99, 104, 105, 109, 101, 68, 111, 117, - 98, 108, 101, 0, 0, 0, 0, 0, - 99, 104, 105, 109, 101, 82, 101, 112, - 101, 97, 116, 101, 100, 0, 0, 0, - 99, 104, 105, 109, 101, 67, 111, 110, - 116, 105, 110, 117, 111, 117, 115, 0, } -}; -::capnp::word const* const bp_f5a5e26c954e339e = b_f5a5e26c954e339e.words; -#if !CAPNP_LITE -static const uint16_t m_f5a5e26c954e339e[] = {3, 1, 2, 7, 5, 6, 4, 0}; -const ::capnp::_::RawSchema s_f5a5e26c954e339e = { - 0xf5a5e26c954e339e, b_f5a5e26c954e339e.words, 59, nullptr, m_f5a5e26c954e339e, - 0, 8, nullptr, nullptr, nullptr, { &s_f5a5e26c954e339e, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(AudibleAlert_f5a5e26c954e339e, f5a5e26c954e339e); -} // namespace schemas -} // namespace capnp - -// ======================================================================================= - -namespace cereal { - -// CarState -#ifndef _MSC_VER -constexpr uint16_t CarState::_capnpPrivate::dataWordSize; -constexpr uint16_t CarState::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarState::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarState::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarState::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarState::WheelSpeeds -#ifndef _MSC_VER -constexpr uint16_t CarState::WheelSpeeds::_capnpPrivate::dataWordSize; -constexpr uint16_t CarState::WheelSpeeds::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarState::WheelSpeeds::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarState::WheelSpeeds::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarState::WheelSpeeds::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarState::CruiseState -#ifndef _MSC_VER -constexpr uint16_t CarState::CruiseState::_capnpPrivate::dataWordSize; -constexpr uint16_t CarState::CruiseState::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarState::CruiseState::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarState::CruiseState::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarState::CruiseState::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarState::ButtonEvent -#ifndef _MSC_VER -constexpr uint16_t CarState::ButtonEvent::_capnpPrivate::dataWordSize; -constexpr uint16_t CarState::ButtonEvent::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarState::ButtonEvent::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarState::ButtonEvent::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarState::ButtonEvent::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// RadarState -#ifndef _MSC_VER -constexpr uint16_t RadarState::_capnpPrivate::dataWordSize; -constexpr uint16_t RadarState::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind RadarState::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* RadarState::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* RadarState::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// RadarState::RadarPoint -#ifndef _MSC_VER -constexpr uint16_t RadarState::RadarPoint::_capnpPrivate::dataWordSize; -constexpr uint16_t RadarState::RadarPoint::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind RadarState::RadarPoint::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* RadarState::RadarPoint::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* RadarState::RadarPoint::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarControl -#ifndef _MSC_VER -constexpr uint16_t CarControl::_capnpPrivate::dataWordSize; -constexpr uint16_t CarControl::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarControl::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarControl::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarControl::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarControl::CruiseControl -#ifndef _MSC_VER -constexpr uint16_t CarControl::CruiseControl::_capnpPrivate::dataWordSize; -constexpr uint16_t CarControl::CruiseControl::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarControl::CruiseControl::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarControl::CruiseControl::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarControl::CruiseControl::_capnpPrivate::brand; -#endif // !CAPNP_LITE - -// CarControl::HUDControl -#ifndef _MSC_VER -constexpr uint16_t CarControl::HUDControl::_capnpPrivate::dataWordSize; -constexpr uint16_t CarControl::HUDControl::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind CarControl::HUDControl::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarControl::HUDControl::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* CarControl::HUDControl::_capnpPrivate::brand; -#endif // !CAPNP_LITE - - -} // namespace - diff --git a/cereal/gen/cpp/car.capnp.h b/cereal/gen/cpp/car.capnp.h deleted file mode 100644 index 5f7cf8d6de..0000000000 --- a/cereal/gen/cpp/car.capnp.h +++ /dev/null @@ -1,2032 +0,0 @@ -// Generated by Cap'n Proto compiler, DO NOT EDIT -// source: car.capnp - -#ifndef CAPNP_INCLUDED_8e2af1e708af8b8d_ -#define CAPNP_INCLUDED_8e2af1e708af8b8d_ - -#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(9da4fa09e052903c); -CAPNP_DECLARE_SCHEMA(991a37a6155935a3); -CAPNP_DECLARE_SCHEMA(e64e81478e6e60af); -CAPNP_DECLARE_SCHEMA(baa8c5d505f727de); -enum class Error_baa8c5d505f727de: uint16_t { - COMM_ISSUE, - STEER_UNAVAILABLE, - BRAKE_UNAVAILABLE, - GAS_UNAVAILABLE, - WRONG_GEAR, - DOOR_OPEN, - SEATBELT_NOT_LATCHED, - ESP_DISABLED, - WRONG_CAR_MODE, - STEER_TEMPORARILY_UNAVAILABLE, - REVERSE_GEAR, -}; -CAPNP_DECLARE_ENUM(Error, baa8c5d505f727de); -CAPNP_DECLARE_SCHEMA(ff5ca6835b4acef6); -CAPNP_DECLARE_SCHEMA(e16100205414717c); -enum class Type_e16100205414717c: uint16_t { - UNKNOWN, - LEFT_BLINKER, - RIGHT_BLINKER, - ACCEL_CRUISE, - DECEL_CRUISE, - CANCEL, - ALT_BUTTON1, - ALT_BUTTON2, - ALT_BUTTON3, -}; -CAPNP_DECLARE_ENUM(Type, e16100205414717c); -CAPNP_DECLARE_SCHEMA(888ad6581cf0aacb); -CAPNP_DECLARE_SCHEMA(e8a86679ebba76ad); -enum class Error_e8a86679ebba76ad: uint16_t { - NOT_VALID, -}; -CAPNP_DECLARE_ENUM(Error, e8a86679ebba76ad); -CAPNP_DECLARE_SCHEMA(8ff333ebac1fdf36); -CAPNP_DECLARE_SCHEMA(f78829049ab814af); -CAPNP_DECLARE_SCHEMA(b20e386e0e0ba8d3); -CAPNP_DECLARE_SCHEMA(d895c87c4eb03a38); -CAPNP_DECLARE_SCHEMA(90d78e84616e17d4); -enum class VisualAlert_90d78e84616e17d4: uint16_t { - NONE, - FCW, - STEER_REQUIRED, - BRAKE_PRESSED, - WRONG_GEAR, - SEATBELT_UNBUCKLED, - SPEED_TOO_HIGH, -}; -CAPNP_DECLARE_ENUM(VisualAlert, 90d78e84616e17d4); -CAPNP_DECLARE_SCHEMA(f5a5e26c954e339e); -enum class AudibleAlert_f5a5e26c954e339e: uint16_t { - NONE, - BEEP_SINGLE, - BEEP_TRIPLE, - BEEP_REPEATED, - CHIME_SINGLE, - CHIME_DOUBLE, - CHIME_REPEATED, - CHIME_CONTINUOUS, -}; -CAPNP_DECLARE_ENUM(AudibleAlert, f5a5e26c954e339e); - -} // namespace schemas -} // namespace capnp - -namespace cereal { - -struct CarState { - CarState() = delete; - - class Reader; - class Builder; - class Pipeline; - struct WheelSpeeds; - struct CruiseState; - typedef ::capnp::schemas::Error_baa8c5d505f727de Error; - - struct ButtonEvent; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(9da4fa09e052903c, 3, 5) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarState::WheelSpeeds { - WheelSpeeds() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(991a37a6155935a3, 2, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarState::CruiseState { - CruiseState() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(e64e81478e6e60af, 1, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarState::ButtonEvent { - ButtonEvent() = delete; - - class Reader; - class Builder; - class Pipeline; - typedef ::capnp::schemas::Type_e16100205414717c Type; - - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(ff5ca6835b4acef6, 1, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct RadarState { - RadarState() = delete; - - class Reader; - class Builder; - class Pipeline; - typedef ::capnp::schemas::Error_e8a86679ebba76ad Error; - - struct RadarPoint; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(888ad6581cf0aacb, 0, 3) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct RadarState::RadarPoint { - RadarPoint() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(8ff333ebac1fdf36, 4, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarControl { - CarControl() = delete; - - class Reader; - class Builder; - class Pipeline; - struct CruiseControl; - struct HUDControl; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(f78829049ab814af, 2, 2) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarControl::CruiseControl { - CruiseControl() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(b20e386e0e0ba8d3, 2, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -struct CarControl::HUDControl { - HUDControl() = delete; - - class Reader; - class Builder; - class Pipeline; - typedef ::capnp::schemas::VisualAlert_90d78e84616e17d4 VisualAlert; - - typedef ::capnp::schemas::AudibleAlert_f5a5e26c954e339e AudibleAlert; - - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(d895c87c4eb03a38, 2, 0) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; - #endif // !CAPNP_LITE - }; -}; - -// ======================================================================================= - -class CarState::Reader { -public: - typedef CarState 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 hasErrors() const; - inline ::capnp::List< ::cereal::CarState::Error>::Reader getErrors() const; - - inline float getVEgo() const; - - inline bool hasWheelSpeeds() const; - inline ::cereal::CarState::WheelSpeeds::Reader getWheelSpeeds() const; - - inline float getGas() const; - - inline bool getGasPressed() const; - - inline float getBrake() const; - - inline bool getBrakePressed() const; - - inline float getSteeringAngle() const; - - inline float getSteeringTorque() const; - - inline bool getSteeringPressed() const; - - inline bool hasCruiseState() const; - inline ::cereal::CarState::CruiseState::Reader getCruiseState() const; - - inline bool hasButtonEvents() const; - inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Reader getButtonEvents() 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 CarState::Builder { -public: - typedef CarState 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 hasErrors(); - inline ::capnp::List< ::cereal::CarState::Error>::Builder getErrors(); - inline void setErrors( ::capnp::List< ::cereal::CarState::Error>::Reader value); - inline void setErrors(::kj::ArrayPtr value); - inline ::capnp::List< ::cereal::CarState::Error>::Builder initErrors(unsigned int size); - inline void adoptErrors(::capnp::Orphan< ::capnp::List< ::cereal::CarState::Error>>&& value); - inline ::capnp::Orphan< ::capnp::List< ::cereal::CarState::Error>> disownErrors(); - - inline float getVEgo(); - inline void setVEgo(float value); - - inline bool hasWheelSpeeds(); - inline ::cereal::CarState::WheelSpeeds::Builder getWheelSpeeds(); - inline void setWheelSpeeds( ::cereal::CarState::WheelSpeeds::Reader value); - inline ::cereal::CarState::WheelSpeeds::Builder initWheelSpeeds(); - inline void adoptWheelSpeeds(::capnp::Orphan< ::cereal::CarState::WheelSpeeds>&& value); - inline ::capnp::Orphan< ::cereal::CarState::WheelSpeeds> disownWheelSpeeds(); - - inline float getGas(); - inline void setGas(float value); - - inline bool getGasPressed(); - inline void setGasPressed(bool value); - - inline float getBrake(); - inline void setBrake(float value); - - inline bool getBrakePressed(); - inline void setBrakePressed(bool value); - - inline float getSteeringAngle(); - inline void setSteeringAngle(float value); - - inline float getSteeringTorque(); - inline void setSteeringTorque(float value); - - inline bool getSteeringPressed(); - inline void setSteeringPressed(bool value); - - inline bool hasCruiseState(); - inline ::cereal::CarState::CruiseState::Builder getCruiseState(); - inline void setCruiseState( ::cereal::CarState::CruiseState::Reader value); - inline ::cereal::CarState::CruiseState::Builder initCruiseState(); - inline void adoptCruiseState(::capnp::Orphan< ::cereal::CarState::CruiseState>&& value); - inline ::capnp::Orphan< ::cereal::CarState::CruiseState> disownCruiseState(); - - inline bool hasButtonEvents(); - inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Builder getButtonEvents(); - inline void setButtonEvents( ::capnp::List< ::cereal::CarState::ButtonEvent>::Reader value); - inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Builder initButtonEvents(unsigned int size); - inline void adoptButtonEvents(::capnp::Orphan< ::capnp::List< ::cereal::CarState::ButtonEvent>>&& value); - inline ::capnp::Orphan< ::capnp::List< ::cereal::CarState::ButtonEvent>> disownButtonEvents(); - - 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 CarState::Pipeline { -public: - typedef CarState Pipelines; - - inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} - inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) - : _typeless(kj::mv(typeless)) {} - - inline ::cereal::CarState::WheelSpeeds::Pipeline getWheelSpeeds(); - inline ::cereal::CarState::CruiseState::Pipeline getCruiseState(); -private: - ::capnp::AnyPointer::Pipeline _typeless; - friend class ::capnp::PipelineHook; - template - friend struct ::capnp::ToDynamic_; -}; -#endif // !CAPNP_LITE - -class CarState::WheelSpeeds::Reader { -public: - typedef WheelSpeeds 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 getFl() const; - - inline float getFr() const; - - inline float getRl() const; - - inline float getRr() 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 CarState::WheelSpeeds::Builder { -public: - typedef WheelSpeeds 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 getFl(); - inline void setFl(float value); - - inline float getFr(); - inline void setFr(float value); - - inline float getRl(); - inline void setRl(float value); - - inline float getRr(); - inline void setRr(float value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarState::WheelSpeeds::Pipeline { -public: - typedef WheelSpeeds 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 CarState::CruiseState::Reader { -public: - typedef CruiseState 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 getEnabled() const; - - inline float getSpeed() 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 CarState::CruiseState::Builder { -public: - typedef CruiseState 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 getEnabled(); - inline void setEnabled(bool value); - - inline float getSpeed(); - inline void setSpeed(float value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarState::CruiseState::Pipeline { -public: - typedef CruiseState 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 CarState::ButtonEvent::Reader { -public: - typedef ButtonEvent 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 getPressed() const; - - inline ::cereal::CarState::ButtonEvent::Type getType() 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 CarState::ButtonEvent::Builder { -public: - typedef ButtonEvent 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 getPressed(); - inline void setPressed(bool value); - - inline ::cereal::CarState::ButtonEvent::Type getType(); - inline void setType( ::cereal::CarState::ButtonEvent::Type value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarState::ButtonEvent::Pipeline { -public: - typedef ButtonEvent 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 RadarState::Reader { -public: - typedef RadarState 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 hasErrors() const; - inline ::capnp::List< ::cereal::RadarState::Error>::Reader getErrors() const; - - inline bool hasPoints() const; - inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Reader getPoints() 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 RadarState::Builder { -public: - typedef RadarState 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 hasErrors(); - inline ::capnp::List< ::cereal::RadarState::Error>::Builder getErrors(); - inline void setErrors( ::capnp::List< ::cereal::RadarState::Error>::Reader value); - inline void setErrors(::kj::ArrayPtr value); - inline ::capnp::List< ::cereal::RadarState::Error>::Builder initErrors(unsigned int size); - inline void adoptErrors(::capnp::Orphan< ::capnp::List< ::cereal::RadarState::Error>>&& value); - inline ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::Error>> disownErrors(); - - inline bool hasPoints(); - inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Builder getPoints(); - inline void setPoints( ::capnp::List< ::cereal::RadarState::RadarPoint>::Reader value); - inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Builder initPoints(unsigned int size); - inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::cereal::RadarState::RadarPoint>>&& value); - inline ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::RadarPoint>> disownPoints(); - - 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 RadarState::Pipeline { -public: - typedef RadarState 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 RadarState::RadarPoint::Reader { -public: - typedef RadarPoint 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 ::uint64_t getTrackId() const; - - inline float getDRel() const; - - inline float getYRel() const; - - inline float getVRel() const; - - inline float getARel() const; - - inline float getYvRel() 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 RadarState::RadarPoint::Builder { -public: - typedef RadarPoint 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 ::uint64_t getTrackId(); - inline void setTrackId( ::uint64_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 getYvRel(); - inline void setYvRel(float value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class RadarState::RadarPoint::Pipeline { -public: - typedef RadarPoint 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 CarControl::Reader { -public: - typedef CarControl 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 getEnabled() const; - - inline float getGas() const; - - inline float getBrake() const; - - inline float getSteeringTorque() const; - - inline bool hasCruiseControl() const; - inline ::cereal::CarControl::CruiseControl::Reader getCruiseControl() const; - - inline bool hasHudControl() const; - inline ::cereal::CarControl::HUDControl::Reader getHudControl() 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 CarControl::Builder { -public: - typedef CarControl 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 getEnabled(); - inline void setEnabled(bool value); - - inline float getGas(); - inline void setGas(float value); - - inline float getBrake(); - inline void setBrake(float value); - - inline float getSteeringTorque(); - inline void setSteeringTorque(float value); - - inline bool hasCruiseControl(); - inline ::cereal::CarControl::CruiseControl::Builder getCruiseControl(); - inline void setCruiseControl( ::cereal::CarControl::CruiseControl::Reader value); - inline ::cereal::CarControl::CruiseControl::Builder initCruiseControl(); - inline void adoptCruiseControl(::capnp::Orphan< ::cereal::CarControl::CruiseControl>&& value); - inline ::capnp::Orphan< ::cereal::CarControl::CruiseControl> disownCruiseControl(); - - inline bool hasHudControl(); - inline ::cereal::CarControl::HUDControl::Builder getHudControl(); - inline void setHudControl( ::cereal::CarControl::HUDControl::Reader value); - inline ::cereal::CarControl::HUDControl::Builder initHudControl(); - inline void adoptHudControl(::capnp::Orphan< ::cereal::CarControl::HUDControl>&& value); - inline ::capnp::Orphan< ::cereal::CarControl::HUDControl> disownHudControl(); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarControl::Pipeline { -public: - typedef CarControl Pipelines; - - inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} - inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) - : _typeless(kj::mv(typeless)) {} - - inline ::cereal::CarControl::CruiseControl::Pipeline getCruiseControl(); - inline ::cereal::CarControl::HUDControl::Pipeline getHudControl(); -private: - ::capnp::AnyPointer::Pipeline _typeless; - friend class ::capnp::PipelineHook; - template - friend struct ::capnp::ToDynamic_; -}; -#endif // !CAPNP_LITE - -class CarControl::CruiseControl::Reader { -public: - typedef CruiseControl 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 getCancel() const; - - inline bool getOverride() const; - - inline float getSpeedOverride() const; - - inline float getAccelOverride() 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 CarControl::CruiseControl::Builder { -public: - typedef CruiseControl 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 getCancel(); - inline void setCancel(bool value); - - inline bool getOverride(); - inline void setOverride(bool value); - - inline float getSpeedOverride(); - inline void setSpeedOverride(float value); - - inline float getAccelOverride(); - inline void setAccelOverride(float value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarControl::CruiseControl::Pipeline { -public: - typedef CruiseControl 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 CarControl::HUDControl::Reader { -public: - typedef HUDControl 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 getSpeedVisible() const; - - inline float getSetSpeed() const; - - inline bool getLanesVisible() const; - - inline bool getLeadVisible() const; - - inline ::cereal::CarControl::HUDControl::VisualAlert getVisualAlert() const; - - inline ::cereal::CarControl::HUDControl::AudibleAlert getAudibleAlert() 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 CarControl::HUDControl::Builder { -public: - typedef HUDControl 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 getSpeedVisible(); - inline void setSpeedVisible(bool value); - - inline float getSetSpeed(); - inline void setSetSpeed(float value); - - inline bool getLanesVisible(); - inline void setLanesVisible(bool value); - - inline bool getLeadVisible(); - inline void setLeadVisible(bool value); - - inline ::cereal::CarControl::HUDControl::VisualAlert getVisualAlert(); - inline void setVisualAlert( ::cereal::CarControl::HUDControl::VisualAlert value); - - inline ::cereal::CarControl::HUDControl::AudibleAlert getAudibleAlert(); - inline void setAudibleAlert( ::cereal::CarControl::HUDControl::AudibleAlert value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarControl::HUDControl::Pipeline { -public: - typedef HUDControl 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 CarState::Reader::hasErrors() const { - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool CarState::Builder::hasErrors() { - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::cereal::CarState::Error>::Reader CarState::Reader::getErrors() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::cereal::CarState::Error>::Builder CarState::Builder::getErrors() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void CarState::Builder::setErrors( ::capnp::List< ::cereal::CarState::Error>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline void CarState::Builder::setErrors(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::cereal::CarState::Error>::Builder CarState::Builder::initErrors(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::init( - _builder.getPointerField(0 * ::capnp::POINTERS), size); -} -inline void CarState::Builder::adoptErrors( - ::capnp::Orphan< ::capnp::List< ::cereal::CarState::Error>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::cereal::CarState::Error>> CarState::Builder::disownErrors() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::Error>>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline float CarState::Reader::getVEgo() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getVEgo() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setVEgo(float value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::Reader::hasWheelSpeeds() const { - return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline bool CarState::Builder::hasWheelSpeeds() { - return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarState::WheelSpeeds::Reader CarState::Reader::getWheelSpeeds() const { - return ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::get( - _reader.getPointerField(1 * ::capnp::POINTERS)); -} -inline ::cereal::CarState::WheelSpeeds::Builder CarState::Builder::getWheelSpeeds() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::get( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarState::WheelSpeeds::Pipeline CarState::Pipeline::getWheelSpeeds() { - return ::cereal::CarState::WheelSpeeds::Pipeline(_typeless.getPointerField(1)); -} -#endif // !CAPNP_LITE -inline void CarState::Builder::setWheelSpeeds( ::cereal::CarState::WheelSpeeds::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::set( - _builder.getPointerField(1 * ::capnp::POINTERS), value); -} -inline ::cereal::CarState::WheelSpeeds::Builder CarState::Builder::initWheelSpeeds() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::init( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} -inline void CarState::Builder::adoptWheelSpeeds( - ::capnp::Orphan< ::cereal::CarState::WheelSpeeds>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::adopt( - _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarState::WheelSpeeds> CarState::Builder::disownWheelSpeeds() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::WheelSpeeds>::disown( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} - -inline float CarState::Reader::getGas() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getGas() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setGas(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::Reader::getGasPressed() const { - return _reader.getDataField( - 64 * ::capnp::ELEMENTS); -} - -inline bool CarState::Builder::getGasPressed() { - return _builder.getDataField( - 64 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setGasPressed(bool value) { - _builder.setDataField( - 64 * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getBrake() const { - return _reader.getDataField( - 3 * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getBrake() { - return _builder.getDataField( - 3 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setBrake(float value) { - _builder.setDataField( - 3 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::Reader::getBrakePressed() const { - return _reader.getDataField( - 65 * ::capnp::ELEMENTS); -} - -inline bool CarState::Builder::getBrakePressed() { - return _builder.getDataField( - 65 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setBrakePressed(bool value) { - _builder.setDataField( - 65 * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getSteeringAngle() const { - return _reader.getDataField( - 4 * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getSteeringAngle() { - return _builder.getDataField( - 4 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setSteeringAngle(float value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getSteeringTorque() const { - return _reader.getDataField( - 5 * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getSteeringTorque() { - return _builder.getDataField( - 5 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setSteeringTorque(float value) { - _builder.setDataField( - 5 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::Reader::getSteeringPressed() const { - return _reader.getDataField( - 66 * ::capnp::ELEMENTS); -} - -inline bool CarState::Builder::getSteeringPressed() { - return _builder.getDataField( - 66 * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setSteeringPressed(bool value) { - _builder.setDataField( - 66 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::Reader::hasCruiseState() const { - return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); -} -inline bool CarState::Builder::hasCruiseState() { - return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarState::CruiseState::Reader CarState::Reader::getCruiseState() const { - return ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::get( - _reader.getPointerField(2 * ::capnp::POINTERS)); -} -inline ::cereal::CarState::CruiseState::Builder CarState::Builder::getCruiseState() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::get( - _builder.getPointerField(2 * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarState::CruiseState::Pipeline CarState::Pipeline::getCruiseState() { - return ::cereal::CarState::CruiseState::Pipeline(_typeless.getPointerField(2)); -} -#endif // !CAPNP_LITE -inline void CarState::Builder::setCruiseState( ::cereal::CarState::CruiseState::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::set( - _builder.getPointerField(2 * ::capnp::POINTERS), value); -} -inline ::cereal::CarState::CruiseState::Builder CarState::Builder::initCruiseState() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::init( - _builder.getPointerField(2 * ::capnp::POINTERS)); -} -inline void CarState::Builder::adoptCruiseState( - ::capnp::Orphan< ::cereal::CarState::CruiseState>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::adopt( - _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarState::CruiseState> CarState::Builder::disownCruiseState() { - return ::capnp::_::PointerHelpers< ::cereal::CarState::CruiseState>::disown( - _builder.getPointerField(2 * ::capnp::POINTERS)); -} - -inline bool CarState::Reader::hasButtonEvents() const { - return !_reader.getPointerField(3 * ::capnp::POINTERS).isNull(); -} -inline bool CarState::Builder::hasButtonEvents() { - return !_builder.getPointerField(3 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Reader CarState::Reader::getButtonEvents() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::get( - _reader.getPointerField(3 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Builder CarState::Builder::getButtonEvents() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::get( - _builder.getPointerField(3 * ::capnp::POINTERS)); -} -inline void CarState::Builder::setButtonEvents( ::capnp::List< ::cereal::CarState::ButtonEvent>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::set( - _builder.getPointerField(3 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::cereal::CarState::ButtonEvent>::Builder CarState::Builder::initButtonEvents(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::init( - _builder.getPointerField(3 * ::capnp::POINTERS), size); -} -inline void CarState::Builder::adoptButtonEvents( - ::capnp::Orphan< ::capnp::List< ::cereal::CarState::ButtonEvent>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::adopt( - _builder.getPointerField(3 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::cereal::CarState::ButtonEvent>> CarState::Builder::disownButtonEvents() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CarState::ButtonEvent>>::disown( - _builder.getPointerField(3 * ::capnp::POINTERS)); -} - -inline bool CarState::Reader::hasCanMonoTimes() const { - return !_reader.getPointerField(4 * ::capnp::POINTERS).isNull(); -} -inline bool CarState::Builder::hasCanMonoTimes() { - return !_builder.getPointerField(4 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::uint64_t>::Reader CarState::Reader::getCanMonoTimes() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( - _reader.getPointerField(4 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::uint64_t>::Builder CarState::Builder::getCanMonoTimes() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( - _builder.getPointerField(4 * ::capnp::POINTERS)); -} -inline void CarState::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( - _builder.getPointerField(4 * ::capnp::POINTERS), value); -} -inline void CarState::Builder::setCanMonoTimes(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( - _builder.getPointerField(4 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::uint64_t>::Builder CarState::Builder::initCanMonoTimes(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( - _builder.getPointerField(4 * ::capnp::POINTERS), size); -} -inline void CarState::Builder::adoptCanMonoTimes( - ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( - _builder.getPointerField(4 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> CarState::Builder::disownCanMonoTimes() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( - _builder.getPointerField(4 * ::capnp::POINTERS)); -} - -inline float CarState::WheelSpeeds::Reader::getFl() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline float CarState::WheelSpeeds::Builder::getFl() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarState::WheelSpeeds::Builder::setFl(float value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline float CarState::WheelSpeeds::Reader::getFr() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarState::WheelSpeeds::Builder::getFr() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarState::WheelSpeeds::Builder::setFr(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline float CarState::WheelSpeeds::Reader::getRl() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline float CarState::WheelSpeeds::Builder::getRl() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void CarState::WheelSpeeds::Builder::setRl(float value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline float CarState::WheelSpeeds::Reader::getRr() const { - return _reader.getDataField( - 3 * ::capnp::ELEMENTS); -} - -inline float CarState::WheelSpeeds::Builder::getRr() { - return _builder.getDataField( - 3 * ::capnp::ELEMENTS); -} -inline void CarState::WheelSpeeds::Builder::setRr(float value) { - _builder.setDataField( - 3 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::CruiseState::Reader::getEnabled() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline bool CarState::CruiseState::Builder::getEnabled() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarState::CruiseState::Builder::setEnabled(bool value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline float CarState::CruiseState::Reader::getSpeed() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarState::CruiseState::Builder::getSpeed() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarState::CruiseState::Builder::setSpeed(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline bool CarState::ButtonEvent::Reader::getPressed() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline bool CarState::ButtonEvent::Builder::getPressed() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarState::ButtonEvent::Builder::setPressed(bool value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline ::cereal::CarState::ButtonEvent::Type CarState::ButtonEvent::Reader::getType() const { - return _reader.getDataField< ::cereal::CarState::ButtonEvent::Type>( - 1 * ::capnp::ELEMENTS); -} - -inline ::cereal::CarState::ButtonEvent::Type CarState::ButtonEvent::Builder::getType() { - return _builder.getDataField< ::cereal::CarState::ButtonEvent::Type>( - 1 * ::capnp::ELEMENTS); -} -inline void CarState::ButtonEvent::Builder::setType( ::cereal::CarState::ButtonEvent::Type value) { - _builder.setDataField< ::cereal::CarState::ButtonEvent::Type>( - 1 * ::capnp::ELEMENTS, value); -} - -inline bool RadarState::Reader::hasErrors() const { - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool RadarState::Builder::hasErrors() { - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::cereal::RadarState::Error>::Reader RadarState::Reader::getErrors() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::cereal::RadarState::Error>::Builder RadarState::Builder::getErrors() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void RadarState::Builder::setErrors( ::capnp::List< ::cereal::RadarState::Error>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline void RadarState::Builder::setErrors(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::cereal::RadarState::Error>::Builder RadarState::Builder::initErrors(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::init( - _builder.getPointerField(0 * ::capnp::POINTERS), size); -} -inline void RadarState::Builder::adoptErrors( - ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::Error>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::Error>> RadarState::Builder::disownErrors() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::Error>>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline bool RadarState::Reader::hasPoints() const { - return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline bool RadarState::Builder::hasPoints() { - return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Reader RadarState::Reader::getPoints() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::get( - _reader.getPointerField(1 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Builder RadarState::Builder::getPoints() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::get( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} -inline void RadarState::Builder::setPoints( ::capnp::List< ::cereal::RadarState::RadarPoint>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::set( - _builder.getPointerField(1 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::cereal::RadarState::RadarPoint>::Builder RadarState::Builder::initPoints(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::init( - _builder.getPointerField(1 * ::capnp::POINTERS), size); -} -inline void RadarState::Builder::adoptPoints( - ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::RadarPoint>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::adopt( - _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::cereal::RadarState::RadarPoint>> RadarState::Builder::disownPoints() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::RadarState::RadarPoint>>::disown( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} - -inline bool RadarState::Reader::hasCanMonoTimes() const { - return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); -} -inline bool RadarState::Builder::hasCanMonoTimes() { - return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::uint64_t>::Reader RadarState::Reader::getCanMonoTimes() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( - _reader.getPointerField(2 * ::capnp::POINTERS)); -} -inline ::capnp::List< ::uint64_t>::Builder RadarState::Builder::getCanMonoTimes() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( - _builder.getPointerField(2 * ::capnp::POINTERS)); -} -inline void RadarState::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( - _builder.getPointerField(2 * ::capnp::POINTERS), value); -} -inline void RadarState::Builder::setCanMonoTimes(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( - _builder.getPointerField(2 * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::uint64_t>::Builder RadarState::Builder::initCanMonoTimes(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( - _builder.getPointerField(2 * ::capnp::POINTERS), size); -} -inline void RadarState::Builder::adoptCanMonoTimes( - ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( - _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> RadarState::Builder::disownCanMonoTimes() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( - _builder.getPointerField(2 * ::capnp::POINTERS)); -} - -inline ::uint64_t RadarState::RadarPoint::Reader::getTrackId() const { - return _reader.getDataField< ::uint64_t>( - 0 * ::capnp::ELEMENTS); -} - -inline ::uint64_t RadarState::RadarPoint::Builder::getTrackId() { - return _builder.getDataField< ::uint64_t>( - 0 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setTrackId( ::uint64_t value) { - _builder.setDataField< ::uint64_t>( - 0 * ::capnp::ELEMENTS, value); -} - -inline float RadarState::RadarPoint::Reader::getDRel() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline float RadarState::RadarPoint::Builder::getDRel() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setDRel(float value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline float RadarState::RadarPoint::Reader::getYRel() const { - return _reader.getDataField( - 3 * ::capnp::ELEMENTS); -} - -inline float RadarState::RadarPoint::Builder::getYRel() { - return _builder.getDataField( - 3 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setYRel(float value) { - _builder.setDataField( - 3 * ::capnp::ELEMENTS, value); -} - -inline float RadarState::RadarPoint::Reader::getVRel() const { - return _reader.getDataField( - 4 * ::capnp::ELEMENTS); -} - -inline float RadarState::RadarPoint::Builder::getVRel() { - return _builder.getDataField( - 4 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setVRel(float value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, value); -} - -inline float RadarState::RadarPoint::Reader::getARel() const { - return _reader.getDataField( - 5 * ::capnp::ELEMENTS); -} - -inline float RadarState::RadarPoint::Builder::getARel() { - return _builder.getDataField( - 5 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setARel(float value) { - _builder.setDataField( - 5 * ::capnp::ELEMENTS, value); -} - -inline float RadarState::RadarPoint::Reader::getYvRel() const { - return _reader.getDataField( - 6 * ::capnp::ELEMENTS); -} - -inline float RadarState::RadarPoint::Builder::getYvRel() { - return _builder.getDataField( - 6 * ::capnp::ELEMENTS); -} -inline void RadarState::RadarPoint::Builder::setYvRel(float value) { - _builder.setDataField( - 6 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::Reader::getEnabled() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline bool CarControl::Builder::getEnabled() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarControl::Builder::setEnabled(bool value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::Reader::getGas() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarControl::Builder::getGas() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::Builder::setGas(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::Reader::getBrake() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline float CarControl::Builder::getBrake() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void CarControl::Builder::setBrake(float value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::Reader::getSteeringTorque() const { - return _reader.getDataField( - 3 * ::capnp::ELEMENTS); -} - -inline float CarControl::Builder::getSteeringTorque() { - return _builder.getDataField( - 3 * ::capnp::ELEMENTS); -} -inline void CarControl::Builder::setSteeringTorque(float value) { - _builder.setDataField( - 3 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::Reader::hasCruiseControl() const { - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool CarControl::Builder::hasCruiseControl() { - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarControl::CruiseControl::Reader CarControl::Reader::getCruiseControl() const { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::cereal::CarControl::CruiseControl::Builder CarControl::Builder::getCruiseControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarControl::CruiseControl::Pipeline CarControl::Pipeline::getCruiseControl() { - return ::cereal::CarControl::CruiseControl::Pipeline(_typeless.getPointerField(0)); -} -#endif // !CAPNP_LITE -inline void CarControl::Builder::setCruiseControl( ::cereal::CarControl::CruiseControl::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::cereal::CarControl::CruiseControl::Builder CarControl::Builder::initCruiseControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::init( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void CarControl::Builder::adoptCruiseControl( - ::capnp::Orphan< ::cereal::CarControl::CruiseControl>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarControl::CruiseControl> CarControl::Builder::disownCruiseControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::CruiseControl>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline bool CarControl::Reader::hasHudControl() const { - return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline bool CarControl::Builder::hasHudControl() { - return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarControl::HUDControl::Reader CarControl::Reader::getHudControl() const { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::get( - _reader.getPointerField(1 * ::capnp::POINTERS)); -} -inline ::cereal::CarControl::HUDControl::Builder CarControl::Builder::getHudControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::get( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarControl::HUDControl::Pipeline CarControl::Pipeline::getHudControl() { - return ::cereal::CarControl::HUDControl::Pipeline(_typeless.getPointerField(1)); -} -#endif // !CAPNP_LITE -inline void CarControl::Builder::setHudControl( ::cereal::CarControl::HUDControl::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::set( - _builder.getPointerField(1 * ::capnp::POINTERS), value); -} -inline ::cereal::CarControl::HUDControl::Builder CarControl::Builder::initHudControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::init( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} -inline void CarControl::Builder::adoptHudControl( - ::capnp::Orphan< ::cereal::CarControl::HUDControl>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::adopt( - _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarControl::HUDControl> CarControl::Builder::disownHudControl() { - return ::capnp::_::PointerHelpers< ::cereal::CarControl::HUDControl>::disown( - _builder.getPointerField(1 * ::capnp::POINTERS)); -} - -inline bool CarControl::CruiseControl::Reader::getCancel() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline bool CarControl::CruiseControl::Builder::getCancel() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarControl::CruiseControl::Builder::setCancel(bool value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::CruiseControl::Reader::getOverride() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline bool CarControl::CruiseControl::Builder::getOverride() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::CruiseControl::Builder::setOverride(bool value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::CruiseControl::Reader::getSpeedOverride() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarControl::CruiseControl::Builder::getSpeedOverride() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::CruiseControl::Builder::setSpeedOverride(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::CruiseControl::Reader::getAccelOverride() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline float CarControl::CruiseControl::Builder::getAccelOverride() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void CarControl::CruiseControl::Builder::setAccelOverride(float value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::HUDControl::Reader::getSpeedVisible() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline bool CarControl::HUDControl::Builder::getSpeedVisible() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setSpeedVisible(bool value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline float CarControl::HUDControl::Reader::getSetSpeed() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float CarControl::HUDControl::Builder::getSetSpeed() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setSetSpeed(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::HUDControl::Reader::getLanesVisible() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline bool CarControl::HUDControl::Builder::getLanesVisible() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setLanesVisible(bool value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline bool CarControl::HUDControl::Reader::getLeadVisible() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline bool CarControl::HUDControl::Builder::getLeadVisible() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setLeadVisible(bool value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline ::cereal::CarControl::HUDControl::VisualAlert CarControl::HUDControl::Reader::getVisualAlert() const { - return _reader.getDataField< ::cereal::CarControl::HUDControl::VisualAlert>( - 1 * ::capnp::ELEMENTS); -} - -inline ::cereal::CarControl::HUDControl::VisualAlert CarControl::HUDControl::Builder::getVisualAlert() { - return _builder.getDataField< ::cereal::CarControl::HUDControl::VisualAlert>( - 1 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setVisualAlert( ::cereal::CarControl::HUDControl::VisualAlert value) { - _builder.setDataField< ::cereal::CarControl::HUDControl::VisualAlert>( - 1 * ::capnp::ELEMENTS, value); -} - -inline ::cereal::CarControl::HUDControl::AudibleAlert CarControl::HUDControl::Reader::getAudibleAlert() const { - return _reader.getDataField< ::cereal::CarControl::HUDControl::AudibleAlert>( - 4 * ::capnp::ELEMENTS); -} - -inline ::cereal::CarControl::HUDControl::AudibleAlert CarControl::HUDControl::Builder::getAudibleAlert() { - return _builder.getDataField< ::cereal::CarControl::HUDControl::AudibleAlert>( - 4 * ::capnp::ELEMENTS); -} -inline void CarControl::HUDControl::Builder::setAudibleAlert( ::cereal::CarControl::HUDControl::AudibleAlert value) { - _builder.setDataField< ::cereal::CarControl::HUDControl::AudibleAlert>( - 4 * ::capnp::ELEMENTS, value); -} - -} // namespace - -#endif // CAPNP_INCLUDED_8e2af1e708af8b8d_ diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ deleted file mode 100644 index 20949cefaa..0000000000 --- a/cereal/gen/cpp/log.capnp.c++ +++ /dev/null @@ -1,4089 +0,0 @@ -// 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<165> 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, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 255, 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, - 8, 0, 0, 0, 1, 0, 1, 0, - 252, 36, 252, 43, 189, 41, 52, 164, - 9, 0, 0, 0, 82, 0, 0, 0, - 13, 141, 244, 247, 232, 60, 155, 228, - 9, 0, 0, 0, 106, 0, 0, 0, - 83, 101, 110, 115, 111, 114, 86, 101, - 99, 0, 0, 0, 0, 0, 0, 0, - 83, 101, 110, 115, 111, 114, 83, 111, - 117, 114, 99, 101, 0, 0, 0, 0, - 36, 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, - 237, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 232, 0, 0, 0, 3, 0, 1, 0, - 244, 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, - 241, 0, 0, 0, 58, 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, - 2, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 0, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 240, 0, 0, 0, 3, 0, 1, 0, - 252, 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, - 249, 0, 0, 0, 82, 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, - 4, 0, 255, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 1, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 1, 0, 0, 3, 0, 1, 0, - 12, 1, 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, - 9, 1, 0, 0, 74, 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, - 6, 0, 253, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 1, 0, 0, 98, 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, - 7, 0, 252, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 7, 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, - 8, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 1, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 1, 0, 0, 3, 0, 1, 0, - 36, 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, - 115, 111, 117, 114, 99, 101, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 13, 141, 244, 247, 232, 60, 155, 228, - 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, } -}; -::capnp::word const* const bp_a2b29a69d44529a1 = b_a2b29a69d44529a1.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = { - &s_a43429bd2bfc24fc, - &s_e49b3ce8f7f48d0d, -}; -static const uint16_t m_a2b29a69d44529a1[] = {4, 7, 5, 6, 1, 8, 3, 2, 0}; -static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 0, 1, 2, 3, 8}; -const ::capnp::_::RawSchema s_a2b29a69d44529a1 = { - 0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 165, d_a2b29a69d44529a1, m_a2b29a69d44529a1, - 2, 9, 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<36> b_e49b3ce8f7f48d0d = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 13, 141, 244, 247, 232, 60, 155, 228, - 26, 0, 0, 0, 2, 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, - 21, 0, 0, 0, 58, 1, 0, 0, - 37, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 103, 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, - 83, 111, 117, 114, 99, 101, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 16, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 25, 0, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 17, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 110, 100, 114, 111, 105, 100, 0, - 105, 79, 83, 0, 0, 0, 0, 0, - 102, 105, 98, 101, 114, 0, 0, 0, - 118, 101, 108, 111, 100, 121, 110, 101, - 0, 0, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_e49b3ce8f7f48d0d = b_e49b3ce8f7f48d0d.words; -#if !CAPNP_LITE -static const uint16_t m_e49b3ce8f7f48d0d[] = {0, 2, 1, 3}; -const ::capnp::_::RawSchema s_e49b3ce8f7f48d0d = { - 0xe49b3ce8f7f48d0d, b_e49b3ce8f7f48d0d.words, 36, nullptr, m_e49b3ce8f7f48d0d, - 0, 4, nullptr, nullptr, nullptr, { &s_e49b3ce8f7f48d0d, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(SensorSource_e49b3ce8f7f48d0d, e49b3ce8f7f48d0d); -static const ::capnp::_::AlignedData<143> b_e946524859add50e = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 14, 213, 173, 89, 72, 82, 70, 233, - 10, 0, 0, 0, 1, 0, 6, 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, 210, 0, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 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, 71, 112, 115, 76, 111, 99, - 97, 116, 105, 111, 110, 68, 97, 116, - 97, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 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, 50, 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, 74, 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, - 2, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 2, 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, - 3, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 229, 0, 0, 0, 74, 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, - 4, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 237, 0, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 232, 0, 0, 0, 3, 0, 1, 0, - 244, 0, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 0, 0, 0, 66, 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, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 0, 0, 0, 74, 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, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 253, 0, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 0, 0, 0, 3, 0, 1, 0, - 8, 1, 0, 0, 2, 0, 1, 0, - 102, 108, 97, 103, 115, 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, - 108, 97, 116, 105, 116, 117, 100, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 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, 110, 103, 105, 116, 117, 100, - 101, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 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, 116, 105, 116, 117, 100, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 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, - 98, 101, 97, 114, 105, 110, 103, 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, 99, 99, 117, 114, 97, 99, 121, - 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, - 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, } -}; -::capnp::word const* const bp_e946524859add50e = b_e946524859add50e.words; -#if !CAPNP_LITE -static const uint16_t m_e946524859add50e[] = {6, 3, 5, 0, 1, 2, 4, 7}; -static const uint16_t i_e946524859add50e[] = {0, 1, 2, 3, 4, 5, 6, 7}; -const ::capnp::_::RawSchema s_e946524859add50e = { - 0xe946524859add50e, b_e946524859add50e.words, 143, nullptr, m_e946524859add50e, - 0, 8, i_e946524859add50e, nullptr, nullptr, { &s_e946524859add50e, 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<170> b_8d8231a40b7fe6e0 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 224, 230, 127, 11, 164, 49, 130, 141, - 10, 0, 0, 0, 1, 0, 3, 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, 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, 84, 104, 101, 114, 109, 97, - 108, 68, 97, 116, 97, 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, 42, 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, 34, 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, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 1, 0, 0, 3, 0, 1, 0, - 36, 1, 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, - 33, 1, 0, 0, 34, 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, - 7, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 1, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 1, 0, 0, 3, 0, 1, 0, - 48, 1, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 1, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 1, 0, 0, 3, 0, 1, 0, - 56, 1, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 1, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 52, 1, 0, 0, 3, 0, 1, 0, - 64, 1, 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, - 102, 114, 101, 101, 83, 112, 97, 99, - 101, 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, - 98, 97, 116, 116, 101, 114, 121, 80, - 101, 114, 99, 101, 110, 116, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 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, 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, 116, 101, 114, 121, 83, - 116, 97, 116, 117, 115, 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_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words; -#if !CAPNP_LITE -static const uint16_t m_8d8231a40b7fe6e0[] = {6, 8, 9, 0, 1, 2, 3, 7, 5, 4}; -static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; -const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { - 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 170, nullptr, m_8d8231a40b7fe6e0, - 0, 10, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<112> 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, 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, 72, 101, 97, 108, 116, 104, - 68, 97, 116, 97, 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, 64, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 161, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 0, 0, 0, 3, 0, 1, 0, - 168, 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, - 165, 0, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 0, 0, 0, 3, 0, 1, 0, - 176, 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, - 173, 0, 0, 0, 186, 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, - 5, 0, 0, 0, 67, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 0, 0, 0, 178, 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, - 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, - 115, 116, 97, 114, 116, 101, 100, 83, - 105, 103, 110, 97, 108, 68, 101, 116, - 101, 99, 116, 101, 100, 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_cfa2b0c2c82af1e4 = b_cfa2b0c2c82af1e4.words; -#if !CAPNP_LITE -static const uint16_t m_cfa2b0c2c82af1e4[] = {3, 1, 4, 2, 5, 0}; -static const uint16_t i_cfa2b0c2c82af1e4[] = {0, 1, 2, 3, 4, 5}; -const ::capnp::_::RawSchema s_cfa2b0c2c82af1e4 = { - 0xcfa2b0c2c82af1e4, b_cfa2b0c2c82af1e4.words, 112, nullptr, m_cfa2b0c2c82af1e4, - 0, 6, 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<208> 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, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 1, 0, 0, 3, 0, 1, 0, - 68, 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, - 65, 1, 0, 0, 178, 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, - 5, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 1, 0, 0, 162, 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, - 8, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 89, 1, 0, 0, 66, 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, - 9, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 93, 1, 0, 0, 66, 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, - 10, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 1, 0, 0, 74, 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, - 1, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 1, 0, 0, 90, 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, - 2, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 1, 0, 0, 90, 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, - 6, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 1, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 124, 1, 0, 0, 3, 0, 1, 0, - 136, 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, - 133, 1, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 136, 1, 0, 0, 3, 0, 1, 0, - 148, 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, - 145, 1, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 144, 1, 0, 0, 3, 0, 1, 0, - 172, 1, 0, 0, 2, 0, 1, 0, - 119, 97, 114, 112, 77, 97, 116, 114, - 105, 120, 68, 69, 80, 82, 69, 67, - 65, 84, 69, 68, 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, 68, 69, 80, 82, 69, - 67, 65, 84, 69, 68, 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, 68, 69, 80, 82, 69, 67, 65, - 84, 69, 68, 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, - 68, 69, 80, 82, 69, 67, 65, 84, - 69, 68, 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, 68, - 69, 80, 82, 69, 67, 65, 84, 69, - 68, 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, 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, 208, 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<446> 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, 122, 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, - 6, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 2, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 236, 2, 0, 0, 3, 0, 1, 0, - 248, 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, - 245, 2, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 244, 2, 0, 0, 3, 0, 1, 0, - 0, 3, 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, - 253, 2, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 2, 0, 0, 3, 0, 1, 0, - 8, 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, - 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, - 10, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 3, 0, 0, 66, 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, - 11, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 3, 0, 0, 42, 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, - 12, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 8, 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, - 13, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 3, 0, 0, 66, 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, - 14, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 3, 0, 0, 3, 0, 1, 0, - 40, 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, - 37, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 3, 0, 0, 3, 0, 1, 0, - 48, 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, - 45, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 3, 0, 0, 3, 0, 1, 0, - 56, 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, - 53, 3, 0, 0, 98, 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, - 18, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 3, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 64, 3, 0, 0, 3, 0, 1, 0, - 76, 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, - 73, 3, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 72, 3, 0, 0, 3, 0, 1, 0, - 84, 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, - 81, 3, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 80, 3, 0, 0, 3, 0, 1, 0, - 92, 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, - 89, 3, 0, 0, 98, 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, - 3, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 3, 0, 0, 90, 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, - 20, 0, 0, 0, 192, 2, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 3, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 3, 0, 0, 3, 0, 1, 0, - 112, 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, - 109, 3, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 3, 0, 0, 3, 0, 1, 0, - 120, 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, - 117, 3, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 3, 0, 0, 3, 0, 1, 0, - 144, 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, - 141, 3, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 136, 3, 0, 0, 3, 0, 1, 0, - 148, 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, - 145, 3, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 144, 3, 0, 0, 3, 0, 1, 0, - 156, 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, - 153, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 3, 0, 0, 3, 0, 1, 0, - 164, 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, - 161, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 3, 0, 0, 3, 0, 1, 0, - 172, 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, - 169, 3, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 168, 3, 0, 0, 3, 0, 1, 0, - 180, 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, 68, 69, 80, 82, - 69, 67, 65, 84, 69, 68, 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, 68, - 69, 80, 82, 69, 67, 65, 84, 69, - 68, 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, 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, 446, 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<414> 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, 23, 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, 71, 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, 69, 118, 101, 110, 116, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 96, 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, - 145, 2, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 144, 2, 0, 0, 3, 0, 1, 0, - 156, 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, - 153, 2, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 2, 0, 0, 3, 0, 1, 0, - 164, 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, - 161, 2, 0, 0, 50, 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, - 3, 0, 253, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 2, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 2, 0, 0, 3, 0, 1, 0, - 172, 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, - 169, 2, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 2, 0, 0, 3, 0, 1, 0, - 184, 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, - 181, 2, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 176, 2, 0, 0, 3, 0, 1, 0, - 204, 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, - 201, 2, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 196, 2, 0, 0, 3, 0, 1, 0, - 208, 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, - 205, 2, 0, 0, 66, 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, - 8, 0, 248, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 209, 2, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 2, 0, 0, 3, 0, 1, 0, - 240, 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, - 237, 2, 0, 0, 50, 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, - 10, 0, 246, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 2, 0, 0, 74, 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, - 11, 0, 245, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 249, 2, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 248, 2, 0, 0, 3, 0, 1, 0, - 20, 3, 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, - 17, 3, 0, 0, 58, 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, 243, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 3, 0, 0, 58, 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, 242, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 3, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 3, 0, 0, 3, 0, 1, 0, - 40, 3, 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, - 37, 3, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 3, 0, 0, 3, 0, 1, 0, - 48, 3, 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, - 45, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 3, 0, 0, 3, 0, 1, 0, - 72, 3, 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, - 69, 3, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 64, 3, 0, 0, 3, 0, 1, 0, - 92, 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, - 89, 3, 0, 0, 90, 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, - 19, 0, 237, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 3, 0, 0, 130, 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, - 20, 0, 236, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 3, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 104, 3, 0, 0, 3, 0, 1, 0, - 116, 3, 0, 0, 2, 0, 1, 0, - 21, 0, 235, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 3, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 112, 3, 0, 0, 3, 0, 1, 0, - 124, 3, 0, 0, 2, 0, 1, 0, - 22, 0, 234, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 3, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 3, 0, 0, 3, 0, 1, 0, - 132, 3, 0, 0, 2, 0, 1, 0, - 23, 0, 233, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 23, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 129, 3, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 3, 0, 0, 3, 0, 1, 0, - 140, 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, - 103, 112, 115, 76, 111, 99, 97, 116, - 105, 111, 110, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 14, 213, 173, 89, 72, 82, 70, 233, - 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, 114, 83, 116, 97, 116, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 60, 144, 82, 224, 9, 250, 164, 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, - 99, 97, 114, 67, 111, 110, 116, 114, - 111, 108, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 175, 20, 184, 154, 4, 41, 136, 247, - 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_9da4fa09e052903c, - &s_a2b29a69d44529a1, - &s_b8aad62cffef28a9, - &s_c08240f996aefced, - &s_cfa2b0c2c82af1e4, - &s_e71008caeb3fb65c, - &s_e946524859add50e, - &s_ea0245f695ae0a33, - &s_ea095da1894f7d85, - &s_f78829049ab814af, -}; -static const uint16_t m_d314cfd957229c11[] = {20, 5, 23, 22, 15, 10, 2, 21, 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, 21, 22, 23, 0}; -const ::capnp::_::RawSchema s_d314cfd957229c11 = { - 0xd314cfd957229c11, b_d314cfd957229c11.words, 414, d_d314cfd957229c11, m_d314cfd957229c11, - 20, 24, 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 - -// GpsLocationData -#ifndef _MSC_VER -constexpr uint16_t GpsLocationData::_capnpPrivate::dataWordSize; -constexpr uint16_t GpsLocationData::_capnpPrivate::pointerCount; -#endif -#if !CAPNP_LITE -constexpr ::capnp::Kind GpsLocationData::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* GpsLocationData::_capnpPrivate::schema; -constexpr ::capnp::_::RawBrandedSchema const* GpsLocationData::_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 deleted file mode 100644 index ff33d05a04..0000000000 --- a/cereal/gen/cpp/log.capnp.h +++ /dev/null @@ -1,7814 +0,0 @@ -// 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 - -#include "car.capnp.h" - -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(e49b3ce8f7f48d0d); -enum class SensorSource_e49b3ce8f7f48d0d: uint16_t { - ANDROID, - I_O_S, - FIBER, - VELODYNE, -}; -CAPNP_DECLARE_ENUM(SensorSource, e49b3ce8f7f48d0d); -CAPNP_DECLARE_SCHEMA(e946524859add50e); -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; - typedef ::capnp::schemas::SensorSource_e49b3ce8f7f48d0d SensorSource; - - - 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 GpsLocationData { - GpsLocationData() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(e946524859add50e, 6, 0) - #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, 3, 1) - #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, - GPS_LOCATION, - CAR_STATE, - CAR_CONTROL, - }; - - 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; - - inline ::cereal::SensorEventData::SensorSource getSource() 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(); - - inline ::cereal::SensorEventData::SensorSource getSource(); - inline void setSource( ::cereal::SensorEventData::SensorSource value); - -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 GpsLocationData::Reader { -public: - typedef GpsLocationData 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 getFlags() const; - - inline double getLatitude() const; - - inline double getLongitude() const; - - inline double getAltitude() const; - - inline float getSpeed() const; - - inline float getBearing() const; - - inline float getAccuracy() const; - - inline ::int64_t getTimestamp() 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 GpsLocationData::Builder { -public: - typedef GpsLocationData 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 getFlags(); - inline void setFlags( ::uint16_t value); - - inline double getLatitude(); - inline void setLatitude(double value); - - inline double getLongitude(); - inline void setLongitude(double value); - - inline double getAltitude(); - inline void setAltitude(double value); - - inline float getSpeed(); - inline void setSpeed(float value); - - inline float getBearing(); - inline void setBearing(float value); - - inline float getAccuracy(); - inline void setAccuracy(float value); - - inline ::int64_t getTimestamp(); - inline void setTimestamp( ::int64_t value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class GpsLocationData::Pipeline { -public: - typedef GpsLocationData 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; - - inline float getFreeSpace() const; - - inline ::int16_t getBatteryPercent() const; - - inline bool hasBatteryStatus() const; - inline ::capnp::Text::Reader getBatteryStatus() 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); - - inline float getFreeSpace(); - inline void setFreeSpace(float value); - - inline ::int16_t getBatteryPercent(); - inline void setBatteryPercent( ::int16_t value); - - inline bool hasBatteryStatus(); - inline ::capnp::Text::Builder getBatteryStatus(); - inline void setBatteryStatus( ::capnp::Text::Reader value); - inline ::capnp::Text::Builder initBatteryStatus(unsigned int size); - inline void adoptBatteryStatus(::capnp::Orphan< ::capnp::Text>&& value); - inline ::capnp::Orphan< ::capnp::Text> disownBatteryStatus(); - -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; - - inline bool getStartedSignalDetected() 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); - - inline bool getStartedSignalDetected(); - inline void setStartedSignalDetected(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 hasWarpMatrixDEPRECATED() const; - inline ::capnp::List::Reader getWarpMatrixDEPRECATED() const; - - inline float getAngleOffsetDEPRECATED() const; - - inline ::int8_t getCalStatusDEPRECATED() 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 getCalCycleDEPRECATED() const; - - inline ::int8_t getCalPercDEPRECATED() 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 hasWarpMatrixDEPRECATED(); - inline ::capnp::List::Builder getWarpMatrixDEPRECATED(); - inline void setWarpMatrixDEPRECATED( ::capnp::List::Reader value); - inline void setWarpMatrixDEPRECATED(::kj::ArrayPtr value); - inline ::capnp::List::Builder initWarpMatrixDEPRECATED(unsigned int size); - inline void adoptWarpMatrixDEPRECATED(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownWarpMatrixDEPRECATED(); - - inline float getAngleOffsetDEPRECATED(); - inline void setAngleOffsetDEPRECATED(float value); - - inline ::int8_t getCalStatusDEPRECATED(); - inline void setCalStatusDEPRECATED( ::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 getCalCycleDEPRECATED(); - inline void setCalCycleDEPRECATED( ::int32_t value); - - inline ::int8_t getCalPercDEPRECATED(); - inline void setCalPercDEPRECATED( ::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 getAEgoDEPRECATED() 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 getHudLeadDEPRECATED() 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 getAEgoDEPRECATED(); - inline void setAEgoDEPRECATED(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 getHudLeadDEPRECATED(); - inline void setHudLeadDEPRECATED( ::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; - - inline bool isGpsLocation() const; - inline bool hasGpsLocation() const; - inline ::cereal::GpsLocationData::Reader getGpsLocation() const; - - inline bool isCarState() const; - inline bool hasCarState() const; - inline ::cereal::CarState::Reader getCarState() const; - - inline bool isCarControl() const; - inline bool hasCarControl() const; - inline ::cereal::CarControl::Reader getCarControl() 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(); - - inline bool isGpsLocation(); - inline bool hasGpsLocation(); - inline ::cereal::GpsLocationData::Builder getGpsLocation(); - inline void setGpsLocation( ::cereal::GpsLocationData::Reader value); - inline ::cereal::GpsLocationData::Builder initGpsLocation(); - inline void adoptGpsLocation(::capnp::Orphan< ::cereal::GpsLocationData>&& value); - inline ::capnp::Orphan< ::cereal::GpsLocationData> disownGpsLocation(); - - inline bool isCarState(); - inline bool hasCarState(); - inline ::cereal::CarState::Builder getCarState(); - inline void setCarState( ::cereal::CarState::Reader value); - inline ::cereal::CarState::Builder initCarState(); - inline void adoptCarState(::capnp::Orphan< ::cereal::CarState>&& value); - inline ::capnp::Orphan< ::cereal::CarState> disownCarState(); - - inline bool isCarControl(); - inline bool hasCarControl(); - inline ::cereal::CarControl::Builder getCarControl(); - inline void setCarControl( ::cereal::CarControl::Reader value); - inline ::cereal::CarControl::Builder initCarControl(); - inline void adoptCarControl(::capnp::Orphan< ::cereal::CarControl>&& value); - inline ::capnp::Orphan< ::cereal::CarControl> disownCarControl(); - -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 ::cereal::SensorEventData::SensorSource SensorEventData::Reader::getSource() const { - return _reader.getDataField< ::cereal::SensorEventData::SensorSource>( - 7 * ::capnp::ELEMENTS); -} - -inline ::cereal::SensorEventData::SensorSource SensorEventData::Builder::getSource() { - return _builder.getDataField< ::cereal::SensorEventData::SensorSource>( - 7 * ::capnp::ELEMENTS); -} -inline void SensorEventData::Builder::setSource( ::cereal::SensorEventData::SensorSource value) { - _builder.setDataField< ::cereal::SensorEventData::SensorSource>( - 7 * ::capnp::ELEMENTS, value); -} - -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 ::uint16_t GpsLocationData::Reader::getFlags() const { - return _reader.getDataField< ::uint16_t>( - 0 * ::capnp::ELEMENTS); -} - -inline ::uint16_t GpsLocationData::Builder::getFlags() { - return _builder.getDataField< ::uint16_t>( - 0 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setFlags( ::uint16_t value) { - _builder.setDataField< ::uint16_t>( - 0 * ::capnp::ELEMENTS, value); -} - -inline double GpsLocationData::Reader::getLatitude() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline double GpsLocationData::Builder::getLatitude() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setLatitude(double value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline double GpsLocationData::Reader::getLongitude() const { - return _reader.getDataField( - 2 * ::capnp::ELEMENTS); -} - -inline double GpsLocationData::Builder::getLongitude() { - return _builder.getDataField( - 2 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setLongitude(double value) { - _builder.setDataField( - 2 * ::capnp::ELEMENTS, value); -} - -inline double GpsLocationData::Reader::getAltitude() const { - return _reader.getDataField( - 3 * ::capnp::ELEMENTS); -} - -inline double GpsLocationData::Builder::getAltitude() { - return _builder.getDataField( - 3 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setAltitude(double value) { - _builder.setDataField( - 3 * ::capnp::ELEMENTS, value); -} - -inline float GpsLocationData::Reader::getSpeed() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float GpsLocationData::Builder::getSpeed() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setSpeed(float value) { - _builder.setDataField( - 1 * ::capnp::ELEMENTS, value); -} - -inline float GpsLocationData::Reader::getBearing() const { - return _reader.getDataField( - 8 * ::capnp::ELEMENTS); -} - -inline float GpsLocationData::Builder::getBearing() { - return _builder.getDataField( - 8 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setBearing(float value) { - _builder.setDataField( - 8 * ::capnp::ELEMENTS, value); -} - -inline float GpsLocationData::Reader::getAccuracy() const { - return _reader.getDataField( - 9 * ::capnp::ELEMENTS); -} - -inline float GpsLocationData::Builder::getAccuracy() { - return _builder.getDataField( - 9 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setAccuracy(float value) { - _builder.setDataField( - 9 * ::capnp::ELEMENTS, value); -} - -inline ::int64_t GpsLocationData::Reader::getTimestamp() const { - return _reader.getDataField< ::int64_t>( - 5 * ::capnp::ELEMENTS); -} - -inline ::int64_t GpsLocationData::Builder::getTimestamp() { - return _builder.getDataField< ::int64_t>( - 5 * ::capnp::ELEMENTS); -} -inline void GpsLocationData::Builder::setTimestamp( ::int64_t value) { - _builder.setDataField< ::int64_t>( - 5 * ::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 float ThermalData::Reader::getFreeSpace() const { - return _reader.getDataField( - 4 * ::capnp::ELEMENTS); -} - -inline float ThermalData::Builder::getFreeSpace() { - return _builder.getDataField( - 4 * ::capnp::ELEMENTS); -} -inline void ThermalData::Builder::setFreeSpace(float value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, value); -} - -inline ::int16_t ThermalData::Reader::getBatteryPercent() const { - return _reader.getDataField< ::int16_t>( - 10 * ::capnp::ELEMENTS); -} - -inline ::int16_t ThermalData::Builder::getBatteryPercent() { - return _builder.getDataField< ::int16_t>( - 10 * ::capnp::ELEMENTS); -} -inline void ThermalData::Builder::setBatteryPercent( ::int16_t value) { - _builder.setDataField< ::int16_t>( - 10 * ::capnp::ELEMENTS, value); -} - -inline bool ThermalData::Reader::hasBatteryStatus() const { - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool ThermalData::Builder::hasBatteryStatus() { - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::Text::Reader ThermalData::Reader::getBatteryStatus() const { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::capnp::Text::Builder ThermalData::Builder::getBatteryStatus() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void ThermalData::Builder::setBatteryStatus( ::capnp::Text::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::capnp::Text::Builder ThermalData::Builder::initBatteryStatus(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::Text>::init( - _builder.getPointerField(0 * ::capnp::POINTERS), size); -} -inline void ThermalData::Builder::adoptBatteryStatus( - ::capnp::Orphan< ::capnp::Text>&& value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::Text> ThermalData::Builder::disownBatteryStatus() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -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 HealthData::Reader::getStartedSignalDetected() const { - return _reader.getDataField( - 67 * ::capnp::ELEMENTS); -} - -inline bool HealthData::Builder::getStartedSignalDetected() { - return _builder.getDataField( - 67 * ::capnp::ELEMENTS); -} -inline void HealthData::Builder::setStartedSignalDetected(bool value) { - _builder.setDataField( - 67 * ::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::hasWarpMatrixDEPRECATED() const { - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool Live20Data::Builder::hasWarpMatrixDEPRECATED() { - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader Live20Data::Reader::getWarpMatrixDEPRECATED() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder Live20Data::Builder::getWarpMatrixDEPRECATED() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Live20Data::Builder::setWarpMatrixDEPRECATED( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline void Live20Data::Builder::setWarpMatrixDEPRECATED(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder Live20Data::Builder::initWarpMatrixDEPRECATED(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init( - _builder.getPointerField(0 * ::capnp::POINTERS), size); -} -inline void Live20Data::Builder::adoptWarpMatrixDEPRECATED( - ::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::disownWarpMatrixDEPRECATED() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline float Live20Data::Reader::getAngleOffsetDEPRECATED() const { - return _reader.getDataField( - 0 * ::capnp::ELEMENTS); -} - -inline float Live20Data::Builder::getAngleOffsetDEPRECATED() { - return _builder.getDataField( - 0 * ::capnp::ELEMENTS); -} -inline void Live20Data::Builder::setAngleOffsetDEPRECATED(float value) { - _builder.setDataField( - 0 * ::capnp::ELEMENTS, value); -} - -inline ::int8_t Live20Data::Reader::getCalStatusDEPRECATED() const { - return _reader.getDataField< ::int8_t>( - 4 * ::capnp::ELEMENTS); -} - -inline ::int8_t Live20Data::Builder::getCalStatusDEPRECATED() { - return _builder.getDataField< ::int8_t>( - 4 * ::capnp::ELEMENTS); -} -inline void Live20Data::Builder::setCalStatusDEPRECATED( ::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::getCalCycleDEPRECATED() const { - return _reader.getDataField< ::int32_t>( - 3 * ::capnp::ELEMENTS); -} - -inline ::int32_t Live20Data::Builder::getCalCycleDEPRECATED() { - return _builder.getDataField< ::int32_t>( - 3 * ::capnp::ELEMENTS); -} -inline void Live20Data::Builder::setCalCycleDEPRECATED( ::int32_t value) { - _builder.setDataField< ::int32_t>( - 3 * ::capnp::ELEMENTS, value); -} - -inline ::int8_t Live20Data::Reader::getCalPercDEPRECATED() const { - return _reader.getDataField< ::int8_t>( - 5 * ::capnp::ELEMENTS); -} - -inline ::int8_t Live20Data::Builder::getCalPercDEPRECATED() { - return _builder.getDataField< ::int8_t>( - 5 * ::capnp::ELEMENTS); -} -inline void Live20Data::Builder::setCalPercDEPRECATED( ::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::getAEgoDEPRECATED() const { - return _reader.getDataField( - 1 * ::capnp::ELEMENTS); -} - -inline float Live100Data::Builder::getAEgoDEPRECATED() { - return _builder.getDataField( - 1 * ::capnp::ELEMENTS); -} -inline void Live100Data::Builder::setAEgoDEPRECATED(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::getHudLeadDEPRECATED() const { - return _reader.getDataField< ::int32_t>( - 14 * ::capnp::ELEMENTS); -} - -inline ::int32_t Live100Data::Builder::getHudLeadDEPRECATED() { - return _builder.getDataField< ::int32_t>( - 14 * ::capnp::ELEMENTS); -} -inline void Live100Data::Builder::setHudLeadDEPRECATED( ::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)); -} - -inline bool Event::Reader::isGpsLocation() const { - return which() == Event::GPS_LOCATION; -} -inline bool Event::Builder::isGpsLocation() { - return which() == Event::GPS_LOCATION; -} -inline bool Event::Reader::hasGpsLocation() const { - if (which() != Event::GPS_LOCATION) return false; - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool Event::Builder::hasGpsLocation() { - if (which() != Event::GPS_LOCATION) return false; - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::GpsLocationData::Reader Event::Reader::getGpsLocation() const { - KJ_IREQUIRE(which() == Event::GPS_LOCATION, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::cereal::GpsLocationData::Builder Event::Builder::getGpsLocation() { - KJ_IREQUIRE(which() == Event::GPS_LOCATION, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::setGpsLocation( ::cereal::GpsLocationData::Reader value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::GPS_LOCATION); - ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::cereal::GpsLocationData::Builder Event::Builder::initGpsLocation() { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::GPS_LOCATION); - return ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::init( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::adoptGpsLocation( - ::capnp::Orphan< ::cereal::GpsLocationData>&& value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::GPS_LOCATION); - ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::GpsLocationData> Event::Builder::disownGpsLocation() { - KJ_IREQUIRE(which() == Event::GPS_LOCATION, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::GpsLocationData>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline bool Event::Reader::isCarState() const { - return which() == Event::CAR_STATE; -} -inline bool Event::Builder::isCarState() { - return which() == Event::CAR_STATE; -} -inline bool Event::Reader::hasCarState() const { - if (which() != Event::CAR_STATE) return false; - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool Event::Builder::hasCarState() { - if (which() != Event::CAR_STATE) return false; - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarState::Reader Event::Reader::getCarState() const { - KJ_IREQUIRE(which() == Event::CAR_STATE, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarState>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::cereal::CarState::Builder Event::Builder::getCarState() { - KJ_IREQUIRE(which() == Event::CAR_STATE, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarState>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::setCarState( ::cereal::CarState::Reader value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_STATE); - ::capnp::_::PointerHelpers< ::cereal::CarState>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::cereal::CarState::Builder Event::Builder::initCarState() { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_STATE); - return ::capnp::_::PointerHelpers< ::cereal::CarState>::init( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::adoptCarState( - ::capnp::Orphan< ::cereal::CarState>&& value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_STATE); - ::capnp::_::PointerHelpers< ::cereal::CarState>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarState> Event::Builder::disownCarState() { - KJ_IREQUIRE(which() == Event::CAR_STATE, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarState>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -inline bool Event::Reader::isCarControl() const { - return which() == Event::CAR_CONTROL; -} -inline bool Event::Builder::isCarControl() { - return which() == Event::CAR_CONTROL; -} -inline bool Event::Reader::hasCarControl() const { - if (which() != Event::CAR_CONTROL) return false; - return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline bool Event::Builder::hasCarControl() { - if (which() != Event::CAR_CONTROL) return false; - return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarControl::Reader Event::Reader::getCarControl() const { - KJ_IREQUIRE(which() == Event::CAR_CONTROL, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarControl>::get( - _reader.getPointerField(0 * ::capnp::POINTERS)); -} -inline ::cereal::CarControl::Builder Event::Builder::getCarControl() { - KJ_IREQUIRE(which() == Event::CAR_CONTROL, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarControl>::get( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::setCarControl( ::cereal::CarControl::Reader value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); - ::capnp::_::PointerHelpers< ::cereal::CarControl>::set( - _builder.getPointerField(0 * ::capnp::POINTERS), value); -} -inline ::cereal::CarControl::Builder Event::Builder::initCarControl() { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); - return ::capnp::_::PointerHelpers< ::cereal::CarControl>::init( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} -inline void Event::Builder::adoptCarControl( - ::capnp::Orphan< ::cereal::CarControl>&& value) { - _builder.setDataField( - 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); - ::capnp::_::PointerHelpers< ::cereal::CarControl>::adopt( - _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarControl> Event::Builder::disownCarControl() { - KJ_IREQUIRE(which() == Event::CAR_CONTROL, - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CarControl>::disown( - _builder.getPointerField(0 * ::capnp::POINTERS)); -} - -} // namespace - -#endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ diff --git a/cereal/java.capnp b/cereal/java.capnp new file mode 100644 index 0000000000..cddf6eba3d --- /dev/null +++ b/cereal/java.capnp @@ -0,0 +1,28 @@ +# Copyright (c) 2013-2015 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. + +@0xc5f1af96651f70ea; + +annotation package @0x9ee4c8f803b3b596 (file) : Text; +# Name of the package, such as "org.example.foo", in which the generated code will reside. + +annotation outerClassname @0x9b066bb4881f7cd3 (file) : Text; +# Name of the outer class that will wrap the generated code. diff --git a/cereal/log.capnp b/cereal/log.capnp index 34637c6f42..885339ac39 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1,16 +1,89 @@ using Cxx = import "c++.capnp"; $Cxx.namespace("cereal"); +using Java = import "java.capnp"; +$Java.package("ai.comma.openpilot.cereal"); +$Java.outerClassname("Log"); + using Car = import "car.capnp"; @0xf3b1f17e25a4285b; const logVersion :Int32 = 1; +struct Map(Key, Value) { + entries @0 :List(Entry); + struct Entry { + key @0 :Key; + value @1 :Value; + } +} + struct InitData { kernelArgs @0 :List(Text); gctx @1 :Text; dongleId @2 :Text; + + deviceType @3 :DeviceType; + version @4 :Text; + + androidBuildInfo @5 :AndroidBuildInfo; + androidSensors @6 :List(AndroidSensor); + chffrAndroidExtra @7 :ChffrAndroidExtra; + + enum DeviceType { + unknown @0; + neo @1; + chffrAndroid @2; + } + + struct AndroidBuildInfo { + board @0 :Text; + bootloader @1 :Text; + brand @2 :Text; + device @3 :Text; + display @4 :Text; + fingerprint @5 :Text; + hardware @6 :Text; + host @7 :Text; + id @8 :Text; + manufacturer @9 :Text; + model @10 :Text; + product @11 :Text; + radioVersion @12 :Text; + serial @13 :Text; + supportedAbis @14 :List(Text); + tags @15 :Text; + time @16 :Int64; + type @17 :Text; + user @18 :Text; + + versionCodename @19 :Text; + versionRelease @20 :Text; + versionSdk @21 :Int32; + versionSecurityPatch @22 :Text; + } + + struct AndroidSensor { + id @0 :Int32; + name @1 :Text; + vendor @2 :Text; + version @3 :Int32; + handle @4 :Int32; + type @5 :Int32; + maxRange @6 :Float32; + resolution @7 :Float32; + power @8 :Float32; + minDelay @9 :Int32; + fifoReservedEventCount @10 :UInt32; + fifoMaxEventCount @11 :UInt32; + stringType @12 :Text; + maxDelay @13 :Int32; + } + + struct ChffrAndroidExtra { + allCameraCharacteristics @0 :Map(Text, Text); + } } struct FrameData { @@ -21,6 +94,27 @@ struct FrameData { integLines @4 :Int32; globalGain @5 :Int32; image @6 :Data; + + frameType @7 :FrameType; + timestampSof @8 :UInt64; + + androidCaptureResult @9 :AndroidCaptureResult; + + enum FrameType { + unknown @0; + neo @1; + chffrAndroid @2; + } + + struct AndroidCaptureResult { + sensitivity @0 :Int32; + frameDuration @1 :Int64; + exposureTime @2 :Int64; + rollingShutterSkew @3 :UInt64; + colorCorrectionTransform @4 :List(Int32); + colorCorrectionGains @5 :List(Float32); + displayRotation @6 :Int8; + } } struct GPSNMEAData { @@ -82,6 +176,17 @@ struct GpsLocationData { # Timestamp for the location fix. # Milliseconds since January 1, 1970. timestamp @7 :Int64; + + source @8 :SensorSource; + + enum SensorSource { + android @0; + iOS @1; + car @2; + velodyne @3; # Velodyne IMU + fusion @4; + external @5; + } } struct CanData { @@ -160,6 +265,9 @@ struct LiveCalibrationData { calStatus @1 :Int8; calCycle @2 :Int32; calPerc @3 :Int8; + + # Maps car space to normalized image space. + extrinsicMatrix @4 :List(Float32); } struct LiveTracks { @@ -194,7 +302,7 @@ struct Live100Data { aTargetMin @10 :Float32; aTargetMax @11 :Float32; jerkFactor @12 :Float32; - angleSteers @13 :Float32; + angleSteers @13 :Float32; # Steering angle in degrees. hudLeadDEPRECATED @14 :Int32; cumLagMs @15 :Float32; @@ -262,13 +370,16 @@ struct EncodeIndex { encodeId @2 :UInt32; # minute long segment this frame is in segmentNum @3 :Int32; - # index into camera file in segment from 0 + # index into camera file in segment in presentation order segmentId @4 :UInt32; + # index into camera file in segment in encode order + segmentIdEncode @5 :UInt32; enum Type { bigBoxLossless @0; # rcamera.mkv fullHEVC @1; # fcamera.hevc bigBoxHEVC @2; # bcamera.hevc + chffrAndroidH264 @3; # camera } } @@ -287,8 +398,504 @@ struct LogRotate { path @1 :Text; } +struct Plan { + # lateral, 3rd order polynomial + lateralValid @0: Bool; + dPoly @1 :List(Float32); + + # longitudinal + longitudinalValid @2: Bool; + vTarget @3 :Float32; + aTargetMin @4 :Float32; + aTargetMax @5 :Float32; + jerkFactor @6 :Float32; +} + +struct LiveLocationData { + status @0: UInt8; + + # 3D fix + lat @1: Float64; + lon @2: Float64; + alt @3: Float32; # m + + # speed + speed @4: Float32; # m/s + + # NED velocity components + vNED @5: List(Float32); + + # roll, pitch, heading (x,y,z) + roll @6: Float32; # WRT to center of earth? + pitch @7: Float32; # WRT to center of earth? + heading @8: Float32; # WRT to north? + + # what are these? + wanderAngle @9: Float32; + trackAngle @10: Float32; + + # car frame -- https://upload.wikimedia.org/wikipedia/commons/f/f5/RPY_angles_of_cars.png + + # gyro, in car frame, deg/s + gyro @11: List(Float32); + + # accel, in car frame, m/s^2 + accel @12: List(Float32); + + accuracy @13: Accuracy; + + struct Accuracy { + pNEDError @0: List(Float32); + vNEDError @1: List(Float32); + rollError @2: Float32; + pitchError @3: Float32; + headingError @4: Float32; + ellipsoidSemiMajorError @5: Float32; + ellipsoidSemiMinorError @6: Float32; + ellipsoidOrientationError @7: Float32; + } +} + +struct EthernetPacket { + pkt @0 :Data; + ts @1: Float32; +} + +struct NavUpdate { + isNavigating @0 :Bool; + curSegment @1 :Int32; + segments @2 :List(Segment); + + struct LatLng { + lat @0 :Float64; + lng @1 :Float64; + } + + struct Segment { + from @0 :LatLng; + to @1 :LatLng; + updateTime @2 :Int32; + distance @3 :Int32; + crossTime @4 :Int32; + exitNo @5 :Int32; + instruction @6 :Instruction; + + parts @7 :List(LatLng); + + enum Instruction { + turnLeft @0; + turnRight @1; + keepLeft @2; + keepRight @3; + straight @4; + roundaboutExitNumber @5; + roundaboutExit @6; + roundaboutTurnLeft @7; + unkn8 @8; + roundaboutStraight @9; + unkn10 @10; + roundaboutTurnRight @11; + unkn12 @12; + roundaboutUturn @13; + unkn14 @14; + arrive @15; + exitLeft @16; + exitRight @17; + unkn18 @18; + uturn @19; + # ... + } + } +} + +struct CellInfo { + timestamp @0 :UInt64; + repr @1 :Text; # android toString() for now +} + +struct WifiScan { + bssid @0 :Text; + ssid @1 :Text; + capabilities @2 :Text; + frequency @3 :Int32; + level @4 :Int32; + timestamp @5 :Int64; + + centerFreq0 @6 :Int32; + centerFreq1 @7 :Int32; + channelWidth @8 :ChannelWidth; + operatorFriendlyName @9 :Text; + venueName @10 :Text; + is80211mcResponder @11 :Bool; + passpoint @12 :Bool; + + distanceCm @13 :Int32; + distanceSdCm @14 :Int32; + + enum ChannelWidth { + w20Mhz @0; + w40Mhz @1; + w80Mhz @2; + w160Mhz @3; + w80Plus80Mhz @4; + } +} + +struct AndroidGnss { + union { + measurements @0 :Measurements; + navigationMessage @1 :NavigationMessage; + } + + struct Measurements { + clock @0 :Clock; + measurements @1 :List(Measurement); + + struct Clock { + timeNanos @0 :Int64; + hardwareClockDiscontinuityCount @1 :Int32; + + hasTimeUncertaintyNanos @2 :Bool; + timeUncertaintyNanos @3 :Float64; + + hasLeapSecond @4 :Bool; + leapSecond @5 :Int32; + + hasFullBiasNanos @6 :Bool; + fullBiasNanos @7 :Int64; + + hasBiasNanos @8 :Bool; + biasNanos @9 :Float64; + + hasBiasUncertaintyNanos @10 :Bool; + biasUncertaintyNanos @11 :Float64; + + hasDriftNanosPerSecond @12 :Bool; + driftNanosPerSecond @13 :Float64; + + hasDriftUncertaintyNanosPerSecond @14 :Bool; + driftUncertaintyNanosPerSecond @15 :Float64; + } + + struct Measurement { + svId @0 :Int32; + constellation @1 :Constellation; + + timeOffsetNanos @2 :Float64; + state @3 :Int32; + receivedSvTimeNanos @4 :Int64; + receivedSvTimeUncertaintyNanos @5 :Int64; + cn0DbHz @6 :Float64; + pseudorangeRateMetersPerSecond @7 :Float64; + pseudorangeRateUncertaintyMetersPerSecond @8 :Float64; + accumulatedDeltaRangeState @9 :Int32; + accumulatedDeltaRangeMeters @10 :Float64; + accumulatedDeltaRangeUncertaintyMeters @11 :Float64; + + hasCarrierFrequencyHz @12 :Bool; + carrierFrequencyHz @13 :Float32; + hasCarrierCycles @14 :Bool; + carrierCycles @15 :Int64; + hasCarrierPhase @16 :Bool; + carrierPhase @17 :Float64; + hasCarrierPhaseUncertainty @18 :Bool; + carrierPhaseUncertainty @19 :Float64; + hasSnrInDb @20 :Bool; + snrInDb @21 :Float64; + + multipathIndicator @22 :MultipathIndicator; + + enum Constellation { + unknown @0; + gps @1; + sbas @2; + glonass @3; + qzss @4; + beidou @5; + galileo @6; + } + + enum State { + unknown @0; + codeLock @1; + bitSync @2; + subframeSync @3; + towDecoded @4; + msecAmbiguous @5; + symbolSync @6; + gloStringSync @7; + gloTodDecoded @8; + bdsD2BitSync @9; + bdsD2SubframeSync @10; + galE1bcCodeLock @11; + galE1c2ndCodeLock @12; + galE1bPageSync @13; + sbasSync @14; + } + + enum MultipathIndicator { + unknown @0; + detected @1; + notDetected @2; + } + } + } + + struct NavigationMessage { + type @0 :Int32; + svId @1 :Int32; + messageId @2 :Int32; + submessageId @3 :Int32; + data @4 :Data; + status @5 :Status; + + enum Status { + unknown @0; + parityPassed @1; + parityRebuilt @2; + } + } +} + +struct QcomGnss { + logTs @0 :UInt64; + union { + measurementReport @1 :MeasurementReport; + clockReport @2 :ClockReport; + } + + struct MeasurementReport { + source @0 :Source; + + fCount @1 :UInt32; + + gpsWeek @2 :UInt16; + glonassCycleNumber @3 :UInt8; + glonassNumberOfDays @4 :UInt16; + + milliseconds @5 :UInt32; + timeBias @6 :Float32; + clockTimeUncertainty @7 :Float32; + clockFrequencyBias @8 :Float32; + clockFrequencyUncertainty @9 :Float32; + + sv @10 :List(SV); + + enum Source { + gps @0; + glonass @1; + } + + struct SV { + svId @0 :UInt8; + observationState @2 :SVObservationState; + observations @3 :UInt8; + goodObservations @4 :UInt8; + gpsParityErrorCount @5 :UInt16; + glonassFrequencyIndex @1 :Int8; + glonassHemmingErrorCount @6 :UInt8; + filterStages @7 :UInt8; + carrierNoise @8 :UInt16; + latency @9 :Int16; + predetectIntegration @10 :UInt8; + postdetections @11 :UInt16; + + unfilteredMeasurementIntegral @12 :UInt32; + unfilteredMeasurementFraction @13 :Float32; + unfilteredTimeUncertainty @14 :Float32; + unfilteredSpeed @15 :Float32; + unfilteredSpeedUncertainty @16 :Float32; + measurementStatus @17 :MeasurementStatus; + multipathEstimate @18 :UInt32; + azimuth @19 :Float32; + elevation @20 :Float32; + carrierPhaseCyclesIntegral @21 :Int32; + carrierPhaseCyclesFraction @22 :UInt16; + fineSpeed @23 :Float32; + fineSpeedUncertainty @24 :Float32; + cycleSlipCount @25 :UInt8; + + struct MeasurementStatus { + subMillisecondIsValid @0 :Bool; + subBitTimeIsKnown @1 :Bool; + satelliteTimeIsKnown @2 :Bool; + bitEdgeConfirmedFromSignal @3 :Bool; + measuredVelocity @4 :Bool; + fineOrCoarseVelocity @5 :Bool; + lockPointValid @6 :Bool; + lockPointPositive @7 :Bool; + lastUpdateFromDifference @8 :Bool; + lastUpdateFromVelocityDifference @9 :Bool; + strongIndicationOfCrossCorelation @10 :Bool; + tentativeMeasurement @11 :Bool; + measurementNotUsable @12 :Bool; + sirCheckIsNeeded @13 :Bool; + probationMode @14 :Bool; + + glonassMeanderBitEdgeValid @15 :Bool; + glonassTimeMarkValid @16 :Bool; + + gpsRoundRobinRxDiversity @17 :Bool; + gpsRxDiversity @18 :Bool; + gpsLowBandwidthRxDiversityCombined @19 :Bool; + gpsHighBandwidthNu4 @20 :Bool; + gpsHighBandwidthNu8 @21 :Bool; + gpsHighBandwidthUniform @22 :Bool; + gpsMultipathIndicator @23 :Bool; + + imdJammingIndicator @24 :Bool; + lteB13TxJammingIndicator @25 :Bool; + freshMeasurementIndicator @26 :Bool; + + multipathEstimateIsValid @27 :Bool; + directionIsValid @28 :Bool; + } + + enum SVObservationState { + idle @0; + search @1; + searchVerify @2; + bitEdge @3; + trackVerify @4; + track @5; + restart @6; + dpo @7; + glo10msBe @8; + glo10msAt @9; + } + } + + } + + struct ClockReport { + hasFCount @0 :Bool; + fCount @1 :UInt32; + + hasGpsWeekNumber @2 :Bool; + gpsWeekNumber @3 :UInt16; + hasGpsMilliseconds @4 :Bool; + gpsMilliseconds @5 :UInt32; + gpsTimeBias @6 :Float32; + gpsClockTimeUncertainty @7 :Float32; + gpsClockSource @8 :UInt8; + + hasGlonassYear @9 :Bool; + glonassYear @10 :UInt8; + hasGlonassDay @11 :Bool; + glonassDay @12 :UInt16; + hasGlonassMilliseconds @13 :Bool; + glonassMilliseconds @14 :UInt32; + glonassTimeBias @15 :Float32; + glonassClockTimeUncertainty @16 :Float32; + glonassClockSource @17 :UInt8; + + bdsWeek @18 :UInt16; + bdsMilliseconds @19 :UInt32; + bdsTimeBias @20 :Float32; + bdsClockTimeUncertainty @21 :Float32; + bdsClockSource @22 :UInt8; + + galWeek @23 :UInt16; + galMilliseconds @24 :UInt32; + galTimeBias @25 :Float32; + galClockTimeUncertainty @26 :Float32; + galClockSource @27 :UInt8; + + clockFrequencyBias @28 :Float32; + clockFrequencyUncertainty @29 :Float32; + frequencySource @30 :UInt8; + gpsLeapSeconds @31 :UInt8; + gpsLeapSecondsUncertainty @32 :UInt8; + gpsLeapSecondsSource @33 :UInt8; + + gpsToGlonassTimeBiasMilliseconds @34 :Float32; + gpsToGlonassTimeBiasMillisecondsUncertainty @35 :Float32; + gpsToBdsTimeBiasMilliseconds @36 :Float32; + gpsToBdsTimeBiasMillisecondsUncertainty @37 :Float32; + bdsToGloTimeBiasMilliseconds @38 :Float32; + bdsToGloTimeBiasMillisecondsUncertainty @39 :Float32; + gpsToGalTimeBiasMilliseconds @40 :Float32; + gpsToGalTimeBiasMillisecondsUncertainty @41 :Float32; + galToGloTimeBiasMilliseconds @42 :Float32; + galToGloTimeBiasMillisecondsUncertainty @43 :Float32; + galToBdsTimeBiasMilliseconds @44 :Float32; + galToBdsTimeBiasMillisecondsUncertainty @45 :Float32; + + hasRtcTime @46 :Bool; + systemRtcTime @47 :UInt32; + fCountOffset @48 :UInt32; + lpmRtcCount @49 :UInt32; + clockResets @50 :UInt32; + } +} + +struct LidarPts { + r @0 :List(UInt16); # uint16 m*500.0 + theta @1 :List(UInt16); # uint16 deg*100.0 + reflect @2 :List(UInt8); # uint8 0-255 + + # For storing out of file. + idx @3 :UInt64; + + # For storing in file + pkt @4 :Data; +} + +struct ProcLog { + cpuTimes @0 :List(CPUTimes); + mem @1 :Mem; + procs @2 :List(Process); + + struct Process { + pid @0 :Int32; + name @1 :Text; + state @2 :UInt8; + ppid @3 :Int32; + + cpuUser @4 :Float32; + cpuSystem @5 :Float32; + cpuChildrenUser @6 :Float32; + cpuChildrenSystem @7 :Float32; + priority @8 :Int64; + nice @9 :Int32; + numThreads @10 :Int32; + startTime @11 :Float64; + + memVms @12 :UInt64; + memRss @13 :UInt64; + + processor @14 :Int32; + + cmdline @15 :List(Text); + exe @16 :Text; + } + + struct CPUTimes { + cpuNum @0 :Int64; + user @1 :Float32; + nice @2 :Float32; + system @3 :Float32; + idle @4 :Float32; + iowait @5 :Float32; + irq @6 :Float32; + softirq @7 :Float32; + } + + struct Mem { + total @0 :UInt64; + free @1 :UInt64; + available @2 :UInt64; + buffers @3 :UInt64; + cached @4 :UInt64; + active @5 :UInt64; + inactive @6 :UInt64; + shared @7 :UInt64; + } + +} struct Event { + # in nanoseconds? logMonoTime @0 :UInt64; union { @@ -315,5 +922,15 @@ struct Event { gpsLocation @21 :GpsLocationData; carState @22 :Car.CarState; carControl @23 :Car.CarControl; + plan @24 :Plan; + liveLocation @25 :LiveLocationData; + ethernetData @26 :List(EthernetPacket); + navUpdate @27 :NavUpdate; + cellInfo @28 :List(CellInfo); + wifiScan @29 :List(WifiScan); + androidGnss @30 :AndroidGnss; + qcomGnss @31 :QcomGnss; + lidarPts @32 :LidarPts; + procLog @33 :ProcLog; } } diff --git a/common/api/__init__.py b/common/api/__init__.py index ad9833593a..dcb17fdb35 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -1,8 +1,13 @@ import requests -def api_get(endpoint, method='GET', timeout=None, **params): +def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): backend = "https://api.commadotai.com/" - params['_version'] = "OPENPILOTv0.2" + params['_version'] = "OPENPILOTv0.3" + + headers = {} + if access_token is not None: + headers['Authorization'] = "JWT "+access_token + + return requests.request(method, backend+endpoint, timeout=timeout, headers = headers, params=params) - return requests.request(method, backend+endpoint, timeout=timeout, params=params) diff --git a/common/crash.py b/common/crash.py index e57371d0f5..06fe9a9132 100644 --- a/common/crash.py +++ b/common/crash.py @@ -7,6 +7,8 @@ if os.getenv("NOLOG"): pass def bind_user(**kwargs): pass + def bind_extra(**kwargs): + pass def install(): pass else: @@ -21,6 +23,9 @@ else: def bind_user(**kwargs): client.user_context(kwargs) + def bind_extra(**kwargs): + client.extra_context(kwargs) + def install(): # installs a sys.excepthook __excepthook__ = sys.excepthook diff --git a/common/filters.py b/common/filters.py deleted file mode 100644 index bdc4bf791f..0000000000 --- a/common/filters.py +++ /dev/null @@ -1,17 +0,0 @@ -"""Classes for filtering discrete time signals.""" -import numpy as np - - -class FirstOrderLowpassFilter(object): - def __init__(self, fc, dt, x1=0): - self.kf = 2 * np.pi * fc * dt / (1 + 2 * np.pi * fc * dt) - self.x1 = x1 - - def __call__(self, x): - self.x1 = (1 - self.kf) * self.x1 + self.kf * x - - # If previous or current is NaN, reset filter. - if np.isnan(self.x1): - self.x1 = x - - return self.x1 diff --git a/common/fingerprints.py b/common/fingerprints.py new file mode 100644 index 0000000000..cbb85d3082 --- /dev/null +++ b/common/fingerprints.py @@ -0,0 +1,128 @@ + +_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, + # sent messages + 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 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, + # sent messages + 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8, + }, + "HONDA ACCORD 2016 TOURING": { + 1024L: 5, 929L: 8, 1027L: 5, 773L: 7, 1601L: 8, 777L: 8, 1036L: 8, 398L: 3, 1039L: 8, 401L: 8, 145L: 8, 1424L: 5, 660L: 8, 661L: 4, 918L: 7, 985L: 3, 923L: 2, 542L: 7, 927L: 8, 800L: 8, 545L: 4, 420L: 8, 422L: 8, 808L: 8, 426L: 8, 1029L: 8, 432L: 7, 57L: 3, 316L: 8, 829L: 5, 1600L: 5, 1089L: 8, 1057L: 5, 780L: 8, 1088L: 8, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 476L: 4, 1296L: 3, 891L: 8, 1125L: 8, 487L: 4, 892L: 8, 490L: 8, 871L: 8, 1064L: 7, 882L: 2, 884L: 8, 506L: 8, 507L: 1, 380L: 8, 1365L: 5 + } +} + +def eliminate_incompatible_cars(msg, candidate_cars): + """Removes cars that could not have sent msg. + + Inputs: + msg: A cereal/log CanData message from the car. + candidate_cars: A list of cars to consider. + + Returns: + A list containing the subset of candidate_cars that could have sent msg. + """ + compatible_cars = [] + for car_name in candidate_cars: + adr = msg.address + if msg.src != 0 or (adr in _FINGERPRINTS[car_name] and + _FINGERPRINTS[car_name][adr] == len(msg.dat)): + compatible_cars.append(car_name) + else: + pass + #isin = adr in _FINGERPRINTS[car_name] + #print "eliminate", car_name, hex(adr), isin, len(msg.dat), msg.dat.encode("hex") + return compatible_cars + +def all_known_cars(): + """Returns a list of all known car strings.""" + return _FINGERPRINTS.keys() + +# **** for use live only **** +def fingerprint(logcan): + import selfdrive.messaging as messaging + from cereal import car + from common.realtime import sec_since_boot + import os + if os.getenv("SIMULATOR") is not None or logcan is None: + # send message + ret = car.CarParams.new_message() + + ret.carName = "simulator" + ret.radarName = "nidec" + ret.carFingerprint = "THE LOW QUALITY SIMULATOR" + + ret.enableSteer = True + ret.enableBrake = True + ret.enableGas = True + ret.enableCruise = False + + ret.wheelBase = 2.67 + ret.steerRatio = 15.3 + ret.slipFactor = 0.0014 + + ret.steerKp, ret.steerKi = 12.0, 1.0 + return ret + + print "waiting for fingerprint..." + brake_only = True + + candidate_cars = all_known_cars() + finger = {} + st = None + while 1: + for a in messaging.drain_sock(logcan, wait_for_one=True): + if st is None: + st = sec_since_boot() + for can in a.can: + # pedal + if can.address == 0x201 and can.src == 0: + brake_only = False + if can.src == 0: + finger[can.address] = len(can.dat) + candidate_cars = eliminate_incompatible_cars(can, candidate_cars) + + # if we only have one car choice and it's been 100ms since we got our first message, exit + if len(candidate_cars) == 1 and st is not None and (sec_since_boot()-st) > 0.1: + break + elif len(candidate_cars) == 0: + print map(hex, finger.keys()) + raise Exception("car doesn't match any fingerprints") + + print "fingerprinted", candidate_cars[0] + + # send message + ret = car.CarParams.new_message() + + ret.carName = "honda" + ret.radarName = "nidec" + ret.carFingerprint = candidate_cars[0] + + ret.enableSteer = True + ret.enableBrake = True + ret.enableGas = not brake_only + ret.enableCruise = brake_only + #ret.enableCruise = False + + ret.wheelBase = 2.67 + ret.steerRatio = 15.3 + ret.slipFactor = 0.0014 + + if candidate_cars[0] == "HONDA CIVIC 2016 TOURING": + ret.steerKp, ret.steerKi = 12.0, 1.0 + elif candidate_cars[0] == "ACURA ILX 2016 ACURAWATCH PLUS": + if not brake_only: + # assuming if we have an interceptor we also have a torque mod + ret.steerKp, ret.steerKi = 6.0, 0.5 + else: + ret.steerKp, ret.steerKi = 12.0, 1.0 + elif candidate_cars[0] == "HONDA ACCORD 2016 TOURING": + ret.steerKp, ret.steerKi = 12.0, 1.0 + else: + raise ValueError("unsupported car %s" % candidate_cars[0]) + + return ret + diff --git a/common/params.py b/common/params.py new file mode 100755 index 0000000000..6f58901f65 --- /dev/null +++ b/common/params.py @@ -0,0 +1,285 @@ +#!/usr/bin/env python +"""ROS has a parameter server, we have files. + +The parameter store is a persistent key value store, implemented as a directory with a writer lock. +On Android, we store params under params_dir = /data/params. The writer lock is a file +"/.lock" taken using flock(), and data is stored in a directory symlinked to by +"/d". + +Each key, value pair is stored as a file with named with contents , located in + /d/ + +Readers of a single key can just open("/d/") and read the file contents. +Readers who want a consistent snapshot of multiple keys should take the lock. + +Writers should take the lock before modifying anything. Writers should also leave the DB in a +consistent state after a crash. The implementation below does this by copying all params to a temp +directory /, then atomically symlinking / to / +before deleting the old / directory. + +Writers that only modify a single key can simply take the lock, then swap the corresponding value +file in place without messing with /d. +""" +import time +import os +import errno +import sys +import shutil +import fcntl +import tempfile +from enum import Enum + +def mkdirs_exists_ok(path): + try: + os.makedirs(path) + except OSError: + if not os.path.isdir(path): + raise + +class TxType(Enum): + PERSISTANT = 1 + CLEAR_ON_MANAGER_START = 2 + CLEAR_ON_CAR_START = 3 + +class UnknownKeyName(Exception): + pass + +keys = { +# written: manager +# read: loggerd, uploaderd, baseui + "DongleId": TxType.PERSISTANT, + "AccessToken": TxType.PERSISTANT, + "Version": TxType.PERSISTANT, + "GitCommit": TxType.PERSISTANT, + "GitBranch": TxType.PERSISTANT, +# written: visiond +# read: visiond + "CalibrationParams": TxType.PERSISTANT, +# written: visiond +# read: visiond, ui + "CloudCalibration": TxType.PERSISTANT, +# written: controlsd +# read: radard + "CarParams": TxType.CLEAR_ON_CAR_START} + + +class FileLock(object): + def __init__(self, path, create): + self._path = path + self._create = create + self._fd = None + + def acquire(self): + self._fd = os.open(self._path, os.O_CREAT if self._create else 0) + fcntl.flock(self._fd, fcntl.LOCK_EX) + + def release(self): + if self._fd is not None: + os.close(self._fd) + self._fd = None + + +class DBAccessor(object): + def __init__(self, path): + self._path = path + self._vals = None + + def keys(self): + self._check_entered() + return self._vals.keys() + + def get(self, key): + self._check_entered() + try: + return self._vals[key] + except KeyError: + return None + + def _get_lock(self, create): + lock = FileLock(os.path.join(self._path, ".lock"), create) + lock.acquire() + return lock + + def _read_values_locked(self): + """Callers should hold a lock while calling this method.""" + vals = {} + try: + data_path = self._data_path() + keys = os.listdir(data_path) + for key in keys: + with open(os.path.join(data_path, key), "rb") as f: + vals[key] = f.read() + except (OSError, IOError) as e: + # Either the DB hasn't been created yet, or somebody wrote a bug and left the DB in an + # inconsistent state. Either way, return empty. + if e.errno == errno.ENOENT: + return {} + + return vals + + def _data_path(self): + return os.path.join(self._path, "d") + + def _check_entered(self): + if self._vals is None: + raise Exception("Must call __enter__ before using DB") + + +class DBReader(DBAccessor): + def __enter__(self): + try: + lock = self._get_lock(False) + except OSError as e: + # Do not create lock if it does not exist. + if e.errno == errno.ENOENT: + self._vals = {} + return self + + try: + # Read everything. + self._vals = self._read_values_locked() + return self + finally: + lock.release() + + def __exit__(self, type, value, traceback): pass + + +class DBWriter(DBAccessor): + def __init__(self, path): + super(DBWriter, self).__init__(path) + self._lock = None + self._prev_umask = None + + def put(self, key, value): + self._vals[key] = value + + def delete(self, key): + self._vals.pop(key, None) + + def __enter__(self): + mkdirs_exists_ok(self._path) + + # Make sure we can write and that permissions are correct. + self._prev_umask = os.umask(0) + + try: + os.chmod(self._path, 0o777) + self._lock = self._get_lock(True) + self._vals = self._read_values_locked() + except: + os.umask(self._prev_umask) + self._prev_umask = None + raise + + return self + + def __exit__(self, type, value, traceback): + self._check_entered() + + try: + old_data_path = None + new_data_path = None + tempdir_path = tempfile.mkdtemp(prefix=".tmp", dir=self._path) + try: + # Write back all keys. + os.chmod(tempdir_path, 0o777) + for k, v in self._vals.items(): + with open(os.path.join(tempdir_path, k), "wb") as f: + f.write(v) + + data_path = self._data_path() + try: + old_data_path = os.path.join(self._path, os.readlink(data_path)) + except (OSError, IOError) as e: + # NOTE(mgraczyk): If other DB implementations have bugs, this could cause + # copies to be left behind, but we still want to overwrite. + pass + + new_data_path = "{}.link".format(tempdir_path) + os.symlink(os.path.basename(tempdir_path), new_data_path) + os.rename(new_data_path, data_path) + # TODO(mgraczyk): raise useful error when values are bad. + except: + shutil.rmtree(tempdir_path) + if new_data_path is not None: + os.remove(new_data_path) + raise + + # Keep holding the lock while we clean up the old data. + if old_data_path is not None: + shutil.rmtree(old_data_path) + finally: + os.umask(self._prev_umask) + self._prev_umask = None + + # Always release the lock. + self._lock.release() + self._lock = None + + + +class JSDB(object): + def __init__(self, fn): + self._fn = fn + + def begin(self, write=False): + if write: + return DBWriter(self._fn) + else: + return DBReader(self._fn) + +class Params(object): + def __init__(self, db='/data/params'): + self.env = JSDB(db) + + def _clear_keys_with_type(self, tx_type): + with self.env.begin(write=True) as txn: + for key in keys: + if keys[key] == tx_type: + txn.delete(key) + + def manager_start(self): + self._clear_keys_with_type(TxType.CLEAR_ON_MANAGER_START) + + def car_start(self): + self._clear_keys_with_type(TxType.CLEAR_ON_CAR_START) + + def get(self, key, block=False): + if key not in keys: + raise UnknownKeyName(key) + + while 1: + with self.env.begin() as txn: + ret = txn.get(key) + if not block or ret is not None: + break + # is polling really the best we can do? + time.sleep(0.05) + return ret + + def put(self, key, dat): + if key not in keys: + raise UnknownKeyName(key) + + with self.env.begin(write=True) as txn: + txn.put(key, dat) + print "set", key + +if __name__ == "__main__": + params = Params() + if len(sys.argv) > 2: + params.put(sys.argv[1], sys.argv[2]) + else: + for k in keys: + pp = params.get(k) + if pp is None: + print k, "is None" + elif all(ord(c) < 128 and ord(c) >= 32 for c in pp): + print k, pp + else: + print k, pp.encode("hex") + + # Test multiprocess: + # seq 0 100000 | xargs -P20 -I{} python common/params.py DongleId {} && sleep 0.05 + # while python common/params.py DongleId; do sleep 0.05; done diff --git a/common/realtime.py b/common/realtime.py index 7a6a072218..282e662220 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -19,24 +19,19 @@ class timespec(ctypes.Structure): ] libc_name = find_library('c') -if libc_name is None: - platform_name = platform.system() - if platform_name.startswith('linux'): - libc_name = 'libc.so.6' - if platform_name.startswith(('freebsd', 'netbsd')): - libc_name = 'libc.so' - elif platform_name.lower() == 'darwin': - libc_name = 'libc.dylib' - -try: - libc = ctypes.CDLL(libc_name, use_errno=True) -except OSError: - libc = None - -if libc is not None: +libc = ctypes.CDLL(libc_name, use_errno=True) + +if hasattr(libc, 'clock_gettime'): libc.clock_gettime.argtypes = [ctypes.c_int, ctypes.POINTER(timespec)] + has_clock_gettime = True +else: + has_clock_gettime = False def clock_gettime(clk_id): + if not has_clock_gettime: + # hack. only for OS X < 10.12 + return time.time() + t = timespec() if libc.clock_gettime(clk_id, ctypes.pointer(t)) != 0: errno_ = ctypes.get_errno() diff --git a/common/services.py b/common/services.py deleted file mode 100644 index 1c85cd82ed..0000000000 --- a/common/services.py +++ /dev/null @@ -1,90 +0,0 @@ -# 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), - "carState": Service(8021, True), - # 8022 is reserved for sshd - "carControl": Service(8023, True), -} - -# manager -- base process to manage starting and stopping of all others -# subscribes: health -# publishes: thermal - -# **** processes that communicate with the outside world **** - -# boardd -- communicates with the car -# subscribes: sendcan -# publishes: can, health - -# sensord -- publishes the IMU and GPS -# publishes: sensorEvents, gpsNMEA - -# visiond -- talks to the cameras, runs the model, saves the videos -# subscribes: liveCalibration, sensorEvents -# publishes: frame, encodeIdx, model, features - -# **** stateful data transformers **** - -# controlsd -- actually drives the car -# subscribes: can, thermal, model, live20 -# publishes: carState, carControl, sendcan, live100 - -# radard -- processes the radar data -# subscribes: can, live100, model -# publishes: live20, liveTracks - -# 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/acura_ilx_2016_can.dbc b/dbcs/acura_ilx_2016_can.dbc index 6bf6d55870..24e4817740 100644 --- a/dbcs/acura_ilx_2016_can.dbc +++ b/dbcs/acura_ilx_2016_can.dbc @@ -100,7 +100,7 @@ BO_ 419 GEARBOX: 8 PCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO @@ -155,13 +155,13 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-328) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-328) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-656) [0|1] "" NEO + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO diff --git a/dbcs/honda_accord_touring_2016_can.dbc b/dbcs/honda_accord_touring_2016_can.dbc new file mode 100644 index 0000000000..0ab55c7277 --- /dev/null +++ b/dbcs/honda_accord_touring_2016_can.dbc @@ -0,0 +1,305 @@ +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_: + +BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB + + +BO_ 57 XXX_1: 3 XXX + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO + +BO_ 344 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 380 POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_LIGHTS_ON : 32|1@0+ (1,0) [0|1] "rpm" NEO + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 427 XXX_3: 3 VSA + +BO_ 428 XXX_4: 8 XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + +BO_ 450 XXX_5: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 470 XXX_6: 2 VSA + +BO_ 476 XXX_7: 7 XXX + +BO_ 487 XXX_8: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO + +BO_ 493 XXX_9: 5 VSA + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM + SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM + +BO_ 512 GAS_COMMAND: 3 NEO + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-328) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-328) [0|1] "" NEO + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-656) [0|1] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + +BO_ 545 XXX_10: 6 XXX + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" NEO + SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO + +BO_ 660 SCM_COMMANDS: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO + +BO_ 662 CRUISE_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + +BO_ 777 XXX_11: 8 XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 795 XXX_12: 8 XXX + +BO_ 800 XXX_13: 8 XXX + +BO_ 804 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO + SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 808 XXX_14: 8 XXX + +BO_ 829 LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY + +BO_ 862 XXX_15: 8 ADAS + SG_ UI_ALERTS : 7|56@0+ (1,0) [0|127] "" BDY + +BO_ 884 XXX_16: 8 XXX + +BO_ 891 XXX_17: 8 XXX + +BO_ 892 XXX_18: 8 XXX + +BO_ 927 XXX_19: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 22|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + +BO_ 929 XXX_20: 8 XXX + +BO_ 985 XXX_21: 3 XXX + +BO_ 1024 XXX_22: 5 XXX + +BO_ 1027 XXX_23: 5 XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1036 XXX_24: 8 XXX + +BO_ 1039 XXX_25: 8 XXX + +BO_ 1108 XXX_26: 8 XXX + +BO_ 1302 XXX_27: 8 XXX + +BO_ 1322 XXX_28: 5 XXX + +BO_ 1361 XXX_29: 5 XXX + +BO_ 1365 XXX_30: 5 XXX + +BO_ 1424 XXX_31: 5 XXX + +BO_ 1600 XXX_32: 5 XXX + +BO_ 1601 XXX_33: 8 XXX + +BO_ 1633 XXX_34: 8 XXX + +BO_TX_BU_ 228 : NEO,ADAS; +BO_TX_BU_ 506 : NEO,ADAS; +BO_TX_BU_ 780 : NEO,ADAS; +BO_TX_BU_ 829 : NEO,ADAS; +BO_TX_BU_ 862 : NEO,ADAS; +BO_TX_BU_ 927 : NEO,ADAS; + diff --git a/dbcs/honda_civic_touring_2016_can.dbc b/dbcs/honda_civic_touring_2016_can.dbc index 6e60df3fa5..ddf2d2699c 100644 --- a/dbcs/honda_civic_touring_2016_can.dbc +++ b/dbcs/honda_civic_touring_2016_can.dbc @@ -98,7 +98,7 @@ BO_ 401 GEARBOX: 8 PCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO @@ -194,7 +194,7 @@ BO_ 773 SEATBELT_STATUS: 7 BDY BO_ 777 XXX_11: 8 XXX BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY + SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY diff --git a/dbcs/tesla_can.dbc b/dbcs/tesla_can.dbc new file mode 100644 index 0000000000..84e8d7b24d --- /dev/null +++ b/dbcs/tesla_can.dbc @@ -0,0 +1,405 @@ +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_: + +BU_: + NEO + MCU + GTW + EPAS + DI + ESP + SBW + STW + +VAL_TABLE_ StW_AnglHP_Spd 16383 "SNA" ; +VAL_TABLE_ DI_aebFaultReason 15 "DI_AEB_FAULT_DAS_REQ_DI_UNAVAIL" 14 "DI_AEB_FAULT_ACCEL_REQ_INVALID" 13 "DI_AEB_FAULT_MIN_TIME_BTWN_EVENTS" 12 "DI_AEB_FAULT_ESP_MIA" 11 "DI_AEB_FAULT_ESP_FAULT" 10 "DI_AEB_FAULT_EPB_NOT_PARKED" 9 "DI_AEB_FAULT_ACCEL_OUT_OF_BOUNDS" 8 "DI_AEB_FAULT_PM_REQUEST" 7 "DI_AEB_FAULT_VEL_EST_ABNORMAL" 6 "DI_AEB_FAULT_DAS_SNA" 5 "DI_AEB_FAULT_DAS_CONTROL_MIA" 4 "DI_AEB_FAULT_SPEED_DELTA" 3 "DI_AEB_FAULT_EBR_FAULT" 2 "DI_AEB_FAULT_PM_MIA" 1 "DI_AEB_FAULT_EPB_MIA" 0 "DI_AEB_FAULT_NONE" ; +VAL_TABLE_ DI_aebLockState 3 "AEB_LOCK_STATE_SNA" 2 "AEB_LOCK_STATE_UNUSED" 1 "AEB_LOCK_STATE_UNLOCKED" 0 "AEB_LOCK_STATE_LOCKED" ; +VAL_TABLE_ DI_aebSmState 7 "DI_AEB_STATE_FAULT" 6 "DI_AEB_STATE_EXIT" 5 "DI_AEB_STATE_STANDSTILL" 4 "DI_AEB_STATE_STOPPING" 3 "DI_AEB_STATE_ENABLE" 2 "DI_AEB_STATE_ENABLE_INIT" 1 "DI_AEB_STATE_STANDBY" 0 "DI_AEB_STATE_UNAVAILABLE" ; +VAL_TABLE_ DI_aebState 7 "AEB_CAN_STATE_SNA" 4 "AEB_CAN_STATE_FAULT" 3 "AEB_CAN_STATE_STANDSTILL" 2 "AEB_CAN_STATE_ENABLED" 1 "AEB_CAN_STATE_STANDBY" 0 "AEB_CAN_STATE_UNAVAILABLE" ; +VAL_TABLE_ DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ; +VAL_TABLE_ DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_TABLE_ DI_gpoReason 8 "DI_GPO_NUMREASONS" 7 "DI_GPO_CAPACITOR_OVERTEMP" 6 "DI_GPO_NOT_ENOUGH_12V" 5 "DI_GPO_NO_BATTERY_POWER" 4 "DI_GPO_AMBIENT_OVERTEMP" 3 "DI_GPO_FLUID_DELTAT" 2 "DI_GPO_STATOR_OVERTEMP" 1 "DI_GPO_HEATSINK_OVERTEMP" 0 "DI_GPO_OUTLET_OVERTEMP" ; +VAL_TABLE_ DI_immobilizerCondition 1 "DI_IMM_CONDITION_LEARNED" 0 "DI_IMM_CONDITION_VIRGIN_SNA" ; +VAL_TABLE_ DI_immobilizerState 7 "DI_IMM_STATE_FAULT" 6 "DI_IMM_STATE_FAULTRETRY" 5 "DI_IMM_STATE_RESET" 4 "DI_IMM_STATE_LEARN" 3 "DI_IMM_STATE_DISARMED" 2 "DI_IMM_STATE_AUTHENTICATING" 1 "DI_IMM_STATE_REQUEST" 0 "DI_IMM_STATE_INIT_SNA" ; +VAL_TABLE_ DI_limpReason 24 "DI_LIMP_NUMREASONS" 23 "DI_LIMP_CAPACITOR_OVERTEMP" 22 "DI_LIMP_GTW_MIA" 21 "DI_LIMP_TRQCMD_VALIDITY_UNKNOWN" 20 "DI_LIMP_DI_MIA" 19 "DI_LIMP_CONFIG_MISMATCH" 18 "DI_LIMP_HEATSINK_TEMP" 17 "DI_LIMP_PMREQUEST" 16 "DI_LIMP_PMHEARTBEAT" 15 "DI_LIMP_TRQ_CROSS_CHECK" 14 "DI_LIMP_EXTERNAL_COMMAND" 13 "DI_LIMP_WRONG_CS_CALIBRATION" 12 "DI_LIMP_STATOR_TEMP" 11 "DI_LIMP_DELTAT_TOO_NEGATIVE" 10 "DI_LIMP_DELTAT_TOO_POSITIVE" 9 "DI_LIMP_AMBIENT_TEMP" 8 "DI_LIMP_OUTLET_TEMP" 7 "DI_LIMP_LOW_FLOW" 6 "DI_LIMP_BMS_MIA" 5 "DI_LIMP_12V_SUPPLY_UNDERVOLTAGE" 4 "DI_LIMP_NO_FLUID" 3 "DI_LIMP_NO_FUNC_HEATSINK_SENSOR" 2 "DI_LIMP_NO_FUNC_STATORT_SENSOR" 1 "DI_LIMP_BUSV_SENSOR_IRRATIONAL" 0 "DI_LIMP_PHASE_IMBALANCE" ; +VAL_TABLE_ DI_mode 2 "DI_MODE_DYNO" 1 "DI_MODE_DRIVE" 0 "DI_MODE_UNDEF" ; +VAL_TABLE_ DI_motorType 14 "DI_MOTOR_F2AE" 13 "DI_MOTOR_F2AD" 12 "DI_MOTOR_F2AC" 11 "DI_MOTOR_F2AB" 10 "DI_MOTOR_F1AC" 9 "DI_MOTOR_SSR1A" 8 "DI_MOTOR_F1A" 7 "DI_MOTOR_M7M6" 6 "DI_MOTOR_M8A" 5 "DI_MOTOR_M7M5" 4 "DI_MOTOR_M7M4" 3 "DI_MOTOR_M7M3" 2 "DI_MOTOR_ROADSTER_SPORT" 1 "DI_MOTOR_ROADSTER_BASE" 0 "DI_MOTOR_SNA" ; +VAL_TABLE_ DI_speedUnits 1 "DI_SPEED_KPH" 0 "DI_SPEED_MPH" ; +VAL_TABLE_ DI_state 4 "DI_STATE_ENABLE" 3 "DI_STATE_FAULT" 2 "DI_STATE_CLEAR_FAULT" 1 "DI_STATE_STANDBY" 0 "DI_STATE_PREAUTH" ; +VAL_TABLE_ DI_velocityEstimatorState 4 "VE_STATE_BACKUP_MOTOR" 3 "VE_STATE_BACKUP_WHEELS_B" 2 "VE_STATE_BACKUP_WHEELS_A" 1 "VE_STATE_WHEELS_NORMAL" 0 "VE_STATE_NOT_INITIALIZED" ; + + +BO_ 1160 DAS_steeringControl: 4 NEO + SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" EPAS + SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|0] "" EPAS + +BO_ 257 GTW_epasControl: 3 NEO + SG_ GTW_epasControlChecksum : 16|8@1+ (1,0) [0|255] "" NEO + SG_ GTW_epasControlCounter : 12|4@1+ (1,0) [0|15] "" NEO + SG_ GTW_epasControlType : 8|2@1+ (1,0) [4|-1] "" NEO + SG_ GTW_epasEmergencyOn : 0|1@1+ (1,0) [2|-1] "" NEO + SG_ GTW_epasLDWEnabled : 11|1@1+ (1,0) [2|-1] "" NEO + SG_ GTW_epasPowerMode : 1|4@1+ (1,0) [4|14] "" NEO + SG_ GTW_epasTuneRequest : 5|3@1+ (1,0) [8|-1] "" NEO + +BO_ 880 EPAS_sysStatus: 8 EPAS + SG_ EPAS_currentTuneMode : 0|4@1+ (1,0) [8|15] "" NEO + SG_ EPAS_eacErrorCode : 16|4@1+ (1,0) [16|-1] "" NEO + SG_ EPAS_eacStatus : 48|3@1+ (1,0) [5|7] "" NEO + SG_ EPAS_handsOnLevel : 32|2@1+ (1,0) [4|-1] "" NEO + SG_ EPAS_internalSAS : 37|14@0+ (0.10,-819.200010) [0|0] "deg" NEO + SG_ EPAS_steeringFault : 5|1@1+ (1,0) [2|-1] "" NEO + SG_ EPAS_steeringRackForce : 1|10@0+ (50,-25575) [0|0] "N" NEO + SG_ EPAS_steeringReduced : 4|1@1+ (1,0) [2|-1] "" NEO + SG_ EPAS_sysStatusChecksum : 56|8@1+ (1,0) [0|255] "" NEO + SG_ EPAS_sysStatusCounter : 52|4@1+ (1,0) [0|15] "" NEO + SG_ EPAS_torsionBarTorque : 19|12@0+ (0.010,-20.50) [0|0] "Nm" NEO + +BO_ 3 STW_ANGL_STAT: 8 STW + SG_ CRC_STW_ANGL_STAT : 56|8@1+ (1,0) [0|255] "" NEO + SG_ MC_STW_ANGL_STAT : 52|4@1+ (1,0) [0|15] "" NEO + SG_ StW_Angl : 5|14@0+ (0.50,-2048) [0|0] "deg" NEO + SG_ StW_AnglSens_Id : 36|2@1+ (1,0) [3|3] "" NEO + SG_ StW_AnglSens_Stat : 38|2@1+ (1,0) [4|-1] "" NEO + SG_ StW_AnglSpd : 21|14@0+ (0.50,-2048) [0|0] "/s" NEO + +BO_ 14 STW_ANGLHP_STAT: 8 GTW + SG_ StW_AnglHP : 5|14@0+ (0.1,-819.2) [-819.2|819] "deg" NEO + SG_ StW_AnglHP_Spd : 21|14@0+ (0.5,-4096) [-4096|4095.5] "deg/s" NEO + SG_ StW_AnglHP_Sens_Stat : 33|2@0+ (1,0) [0|0] "" NEO + SG_ StW_AnglHP_Sens_Id : 35|2@0+ (1,0) [0|0] "" NEO + SG_ MC_STW_ANGLHP_STAT : 55|4@0+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ANGLHP_STAT : 63|8@0+ (1,0) [0|0] "" NEO + +BO_ 264 DI_torque1: 8 DI + SG_ DI_torqueDriver : 0|13@1- (0.25,0) [-750|750] "Nm" NEO + SG_ DI_torque1Counter : 13|3@1+ (1,0) [0|0] "" NEO + SG_ DI_torqueMotor : 16|13@1- (0.25,0) [-750|750] "Nm" NEO + SG_ DI_soptState : 29|3@1+ (1,0) [0|0] "" NEO + SG_ DI_motorRPM : 32|16@1- (1,0) [-17000|17000] "RPM" NEO + SG_ DI_pedalPos : 48|8@1+ (0.4,0) [0|100] "%" NEO + SG_ DI_torque1Checksum : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 280 DI_torque2: 6 DI + SG_ DI_torqueEstimate : 0|12@1- (0.5,0) [-750|750] "Nm" NEO + SG_ DI_gear : 12|3@1+ (1,0) [0|0] "" NEO + SG_ DI_brakePedal : 15|1@1+ (1,0) [0|0] "" NEO + SG_ DI_vehicleSpeed : 16|12@1+ (0.05,-25) [-25|179.75] "MPH" NEO + SG_ DI_gearRequest : 28|3@1+ (1,0) [0|0] "" NEO + SG_ DI_torqueInterfaceFailure : 31|1@1+ (1,0) [0|0] "" NEO + SG_ DI_torque2Counter : 32|4@1+ (1,0) [0|0] "" NEO + SG_ DI_brakePedalState : 36|2@1+ (1,0) [0|0] "" NEO + SG_ DI_epbParkRequest : 38|1@1+ (1,0) [0|0] "" NEO + SG_ DI_epbInterfaceReady : 39|1@1+ (1,0) [0|0] "" NEO + SG_ DI_torque2Checksum : 40|8@1+ (1,0) [0|0] "" NEO + +BO_ 309 ESP_135h: 5 ESP + SG_ ESP_135hChecksum : 16|8@1+ (1,0) [0|255] "" NEO + SG_ ESP_135hCounter : 12|4@1+ (1,0) [0|15] "" NEO + SG_ ESP_absBrakeEvent : 5|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_brakeDiscWipingActive : 3|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_brakeLamp : 4|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_espFaultLamp : 1|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_espLampFlash : 0|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_hillStartAssistActive : 6|2@1+ (1,0) [4|-1] "" NEO + SG_ ESP_messagePumpService : 31|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_messagePumpFailure : 30|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_messageEBDFailure : 29|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_absFaultLamp : 28|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_tcDisabledByFault : 27|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_messageDynoModeActive : 26|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_hydraulicBoostEnabled : 25|1@1+ (1,0) [0|1] "" NEO + SG_ ESP_espOffLamp : 24|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_stabilityControlSts : 9|3@1+ (1,0) [6|7] "" NEO + SG_ ESP_tcLampFlash : 2|1@1+ (1,0) [2|-1] "" NEO + SG_ ESP_tcOffLamp : 8|1@1+ (1,0) [0|1] "" NEO + +BO_ 792 GTW_carState: 8 GTW + SG_ BOOT_STATE : 40|2@1+ (1,0) [4|-1] "" NEO + SG_ CERRD : 0|1@1+ (1,0) [2|-1] "" NEO + SG_ DAY : 35|5@1+ (1,0) [2|31] "" NEO + SG_ DOOR_STATE_FL : 10|2@1+ (1,0) [4|-1] "" NEO + SG_ DOOR_STATE_FR : 8|2@1+ (1,0) [4|-1] "" NEO + SG_ DOOR_STATE_FrontTrunk : 52|2@1+ (1,0) [4|-1] "" NEO + SG_ DOOR_STATE_RL : 16|2@1+ (1,0) [4|-1] "" NEO + SG_ DOOR_STATE_RR : 25|2@1+ (1,0) [4|-1] "" NEO + SG_ GTW_updateInProgress : 54|2@1+ (1,0) [4|-1] "" NEO + SG_ Hour : 27|5@1+ (1,0) [0|29] "h" NEO + SG_ MCU_factoryMode : 51|1@1+ (1,0) [2|-1] "" NEO + SG_ MCU_transportModeOn : 50|1@1+ (1,0) [1|1] "" NEO + SG_ MINUTE : 42|6@1+ (1,0) [0|61] "min" NEO + SG_ MONTH : 12|4@1+ (1,0) [0|14] "Month" NEO + SG_ SECOND : 18|6@1+ (1,0) [0|61] "s" NEO + SG_ YEAR : 1|7@1+ (1,2000) [2000|2125] "Year" NEO + +BO_ 872 DI_state: 8 DI + SG_ DI_aebState : 44|3@1+ (1,0) [5|6] "" NEO + SG_ DI_analogSpeed : 20|12@1+ (0.10,0) [0|409.40] "speed" NEO + SG_ DI_cruiseSet : 39|9@1+ (0.50,0) [0|255.50] "speed" NEO + SG_ DI_cruiseState : 8|4@1+ (1,0) [8|15] "" NEO + SG_ DI_digitalSpeed : 48|8@1+ (1,0) [0|254] "" NEO + SG_ DI_driveReady : 0|1@1+ (1,0) [0|1] "" NEO + SG_ DI_immobilizerState : 25|3@1+ (1,0) [7|7] "" NEO + SG_ DI_proximity : 1|1@1+ (1,0) [0|1] "" NEO + SG_ DI_regenLight : 15|1@1+ (1,0) [0|1] "" NEO + SG_ DI_speedUnits : 24|1@1+ (1,0) [2|-1] "" NEO + SG_ DI_state : 12|3@1+ (1,0) [5|7] "" NEO + SG_ DI_stateChecksum : 56|8@1+ (1,0) [0|255] "" NEO + SG_ DI_stateCounter : 40|4@1+ (1,0) [0|15] "" NEO + SG_ DI_systemState : 5|3@1+ (1,0) [5|7] "" NEO + SG_ DI_vehicleHoldState : 2|3@1+ (1,0) [8|-1] "" NEO + +BO_ 109 SBW_RQ_SCCM: 4 STW + SG_ StW_Sw_Stat3 : 0|3@1+ (1,0) [0|0] "" NEO + SG_ MsgTxmtId : 6|2@1+ (1,0) [0|0] "" NEO + SG_ TSL_RND_Posn_StW : 8|4@1+ (1,0) [0|0] "" NEO + SG_ TSL_P_Psd_StW : 12|2@1+ (1,0) [0|0] "" NEO + SG_ MC_SBW_RQ_SCCM : 20|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_SBW_RQ_SCCM : 24|8@1+ (1,0) [0|0] "" NEO + +BO_ 69 STW_ACTN_RQ: 8 STW + SG_ SpdCtrlLvr_Stat : 0|6@1+ (1,0) [0|0] "" NEO + SG_ VSL_Enbl_Rq : 6|1@1+ (1,0) [0|0] "" NEO + SG_ SpdCtrlLvrStat_Inv : 7|1@1+ (1,0) [0|0] "" NEO + SG_ DTR_Dist_Rq : 8|8@1+ (1,0) [0|200] "" NEO + SG_ TurnIndLvr_Stat : 16|2@1+ (1,0) [0|0] "" NEO + SG_ HiBmLvr_Stat : 18|2@1+ (1,0) [0|0] "" NEO + SG_ WprWashSw_Psd : 20|2@1+ (1,0) [0|0] "" NEO + SG_ WprWash_R_Sw_Posn_V2 : 22|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Lvr_Stat : 24|3@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Flt : 27|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Psd : 28|2@1+ (1,0) [0|0] "" NEO + SG_ HrnSw_Psd : 30|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw00_Psd : 32|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw01_Psd : 33|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw02_Psd : 34|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw03_Psd : 35|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw04_Psd : 36|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw05_Psd : 37|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw06_Psd : 38|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw07_Psd : 39|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw08_Psd : 40|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw09_Psd : 41|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw10_Psd : 42|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw11_Psd : 43|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw12_Psd : 44|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw13_Psd : 45|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw14_Psd : 46|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw15_Psd : 47|1@1+ (1,0) [0|0] "" NEO + SG_ WprSw6Posn : 48|3@1+ (1,0) [0|0] "" NEO + SG_ MC_STW_ACTN_RQ : 52|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ACTN_RQ : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 643 BODY_R1: 8 GTW + SG_ AirTemp_Insd : 40|8@1+ (0.25,0) [0|63.5] "C" NEO + SG_ AirTemp_Outsd : 56|8@1+ (0.5,-40) [-40|86.5] "C" NEO + SG_ Bckl_Sw_RL_Stat_SAM_R : 54|2@1+ (1,0) [4|-1] "" NEO + SG_ Bckl_Sw_RM_Stat_SAM_R : 50|2@1+ (1,0) [4|-1] "" NEO + SG_ Bckl_Sw_RR_Stat_SAM_R : 52|2@1+ (1,0) [4|-1] "" NEO + SG_ DL_RLtch_Stat : 14|2@1+ (1,0) [4|-1] "" NEO + SG_ DrRLtch_FL_Stat : 6|2@1+ (1,0) [4|-1] "" NEO + SG_ DrRLtch_FR_Stat : 4|2@1+ (1,0) [4|-1] "" NEO + SG_ DrRLtch_RL_Stat : 2|2@1+ (1,0) [4|-1] "" NEO + SG_ DrRLtch_RR_Stat : 0|2@1+ (1,0) [4|-1] "" NEO + SG_ EngHd_Stat : 12|2@1+ (1,0) [4|-1] "" NEO + SG_ LoBm_On_Rq : 39|1@1+ (1,0) [0|1] "" NEO + SG_ HiBm_On : 38|1@1+ (1,0) [0|1] "" NEO + SG_ Hrn_On : 29|1@1+ (1,0) [0|1] "" NEO + SG_ IrLmp_D_Lt_Flt : 37|1@1+ (1,0) [0|1] "" NEO + SG_ IrLmp_P_Rt_Flt : 36|1@1+ (1,0) [0|1] "" NEO + SG_ LgtSens_Twlgt : 21|3@1+ (1,0) [0|7] "Steps" NEO + SG_ LgtSens_SNA : 20|1@1+ (1,0) [0|1] "" NEO + SG_ LgtSens_Tunnel : 19|1@1+ (1,0) [0|1] "" NEO + SG_ LgtSens_Flt : 18|1@1+ (1,0) [0|1] "" NEO + SG_ LgtSens_Night : 17|1@1+ (1,0) [2|-1] "" NEO + SG_ ADL_LoBm_On_Rq : 16|1@1+ (1,0) [0|1] "" NEO + SG_ LoBm_D_Lt_Flt : 35|1@1+ (1,0) [0|1] "" NEO + SG_ LoBm_P_Rt_Flt : 34|1@1+ (1,0) [0|1] "" NEO + SG_ MPkBrk_Stat : 27|1@1+ (1,0) [2|-1] "" NEO + SG_ RevGr_Engg : 32|2@1+ (1,0) [4|-1] "" NEO + SG_ StW_Cond_Stat : 48|2@1+ (1,0) [4|-1] "" NEO + SG_ Term54_Actv : 28|1@1+ (1,0) [0|1] "" NEO + SG_ Trlr_Stat : 30|2@1+ (1,0) [4|-1] "" NEO + SG_ VTA_Alm_Actv : 10|1@1+ (1,0) [0|1] "" NEO + SG_ WprOutsdPkPosn : 26|1@1+ (1,0) [0|1] "" NEO + +BO_ 760 MCU_gpsVehicleSpeed: 8 MCU + SG_ MCU_gpsHDOP : 0|8@1+ (0.10,0) [0|25.50] "1" NEO + SG_ MCU_gpsVehicleHeading : 8|16@1+ (0.007810,0) [0|511.828350] "deg" NEO + SG_ MCU_gpsVehicleSpeed : 24|16@1+ (0.003910,0) [0|256.241850] "km/hr" NEO + SG_ MCU_mppSpeedLimit : 51|5@1+ (5,0) [0|155] "kph/mph" NEO + SG_ MCU_speedLimitUnits : 41|1@1+ (1,0) [2|-1] "" NEO + SG_ MCU_userSpeedOffset : 42|6@1+ (1,-30) [-30|33] "kph/mph" NEO + SG_ MCU_userSpeedOffsetUnits : 40|1@1+ (1,0) [2|-1] "" NEO + +BO_ 904 MCU_clusterBacklightRequest: 3 NEO + SG_ MCU_clusterBacklightOn : 7|1@1+ (1,0) [0|1] "" NEO + SG_ MCU_clusterBrightnessLevel : 8|8@1+ (0.5,0) [0|127.5] "%" NEO + SG_ MCU_clusterReadyForDrive : 6|1@1+ (1,0) [2|-1] "" NEO + SG_ MCU_clusterReadyForPowerOff : 5|1@1+ (1,0) [0|1] "" NEO + +BO_ 984 MCU_locationStatus: 8 MCU + SG_ MCU_gpsAccuracy : 56|7@1+ (0.200000003,0) [0|25.200000378] "m" NEO + SG_ MCU_latitude : 0|28@1- (0.000001,0) [-134.21772759734682|134.21772659734683] "deg" NEO + SG_ MCU_longitude : 28|28@1- (0.000001,0) [-268.43545519469365|268.43545419469365] "deg" NEO + +BO_ 840 GTW_status: 8 GTW + SG_ GTW_accGoingDown : 1|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_accRailReq : 15|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_brakePressed : 6|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_driveGoingDown : 0|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_driveRailReq : 7|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_driverIsLeaving : 2|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_driverPresent : 5|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_hvacGoingDown : 12|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_hvacRailReq : 14|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_icPowerOff : 3|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_notEnough12VForDrive : 4|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_preconditionRequest : 13|1@1+ (1,0) [0|1] "" NEO + SG_ GTW_statusChecksum : 56|8@1+ (1,0) [0|255] "" NEO + SG_ GTW_statusCounter : 52|4@1+ (1,0) [0|15] "" NEO + +VAL_ 3 StW_Angl 16383 "SNA" ; +VAL_ 3 StW_AnglSens_Id 2 "MUST" 0 "PSBL" 1 "SELF" ; +VAL_ 3 StW_AnglSens_Stat 2 "ERR" 3 "ERR_INI" 1 "INI" 0 "OK" ; +VAL_ 3 StW_AnglSpd 16383 "SNA" ; +VAL_ 14 StW_AnglHP 16383 "SNA" ; +VAL_ 14 StW_AnglHP_Spd 16383 "SNA" ; +VAL_ 14 StW_AnglHP_Sens_Stat 3 "SNA" 2 "ERR" 1 "INI" 0 "OK" ; +VAL_ 14 StW_AnglHP_Sens_Id 3 "SNA" 2 "KOSTAL" 1 "DELPHI" 0 "TEST" ; +VAL_ 69 SpdCtrlLvr_Stat 32 "DN_1ST" 16 "UP_1ST" 8 "DN_2ND" 4 "UP_2ND" 2 "RWD" 1 "FWD" 0 "IDLE" ; +VAL_ 69 DTR_Dist_Rq 255 "SNA" 200 "ACC_DIST_7" 166 "ACC_DIST_6" 133 "ACC_DIST_5" 100 "ACC_DIST_4" 66 "ACC_DIST_3" 33 "ACC_DIST_2" 0 "ACC_DIST_1" ; +VAL_ 69 TurnIndLvr_Stat 3 "SNA" 2 "RIGHT" 1 "LEFT" 0 "IDLE" ; +VAL_ 69 HiBmLvr_Stat 3 "SNA" 2 "HIBM_FLSH_ON_PSD" 1 "HIBM_ON_PSD" 0 "IDLE" ; +VAL_ 69 WprWashSw_Psd 3 "SNA" 2 "WASH" 1 "TIPWIPE" 0 "NPSD" ; +VAL_ 69 WprWash_R_Sw_Posn_V2 3 "SNA" 2 "WASH" 1 "INTERVAL" 0 "OFF" ; +VAL_ 69 StW_Lvr_Stat 4 "STW_BACK" 3 "STW_FWD" 2 "STW_DOWN" 1 "STW_UP" 0 "NPSD" ; +VAL_ 69 StW_Cond_Psd 3 "SNA" 2 "DOWN" 1 "UP" 0 "NPSD" ; +VAL_ 69 HrnSw_Psd 3 "SNA" 2 "NDEF2" 1 "PSD" 0 "NPSD" ; +VAL_ 69 StW_Sw00_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw01_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw03_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw04_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 WprSw6Posn 7 "SNA" 6 "STAGE2" 5 "STAGE1" 4 "INTERVAL4" 3 "INTERVAL3" 2 "INTERVAL2" 1 "INTERVAL1" 0 "OFF" ;VAL_ 257 GTW_epasControlType 0 "WITHOUT" 1 "WITH_ANGLE" 3 "WITH_BOTH" 2 "WITH_TORQUE" ; +VAL_ 109 StW_Sw_Stat3 7 "SNA" 6 "NDEF6" 5 "NDEF5" 4 "NDEF4" 3 "PLUS_MINUS" 2 "MINUS" 1 "PLUS" 0 "NPSD" ; +VAL_ 109 MsgTxmtId 3 "NDEF3" 2 "NDEF2" 1 "SCCM" 0 "EWM" ; +VAL_ 109 TSL_RND_Posn_StW 15 "SNA" 8 "D" 6 "INI" 4 "N_DOWN" 2 "N_UP" 1 "R" 0 "IDLE" ; +VAL_ 109 TSL_P_Psd_StW 3 "SNA" 2 "INI" 1 "PSD" 0 "IDLE" ; +VAL_ 257 GTW_epasEmergencyOn 1 "EMERGENCY_POWER" 0 "NONE" ; +VAL_ 257 GTW_epasLDWEnabled 1 "ALLOWED" 0 "INHIBITED" ; +VAL_ 257 GTW_epasPowerMode 0 "DRIVE_OFF" 1 "DRIVE_ON" 3 "LOAD_SHED" 2 "SHUTTING_DOWN" 15 "SNA" ; +VAL_ 257 GTW_epasTuneRequest 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "SNA" ; +VAL_ 264 DI_torqueDriver -4096 "SNA" ; +VAL_ 264 DI_torqueMotor -4096 "SNA" ; +VAL_ 264 DI_soptState 7 "SOPT_TEST_SNA" 4 "SOPT_TEST_NOT_RUN" 3 "SOPT_TEST_PASSED" 2 "SOPT_TEST_FAILED" 1 "SOPT_TEST_IN_PROGRESS" 0 "SOPT_PRE_TEST" ; +VAL_ 264 DI_motorRPM -32768 "SNA" ; +VAL_ 264 DI_pedalPos 255 "SNA" ; +VAL_ 280 DI_torqueEstimate -2048 "SNA" ; +VAL_ 280 DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_ 280 DI_brakePedal 1 "Applied" 0 "Not_applied" ; +VAL_ 280 DI_vehicleSpeed 4095 "SNA" ; +VAL_ 280 DI_gearRequest 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_ 280 DI_torqueInterfaceFailure 1 "TORQUE_INTERFACE_FAILED" 0 "TORQUE_INTERFACE_NORMAL" ; +VAL_ 280 DI_brakePedalState 3 "SNA" 2 "INVALID" 1 "ON" 0 "OFF" ; +VAL_ 280 DI_epbParkRequest 1 "Park_requested" 0 "No_request" ; +VAL_ 280 DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ; +VAL_ 309 ESP_absBrakeEvent 1 "ACTIVE" 0 "NOT_ACTIVE" ; +VAL_ 309 ESP_brakeDiscWipingActive 1 "ACTIVE" 0 "INACTIVE" ; +VAL_ 309 ESP_brakeLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espFaultLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espLampFlash 1 "FLASH" 0 "OFF" ; +VAL_ 309 ESP_hillStartAssistActive 1 "ACTIVE" 0 "INACTIVE" 2 "NOT_AVAILABLE" 3 "SNA" ; +VAL_ 309 ESP_absFaultLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espOffLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_stabilityControlSts 2 "ENGAGED" 3 "FAULTED" 5 "INIT" 4 "NOT_CONFIGURED" 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_tcLampFlash 1 "FLASH" 0 "OFF" ; +VAL_ 760 MCU_speedLimitUnits 1 "KPH" 0 "MPH" ; +VAL_ 760 MCU_userSpeedOffsetUnits 1 "KPH" 0 "MPH" ; +VAL_ 643 AirTemp_Insd 255 "SNA" ; +VAL_ 643 AirTemp_Outsd 254 "INIT" 255 "SNA" ; +VAL_ 643 Bckl_Sw_RL_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 Bckl_Sw_RM_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 Bckl_Sw_RR_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 DL_RLtch_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_FL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_FR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_RL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_RR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 EngHd_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 LgtSens_Night 0 "DAY" 1 "NIGHT" ; +VAL_ 643 MPkBrk_Stat 1 "ENGG" 0 "RELS" ; +VAL_ 643 RevGr_Engg 0 "DISENGG" 1 "ENGG" 2 "NDEF2" 3 "SNA" ; +VAL_ 643 StW_Cond_Stat 3 "BLINK" 1 "NDEF1" 0 "OFF" 2 "ON" ; +VAL_ 643 Trlr_Stat 2 "NDEF2" 0 "NONE" 1 "OK" 3 "SNA" ; +VAL_ 792 BOOT_STATE 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 CERRD 1 "CAN error detect" 0 "no Can error detected" ; +VAL_ 792 DAY 1 "Init" 0 "SNA" ; +VAL_ 792 DOOR_STATE_FL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_FR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_FrontTrunk 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_RL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_RR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 GTW_updateInProgress 1 "IN_PROGRESS" 2 "IN_PROGRESS_NOT_USED" 3 "IN_PROGRESS_SNA" 0 "NOT_IN_PROGRESS" ; +VAL_ 792 Hour 30 "Init" 31 "SNA" ; +VAL_ 792 MCU_factoryMode 1 "FACTORY_MODE" 0 "NORMAL_MODE" ; +VAL_ 792 MCU_transportModeOn 0 "NORMAL_MODE" ; +VAL_ 792 MINUTE 62 "Init" 63 "SNA" ; +VAL_ 792 MONTH 1 "Init" 15 "SNA" ; +VAL_ 792 SECOND 62 "Init" 63 "SNA" ; +VAL_ 792 YEAR 126 "Init" 127 "SNA" ; +VAL_ 872 DI_aebState 2 "ENABLED" 4 "FAULT" 7 "SNA" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ; +VAL_ 872 DI_analogSpeed 4095 "SNA" ; +VAL_ 872 DI_cruiseState 2 "ENABLED" 5 "FAULT" 0 "OFF" 4 "OVERRIDE" 7 "PRE_CANCEL" 6 "PRE_FAULT" 1 "STANDBY" 3 "STANDSTILL" ; +VAL_ 872 DI_digitalSpeed 255 "SNA" ; +VAL_ 872 DI_immobilizerState 2 "AUTHENTICATING" 3 "DISARMED" 6 "FAULT" 4 "IDLE" 0 "INIT_SNA" 1 "REQUEST" 5 "RESET" ; +VAL_ 872 DI_speedUnits 1 "KPH" 0 "MPH" ; +VAL_ 872 DI_state 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ; +VAL_ 872 DI_systemState 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ; +VAL_ 872 DI_vehicleHoldState 2 "BLEND_IN" 4 "BLEND_OUT" 6 "FAULT" 7 "INIT" 5 "PARK" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ; +VAL_ 880 EPAS_currentTuneMode 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "UNAVAILABLE" ; +VAL_ 880 EPAS_eacErrorCode 14 "EAC_ERROR_EPB_INHIBIT" 3 "EAC_ERROR_HANDS_ON" 7 "EAC_ERROR_HIGH_ANGLE_RATE_REQ" 9 "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY" 6 "EAC_ERROR_HIGH_ANGLE_REQ" 8 "EAC_ERROR_HIGH_ANGLE_SAFETY" 10 "EAC_ERROR_HIGH_MMOT_SAFETY" 11 "EAC_ERROR_HIGH_TORSION_SAFETY" 0 "EAC_ERROR_IDLE" 12 "EAC_ERROR_LOW_ASSIST" 2 "EAC_ERROR_MAX_SPEED" 1 "EAC_ERROR_MIN_SPEED" 13 "EAC_ERROR_PINION_VEL_DIFF" 4 "EAC_ERROR_TMP_FAULT" 5 "EAR_ERROR_MAX_STEER_DELTA" 15 "SNA" ; +VAL_ 880 EPAS_eacStatus 2 "EAC_ACTIVE" 1 "EAC_AVAILABLE" 3 "EAC_FAULT" 0 "EAC_INHIBITED" 4 "SNA" ; +VAL_ 880 EPAS_handsOnLevel 0 "0" 1 "1" 2 "2" 3 "3" ; +VAL_ 880 EPAS_steeringFault 1 "FAULT" 0 "NO_FAULT" ; +VAL_ 880 EPAS_steeringRackForce 1022 "NOT_IN_SPEC" 1023 "SNA" ; +VAL_ 880 EPAS_steeringReduced 0 "NORMAL_ASSIST" 1 "REDUCED_ASSIST" ; +VAL_ 880 EPAS_torsionBarTorque 0 "SEE_SPECIFICATION" 4095 "SNA" 4094 "UNDEFINABLE_DATA" ; +VAL_ 904 MCU_clusterReadyForDrive 0 "NO_SNA" 1 "YES" ; +VAL_ 1160 DAS_steeringAngleRequest 16384 "ZERO_ANGLE" ; +VAL_ 1160 DAS_steeringControlType 1 "ANGLE_CONTROL" 3 "DISABLED" 0 "NONE" 2 "RESERVED" ; +VAL_ 1160 DAS_steeringHapticRequest 1 "ACTIVE" 0 "IDLE" ; diff --git a/panda b/panda new file mode 160000 index 0000000000..49c1e9c3da --- /dev/null +++ b/panda @@ -0,0 +1 @@ +Subproject commit 49c1e9c3da524bf32735e0d2f1cb9df4d62f0e36 diff --git a/phonelibs/capnp-c/include/capnp_c.h b/phonelibs/capnp-c/include/capnp_c.h new file mode 100644 index 0000000000..c55bb8eade --- /dev/null +++ b/phonelibs/capnp-c/include/capnp_c.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6e15562406dbfd526977b4cfadbbfa78d5753be37602da9548c8b892bbd05a88 +size 13180 diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt index 9f6e17cb7c..717a09dedf 100644 --- a/requirements_openpilot.txt +++ b/requirements_openpilot.txt @@ -8,4 +8,5 @@ raven==5.23.0 requests==2.10.0 setproctitle==1.1.10 simplejson==3.8.2 +pyyaml==3.12 -e git+https://github.com/commaai/le_python.git#egg=Logentries diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile index e27459dfb3..d2d3c04e0b 100644 --- a/selfdrive/boardd/Makefile +++ b/selfdrive/boardd/Makefile @@ -2,6 +2,7 @@ CC = clang CXX = clang++ ARCH := $(shell uname -m) +OS := $(shell uname -o) PHONELIBS = ../../phonelibs @@ -23,18 +24,25 @@ JSON_FLAGS = -I$(PHONELIBS)/json/src EXTRA_LIBS = -lusb +ifeq ($(OS),GNU/Linux) +# for Drive PX2 +ZMQ_LIBS = -lczmq -lzmq +CEREAL_LIBS = -lcapnp -lkj -lcapnp_c +EXTRA_LIBS = -lusb-1.0 -lpthread +endif + ifeq ($(ARCH),x86_64) -ZMQ_LIBS = -L$(HOME)/drive/external/zmq/lib/ \ +ZMQ_LIBS = -L$(HOME)/one/external/zmq/lib/ \ -l:libczmq.a -l:libzmq.a -CEREAL_LIBS = -L$(HOME)/drive/external/capnp/lib/ \ - -l:libcapnp.a -l:libkj.a +CEREAL_LIBS = -L$(HOME)/one/external/capnp/lib/ \ + -l:libcapnp.a -l:libcapnp_c.a -l:libkj.a EXTRA_LIBS = -lusb-1.0 -lpthread endif .PHONY: all all: boardd --include ../common/cereal.mk +include ../common/cereal.mk OBJS = boardd.o \ ../common/swaglog.o \ @@ -55,6 +63,7 @@ boardd.o: boardd.cc $(CXX) $(CXXFLAGS) \ -I$(PHONELIBS)/android_system_core/include \ $(CEREAL_CFLAGS) \ + $(CEREAL_CXXFLAGS) \ $(ZMQ_FLAGS) \ -I../ \ -I../../ \ diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 15cea0b4f0..d151845bd3 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -48,6 +48,19 @@ bool usb_connect() { err = libusb_claim_interface(dev_handle, 0); if (err != 0) { return false; } + // power off ESP + libusb_control_transfer(dev_handle, 0xc0, 0xd9, 0, 0, NULL, 0, TIMEOUT); + + // set UART modes for Honda Accord + for (int uart = 2; uart <= 3; uart++) { + // 9600 baud + libusb_control_transfer(dev_handle, 0xc0, 0xe1, uart, 9600, NULL, 0, TIMEOUT); + // even parity + libusb_control_transfer(dev_handle, 0xc0, 0xe2, uart, 1, NULL, 0, TIMEOUT); + // callback 1 + libusb_control_transfer(dev_handle, 0xc0, 0xe3, uart, 1, NULL, 0, TIMEOUT); + } + return true; } @@ -111,7 +124,7 @@ void can_recv(void *s) { 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); + canData[i].setSrc((data[i*4+1] >> 4) & 0xf); } // send to can @@ -124,13 +137,14 @@ void can_health(void *s) { int cnt; // copied from board/main.c - struct health { + struct __attribute__((packed)) health { uint32_t voltage; uint32_t current; uint8_t started; uint8_t controls_allowed; uint8_t gas_interceptor_detected; uint8_t started_signal_detected; + uint8_t started_alt; } health; // recv from board diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py index 2cde2ba663..16715119bb 100755 --- a/selfdrive/boardd/boardd.py +++ b/selfdrive/boardd/boardd.py @@ -2,10 +2,11 @@ import os import struct import zmq +import time import selfdrive.messaging as messaging from common.realtime import Ratekeeper -from common.services import service_list +from selfdrive.services import service_list from selfdrive.swaglog import cloudlog # USB is optional @@ -56,7 +57,7 @@ def __parse_can_buffer(dat): 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)) + ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xF)) return ret def can_send_many(arr): @@ -122,6 +123,19 @@ def boardd_mock_loop(): #print can_msgs +def boardd_test_loop(): + can_init() + cnt = 0 + while 1: + can_send_many([[0xbb,0,"\xaa\xaa\xaa\xaa",0], [0xaa,0,"\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt),1]]) + #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",0]]) + #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) + # recv @ 100hz + can_msgs = can_recv() + print "got %d" % (len(can_msgs)) + time.sleep(0.01) + cnt += 1 + # *** main loop *** def boardd_loop(rate=200): rk = Ratekeeper(rate) @@ -169,6 +183,8 @@ def boardd_loop(rate=200): def main(gctx=None): if os.getenv("MOCK") is not None: boardd_mock_loop() + elif os.getenv("BOARDTEST") is not None: + boardd_test_loop() else: boardd_loop() diff --git a/selfdrive/calibrationd/__init__.py b/selfdrive/calibrationd/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/selfdrive/calibrationd/calibration.py b/selfdrive/calibrationd/calibration.py deleted file mode 100644 index cd5daa6ff4..0000000000 --- a/selfdrive/calibrationd/calibration.py +++ /dev/null @@ -1,208 +0,0 @@ -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 deleted file mode 100755 index 9ae83da3f3..0000000000 --- a/selfdrive/calibrationd/calibrationd.py +++ /dev/null @@ -1,121 +0,0 @@ -#!/usr/bin/env python -from __future__ import print_function - -import os -import numpy as np -import tempfile -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_TMP_DIR = "/sdcard" -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): - try: - # 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()] - return 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]) - except Exception as e: - print("Could not load calibration file: {}".format(e)) - - return ViewCalibrator( - (I.X, I.Y), big_box_size, vp_img, warp_matrix_start, vp_f=vp_guess) - -def store_calibration(calib): - # Tempfile needs to be on the same device as the calbration file. - with tempfile.NamedTemporaryFile(delete=False, dir=CALIBRATION_TMP_DIR) as cal_file: - print(calib.cal_cycle, file=cal_file) - print(calib.cal_status, file=cal_file) - print(calib.vp_f[0], file=cal_file) - print(calib.vp_f[1], file=cal_file) - cal_file_name = cal_file.name - os.rename(cal_file_name, CALIBRATION_FILE) - -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_write_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_write_cycle >= 100: - print("writing cal", calib.cal_cycle) - store_calibration(calib) - last_write_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/car/fingerprints.py b/selfdrive/car/fingerprints.py deleted file mode 100644 index b70b3c49fb..0000000000 --- a/selfdrive/car/fingerprints.py +++ /dev/null @@ -1,12 +0,0 @@ -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, - # sent messages - 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 4, - }, - "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, - # sent messages - 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8, - } -} diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index f7d7b72311..21fd6c6509 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -4,7 +4,39 @@ import common.numpy_fast as np 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.drive_helpers import actuator_hystereses, rate_limit +from selfdrive.controls.lib.drive_helpers import rate_limit +from common.numpy_fast import clip, interp + +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 = 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 class AH: #[alert_idx, value] @@ -108,9 +140,9 @@ class CarController(object): 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)) + apply_gas = int(clip(final_gas*GAS_MAX, 0, GAS_MAX-1)) + apply_brake = int(clip(final_brake*BRAKE_MAX, 0, BRAKE_MAX-1)) + apply_steer = int(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 CS.brake_pressed): @@ -156,8 +188,12 @@ class CarController(object): can_sends = [] # Send steering command. - idx = frame % 4 - can_sends.append(hondacan.create_steering_control(apply_steer, idx)) + if CS.accord: + idx = frame % 2 + can_sends.append(hondacan.create_accord_steering_control(apply_steer, idx)) + else: + idx = frame % 4 + can_sends.append(hondacan.create_steering_control(apply_steer, idx)) # Send gas and brake commands. if (frame % 2) == 0: @@ -174,17 +210,17 @@ class CarController(object): # 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)) + can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.civic, CS.accord, idx)) # radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug) - if CS.civic: + if CS.civic or CS.accord: 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)) + can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.civic, CS.accord, idx)) sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 1da53d1f56..da212eb491 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -1,16 +1,13 @@ import numpy as np import selfdrive.messaging as messaging -from selfdrive.boardd.boardd import can_capnp_to_can_list -from selfdrive.config import VehicleParams from common.realtime import sec_since_boot -from selfdrive.car.fingerprints import fingerprints from selfdrive.car.honda.can_parser import CANParser -def get_can_parser(civic, brake_only): +def get_can_parser(CP): # this function generates lists for signal, messages and initial values - if civic: + if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": dbc_f = 'honda_civic_touring_2016_can.dbc' signals = [ ("XMISSION_SPEED", 0x158, 0), @@ -62,7 +59,7 @@ def get_can_parser(civic, brake_only): (0x405, 3), ] - else: + elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": dbc_f = 'acura_ilx_2016_can.dbc' signals = [ ("XMISSION_SPEED", 0x158, 0), @@ -113,72 +110,85 @@ def get_can_parser(civic, brake_only): (0x324, 10), (0x405, 3), ] + elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": + dbc_f = 'honda_accord_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", 0x156, 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), + ("PEDAL_GAS", 0x17C, 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", 0x191, 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), + ("ENGINE_RPM", 0x17C, 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: + if CP.enableGas: 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.can): - # 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: - print finger - 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": + def __init__(self, CP, logcan): + self.civic = False + self.accord = False + if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": self.civic = True - elif self.car_type == "ACURA ILX 2016 ACURAWATCH PLUS": + elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": self.civic = False + elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": + # fake civic + self.accord = True else: - raise ValueError("unsupported car %s" % self.car_type) + raise ValueError("unsupported car %s" % CP.carFingerprint) + + self.brake_only = CP.enableCruise + self.CP = CP # initialize can parser - self.cp = get_can_parser(self.civic, self.brake_only) + self.cp = get_can_parser(CP) self.user_gas, self.user_gas_pressed = 0., 0 @@ -192,12 +202,6 @@ class CarState(object): # 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, self.brake_only, self.torque_mod) - def update(self, can_pub_main): cp = self.cp cp.update_can(can_pub_main) @@ -230,10 +234,14 @@ class CarState(object): # 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'] + if self.accord: + self.steer_error = False + self.steer_not_allowed = False + else: + 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 @@ -243,10 +251,11 @@ class CarState(object): # 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: + if self.CP.enableGas: + # this is a hack 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 + #print self.user_gas, self.user_gas_pressed if self.civic: self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] @@ -258,6 +267,17 @@ class CarState(object): self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x326]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x326]['RIGHT_BLINKER'] + elif self.accord: + self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] + self.gear = 0 # TODO: accord has CVT... needs rev engineering + 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,8] # TODO: 1/P allowed for debug + self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] + self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] + self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] else: self.gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] @@ -269,11 +289,16 @@ class CarState(object): self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.car_gas = cp.vl[0x130]['CAR_GAS'] + if self.accord: + # on the accord, this doesn't seem to include cruise control + self.car_gas = cp.vl[0x17C]['PEDAL_GAS'] + self.steer_override = False + else: + self.car_gas = cp.vl[0x130]['CAR_GAS'] + self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 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'] diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index fe6d9e79d9..3af33de929 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -44,15 +44,39 @@ def create_gas_command(gas_amount, idx): msg = struct.pack("!H", gas_amount) return make_can_msg(0x200, msg, idx, 0) +def create_accord_steering_control(apply_steer, idx): + # TODO: doesn't work for some reason + if apply_steer == 0: + dat = [0, 0, 0x40, 0] + else: + dat = [0,0,0,0] + rp = clip(apply_steer/0xF, -0xFF, 0xFF) + if rp < 0: + rp += 512 + dat[0] |= (rp >> 5) & 0xf + dat[1] |= (rp) & 0x1f + if idx == 1: + dat[0] |= 0x20 + dat[1] |= 0x20 # always + dat[3] = -(dat[0]+dat[1]+dat[2]) & 0x7f + + # not first byte + dat[1] |= 0x80 + dat[2] |= 0x80 + dat[3] |= 0x80 + dat = ''.join(map(chr, dat)) + + return [0,0,dat,8] + 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): +def create_ui_commands(pcm_speed, hud, civic, accord, idx): """Creates an iterable of CAN messages for the UIs.""" commands = [] - pcm_speed_real = np.clip(int(round(pcm_speed / 0.002763889)), 0, + pcm_speed_real = np.clip(int(round(pcm_speed / 0.002759506)), 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) @@ -63,13 +87,14 @@ def create_ui_commands(pcm_speed, hud, civic, idx): if civic: # 2 more msgs msg_0x35e = chr(0) * 7 commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0)) + if civic or accord: 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): +def create_radar_commands(v_ego, civic, accord, 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) @@ -81,6 +106,12 @@ def create_radar_commands(v_ego, civic, idx): msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" # add 8 on idx. commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) + elif accord: + # 0300( 768)( 69) f9008ad0100000ef + # 0301( 769)( 69) 0ed8522256000029 + msg_0x301 = "\x0e\xd8\x52\x22\x56\x00\x00" + # add 0xc on idx? WTF is this? + commands.append(make_can_msg(0x300, msg_0x300, idx + 0xc, 1)) else: msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00" commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 42866569f6..8e81623afc 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -10,7 +10,7 @@ from selfdrive.boardd.boardd import can_capnp_to_can_list from cereal import car import zmq -from common.services import service_list +from selfdrive.services import service_list import selfdrive.messaging as messaging # Car button codes @@ -37,32 +37,36 @@ class BP: class CarInterface(object): - def __init__(self, read_only=False): - context = zmq.Context() - self.logcan = messaging.sub_sock(context, service_list['can'].port) + def __init__(self, CP, logcan, sendcan=None): + self.logcan = logcan + self.CP = CP self.frame = 0 self.can_invalid_count = 0 # *** init the major players *** - self.CS = CarState(self.logcan) + self.CS = CarState(CP, self.logcan) # sending if read only is False - if not read_only: - self.sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + if sendcan is not None: + self.sendcan = sendcan self.CC = CarController() - def getVehicleParams(self): - return self.CS.VP + if self.CS.accord: + self.accord_msg = [] # returns a car.CarState def update(self): # ******************* do can recv ******************* can_pub_main = [] canMonoTimes = [] + for a in messaging.drain_sock(self.logcan): canMonoTimes.append(a.logMonoTime) can_pub_main.extend(can_capnp_to_can_list(a.can, [0,2])) + if self.CS.accord: + self.accord_msg.extend(can_capnp_to_can_list(a.can, [9])) + self.accord_msg = self.accord_msg[-1:] self.CS.update(can_pub_main) # create message @@ -77,7 +81,7 @@ class CarInterface(object): # gas pedal ret.gas = self.CS.car_gas / 256.0 - if self.CS.VP.brake_only: + if not self.CP.enableGas: ret.gasPressed = self.CS.pedal_gas > 0 else: ret.gasPressed = self.CS.user_gas_pressed @@ -89,8 +93,24 @@ class CarInterface(object): # steering wheel # TODO: units ret.steeringAngle = self.CS.angle_steers - ret.steeringTorque = self.CS.cp.vl[0x18F]['STEER_TORQUE_SENSOR'] - ret.steeringPressed = self.CS.steer_override + + if self.CS.accord: + # TODO: move this into the CAN parser + ret.steeringTorque = 0 + if len(self.accord_msg) > 0: + aa = map(lambda x: ord(x)&0x7f, self.accord_msg[0][2]) + if len(aa) != 5 or (-(aa[0]+aa[1]+aa[2]+aa[3]))&0x7f != aa[4]: + print "ACCORD MSG BAD LEN OR CHECKSUM!" + # TODO: throw an error here? + else: + st = ((aa[0]&0xF) << 5) + (aa[1]&0x1F) + if st >= 256: + st = -(512-st) + ret.steeringTorque = st + ret.steeringPressed = abs(ret.steeringTorque) > 20 + else: + ret.steeringTorque = self.CS.cp.vl[0x18F]['STEER_TORQUE_SENSOR'] + ret.steeringPressed = self.CS.steer_override # cruise state ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 @@ -227,12 +247,3 @@ class CarInterface(object): self.frame += 1 return not (c.enabled and not self.CC.controls_allowed) - -if __name__ == "__main__": - CI = CarInterface(read_only=True) - while 1: - cs = CI.update() - print(chr(27) + "[2J") - print cs - time.sleep(0.1) - diff --git a/selfdrive/common/cereal.mk b/selfdrive/common/cereal.mk index f09bfa7722..8f3a3ad6c4 100644 --- a/selfdrive/common/cereal.mk +++ b/selfdrive/common/cereal.mk @@ -1,17 +1,19 @@ CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/include -CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ - -L$(PHONELIBS)/capnp-c/aarch64/lib/ \ - -l:libcapn.a -l:libcapnp.a -l:libkj.a +ifeq ($(CEREAL_LIBS),) + CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -L$(PHONELIBS)/capnp-c/aarch64/lib/ \ + -l:libcapn.a -l:libcapnp.a -l:libkj.a +endif CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o ../../cereal/gen/c/car.capnp.o log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) $(CEREAL_CFLAGS) \ + $(CXX) $(CXXFLAGS) $(CEREAL_CXXFLAGS) \ -c -o '$@' '$<' car.capnp.o: ../../cereal/gen/cpp/car.capnp.c++ @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) $(CEREAL_CFLAGS) \ + $(CXX) $(CXXFLAGS) $(CEREAL_CXXFLAGS) \ -c -o '$@' '$<' diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 25e5d5577a..3b7b726680 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -33,6 +33,10 @@ struct FramebufferState { EGLContext context; }; +extern "C" void framebuffer_set_power(FramebufferState *s, int mode) { + SurfaceComposerClient::setDisplayPowerMode(s->dtoken, mode); +} + extern "C" FramebufferState* framebuffer_init( const char* name, int32_t layer, EGLDisplay *out_display, EGLSurface *out_surface, diff --git a/selfdrive/common/framebuffer.h b/selfdrive/common/framebuffer.h index cac8590398..2fa6e937a2 100644 --- a/selfdrive/common/framebuffer.h +++ b/selfdrive/common/framebuffer.h @@ -14,8 +14,37 @@ FramebufferState* framebuffer_init( EGLDisplay *out_display, EGLSurface *out_surface, int *out_w, int *out_h); +void framebuffer_set_power(FramebufferState *s, int mode); + +/* Display power modes */ +enum { + /* The display is turned off (blanked). */ + HWC_POWER_MODE_OFF = 0, + /* The display is turned on and configured in a low power state + * that is suitable for presenting ambient information to the user, + * possibly with lower fidelity than normal but greater efficiency. */ + HWC_POWER_MODE_DOZE = 1, + /* The display is turned on normally. */ + HWC_POWER_MODE_NORMAL = 2, + /* The display is configured as in HWC_POWER_MODE_DOZE but may + * stop applying frame buffer updates from the graphics subsystem. + * This power mode is effectively a hint from the doze dream to + * tell the hardware that it is done drawing to the display for the + * time being and that the display should remain on in a low power + * state and continue showing its current contents indefinitely + * until the mode changes. + * + * This mode may also be used as a signal to enable hardware-based doze + * functionality. In this case, the doze dream is effectively + * indicating that the hardware is free to take over the display + * and manage it autonomously to implement low power always-on display + * functionality. */ + HWC_POWER_MODE_DOZE_SUSPEND = 3, +}; + + #ifdef __cplusplus } #endif -#endif \ No newline at end of file +#endif diff --git a/selfdrive/common/mutex.h b/selfdrive/common/mutex.h deleted file mode 100644 index ef01359357..0000000000 --- a/selfdrive/common/mutex.h +++ /dev/null @@ -1,13 +0,0 @@ -#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/params.c b/selfdrive/common/params.c new file mode 100644 index 0000000000..0fc8cc53f6 --- /dev/null +++ b/selfdrive/common/params.c @@ -0,0 +1,124 @@ +#include "selfdrive/common/params.h" + +#include "selfdrive/common/util.h" + +#define _GNU_SOURCE +#include +#include +#include +#include + +int write_db_value(const char* params_path, const char* key, const char* value, + size_t value_size) { + int lock_fd = -1; + int tmp_fd = -1; + int result; + char tmp_path[1024]; + char path[1024]; + + // Write value to temp. + result = + snprintf(tmp_path, sizeof(tmp_path), "%s/.tmp_value_XXXXXX", params_path); + if (result < 0) { + goto cleanup; + } + + tmp_fd = mkstemp(tmp_path); + const ssize_t bytes_written = write(tmp_fd, value, value_size); + if (bytes_written != value_size) { + result = -20; + goto cleanup; + } + + result = snprintf(path, sizeof(path), "%s/.lock", params_path); + if (result < 0) { + goto cleanup; + } + lock_fd = open(path, 0); + + result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); + if (result < 0) { + goto cleanup; + } + + // Take lock. + result = flock(lock_fd, LOCK_EX); + if (result < 0) { + goto cleanup; + } + + // Move temp into place. + result = rename(tmp_path, path); + +cleanup: + // Release lock. + if (lock_fd >= 0) { + close(lock_fd); + } + if (tmp_fd >= 0) { + if (result < 0) { + remove(tmp_path); + } + close(tmp_fd); + } + return result; +} + +int read_db_value(const char* params_path, const char* key, char** value, + size_t* value_sz) { + int lock_fd = -1; + int result; + char path[1024]; + + result = snprintf(path, sizeof(path), "%s/.lock", params_path); + if (result < 0) { + goto cleanup; + } + lock_fd = open(path, 0); + + result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); + if (result < 0) { + goto cleanup; + } + + // Take lock. + result = flock(lock_fd, LOCK_EX); + if (result < 0) { + goto cleanup; + } + + // Read value. + // TODO(mgraczyk): If there is a lot of contention, we can release the lock + // after opening the file, before reading. + *value = read_file(path, value_sz); + if (*value == NULL) { + result = -22; + goto cleanup; + } + + // Remove one for null byte. + if (value_sz != NULL) { + *value_sz -= 1; + } + result = 0; + +cleanup: + // Release lock. + if (lock_fd >= 0) { + close(lock_fd); + } + return result; +} + +void read_db_value_blocking(const char* params_path, const char* key, + char** value, size_t* value_sz) { + while (1) { + const int result = read_db_value(params_path, key, value, value_sz); + if (result == 0) { + return; + } else { + // Sleep for 0.1 seconds. + usleep(100000); + } + } +} diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h new file mode 100644 index 0000000000..ca7bd08a33 --- /dev/null +++ b/selfdrive/common/params.h @@ -0,0 +1,35 @@ +#ifndef _SELFDRIVE_COMMON_PARAMS_H_ +#define _SELFDRIVE_COMMON_PARAMS_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +int write_db_value(const char* params_path, const char* key, const char* value, + size_t value_size); + +// Reads a value from the params database. +// Inputs: +// params_path: The path of the database, eg /sdcard/params. +// key: The key to read. +// value: A pointer where a newly allocated string containing the db value will +// be written. +// value_sz: A pointer where the size of value will be written. Does not +// include the NULL terminator. +// +// Returns: Negative on failure, otherwise 0. +int read_db_value(const char* params_path, const char* key, char** value, + size_t* value_sz); + +// Reads a value from the params database, blocking until successful. +// Inputs are the same as read_db_value. +void read_db_value_blocking(const char* params_path, const char* key, + char** value, size_t* value_sz); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif // _SELFDRIVE_COMMON_PARAMS_H_ diff --git a/selfdrive/common/swaglog.c b/selfdrive/common/swaglog.c index 8d31e99522..da4bf2b185 100644 --- a/selfdrive/common/swaglog.c +++ b/selfdrive/common/swaglog.c @@ -1,3 +1,5 @@ +#define _GNU_SOURCE + #include #include #include @@ -48,7 +50,7 @@ static void cloudlog_init() { s.inited = true; } -void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* fmt, ...) { pthread_mutex_lock(&s.lock); cloudlog_init(); @@ -77,7 +79,6 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func 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); diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h index 47f6af6e8b..b972f98d18 100644 --- a/selfdrive/common/swaglog.h +++ b/selfdrive/common/swaglog.h @@ -11,7 +11,7 @@ extern "C" { #endif -void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; void cloudlog_bind(const char* k, const char* v); @@ -21,7 +21,7 @@ void cloudlog_bind(const char* k, const char* v); #endif #define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ - __func__, __DATE__ " " __TIME__, \ + __func__, \ fmt, ## __VA_ARGS__) #define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h index f682c35dee..fab61c2094 100644 --- a/selfdrive/common/timing.h +++ b/selfdrive/common/timing.h @@ -13,7 +13,13 @@ static inline uint64_t nanos_since_boot() { 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; + return t.tv_sec * 1000.0 + t.tv_nsec * 1e-6; +} + +static inline double seconds_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return (double)t.tv_sec + t.tv_nsec * 1e-9;; } static inline uint64_t nanos_since_epoch() { @@ -25,7 +31,7 @@ static inline uint64_t nanos_since_epoch() { static inline double seconds_since_epoch() { struct timespec t; clock_gettime(CLOCK_REALTIME, &t); - return (double)t.tv_sec + t.tv_nsec / 1000000000.0; + return (double)t.tv_sec + t.tv_nsec * 1e-9; } #endif diff --git a/selfdrive/ui/touch.c b/selfdrive/common/touch.c similarity index 100% rename from selfdrive/ui/touch.c rename to selfdrive/common/touch.c diff --git a/selfdrive/ui/touch.h b/selfdrive/common/touch.h similarity index 74% rename from selfdrive/ui/touch.h rename to selfdrive/common/touch.h index de89a71c5f..3767c06dc3 100644 --- a/selfdrive/ui/touch.h +++ b/selfdrive/common/touch.h @@ -1,6 +1,10 @@ #ifndef TOUCH_H #define TOUCH_H +#ifdef __cplusplus +extern "C" { +#endif + typedef struct TouchState { int fd; int last_x, last_y; @@ -9,4 +13,8 @@ typedef struct TouchState { void touch_init(TouchState *s); int touch_poll(TouchState *s, int *out_x, int *out_y); +#ifdef __cplusplus +} +#endif + #endif diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c new file mode 100644 index 0000000000..dbb7bba33a --- /dev/null +++ b/selfdrive/common/util.c @@ -0,0 +1,27 @@ +#include +#include +#include +#include + +void* read_file(const char* path, size_t* out_len) { + FILE* f = fopen(path, "r"); + if (!f) { + return NULL; + } + fseek(f, 0, SEEK_END); + long f_len = ftell(f); + rewind(f); + + char* buf = malloc(f_len + 1); + assert(buf); + memset(buf, 0, f_len + 1); + size_t num_read = fread(buf, f_len, 1, f); + assert(num_read == 1); + fclose(f); + + if (out_len) { + *out_len = f_len + 1; + } + + return buf; +} diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 3bf3e9e387..0089f1bf3b 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -19,4 +19,8 @@ #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +// Returns NULL on failure, otherwise the NULL-terminated file contents. +void* read_file(const char* path, size_t* out_len); + + #endif diff --git a/selfdrive/common/utilpp.h b/selfdrive/common/utilpp.h new file mode 100644 index 0000000000..a37f9fdc08 --- /dev/null +++ b/selfdrive/common/utilpp.h @@ -0,0 +1,65 @@ +#ifndef UTILPP_H +#define UTILPP_H + +#include +#include + +#include +#include +#include + +namespace util { + +inline bool starts_with(std::string s, std::string prefix) { + return s.compare(0, prefix.size(), prefix) == 0; +} + +template +inline std::string string_format( const std::string& format, Args ... args ) { + size_t size = snprintf( nullptr, 0, format.c_str(), args ... ) + 1; + std::unique_ptr buf( new char[ size ] ); + snprintf( buf.get(), size, format.c_str(), args ... ); + return std::string( buf.get(), buf.get() + size - 1 ); +} + +inline std::string read_file(std::string fn) { + std::ifstream t(fn); + std::stringstream buffer; + buffer << t.rdbuf(); + return buffer.str(); +} + +inline std::string tohex(const uint8_t* buf, size_t buf_size) { + std::unique_ptr hexbuf(new char[buf_size*2+1]); + for (int i=0; i #include +#include #include #include @@ -115,13 +116,124 @@ int vipc_recv(int fd, VisionPacket *out_p) { return ret; } -int vipc_send(int fd, const VisionPacket p2) { - assert(p2.num_fds <= VIPC_MAX_FDS); +int vipc_send(int fd, const VisionPacket *p2) { + assert(p2->num_fds <= VIPC_MAX_FDS); VisionPacketWire p = { - .type = p2.type, - .d = p2.d, + .type = p2->type, + .d = p2->d, }; - return sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2.fds, p2.num_fds, NULL); + return sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); } +void visionbufs_load(VisionBuf *bufs, const VisionStreamBufs *stream_bufs, + int num_fds, const int* fds) { + for (int i=0; ibuf_len; + bufs[i].addr = mmap(NULL, bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, bufs[i].fd, 0); + // printf("b %d %zu -> %p\n", bufs[i].fd, bufs[i].len, bufs[i].addr); + assert(bufs[i].addr != MAP_FAILED); + } +} + + +int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info) { + int err; + + memset(s, 0, sizeof(*s)); + + s->last_idx = -1; + + s->ipc_fd = vipc_connect(); + if (s->ipc_fd < 0) return -1; + + VisionPacket p = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { + .type = type, + .tbuffer = tbuffer, + }, }, + }; + err = vipc_send(s->ipc_fd, &p); + if (err < 0) { + close(s->ipc_fd); + return -1; + } + + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + close(s->ipc_fd); + return -1; + } + assert(rp.type = VIPC_STREAM_BUFS); + assert(rp.d.stream_bufs.type == type); + + s->bufs_info = rp.d.stream_bufs; + + s->num_bufs = rp.num_fds; + s->bufs = calloc(s->num_bufs, sizeof(VisionBuf)); + assert(s->bufs); + + visionbufs_load(s->bufs, &rp.d.stream_bufs, s->num_bufs, rp.fds); + + if (out_bufs_info) { + *out_bufs_info = s->bufs_info; + } + + return 0; +} + +VisionBuf* visionstream_get(VisionStream *s, VisionBufExtra *out_extra) { + int err; + + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + return NULL; + } + assert(rp.type == VIPC_STREAM_ACQUIRE); + + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp.d.stream_acq.type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + if (err <= 0) { + return NULL; + } + } + + s->last_idx = rp.d.stream_acq.idx; + assert(s->last_idx < s->num_bufs); + + if (out_extra) { + *out_extra = rp.d.stream_acq.extra; + } + + return &s->bufs[s->last_idx]; +} + +void visionstream_destroy(VisionStream *s) { + for (int i=0; inum_bufs; i++) { + if (s->bufs[i].addr) { + munmap(s->bufs[i].addr, s->bufs[i].len); + s->bufs[i].addr = NULL; + close(s->bufs[i].fd); + } + } + if (s->bufs) free(s->bufs); + close(s->ipc_fd); +} diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h index 2e71e0faea..dab392ec54 100644 --- a/selfdrive/common/visionipc.h +++ b/selfdrive/common/visionipc.h @@ -1,39 +1,71 @@ #ifndef VISIONIPC_H #define VISIONIPC_H +#include +#include +#include + #define VIPC_SOCKET_PATH "/tmp/vision_socket" #define VIPC_MAX_FDS 64 +#ifdef __cplusplus +extern "C" { +#endif -#define VISION_INVALID 0 -#define VISION_UI_SUBSCRIBE 1 -#define VISION_UI_BUFS 2 -#define VISION_UI_ACQUIRE 3 -#define VISION_UI_RELEASE 4 +typedef enum VisionIPCPacketType { + VIPC_INVALID = 0, + VIPC_STREAM_SUBSCRIBE, + VIPC_STREAM_BUFS, + VIPC_STREAM_ACQUIRE, + VIPC_STREAM_RELEASE, +} VisionIPCPacketType; -typedef struct VisionUIBufs { - int width, height, stride; - int front_width, front_height, front_stride; +typedef enum VisionStreamType { + VISION_STREAM_UI_BACK, + VISION_STREAM_UI_FRONT, + VISION_STREAM_YUV, + VISION_STREAM_MAX, +} VisionStreamType; +typedef struct VisionUIInfo { int big_box_x, big_box_y; int big_box_width, big_box_height; int transformed_width, transformed_height; int front_box_x, front_box_y; int front_box_width, front_box_height; +} VisionUIInfo; +typedef struct VisionStreamBufs { + VisionStreamType type; + + int width, height, stride; size_t buf_len; - int num_bufs; - size_t front_buf_len; - int num_front_bufs; -} VisionUIBufs; + + union { + VisionUIInfo ui_info; + } buf_info; +} VisionStreamBufs; + +typedef struct VisionBufExtra { + uint32_t frame_id; // only for yuv +} VisionBufExtra; typedef union VisionPacketData { - VisionUIBufs ui_bufs; struct { - bool front; + VisionStreamType type; + bool tbuffer; + } stream_sub; + VisionStreamBufs stream_bufs; + struct { + VisionStreamType type; int idx; - } ui_acq, ui_rel; + VisionBufExtra extra; + } stream_acq; + struct { + VisionStreamType type; + int idx; + } stream_rel; } VisionPacketData; typedef struct VisionPacket { @@ -43,8 +75,34 @@ typedef struct VisionPacket { int fds[VIPC_MAX_FDS]; } VisionPacket; -int vipc_connect(); +int vipc_connect(void); int vipc_recv(int fd, VisionPacket *out_p); -int vipc_send(int fd, const VisionPacket p); +int vipc_send(int fd, const VisionPacket *p); + +typedef struct VisionBuf { + int fd; + size_t len; + void* addr; +} VisionBuf; +void visionbufs_load(VisionBuf *bufs, const VisionStreamBufs *stream_bufs, + int num_fds, const int* fds); + + + +typedef struct VisionStream { + int ipc_fd; + int last_idx; + int num_bufs; + VisionStreamBufs bufs_info; + VisionBuf *bufs; +} VisionStream; + +int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); +VisionBuf* visionstream_get(VisionStream *s, VisionBufExtra *out_extra); +void visionstream_destroy(VisionStream *s); + +#ifdef __cplusplus +} +#endif #endif diff --git a/selfdrive/config.py b/selfdrive/config.py index 451474ded0..440da22746 100644 --- a/selfdrive/config.py +++ b/selfdrive/config.py @@ -10,7 +10,7 @@ class Conversions: KNOTS_TO_MS = 1/1.9438 MS_TO_KNOTS = 1.9438 - # Car tecode decimal minutes into decimal degrees, can work with numpy arrays as input + # Car decode decimal minutes into decimal degrees, can work with numpy arrays as input @staticmethod def dm2d(dm): degs = np.round(dm/100.) @@ -56,19 +56,3 @@ class UIParams: car_back = 1.8796 * lidar_zoom car_color = 110 -class VehicleParams: - def __init__(self, civic, brake_only=False, torque_mod=False): - if civic: - self.wheelbase = 2.67 - self.steer_ratio = 15.3 - self.slip_factor = 0.0014 - self.civic = True - else: - self.wheelbase = 2.67 # from http://www.edmunds.com/acura/ilx/2016/sedan/features-specs/ - self.steer_ratio = 15.3 # from http://www.edmunds.com/acura/ilx/2016/road-test-specs/ - self.slip_factor = 0.0014 - self.civic = False - self.brake_only = brake_only - self.torque_mod = torque_mod - self.ui_speed_fudge = 1.01 if self.civic else 1.025 - diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 02566a8696..11a4a6dc3a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -4,31 +4,25 @@ import zmq import numpy as np import selfdrive.messaging as messaging -from cereal import car +from cereal import car, log +from selfdrive.swaglog import cloudlog from common.numpy_fast import clip +from common.fingerprints import fingerprint from selfdrive.config import Conversions as CV -from common.services import service_list +from selfdrive.services import service_list from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper from common.profiler import Profiler +from common.params import Params from selfdrive.controls.lib.drive_helpers import learn_angle_offset from selfdrive.controls.lib.longcontrol import LongControl from selfdrive.controls.lib.latcontrol import LatControl -from selfdrive.controls.lib.pathplanner import PathPlanner -from selfdrive.controls.lib.adaptivecruise import AdaptiveCruise - from selfdrive.controls.lib.alertmanager import AlertManager -car_type = os.getenv("CAR") -if car_type is not None: - exec('from selfdrive.car.'+car_type+'.interface import CarInterface') -else: - from selfdrive.car.honda.interface import CarInterface - V_CRUISE_MAX = 144 V_CRUISE_MIN = 8 V_CRUISE_DELTA = 8 @@ -42,22 +36,35 @@ def controlsd_thread(gctx, rate=100): #rate in Hz carcontrol = messaging.pub_sock(context, service_list['carControl'].port) thermal = messaging.sub_sock(context, service_list['thermal'].port) - live20 = messaging.sub_sock(context, service_list['live20'].port) - model = messaging.sub_sock(context, service_list['model'].port) health = messaging.sub_sock(context, service_list['health'].port) + plan_sock = messaging.sub_sock(context, service_list['plan'].port) + + logcan = messaging.sub_sock(context, service_list['can'].port) + + # connects to can + CP = fingerprint(logcan) - # connects to can and sendcan - CI = CarInterface() - VP = CI.getVehicleParams() + # import the car from the fingerprint + cloudlog.info("controlsd is importing %s", CP.carName) + exec('from selfdrive.car.'+CP.carName+'.interface import CarInterface') - PP = PathPlanner(model) - AC = AdaptiveCruise(live20) + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + CI = CarInterface(CP, logcan, sendcan) + + # write CarParams + Params().put("CarParams", CP.to_bytes()) AM = AlertManager() LoC = LongControl() LaC = LatControl() + # fake plan + plan = log.Plan.new_message() + plan.lateralValid = False + plan.longitudinalValid = False + last_plan_time = 0 + # controls enabled state enabled = False last_enable_request = 0 @@ -128,7 +135,7 @@ def controlsd_thread(gctx, rate=100): #rate in Hz if b.type == "altButton1" and b.pressed: rear_view_toggle = not rear_view_toggle - if not VP.brake_only and enabled and not b.pressed: + if not CP.enableCruise and enabled and not b.pressed: if b.type == "accelCruise": v_cruise_kph = v_cruise_kph - (v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA elif b.type == "decelCruise": @@ -166,13 +173,6 @@ def controlsd_thread(gctx, rate=100): #rate in Hz prof.checkpoint("Health") - # *** getting model logic *** - PP.update(cur_time, CS.vEgo) - - if rk.frame % 5 == 2: - # *** run this at 20hz again *** - angle_offset = learn_angle_offset(enabled, CS.vEgo, angle_offset, np.asarray(PP.d_poly), LaC.y_des, CS.steeringPressed) - # disable if the pedals are pressed while engaged, this is a user disable if enabled: if CS.gasPressed or CS.brakePressed: @@ -192,60 +192,63 @@ def controlsd_thread(gctx, rate=100): #rate in Hz AM.add("outOfSpace", enabled) enable_request = False - if VP.brake_only: + if CP.enableCruise: enable_condition = ((cur_time - last_enable_request) < 0.2) and CS.cruiseState.enabled else: enable_condition = enable_request + if CP.enableCruise and CS.cruiseState.enabled: + v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH + + prof.checkpoint("AdaptiveCruise") + + # *** what's the plan *** + new_plan = messaging.recv_sock(plan_sock) + if new_plan is not None: + plan = new_plan.plan + plan = plan.as_builder() # plan can change in controls + last_plan_time = cur_time + + # check plan for timeout + if cur_time - last_plan_time > 0.5: + plan.lateralValid = False + plan.longitudinalValid = False + + # gives 18 seconds before decel begins (w 6 minute timeout) + if awareness_status < -0.05: + plan.aTargetMax = min(plan.aTargetMax, -0.2) + plan.aTargetMin = min(plan.aTargetMin, plan.aTargetMax) + if enable_request or enable_condition or enabled: # add all alerts from car for alert in CS.errors: AM.add(alert, enabled) - if AC.dead: + if not plan.longitudinalValid: AM.add("radarCommIssue", enabled) - if PP.dead: - AM.add("modelCommIssue", enabled) + if not plan.lateralValid: + # If the model is not broadcasting, assume that it is because + # the user has uploaded insufficient data for calibration. + # Other cases that would trigger this are rare and unactionable by the user. + AM.add("dataNeeded", enabled) if overtemp: AM.add("overheat", enabled) - prof.checkpoint("Model") - - if enable_condition and not enabled and not AM.alertPresent(): - print "*** enabling controls" - - # beep for enabling - AM.add("enable", enabled) - - # enable both lateral and longitudinal controls - enabled = True - - # on activation, let's always set v_cruise from where we are, even if PCM ACC is active - v_cruise_kph = int(round(max(CS.vEgo * CV.MS_TO_KPH * VP.ui_speed_fudge, 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.vEgo) - - if VP.brake_only and CS.cruiseState.enabled: - v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH - - # *** put the adaptive in adaptive cruise control *** - AC.update(cur_time, CS.vEgo, CS.steeringAngle, LoC.v_pid, awareness_status, VP) - - prof.checkpoint("AdaptiveCruise") + # *** angle offset learning *** + if rk.frame % 5 == 2 and plan.lateralValid: + # *** run this at 20hz again *** + angle_offset = learn_angle_offset(enabled, CS.vEgo, angle_offset, np.asarray(plan.dPoly), LaC.y_des, CS.steeringPressed) # *** gas/brake PID loop *** - final_gas, final_brake = LoC.update(enabled, CS.vEgo, v_cruise_kph, AC.v_target_lead, AC.a_target, AC.jerk_factor, VP) + final_gas, final_brake = LoC.update(enabled, CS.vEgo, v_cruise_kph, + plan.vTarget, + [plan.aTargetMin, plan.aTargetMax], + plan.jerkFactor, CP) # *** steering PID loop *** - final_steer, sat_flag = LaC.update(enabled, CS.vEgo, CS.steeringAngle, CS.steeringPressed, PP.d_poly, angle_offset, VP) + final_steer, sat_flag = LaC.update(enabled, CS.vEgo, CS.steeringAngle, CS.steeringPressed, plan.dPoly, angle_offset, CP) prof.checkpoint("PID") @@ -269,6 +272,26 @@ def controlsd_thread(gctx, rate=100): #rate in Hz else: soft_disable_timer = None + if enable_condition and not enabled and not AM.alertPresent(): + print "*** enabling controls" + + # beep for enabling + AM.add("enable", enabled) + + # enable both lateral and longitudinal controls + enabled = True + + # on activation, let's always set v_cruise from where we are, even if PCM ACC is active + v_cruise_kph = int(round(max(CS.vEgo * CV.MS_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.vEgo) + # *** push the alerts to current *** alert_text_1, alert_text_2, visual_alert, audible_alert = AM.process_alerts(cur_time) @@ -282,14 +305,22 @@ def controlsd_thread(gctx, rate=100): #rate in Hz CC.steeringTorque = float(final_steer) CC.cruiseControl.override = True - CC.cruiseControl.cancel = bool((not VP.brake_only) or (not enabled and CS.cruiseState.enabled)) # always cancel if we have an interceptor - CC.cruiseControl.speedOverride = float((LoC.v_pid - .3) if (VP.brake_only and final_brake == 0.) else 0.0) - CC.cruiseControl.accelOverride = float(AC.a_pcm) + CC.cruiseControl.cancel = bool((not CP.enableCruise) or (not enabled and CS.cruiseState.enabled)) # always cancel if we have an interceptor + + # brake discount removes a sharp nonlinearity + brake_discount = (1.0 - clip(final_brake*3., 0.0, 1.0)) + CC.cruiseControl.speedOverride = float(max(0.0, ((LoC.v_pid - .5) * brake_discount)) if CP.enableCruise else 0.0) + + #CC.cruiseControl.accelOverride = float(AC.a_pcm) + # TODO: fix this + CC.cruiseControl.accelOverride = float(1.0) CC.hudControl.setSpeed = float(v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = enabled CC.hudControl.lanesVisible = enabled - CC.hudControl.leadVisible = bool(AC.has_lead) + #CC.hudControl.leadVisible = bool(AC.has_lead) + # TODO: fix this + CC.hudControl.leadVisible = False CC.hudControl.visualAlert = visual_alert CC.hudControl.audibleAlert = audible_alert @@ -320,8 +351,8 @@ def controlsd_thread(gctx, rate=100): #rate in Hz # what packets were used to process dat.live100.canMonoTimes = list(CS.canMonoTimes) - dat.live100.mdMonoTime = PP.logMonoTime - dat.live100.l20MonoTime = AC.logMonoTime + #dat.live100.mdMonoTime = PP.logMonoTime + #dat.live100.l20MonoTime = AC.logMonoTime # if controls is enabled dat.live100.enabled = enabled @@ -344,10 +375,10 @@ def controlsd_thread(gctx, rate=100): #rate in Hz 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) + dat.live100.vTargetLead = float(plan.vTarget) + dat.live100.aTargetMin = float(plan.aTargetMin) + dat.live100.aTargetMax = float(plan.aTargetMax) + dat.live100.jerkFactor = float(plan.jerkFactor) # lag dat.live100.cumLagMs = -rk.remaining*1000. diff --git a/selfdrive/controls/lib/adaptivecruise.py b/selfdrive/controls/lib/adaptivecruise.py index 8d066080cb..f7a42c8cc9 100644 --- a/selfdrive/controls/lib/adaptivecruise.py +++ b/selfdrive/controls/lib/adaptivecruise.py @@ -19,13 +19,13 @@ def calc_cruise_accel_limits(v_ego): _A_TOTAL_MAX_V = [1.5, 1.9, 3.2] _A_TOTAL_MAX_BP = [0., 20., 40.] -def limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP): +def limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, CP): #*** 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 = 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_y = v_ego**2 * angle_steers * deg_to_rad / (CP.steerRatio * CP.wheelBase) a_x_allowed = math.sqrt(max(a_total_max**2 - a_y**2, 0.)) a_target[1] = min(a_target[1], a_x_allowed) @@ -168,8 +168,9 @@ def calc_acc_accel_limits(d_lead, d_des, v_ego, v_pid, v_lead, v_rel, a_lead, 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) + 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 @@ -236,20 +237,9 @@ def calc_ttc(d_rel, v_rel, a_rel, v_lead): 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 = 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] = min(a_target[1], decel) - a_target[0] = min(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): +def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, CP): # drive limits # TODO: Make lims function of speed (more aggressive at low speed). a_lim = [-3., 1.5] @@ -263,7 +253,7 @@ def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, awareness_statu a_pcm = 1 #*** limit max accel in sharp turns - a_target, a_pcm = limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP) + a_target, a_pcm = limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, CP) jerk_factor = 0. if l1 is not None and l1.status: @@ -305,8 +295,6 @@ def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, awareness_statu 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 @@ -317,7 +305,7 @@ class AdaptiveCruise(object): 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): + def update(self, cur_time, v_ego, angle_steers, v_pid, CP): l20 = messaging.recv_sock(self.live20) if l20 is not None: self.l1 = l20.live20.leadOne @@ -331,5 +319,5 @@ class AdaptiveCruise(object): 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) + compute_speed_with_leads(v_ego, angle_steers, v_pid, self.l1, self.l2, CP) self.has_lead = self.v_target_lead != MAX_SPEED_POSSIBLE diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 57246c54c8..07b13f2991 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -57,6 +57,7 @@ class AlertManager(object): "espDisabled": alert("Take Control Immediately","ESP Off", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), "wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), "outOfSpace": alert("Comma Unavailable","Out of Space", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), + "dataNeeded": alert("Comma Unavailable","Data needed for calibration. Upload drive, try again", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), "ethicalDilemma": alert("Take Control Immediately","Ethical Dilemma Detected", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.), "startup": alert("Always Keep Hands on Wheel","Be Ready to Take Over Any Time", ET.NO_ENTRY, None, None, 0., 0., 15.), } diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index bfa6ca74f1..6c3689ebe7 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,5 +1,5 @@ import numpy as np -from common.numpy_fast import clip, interp +from common.numpy_fast import clip def rate_limit(new_value, last_value, dw_step, up_step): return clip(new_value, last_value + dw_step, last_value + up_step) @@ -21,33 +21,3 @@ def learn_angle_offset(lateral_control, v_ego, angle_offset, d_poly, y_des, stee 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 = 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/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index b7b5c75b3a..8c9003562b 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -2,10 +2,10 @@ import math import numpy as np from common.numpy_fast import clip -def calc_curvature(v_ego, angle_steers, VP, angle_offset=0): +def calc_curvature(v_ego, angle_steers, CP, 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)) + curvature = angle_steers_rad/(CP.steerRatio * CP.wheelBase * (1. + CP.slipFactor * v_ego**2)) return curvature def calc_d_lookahead(v_ego): @@ -19,26 +19,23 @@ def calc_d_lookahead(v_ego): d_lookahead = offset_lookahead + math.sqrt(max(v_ego, 0)) * coeff_lookahead return d_lookahead -def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VP, angle_offset): +def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, CP, 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) + curvature = calc_curvature(v_ego, angle_steers, CP, 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): + steer_override, sat_count, enabled, Kp, Ki, 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 @@ -99,7 +96,7 @@ class LatControl(object): def reset(self): self.Ui_steer = 0. - def update(self, enabled, v_ego, angle_steers, steer_override, d_poly, angle_offset, VP): + def update(self, enabled, v_ego, angle_steers, steer_override, d_poly, angle_offset, CP): rate = 100 steer_max = 1.0 @@ -109,14 +106,14 @@ class LatControl(object): # calculate actual offset at the lookahead point self.y_actual, _ = calc_lookahead_offset(v_ego, angle_steers, - d_lookahead, VP, angle_offset) + d_lookahead, CP, 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( v_ego, self.y_actual, self.y_des, self.Ui_steer, steer_max, - steer_override, self.sat_count, enabled, VP.torque_mod, rate) + steer_override, self.sat_count, enabled, CP.steerKp, CP.steerKi, rate) final_steer = 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 index d6e1c8e819..ec9893293b 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -96,7 +96,7 @@ def pid_long_control(v_ego, v_pid, Ui_accel_cmd, gas_max, brake_max, jerk_factor Kp = interp(v_ego, _KP_BP, _KP_V) Ki = interp(v_ego, _kI_BP, _kI_V) - # scle Kp and Ki by jerk factor drom drive_thread + # scale Kp and Ki by jerk factor from drive_thread Kp = (1. + jerk_factor)*Kp Ki = (1. + jerk_factor)*Ki @@ -155,7 +155,7 @@ class LongControl(object): self.Ui_accel_cmd = 0. self.v_pid = v_pid - def update(self, enabled, v_ego, v_cruise, v_target_lead, a_target, jerk_factor, VP): + def update(self, enabled, v_ego, v_cruise, v_target_lead, a_target, jerk_factor, CP): brake_max_bp = [0., 5., 20., 100.] # speeds brake_max_v = [1.0, 1.0, 0.8, 0.8] # values @@ -163,12 +163,12 @@ class LongControl(object): brake_max = interp(v_ego, brake_max_bp, brake_max_v) # TODO: not every time - if VP.brake_only: - gas_max = 0 - else: + if CP.enableGas: gas_max_bp = [0., 100.] # speeds gas_max_v = [0.6, 0.6] # values gas_max = interp(v_ego, gas_max_bp, gas_max_v) + else: + gas_max = 0 overshoot_allowance = 2.0 # overshoot allowed when changing accel sign @@ -177,7 +177,7 @@ class LongControl(object): # 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 = min(v_target_lead, v_cruise_mph * CV.MPH_TO_MS / VP.ui_speed_fudge) + v_target = min(v_target_lead, v_cruise_mph * CV.MPH_TO_MS) max_speed_delta_up = a_target[1]*1.0/rate max_speed_delta_down = a_target[0]*1.0/rate @@ -211,7 +211,7 @@ class LongControl(object): self.v_pid = v_target # to avoid too much wind up on acceleration, limit positive speed error - if not VP.brake_only: + if CP.enableGas: max_speed_error = interp(v_ego, _MAX_SPEED_ERROR_BP, _MAX_SPEED_ERROR_V) self.v_pid = min(self.v_pid, v_ego + max_speed_error) diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py new file mode 100755 index 0000000000..34594309e1 --- /dev/null +++ b/selfdrive/controls/plannerd.py @@ -0,0 +1,80 @@ +#!/usr/bin/env python +import os +import zmq +import numpy as np +import selfdrive.messaging as messaging + +from selfdrive.services import service_list +from common.realtime import sec_since_boot, set_realtime_priority +from common.params import Params + +from selfdrive.swaglog import cloudlog +from cereal import car + +from selfdrive.controls.lib.pathplanner import PathPlanner +from selfdrive.controls.lib.adaptivecruise import AdaptiveCruise + +def plannerd_thread(gctx): + context = zmq.Context() + poller = zmq.Poller() + + carstate = messaging.sub_sock(context, service_list['carState'].port, poller) + live20 = messaging.sub_sock(context, service_list['live20'].port) + model = messaging.sub_sock(context, service_list['model'].port) + + plan = messaging.pub_sock(context, service_list['plan'].port) + + # wait for stats about the car to come in from controls + cloudlog.info("plannerd is waiting for CarParams") + CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) + cloudlog.info("plannerd got CarParams") + + CS = None + PP = PathPlanner(model) + AC = AdaptiveCruise(live20) + + # start the loop + set_realtime_priority(2) + + # this runs whenever we get a packet that can change the plan + while True: + polld = poller.poll(timeout=1000) + for sock, mode in polld: + if mode != zmq.POLLIN or sock != carstate: + continue + + cur_time = sec_since_boot() + CS = messaging.recv_sock(carstate).carState + + PP.update(cur_time, CS.vEgo) + + # LoC.v_pid -> CS.vEgo + # TODO: is this change okay? + AC.update(cur_time, CS.vEgo, CS.steeringAngle, CS.vEgo, CP) + + # **** send the plan **** + plan_send = messaging.new_message() + plan_send.init('plan') + + # lateral plan + plan_send.plan.lateralValid = not PP.dead + if plan_send.plan.lateralValid: + plan_send.plan.dPoly = map(float, PP.d_poly) + + # longitudal plan + plan_send.plan.longitudinalValid = not AC.dead + if plan_send.plan.longitudinalValid: + plan_send.plan.vTarget = float(AC.v_target_lead) + plan_send.plan.aTargetMin = float(AC.a_target[0]) + plan_send.plan.aTargetMax = float(AC.a_target[1]) + plan_send.plan.jerkFactor = float(AC.jerk_factor) + + plan.send(plan_send.to_bytes()) + + +def main(gctx=None): + plannerd_thread(gctx) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 8bd93186f5..60885b4cb8 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -8,20 +8,18 @@ from collections import defaultdict from fastcluster import linkage_vector import selfdrive.messaging as messaging +from selfdrive.services import service_list from selfdrive.controls.lib.latcontrol import calc_lookahead_offset 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 selfdrive.swaglog import cloudlog -from common.services import service_list +from cereal import car + +from common.params import Params from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper from common.kalman.ekf import EKF, SimpleSensor -radar_type = os.getenv("RADAR") -if radar_type is not None: - exec('from selfdrive.radar.'+car_type+'.interface import RadarInterface') -else: - from selfdrive.radar.nidec.interface import RadarInterface #vision point DIMSV = 2 @@ -49,6 +47,15 @@ class EKFV1D(EKF): def radard_thread(gctx=None): set_realtime_priority(1) + # wait for stats about the car to come in from controls + cloudlog.info("radard is waiting for CarParams") + CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) + cloudlog.info("radard got CarParams") + + # import the radar from the fingerprint + cloudlog.info("radard is importing %s", CP.radarName) + exec('from selfdrive.radar.'+CP.radarName+'.interface import RadarInterface') + context = zmq.Context() # *** subscribe to features and model from visiond @@ -62,10 +69,6 @@ def radard_thread(gctx=None): 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, False) # same for ILX and civic - path_x = np.arange(0.0, 140.0, 0.1) # 140 meters is max # Time-alignment @@ -129,7 +132,7 @@ def radard_thread(gctx=None): 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] + path_y = calc_lookahead_offset(v_ego, steer_angle, path_x, CP, angle_offset=0)[0] # *** remove missing points from meta data *** for ids in tracks.keys(): diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py new file mode 100755 index 0000000000..aeab94ed8e --- /dev/null +++ b/selfdrive/debug/can_printer.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python +import os +import struct +from collections import defaultdict +from common.realtime import sec_since_boot +import zmq +import selfdrive.messaging as messaging +from selfdrive.services import service_list + + +def can_printer(): + context = zmq.Context() + logcan = messaging.sub_sock(context, service_list['can'].port) + + start = sec_since_boot() + lp = sec_since_boot() + msgs = defaultdict(list) + canbus = int(os.getenv("CAN", 0)) + while 1: + can_recv = messaging.drain_sock(logcan, wait_for_one=True) + for x in can_recv: + for y in x.can: + if y.src == canbus: + msgs[y.address].append(y.dat) + + if sec_since_boot() - lp > 0.1: + dd = chr(27) + "[2J" + dd += "%5.2f\n" % (sec_since_boot() - start) + for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): + dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) + print dd + lp = sec_since_boot() + +if __name__ == "__main__": + can_printer() + diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index f6a2c81a8d..2387d299fd 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -5,7 +5,7 @@ import zmq from hexdump import hexdump import selfdrive.messaging as messaging -from common.services import service_list +from selfdrive.services import service_list if __name__ == "__main__": context = zmq.Context() @@ -13,11 +13,11 @@ if __name__ == "__main__": parser = argparse.ArgumentParser(description='Sniff a communcation socket') parser.add_argument('--raw', action='store_true') - parser.add_argument("socket", type=str, - help="socket name") + parser.add_argument("socket", type=str, nargs='*', help="socket name") args = parser.parse_args() - messaging.sub_sock(context, service_list[args.socket].port, poller) + for m in args.socket if len(args.socket) > 0 else service_list: + messaging.sub_sock(context, service_list[m].port, poller) while 1: polld = poller.poll(timeout=1000) diff --git a/selfdrive/debug/test_carcontroller.py b/selfdrive/debug/test_carcontroller.py new file mode 100755 index 0000000000..c94a124e34 --- /dev/null +++ b/selfdrive/debug/test_carcontroller.py @@ -0,0 +1,94 @@ +#!/usr/bin/env python +from evdev import InputDevice +from select import select +import time +import numpy as np +import zmq + +from cereal import car + +import selfdrive.messaging as messaging +from selfdrive.services import service_list +from common.realtime import Ratekeeper + +from common.fingerprints import fingerprint + +if __name__ == "__main__": + # ***** connect to joystick ***** + # we use a Mad Catz V.1 + dev = InputDevice("/dev/input/event8") + print dev + + button_values = [0]*7 + axis_values = [0.0, 0.0, 0.0] + + # ***** connect to car ***** + context = zmq.Context() + logcan = messaging.sub_sock(context, service_list['can'].port) + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + + CP = fingerprint(logcan) + exec('from selfdrive.car.'+CP.carName+'.interface import CarInterface') + + CI = CarInterface(CP, logcan, sendcan) + + rk = Ratekeeper(100) + + while 1: + # **** handle joystick **** + r, w, x = select([dev], [], [], 0.0) + if dev in r: + for event in dev.read(): + # button event + if event.type == 1: + btn = event.code - 288 + if btn >= 0 and btn < 7: + button_values[btn] = int(event.value) + + # axis move event + if event.type == 3: + if event.code < 3: + if event.code == 2: + axis_values[event.code] = np.clip((255-int(event.value))/250.0, 0.0, 1.0) + else: + DEADZONE = 5 + if event.value-DEADZONE < 128 and event.value+DEADZONE > 128: + event.value = 128 + axis_values[event.code] = np.clip((int(event.value)-128)/120.0, -1.0, 1.0) + + print axis_values, button_values + # **** handle car **** + + CS = CI.update() + print CS + + CC = car.CarControl.new_message() + + CC.enabled = True + + CC.gas = float(np.clip(-axis_values[1], 0, 1.0)) + CC.brake = float(np.clip(axis_values[1], 0, 1.0)) + CC.steeringTorque = float(axis_values[0]) + + CC.hudControl.speedVisible = bool(button_values[1]) + CC.hudControl.lanesVisible = bool(button_values[2]) + CC.hudControl.leadVisible = bool(button_values[3]) + + CC.cruiseControl.override = bool(button_values[0]) + CC.cruiseControl.cancel = bool(button_values[-1]) + + CC.hudControl.setSpeed = float(axis_values[2] * 100.0) + + # TODO: test alerts + CC.hudControl.visualAlert = "none" + CC.hudControl.audibleAlert = "none" + + print CC + + if not CI.apply(CC): + print "CONTROLS FAILED" + + rk.keep_time() + + + diff --git a/selfdrive/debug/test_carstate.py b/selfdrive/debug/test_carstate.py new file mode 100755 index 0000000000..114f1446bc --- /dev/null +++ b/selfdrive/debug/test_carstate.py @@ -0,0 +1,53 @@ +#!/usr/bin/env python +import os +import zmq + +import selfdrive.messaging as messaging +from selfdrive.services import service_list + +from common.fingerprints import fingerprint + +def bpressed(CS, btype): + for b in CS.buttonEvents: + if b.type == btype: + return True + return False + +def test_loop(): + context = zmq.Context() + logcan = messaging.sub_sock(context, service_list['can'].port) + + CP = fingerprint(logcan) + exec('from selfdrive.car.'+CP.carName+'.interface import CarInterface') + + CI = CarInterface(CP, logcan, None) + + state = 0 + + states = [ + "'seatbeltNotLatched' in CS.errors", + "CS.gasPressed", + "CS.brakePressed", + "CS.steeringPressed", + "bpressed(CS, 'leftBlinker')", + "bpressed(CS, 'rightBlinker')", + "bpressed(CS, 'cancel')", + "bpressed(CS, 'accelCruise')", + "bpressed(CS, 'decelCruise')", + "bpressed(CS, 'altButton1')", + "'doorOpen' in CS.errors", + "False"] + + while 1: + # read CAN + CS = CI.update() + + while eval(states[state]) == True: + state += 1 + + print "IN STATE %d: waiting for %s" % (state, states[state]) + #print CS + +if __name__ == "__main__": + test_loop() + diff --git a/selfdrive/logcatd/Makefile b/selfdrive/logcatd/Makefile index b22ef1e1c6..0d3423647a 100644 --- a/selfdrive/logcatd/Makefile +++ b/selfdrive/logcatd/Makefile @@ -20,7 +20,7 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ .PHONY: all all: logcatd --include ../common/cereal.mk +include ../common/cereal.mk OBJS = logcatd.o \ $(CEREAL_OBJS) diff --git a/selfdrive/loggerd/Makefile b/selfdrive/loggerd/Makefile new file mode 100644 index 0000000000..bd3038ad7a --- /dev/null +++ b/selfdrive/loggerd/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "loggerd: this is a release" diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index bad8fb0588..be22c2057b 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -1,9 +1,4 @@ import os -# fetch from environment -def get_dongle_id_and_secret(): - return os.getenv("DONGLE_ID"), os.getenv("DONGLE_SECRET") - ROOT = '/sdcard/realdata/' - SEGMENT_LENGTH = 60 diff --git a/selfdrive/loggerd/logger.py b/selfdrive/loggerd/logger.py deleted file mode 100644 index 78af9d4740..0000000000 --- a/selfdrive/loggerd/logger.py +++ /dev/null @@ -1,65 +0,0 @@ -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 b/selfdrive/loggerd/loggerd new file mode 100755 index 0000000000..ecd70bd49c --- /dev/null +++ b/selfdrive/loggerd/loggerd @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:11b28827b7523063614eb82cc2ecd10f015b832eceadf6eaad968bedae9c443e +size 1357136 diff --git a/selfdrive/loggerd/loggerd.py b/selfdrive/loggerd/loggerd.py deleted file mode 100755 index 4ecb100f36..0000000000 --- a/selfdrive/loggerd/loggerd.py +++ /dev/null @@ -1,93 +0,0 @@ -#!/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: - cloudlog.info("loggerd exiting...") - - # tell visiond to stop logging - rotate_msg = messaging.log.LogRotate.new_message() - rotate_msg.segmentNum = -1 - rotate_msg.path = "/dev/null" - vision_control_sock.send(rotate_msg.to_bytes()) - - # stop logging - logger.stop() - -if __name__ == "__main__": - main() - diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index ab3d595fb0..ccaf632528 100755 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -2,6 +2,7 @@ import os import time import stat +import json import random import ctypes import inspect @@ -11,8 +12,9 @@ import threading from collections import Counter from selfdrive.swaglog import cloudlog -from selfdrive.loggerd.config import get_dongle_id_and_secret, ROOT +from selfdrive.loggerd.config import ROOT +from common.params import Params from common.api import api_get fake_upload = os.getenv("FAKEUPLOAD") is not None @@ -66,9 +68,9 @@ def clear_locks(root): class Uploader(object): - def __init__(self, dongle_id, dongle_secret, root): + def __init__(self, dongle_id, access_token, root): self.dongle_id = dongle_id - self.dongle_secret = dongle_secret + self.access_token = access_token self.root = root self.upload_thread = None @@ -125,11 +127,11 @@ class Uploader(object): 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}) + url_resp = api_get("v1.1/"+self.dongle_id+"/upload_url/", timeout=2, path=key, access_token=self.access_token) + url_resp_json = json.loads(url_resp.text) + url = url_resp_json['url'] + headers = url_resp_json['headers'] + cloudlog.info({"upload_url v1.1", url, str(headers)}) if fake_upload: print "*** WARNING, THIS IS A FAKE UPLOAD TO %s ***" % url @@ -139,7 +141,7 @@ class Uploader(object): self.last_resp = FakeResponse() else: with open(fn, "rb") as f: - self.last_resp = requests.put(url, data=f) + self.last_resp = requests.put(url, data=f, headers=headers) except Exception as e: self.last_exc = (e, traceback.format_exc()) raise @@ -223,13 +225,14 @@ class Uploader(object): def uploader_fn(exit_event): cloudlog.info("uploader_fn") - dongle_id, dongle_secret = get_dongle_id_and_secret() + params = Params() + dongle_id, access_token = params.get("DongleId"), params.get("AccessToken") - if dongle_id is None or dongle_secret is None: - cloudlog.info("uploader MISSING DONGLE_ID or DONGLE_SECRET") - raise Exception("uploader can't start without dongle id and secret") + if dongle_id is None or access_token is None: + cloudlog.info("uploader MISSING DONGLE_ID or ACCESS_TOKEN") + raise Exception("uploader can't start without dongle id and access token") - uploader = Uploader(dongle_id, dongle_secret, ROOT) + uploader = Uploader(dongle_id, access_token, ROOT) while True: backoff = 0.1 diff --git a/selfdrive/logmessaged.py b/selfdrive/logmessaged.py index 0dbe6373fb..1ed60e01fa 100755 --- a/selfdrive/logmessaged.py +++ b/selfdrive/logmessaged.py @@ -1,7 +1,7 @@ #!/usr/bin/env python import zmq from logentries import LogentriesHandler -from common.services import service_list +from selfdrive.services import service_list import selfdrive.messaging as messaging def main(gctx): diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 997168679f..db0a8417b5 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -1,5 +1,13 @@ #!/usr/bin/env python import os + +# check if NEOS update is required +while 1: + if (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 3) and not os.path.isfile("/sdcard/noupdate"): + os.system("curl -o /tmp/updater https://openpilot.comma.ai/updater && chmod +x /tmp/updater && /tmp/updater") + else: + break + import sys import time import importlib @@ -8,8 +16,9 @@ import signal import traceback import usb1 from multiprocessing import Process -from common.services import service_list +from selfdrive.services import service_list +import hashlib import zmq from setproctitle import setproctitle @@ -18,8 +27,10 @@ from selfdrive.swaglog import cloudlog import selfdrive.messaging as messaging from selfdrive.thermal import read_thermal from selfdrive.registration import register +from selfdrive.version import version -import common.crash +import common.crash as crash +from common.params import Params from selfdrive.loggerd.config import ROOT @@ -27,11 +38,13 @@ from selfdrive.loggerd.config import ROOT managed_processes = { "uploader": "selfdrive.loggerd.uploader", "controlsd": "selfdrive.controls.controlsd", + "plannerd": "selfdrive.controls.plannerd", "radard": "selfdrive.controls.radard", - "calibrationd": "selfdrive.calibrationd.calibrationd", - "loggerd": "selfdrive.loggerd.loggerd", + "loggerd": ("loggerd", ["./loggerd"]), "logmessaged": "selfdrive.logmessaged", + "tombstoned": "selfdrive.tombstoned", "logcatd": ("logcatd", ["./logcatd"]), + "proclogd": ("proclogd", ["./proclogd"]), "boardd": ("boardd", ["./boardd"]), # switch to c++ boardd "ui": ("ui", ["./ui"]), "visiond": ("visiond", ["./visiond"]), @@ -43,10 +56,24 @@ running = {} unkillable_processes = ['visiond'] # processes to end with SIGINT instead of SIGTERM -interrupt_processes = ['loggerd'] - -car_started_processes = ['controlsd', 'loggerd', 'sensord', 'radard', 'calibrationd', 'visiond'] - +interrupt_processes = [] + +car_started_processes = [ + 'controlsd', + 'plannerd', + 'loggerd', + 'sensord', + 'radard', + 'visiond', + 'proclogd', +] + +def register_managed_process(name, desc, car_started=False): + global managed_processes, car_started_processes + print "registering", name + managed_processes[name] = desc + if car_started: + car_started_processes.append(name) # ****************** process management functions ****************** def launcher(proc, gctx): @@ -64,7 +91,7 @@ def launcher(proc, 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() + crash.capture_exception() raise def nativelauncher(pargs, cwd): @@ -97,37 +124,48 @@ def kill_managed_process(name): return cloudlog.info("killing %s" % name) - if name in interrupt_processes: - os.kill(running[name].pid, signal.SIGINT) - else: - running[name].terminate() - - - # give it 5 seconds to die - running[name].join(5.0) if running[name].exitcode is None: - if name in unkillable_processes: - cloudlog.critical("unkillable process %s failed to exit! rebooting in 15 if it doesn't die" % name) - running[name].join(15.0) - if running[name].exitcode is None: - cloudlog.critical("FORCE REBOOTING PHONE!") - os.system("date > /sdcard/unkillable_reboot") - os.system("reboot") - raise RuntimeError + if name in interrupt_processes: + os.kill(running[name].pid, signal.SIGINT) else: - cloudlog.info("killing %s with SIGKILL" % name) - os.kill(running[name].pid, signal.SIGKILL) - running[name].join() + running[name].terminate() + + # give it 5 seconds to die + running[name].join(5.0) + if running[name].exitcode is None: + if name in unkillable_processes: + cloudlog.critical("unkillable process %s failed to exit! rebooting in 15 if it doesn't die" % name) + running[name].join(15.0) + if running[name].exitcode is None: + cloudlog.critical("FORCE REBOOTING PHONE!") + os.system("date > /sdcard/unkillable_reboot") + os.system("reboot") + raise RuntimeError + else: + cloudlog.info("killing %s with SIGKILL" % name) + os.kill(running[name].pid, signal.SIGKILL) + running[name].join() 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)) + manage_baseui(False) for name in running.keys(): kill_managed_process(name) sys.exit(0) +baseui_running = False +def manage_baseui(start): + global baseui_running + if start and not baseui_running: + os.system("am start -n com.baseui/.MainActivity") + baseui_running = True + elif not start and baseui_running: + os.system("am force-stop com.baseui") + baseui_running = False + # ****************** run loop ****************** def manager_init(): @@ -142,53 +180,54 @@ def manager_init(): # 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) - common.crash.bind_user(dongle_id=dongle_id) + cloudlog.bind_global(dongle_id=dongle_id, version=version) + crash.bind_user(id=dongle_id) + crash.bind_extra(version=version) + + os.system("mkdir -p "+ROOT) # 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] - } - } + gctx = {} def manager_thread(): + global baseui_running + # 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) - version = open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")).read().split('"')[1] - - cloudlog.info("manager start %s" % version) + cloudlog.info("manager start") cloudlog.info(dict(os.environ)) start_managed_process("logmessaged") start_managed_process("logcatd") + start_managed_process("tombstoned") start_managed_process("uploader") start_managed_process("ui") + manage_baseui(True) + panda = False if os.getenv("NOBOARD") is None: # *** wait for the board *** - wait_for_device() + panda = wait_for_device() == 0x2300 # flash the device if os.getenv("NOPROG") is None: - boarddir = os.path.dirname(os.path.abspath(__file__))+"/../board/" - os.system("cd %s && make" % boarddir) + # checkout the matching panda repo + rootdir = os.path.dirname(os.path.abspath(__file__)) + os.system("cd %s && git submodule init && git submodule update" % rootdir) + # flash the board + boarddir = os.path.dirname(os.path.abspath(__file__))+"/../panda/board/" + mkfile = "Makefile" if panda else "Makefile.legacy" + print "using", mkfile + os.system("cd %s && make -f %s" % (boarddir, mkfile)) start_managed_process("boardd") - if os.getenv("STARTALL") is not None: - for p in car_started_processes: - start_managed_process(p) - + started = False logger_dead = False - count = 0 # set 5 second timeout on health socket @@ -231,23 +270,31 @@ def manager_thread(): logger_dead = True # start constellation of processes when the car starts - if not os.getenv("STARTALL"): - # with 2% left, we killall, otherwise the phone is bricked - if td is not None and td.health.started and avail > 0.02: - for p in car_started_processes: - if p == "loggerd" and logger_dead: - kill_managed_process(p) - else: - start_managed_process(p) - else: - logger_dead = False - for p in car_started_processes: + # with 2% left, we killall, otherwise the phone is bricked + if td is not None and td.health.started and avail > 0.02: + if not started: + Params().car_start() + started = True + for p in car_started_processes: + if p == "loggerd" and logger_dead: kill_managed_process(p) + else: + start_managed_process(p) + manage_baseui(False) + else: + manage_baseui(True) + started = False + logger_dead = False + for p in car_started_processes: + kill_managed_process(p) # shutdown if the battery gets lower than 10%, we aren't running, and we are discharging if msg.thermal.batteryPercent < 5 and msg.thermal.batteryStatus == "Discharging": os.system('LD_LIBRARY_PATH="" svc power shutdown') + # check the status of baseui + baseui_running = 'com.baseui' in subprocess.check_output(["ps"]) + # check the status of all processes, did any of them die? for p in running: cloudlog.debug(" running %s %s" % (p, running[p])) @@ -258,14 +305,26 @@ def manager_thread(): running=running.keys(), count=count, health=(td.to_dict() if td else None), - thermal=msg.to_dict(), - version=version) + thermal=msg.to_dict()) count += 1 +def get_installed_apks(): + dat = subprocess.check_output(["pm", "list", "packages", "-3", "-f"]).strip().split("\n") + ret = {} + for x in dat: + if x.startswith("package:"): + v,k = x.split("package:")[1].split("=") + ret[k] = v + return ret # optional, build the c++ binaries and preimport the python for speed def manager_prepare(): + # build cereal first + subprocess.check_call(["make", "-j4"], cwd="../cereal") + + # build all processes + os.chdir(os.path.dirname(os.path.abspath(__file__))) for p in managed_processes: proc = managed_processes[p] if isinstance(proc, basestring): @@ -283,6 +342,33 @@ def manager_prepare(): subprocess.check_call(["make", "clean"], cwd=proc[0]) subprocess.check_call(["make", "-j4"], cwd=proc[0]) + # install apks + installed = get_installed_apks() + for app in os.listdir("../apk/"): + if ".apk" in app: + app = app.split(".apk")[0] + if app not in installed: + installed[app] = None + cloudlog.info("installed apks %s" % (str(installed), )) + for app in installed: + apk_path = "../apk/"+app+".apk" + if os.path.isfile(apk_path): + h1 = hashlib.sha1(open(apk_path).read()).hexdigest() + h2 = None + if installed[app] is not None: + h2 = hashlib.sha1(open(installed[app]).read()).hexdigest() + cloudlog.info("comparing version of %s %s vs %s" % (app, h1, h2)) + if h2 is None or h1 != h2: + cloudlog.info("installing %s" % app) + for do_uninstall in [False, True]: + if do_uninstall: + cloudlog.info("needing to uninstall %s" % app) + os.system("pm uninstall %s" % app) + ret = os.system("cp %s /sdcard/%s.apk && pm install -r /sdcard/%s.apk && rm /sdcard/%s.apk" % (apk_path, app, app, app)) + if ret == 0: + break + assert ret == 0 + def wait_for_device(): while 1: try: @@ -290,11 +376,12 @@ def wait_for_device(): 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): + bcd = device.getbcdDevice() handle = device.open() handle.claimInterface(0) cloudlog.info("found board") handle.close() - return + return bcd except Exception as e: print "exception", e, print "waiting..." @@ -303,6 +390,7 @@ def wait_for_device(): def main(): if os.getenv("NOLOG") is not None: del managed_processes['loggerd'] + del managed_processes['tombstoned'] if os.getenv("NOUPLOAD") is not None: del managed_processes['uploader'] if os.getenv("NOVISION") is not None: @@ -314,10 +402,21 @@ def main(): del managed_processes['loggerd'] del managed_processes['logmessaged'] del managed_processes['logcatd'] + del managed_processes['tombstoned'] + del managed_processes['proclogd'] if os.getenv("NOCONTROL") is not None: del managed_processes['controlsd'] del managed_processes['radard'] + # support additional internal only extensions + try: + import selfdrive.manager_extensions + selfdrive.manager_extensions.register(register_managed_process) + except ImportError: + pass + + params = Params() + params.manager_start() manager_init() manager_prepare() @@ -328,7 +427,7 @@ def main(): manager_thread() except Exception: traceback.print_exc() - common.crash.capture_exception() + crash.capture_exception() finally: cleanup_all_processes(None, None) diff --git a/selfdrive/proclogd/Makefile b/selfdrive/proclogd/Makefile new file mode 100644 index 0000000000..cd970c97e7 --- /dev/null +++ b/selfdrive/proclogd/Makefile @@ -0,0 +1,50 @@ +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 + +.PHONY: all +all: proclogd + +include ../common/cereal.mk + +OBJS = proclogd.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +proclogd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -llog + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + $(CEREAL_CFLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f proclogd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc new file mode 100644 index 0000000000..fbb7704e03 --- /dev/null +++ b/selfdrive/proclogd/proclogd.cc @@ -0,0 +1,245 @@ +#include +#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" +#include "common/utilpp.h" + +namespace { + +struct ProcCache { + std::string name; + std::vector cmdline; + std::string exe; +}; + +} + +int main() { + int err; + + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + err = zmq_bind(publisher, "tcp://*:8031"); + assert(err == 0); + + double jiffy = sysconf(_SC_CLK_TCK); + size_t page_size = sysconf(_SC_PAGE_SIZE); + + std::unordered_map proc_cache; + + while (1) { + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto procLog = event.initProcLog(); + + auto orphanage = msg.getOrphanage(); + + // stat + { + std::vector> otimes; + + std::ifstream sstat("/proc/stat"); + std::string stat_line; + while (std::getline(sstat, stat_line)) { + if (util::starts_with(stat_line, "cpu ")) { + // cpu total + } else if (util::starts_with(stat_line, "cpu")) { + // specific cpu + int id; + unsigned long utime, ntime, stime, itime; + unsigned long iowtime, irqtime, sirqtime; + + int count = sscanf(stat_line.data(), "cpu%d %lu %lu %lu %lu %lu %lu %lu", + &id, &utime, &ntime, &stime, &itime, &iowtime, &irqtime, &sirqtime); + + auto ltimeo = orphanage.newOrphan(); + auto ltime = ltimeo.get(); + ltime.setCpuNum(id); + ltime.setUser(utime / jiffy); + ltime.setNice(ntime / jiffy); + ltime.setSystem(stime / jiffy); + ltime.setIdle(itime / jiffy); + ltime.setIowait(iowtime / jiffy); + ltime.setIrq(irqtime / jiffy); + ltime.setSoftirq(irqtime / jiffy); + + otimes.push_back(std::move(ltimeo)); + + } else { + break; + } + } + + auto ltimes = procLog.initCpuTimes(otimes.size()); + for (size_t i = 0; i < otimes.size(); i++) { + ltimes.adoptWithCaveats(i, std::move(otimes[i])); + } + } + + // meminfo + { + auto mem = procLog.initMem(); + + std::ifstream smem("/proc/meminfo"); + std::string mem_line; + + uint64_t mem_total = 0, mem_free = 0, mem_available = 0, mem_buffers = 0; + uint64_t mem_cached = 0, mem_active = 0, mem_inactive = 0, mem_shared = 0; + + while (std::getline(smem, mem_line)) { + if (util::starts_with(mem_line, "MemTotal:")) sscanf(mem_line.data(), "MemTotal: %lu kB", &mem_total); + else if (util::starts_with(mem_line, "MemFree:")) sscanf(mem_line.data(), "MemFree: %lu kB", &mem_free); + else if (util::starts_with(mem_line, "MemAvailable:")) sscanf(mem_line.data(), "MemAvailable: %lu kB", &mem_available); + else if (util::starts_with(mem_line, "Buffers:")) sscanf(mem_line.data(), "Buffers: %lu kB", &mem_buffers); + else if (util::starts_with(mem_line, "Cached:")) sscanf(mem_line.data(), "Cached: %lu kB", &mem_cached); + else if (util::starts_with(mem_line, "Active:")) sscanf(mem_line.data(), "Active: %lu kB", &mem_active); + else if (util::starts_with(mem_line, "Inactive:")) sscanf(mem_line.data(), "Inactive: %lu kB", &mem_inactive); + else if (util::starts_with(mem_line, "Shmem:")) sscanf(mem_line.data(), "Shmem: %lu kB", &mem_shared); + } + + mem.setTotal(mem_total * 1024); + mem.setFree(mem_free * 1024); + mem.setAvailable(mem_available * 1024); + mem.setBuffers(mem_buffers * 1024); + mem.setCached(mem_cached * 1024); + mem.setActive(mem_active * 1024); + mem.setInactive(mem_inactive * 1024); + mem.setShared(mem_shared * 1024); + } + + // processes + { + std::vector> oprocs; + struct dirent *de = NULL; + DIR *d = opendir("/proc"); + assert(d); + while ((de = readdir(d))) { + if (!isdigit(de->d_name[0])) continue; + pid_t pid = atoi(de->d_name); + + + auto lproco = orphanage.newOrphan(); + auto lproc = lproco.get(); + + lproc.setPid(pid); + + char tcomm[PATH_MAX] = {0}; + + { + std::string stat = util::read_file(util::string_format("/proc/%d/stat", pid)); + + char state; + + int ppid; + unsigned long utime, stime; + long cutime, cstime, priority, nice, num_threads; + unsigned long long starttime; + unsigned long vms, rss; + int processor; + + int count = sscanf(stat.data(), + "%*d (%1024[^)]) %c %d %*d %*d %*d %*d %*d %*d %*d %*d %*d " + "%lu %lu %ld %ld %ld %ld %ld %*d %lld " + "%lu %lu %*d %*d %*d %*d %*d %*d %*d " + "%*d %*d %*d %*d %*d %*d %*d %d", + tcomm, &state, &ppid, + &utime, &stime, &cutime, &cstime, &priority, &nice, &num_threads, &starttime, + &vms, &rss, &processor); + + if (count != 14) continue; + + lproc.setState(state); + lproc.setPpid(ppid); + lproc.setCpuUser(utime / jiffy); + lproc.setCpuSystem(stime / jiffy); + lproc.setCpuChildrenUser(cutime / jiffy); + lproc.setCpuChildrenSystem(cstime / jiffy); + lproc.setPriority(priority); + lproc.setNice(nice); + lproc.setNumThreads(num_threads); + lproc.setStartTime(starttime / jiffy); + lproc.setMemVms(vms); + lproc.setMemRss((uint64_t)rss * page_size); + lproc.setProcessor(processor); + } + + std::string name(tcomm); + lproc.setName(name); + + // populate other things from cache + auto cache_it = proc_cache.find(pid); + ProcCache cache; + if (cache_it != proc_cache.end()) { + cache = cache_it->second; + } + if (cache_it == proc_cache.end() || cache.name != name) { + cache = (ProcCache){ + .name = name, + .exe = util::readlink(util::string_format("/proc/%d/exe", pid)), + }; + + // null-delimited cmdline arguments to vector + std::string cmdline_s = util::read_file(util::string_format("/proc/%d/cmdline", pid)); + const char* cmdline_p = cmdline_s.c_str(); + const char* cmdline_ep = cmdline_p + cmdline_s.size(); + + // strip trailing null bytes + while ((cmdline_ep-1) > cmdline_p && *(cmdline_ep-1) == 0) { + cmdline_ep--; + } + + while (cmdline_p < cmdline_ep) { + std::string arg(cmdline_p); + cache.cmdline.push_back(arg); + cmdline_p += arg.size() + 1; + } + + proc_cache[pid] = cache; + } + + auto lcmdline = lproc.initCmdline(cache.cmdline.size()); + for (size_t i = 0; i < lcmdline.size(); i++) { + lcmdline.set(i, cache.cmdline[i]); + } + lproc.setExe(cache.exe); + + oprocs.push_back(std::move(lproco)); + } + closedir(d); + + auto lprocs = procLog.initProcs(oprocs.size()); + for (size_t i = 0; i < oprocs.size(); i++) { + lprocs.adoptWithCaveats(i, std::move(oprocs[i])); + } + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + + usleep(2000000); // 2 secs + } + + return 0; +} diff --git a/selfdrive/radar/nidec/interface.py b/selfdrive/radar/nidec/interface.py index 061b341494..0a02bc8d1c 100755 --- a/selfdrive/radar/nidec/interface.py +++ b/selfdrive/radar/nidec/interface.py @@ -6,7 +6,7 @@ from selfdrive.boardd.boardd import can_capnp_to_can_list from cereal import car import zmq -from common.services import service_list +from selfdrive.services import service_list import selfdrive.messaging as messaging def _create_radard_can_parser(): diff --git a/selfdrive/registration.py b/selfdrive/registration.py index b2dc5d0146..946d6d722f 100644 --- a/selfdrive/registration.py +++ b/selfdrive/registration.py @@ -3,9 +3,9 @@ import json import subprocess from selfdrive.swaglog import cloudlog +from selfdrive.version import version from common.api import api_get - -DONGLEAUTH_PATH = "/sdcard/dongleauth" +from common.params import Params def get_imei(): # Telephony.getDeviceId() @@ -19,16 +19,28 @@ def get_imei(): def get_serial(): return subprocess.check_output(["getprop", "ro.serialno"]).strip() +def get_git_commit(): + return subprocess.check_output(["git", "rev-parse", "HEAD"]).strip() + +def get_git_branch(): + return subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]).strip() + def register(): + params = Params() 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"] + params.put("Version", version) + params.put("GitCommit", get_git_commit()) + params.put("GitBranch", get_git_branch()) + + dongle_id, access_token = params.get("DongleId"), params.get("AccessToken") + if dongle_id is None or access_token is None: + resp = api_get("v1/pilotauth/", method='POST', imei=get_imei(), serial=get_serial()) + dongleauth = json.loads(resp.text) + dongle_id, access_token = dongleauth["dongle_id"].encode('ascii'), dongleauth["access_token"].encode('ascii') + + params.put("DongleId", dongle_id) + params.put("AccessToken", access_token) + return dongle_id, access_token except Exception: cloudlog.exception("failed to authenticate") return None diff --git a/selfdrive/sensord/Makefile b/selfdrive/sensord/Makefile index ac99cbcb23..98508d8d1a 100644 --- a/selfdrive/sensord/Makefile +++ b/selfdrive/sensord/Makefile @@ -1,51 +1,4 @@ -CC = clang -CXX = clang++ +-include build_from_src.mk -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 - -.PHONY: all -all: sensord - --include ../common/cereal.mk - -OBJS = sensors.o \ - $(CEREAL_OBJS) - -DEPS := $(OBJS:.o=.d) - -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_CFLAGS) \ - $(ZMQ_FLAGS) \ - -I../ \ - -I../../ \ - -c -o '$@' '$<' - -.PHONY: clean -clean: - rm -f sensord $(OBJS) $(DEPS) - --include $(DEPS) +release: + @echo "sensord: this is a release" diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord new file mode 100755 index 0000000000..596d0b0d12 --- /dev/null +++ b/selfdrive/sensord/sensord @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:925d26ccc75ec4d7051b68fe98a929536c5224693f4e375fe20fb604299bc079 +size 918928 diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors.cc deleted file mode 100644 index e8ce856225..0000000000 --- a/selfdrive/sensord/sensors.cc +++ /dev/null @@ -1,228 +0,0 @@ -#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].setSource(cereal::SensorEventData::SensorSource::ANDROID); - 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/service_list.yaml b/selfdrive/service_list.yaml new file mode 100644 index 0000000000..d8293d06ab --- /dev/null +++ b/selfdrive/service_list.yaml @@ -0,0 +1,99 @@ +# TODO: these port numbers are hardcoded in c, fix this + +# LogRotate: 8001 is a PUSH PULL socket between loggerd and visiond + +# all ZMQ pub sub: + +# frame syncing packet +frame: [8002, true] +# accel, gyro, and compass +sensorEvents: [8003, true] +# GPS data, also global timestamp +gpsNMEA: [8004, true] +# CPU+MEM+GPU+BAT temps +thermal: [8005, true] +# List(CanData), list of can messages +can: [8006, true] +live100: [8007, true] + +# random events we want to log + +#liveEvent: [8008, true] +model: [8009, true] +features: [8010, true] +health: [8011, true] +live20: [8012, true] +#liveUI: [8014, true] +encodeIdx: [8015, true] +liveTracks: [8016, true] +sendcan: [8017, true] +logMessage: [8018, true] +liveCalibration: [8019, true] +androidLog: [8020, true] +carState: [8021, true] +# 8022 is reserved for sshd +carControl: [8023, true] +plan: [8024, true] +liveLocation: [8025, true] +gpsLocation: [8026, true] +ethernetData: [8027, true] +navUpdate: [8028, true] +qcomGnss: [8029, true] +lidarPts: [8030, true] +procLog: [8031, true] + +# manager -- base process to manage starting and stopping of all others +# subscribes: health +# publishes: thermal + +# **** processes that communicate with the outside world **** + +# boardd -- communicates with the car +# subscribes: sendcan +# publishes: can, health + +# sensord -- publishes the IMU and GPS +# publishes: sensorEvents, gpsNMEA + +# visiond -- talks to the cameras, runs the model, saves the videos +# subscribes: liveCalibration, sensorEvents, live100 +# publishes: frame, encodeIdx, model, liveCalibration + +# **** stateful data transformers **** + +# plannerd -- decides where to drive the car +# subscribes: carState, model, live20 +# publishes: plan + +# controlsd -- actually drives the car +# subscribes: can, thermal, plan +# publishes: carState, carControl, sendcan, live100 + +# radard -- processes the radar data +# blocks: CarParams +# subscribes: can, live100, model +# publishes: live20, liveTracks + +# **** 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 + +# proclogd -- fetches process information +# publishes: procLog + +# tombstoned -- reports native crashes diff --git a/selfdrive/services.py b/selfdrive/services.py new file mode 100644 index 0000000000..d705cd808a --- /dev/null +++ b/selfdrive/services.py @@ -0,0 +1,14 @@ +import os +import yaml + +class Service(object): + def __init__(self, port, should_log): + self.port = port + self.should_log = should_log + +service_list_path = os.path.join(os.path.dirname(__file__), "service_list.yaml") + +service_list = {} +with open(service_list_path, "r") as f: + for k, v in yaml.load(f).iteritems(): + service_list[k] = Service(v[0], v[1]) diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py index a485ac040e..b73988f24a 100755 --- a/selfdrive/test/plant/plant.py +++ b/selfdrive/test/plant/plant.py @@ -8,9 +8,9 @@ import numpy as np from dbcs import DBC_PATH from common.realtime import Ratekeeper -from common.services import service_list import selfdrive.messaging as messaging +from selfdrive.services import service_list from selfdrive.config import CruiseButtons from selfdrive.car.honda.hondacan import fix from selfdrive.car.honda.carstate import get_can_parser @@ -18,10 +18,31 @@ from selfdrive.boardd.boardd import can_capnp_to_can_list, can_list_to_can_capnp from selfdrive.car.honda.can_parser import CANParser - +from cereal import car from common.dbc import dbc acura = dbc(os.path.join(DBC_PATH, "acura_ilx_2016_can.dbc")) +def fake_car_params(): + ret = car.CarParams.new_message() + + # largely copied from honda + ret.carName = "honda" + ret.radarName = "nidec" + ret.carFingerprint = "ACURA ILX 2016 ACURAWATCH PLUS" + + ret.enableSteer = True + ret.enableBrake = True + ret.enableGas = True + ret.enableCruise = False + + ret.wheelBase = 2.67 + ret.steerRatio = 15.3 + ret.slipFactor = 0.0014 + + ret.steerKp, ret.steerKi = 12.0, 1.0 + + return ret + def car_plant(pos, speed, grade, gas, brake): # vehicle parameters mass = 1700 @@ -133,7 +154,7 @@ class Plant(object): def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0): # dbc_f, sgs, ivs, msgs, cks_msgs, frqs = initialize_can_struct(self.civic, self.brake_only) - cp2 = get_can_parser(self.civic, self.brake_only) + cp2 = get_can_parser(fake_car_params()) sgs = cp2._sgs msgs = cp2._msgs cks_msgs = cp2.msgs_ck diff --git a/selfdrive/test/plant/runtest.sh b/selfdrive/test/plant/runtest.sh index be4149afd3..49a638a5c6 100755 --- a/selfdrive/test/plant/runtest.sh +++ b/selfdrive/test/plant/runtest.sh @@ -4,7 +4,9 @@ pushd ../../controls pid1=$! ./radard.py & pid2=$! -trap "trap - SIGTERM && kill $pid1 && kill $pid2" SIGINT SIGTERM EXIT +./plannerd.py & +pid3=$! +trap "trap - SIGTERM && kill $pid1 && kill $pid2 && kill $pid3" SIGINT SIGTERM EXIT popd mkdir -p out MPLBACKEND=svg ./runtracks.py out diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py new file mode 100644 index 0000000000..9c69517502 --- /dev/null +++ b/selfdrive/tombstoned.py @@ -0,0 +1,83 @@ +import os +import re +import time +import uuid +import datetime + +from raven import Client +from raven.transport.http import HTTPTransport + +from selfdrive.version import version +from selfdrive.swaglog import cloudlog + +def get_tombstones(): + return [fn for fn in os.listdir("/data/tombstones") if fn.startswith("tombstone")] + +def report_tombstone(fn, client): + mtime = os.path.getmtime(fn) + with open(fn, "r") as f: + dat = f.read() + + # see system/core/debuggerd/tombstone.cpp + parsed = re.match(r"[* ]*\n" + r"(?P
CM Version:[\s\S]*?ABI:.*\n)" + r"(?Ppid:.*\n)" + r"(?Psignal.*\n)?" + r"(?PAbort.*\n)?" + r"(?P\s+x0[\s\S]*?\n)\n" + r"(?:backtrace:\n" + r"(?P[\s\S]*?\n)\n" + r"stack:\n" + r"(?P[\s\S]*?\n)\n" + r")?", dat) + + logtail = re.search(r"--------- tail end of.*\n([\s\S]*?\n)---", dat) + logtail = logtail and logtail.group(1) + + if parsed: + parsedict = parsed.groupdict() + message = parsedict.get('thread') or '' + message += parsedict.get('signal') or '' + message += parsedict.get('abort') or '' + else: + parsedict = {} + message = fn + + client.send( + event_id=uuid.uuid4().hex, + timestamp=datetime.datetime.utcfromtimestamp(mtime), + logger='tombstoned', + platform='other', + sdk={'name': 'tombstoned', 'version': '0'}, + extra={ + 'tombstone_fn': fn, + 'header': parsedict.get('header'), + 'registers': parsedict.get('registers'), + 'backtrace': parsedict.get('backtrace'), + 'logtail': logtail, + 'version': version, + }, + user={'id': os.environ.get('DONGLE_ID')}, + message=message, + ) + + +def main(gctx): + initial_tombstones = set(get_tombstones()) + + client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615', + install_sys_hook=False, transport=HTTPTransport) + + while True: + now_tombstones = set(get_tombstones()) + + for ts in (now_tombstones - initial_tombstones): + fn = "/data/tombstones/"+ts + cloudlog.info("reporting new tombstone %s", fn) + report_tombstone(fn, client) + + initial_tombstones = now_tombstones + time.sleep(5) + +if __name__ == "__main__": + main(None) diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile index 19b9bc7df6..ce14a448c1 100644 --- a/selfdrive/ui/Makefile +++ b/selfdrive/ui/Makefile @@ -23,17 +23,21 @@ CEREAL_LIBS = -L$(PHONELIBS)/capnp-c/aarch64/lib -l:libcapn.a CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o NANOVG_FLAGS = -I$(PHONELIBS)/nanovg +JSON_FLAGS = -I$(PHONELIBS)/json/src OPENGL_LIBS = -lGLESv3 FRAMEBUFFER_LIBS = -lutils -lgui -lEGL OBJS = ui.o \ - touch.o \ ../common/glutil.o \ ../common/visionipc.o \ ../common/framebuffer.o \ + ../common/params.o \ + ../common/util.o \ + ../common/touch.o \ $(PHONELIBS)/nanovg/nanovg.o \ + $(PHONELIBS)/json/src/json.o \ $(CEREAL_OBJS) DEPS := $(OBJS:.o=.d) @@ -65,6 +69,7 @@ ui: $(OBJS) $(NANOVG_FLAGS) \ $(ZMQ_FLAGS) \ $(CEREAL_CFLAGS) \ + $(JSON_FLAGS) \ -c -o '$@' '$<' .PHONY: clean diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index a2b26b35e5..c8b2cc0c6f 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -10,6 +10,7 @@ #include #include +#include #include #include "nanovg.h" @@ -22,25 +23,17 @@ #include "common/mat.h" #include "common/glutil.h" +#include "common/touch.h" #include "common/framebuffer.h" #include "common/visionipc.h" #include "common/modeldata.h" - -#include "common/version.h" +#include "common/params.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; @@ -51,7 +44,10 @@ typedef struct UIScene { uint64_t model_ts; ModelData model; - mat3 big_box_transform; // transformed box -> big box + bool world_objects_visible; + // TODO(mgraczyk): Remove and use full frame for everything. + mat3 warp_matrix; // transformed box -> big_box. + mat4 extrinsic_matrix; // Last row is 0 so we can use mat4. float v_cruise; float v_ego; @@ -70,7 +66,6 @@ typedef struct UIScene { float awareness_status; } UIScene; - typedef struct UIState { pthread_mutex_t lock; @@ -85,36 +80,22 @@ typedef struct UIState { NVGcontext *vg; int font; - - zsock_t *model_sock; - void* model_sock_raw; + void *model_sock_raw; zsock_t *live100_sock; - void* live100_sock_raw; + void *live100_sock_raw; zsock_t *livecalibration_sock; - void* livecalibration_sock_raw; + void *livecalibration_sock_raw; zsock_t *live20_sock; - void* live20_sock_raw; - - // base ui - uint64_t last_base_update; - 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; + void *live20_sock_raw; // 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]; + VisionBuf bufs[UI_BUF_COUNT]; + VisionBuf front_bufs[UI_BUF_COUNT]; int cur_vision_idx; int cur_vision_front_idx; @@ -134,86 +115,40 @@ typedef struct UIState { unsigned int rgb_front_width, rgb_front_height; GLuint frame_front_tex; + bool intrinsic_matrix_loaded; + mat3 intrinsic_matrix; + UIScene scene; - + bool awake; int awake_timeout; } UIState; static void set_awake(UIState *s, bool awake) { if (awake) { - // 30 second timeout - s->awake_timeout = 30; + // 15 second timeout at 30 fps + s->awake_timeout = 15*30; } if (s->awake != awake) { s->awake = awake; - // TODO: actually turn off the screen and not just the backlight - FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); - if (f != NULL) { - if (awake) { + if (awake) { + printf("awake normal\n"); + framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); + + // can't hurt + FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); + if (f != NULL) { fprintf(f, "205"); - } else { - fprintf(f, "0"); + fclose(f); } - fclose(f); + } else { + printf("awake off\n"); + framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); } } } -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 = 730, .w = 250, .h = 250, - .pressed = wifi_pressed, - .enabled = wifi_enabled, - }, - { - .label = "ap", - .x = 1300, .y = 730, .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" @@ -299,24 +234,15 @@ static void ui_init(UIState *s) { 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)"; - + set_awake(s, true); // 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); @@ -326,7 +252,6 @@ static void ui_init(UIState *s) { 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); @@ -339,76 +264,77 @@ static void ui_init(UIState *s) { glDisable(GL_DEPTH_TEST); assert(glGetError() == GL_NO_ERROR); - - // set awake - set_awake(s, true); } -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); +// If the intrinsics are in the params entry, this copies them to +// intrinsic_matrix and returns true. Otherwise returns false. +static bool try_load_intrinsics(mat3 *intrinsic_matrix) { + char *value; + const int result = + read_db_value("/data/params", "CloudCalibration", &value, NULL); + + if (result == 0) { + JsonNode* calibration_json = json_decode(value); + free(value); - 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); + JsonNode *intrinsic_json = + json_find_member(calibration_json, "intrinsic_matrix"); + + if (intrinsic_json == NULL || intrinsic_json->tag != JSON_ARRAY) { + json_delete(calibration_json); + return false; } - 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); + + int i = 0; + JsonNode* json_num; + json_foreach(json_num, intrinsic_json) { + intrinsic_matrix->v[i++] = json_num->number_; } - 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); + json_delete(calibration_json); + + return true; + } else { + return false; } +} + + +static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, + int num_back_fds, const int *back_fds, + const VisionStreamBufs front_bufs, int num_front_fds, + const int *front_fds) { + const VisionUIInfo ui_info = back_bufs.buf_info.ui_info; + + assert(num_back_fds == UI_BUF_COUNT); + assert(num_front_fds == UI_BUF_COUNT); + + visionbufs_load(s->bufs, &back_bufs, num_back_fds, back_fds); + visionbufs_load(s->front_bufs, &front_bufs, num_front_fds, front_fds); 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, - }}, + .frontview = 0, + .big_box_x = ui_info.big_box_x, + .big_box_y = ui_info.big_box_y, + .big_box_width = ui_info.big_box_width, + .big_box_height = ui_info.big_box_height, + .transformed_width = ui_info.transformed_width, + .transformed_height = ui_info.transformed_height, + .front_box_x = ui_info.front_box_x, + .front_box_y = ui_info.front_box_y, + .front_box_width = ui_info.front_box_width, + .front_box_height = ui_info.front_box_height, + .world_objects_visible = false, // Invisible until we receive a calibration message. }; - s->vision_bufs = vision_bufs; - - s->rgb_width = vision_bufs.width; - s->rgb_height = vision_bufs.height; + s->rgb_width = back_bufs.width; + s->rgb_height = back_bufs.height; - s->rgb_front_width = vision_bufs.front_width; - s->rgb_front_height = vision_bufs.front_height; + s->rgb_front_width = front_bufs.width; + s->rgb_front_height = front_bufs.height; s->rgb_transform = (mat4){{ 2.0/s->rgb_width, 0.0, 0.0, -1.0, @@ -442,37 +368,10 @@ static void ui_update_frame(UIState *s) { 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; + const mat3 bbt = scene->warp_matrix; struct { vec3 pos; @@ -487,8 +386,8 @@ static void ui_draw_transformed_box(UIState *s, uint32_t 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]; + verts[i].pos.v[1] = s->rgb_height - (scene->big_box_y + + verts[i].pos.v[1] / verts[i].pos.v[2]); } glUseProgram(s->line_program); @@ -507,14 +406,29 @@ static void ui_draw_transformed_box(UIState *s, uint32_t color) { glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); } +// Projects a point in car to space to the corresponding point in full frame +// image space. +vec3 car_space_to_full_frame(const UIState *s, vec4 car_space_projective) { + const UIScene *scene = &s->scene; + + // We'll call the car space point p. + // First project into normalized image coordinates with the extrinsics matrix. + const vec4 Ep4 = matvecmul(scene->extrinsic_matrix, car_space_projective); + + // The last entry is zero because of how we store E (to use matvecmul). + const vec3 Ep = {{Ep4.v[0], Ep4.v[1], Ep4.v[2]}}; + const vec3 KEp = matvecmul3(s->intrinsic_matrix, Ep); + + // Project. + const vec3 p_image = {{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2], 1.}}; + return p_image; +} + + // 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 @@ -530,34 +444,28 @@ static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor co 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]; + const vec4 p_car_space = (vec4){{x_in, y_in, 0., 1.}}; + const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - nvgMoveTo(s->vg, x-sz, y); - nvgLineTo(s->vg, x+sz, y); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x >= 0 && y >= 0.) { + nvgMoveTo(s->vg, x-sz, y); + nvgLineTo(s->vg, x+sz, y); - nvgMoveTo(s->vg, x, y-sz); - nvgLineTo(s->vg, x, y+sz); + nvgMoveTo(s->vg, x, y-sz); + nvgLineTo(s->vg, x, y+sz); - nvgStroke(s->vg); + nvgStroke(s->vg); + } nvgRestore(s->vg); } -static void draw_path(UIState *s, const float* points, float off, NVGcolor color) { +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 @@ -569,24 +477,27 @@ static void draw_path(UIState *s, const float* points, float off, NVGcolor color nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); - nvgBeginPath(s->vg); nvgStrokeColor(s->vg, color); nvgStrokeWidth(s->vg, 5); + bool started = false; for (int i=0; i<50; i++) { - float px = (-points[i] + off) * meter_width + car_x; - float py = (float)i * -meter_width + car_y; + float px = (float)i; + float py = points[i] + off; - 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); + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = scene->big_box_x + bbpos.v[0]/bbpos.v[2]; - float y = scene->big_box_y + bbpos.v[1]/bbpos.v[2]; + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } - if (i == 0) { + if (!started) { nvgMoveTo(s->vg, x, y); + started = true; } else { nvgLineTo(s->vg, x, y); } @@ -614,7 +525,8 @@ static double calc_curvature(float v_ego, float angle_steers) { 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)); + double curvature = angle_steers_rad / (steer_ratio * wheel_base * + (1. + slip_fator * v_ego * v_ego)); return curvature; } @@ -622,8 +534,8 @@ 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.); + 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; } @@ -675,15 +587,54 @@ static void draw_frame(UIState *s) { 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); + 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]); + 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]); } +// Draw all world space objects. +static void ui_draw_world(UIState *s) { + const UIScene *scene = &s->scene; + if (!scene->world_objects_visible) { + return; + } + + 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)); + } + + 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)); + } +} + static void ui_draw_vision(UIState *s) { const UIScene *scene = &s->scene; @@ -696,165 +647,90 @@ static void ui_draw_vision(UIState *s) { 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); + // nvg drawings + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + // glEnable(GL_CULL_FACE); - // draw paths + glClear(GL_STENCIL_BUFFER_BIT); - if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) { - draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(128, 0, 255, 255)); + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); - 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)); - } + if (!scene->frontview) { + ui_draw_transformed_box(s, 0xFF00FF00); + ui_draw_world(s); // draw speed char speed_str[16]; nvgFontSize(s->vg, 128.0f); - if (scene->engaged) { - nvgFillColor(s->vg, nvgRGBA(255,128,0,192)); + nvgFillColor(s->vg, nvgRGBA(255, 128, 0, 192)); } else { - nvgFillColor(s->vg, nvgRGBA(64,64,64,192)); + 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)); + 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)); + 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); + 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+550, 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)); + 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_blank(UIState *s) { - glClearColor(0.1, 0.1, 0.1, 1.0); - glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); -} - -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; ialert_text1) > 0) { nvgBeginPath(s->vg); - nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); - nvgRoundedRect(s->vg, b->x, b->y, b->w, b->h, 20); + nvgRoundedRect(s->vg, 100, 200, 1700, 800, 40); + nvgFillColor(s->vg, nvgRGBA(10, 10, 10, 220)); 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); - } + 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); - 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); + if (strlen(scene->alert_text2) > 0) { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgFontSize(s->vg, 100.0f); + nvgTextBox(s->vg, 100 + 50, 200 + 550, 1700 - 2*50, scene->alert_text2, NULL); + } } nvgEndFrame(s->vg); glDisable(GL_BLEND); + glDisable(GL_CULL_FACE); } -static void ui_draw(UIState *s) { +static void ui_draw_blank(UIState *s) { + glClearColor(0.1, 0.1, 0.1, 1.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); +} +static void ui_draw(UIState *s) { if (s->vision_connected) { ui_draw_vision(s); - } else if (s->awake) { - ui_draw_base(s); } else { ui_draw_blank(s); } @@ -863,7 +739,6 @@ static void ui_draw(UIState *s) { assert(glGetError() == GL_NO_ERROR); } - static PathData read_path(cereal_ModelData_PathData_ptr pathp) { PathData ret = {0}; @@ -875,7 +750,7 @@ static PathData read_path(cereal_ModelData_PathData_ptr pathp) { capn_list32 pointl = pathd.points; capn_resolve(&pointl.p); - for (int i=0; i<50; i++) { + for (int i = 0; i < 50; i++) { ret.points[i] = capn_to_f32(capn_get32(pointl, i)); } @@ -895,66 +770,19 @@ static ModelData read_model(cereal_ModelData_ptr modelp) { struct cereal_ModelData_LeadData leadd; cereal_read_ModelData_LeadData(&leadd, modeld.lead); d.lead = (LeadData){ - .dist = leadd.dist, - .prob = leadd.prob, - .std = leadd.std, + .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] == '.') continue; - - char subdirn[255]; - snprintf(subdirn, 255, "/sdcard/realdata/%s", entry->d_name); - DIR *subdirp = opendir(subdirn); - if (!subdirp) continue; - - struct dirent *subentry = NULL; - while ((subentry = readdir(subdirp))) { - if (subentry->d_name[0] == '.') continue; - //snprintf(subdirn, 255, "/sdcard/realdata/%s/%s", entry->d_name, subentry->d_name); - cnt++; - } - closedir(subdirp); - } - closedir(dirp); - return cnt; -} - - static void ui_update(UIState *s) { int err; + if (!s->intrinsic_matrix_loaded) { + s->intrinsic_matrix_loaded = try_load_intrinsics(&s->intrinsic_matrix); + } + 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 @@ -992,7 +820,6 @@ static void ui_update(UIState *s) { // poll for events while (true) { - zmq_pollitem_t polls[5] = {{0}}; polls[0].socket = s->live100_sock_raw; polls[0].events = ZMQ_POLLIN; @@ -1031,9 +858,10 @@ static void ui_update(UIState *s) { 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; + if (rp.type == VIPC_STREAM_ACQUIRE) { + bool front = rp.d.stream_acq.type == VISION_STREAM_UI_FRONT; + int idx = rp.d.stream_acq.idx; + int release_idx; if (front) { release_idx = s->cur_vision_front_idx; @@ -1042,21 +870,21 @@ static void ui_update(UIState *s) { } if (release_idx >= 0) { VisionPacket rep = { - .type = VISION_UI_RELEASE, - .d = { .ui_rel = { - .front = front, + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp.d.stream_acq.type, .idx = release_idx, }}, }; - vipc_send(s->ipc_fd, rep); + vipc_send(s->ipc_fd, &rep); } if (front) { - assert(idx < s->vision_bufs.num_front_bufs); + assert(idx < UI_BUF_COUNT); s->cur_vision_front_idx = idx; s->scene.bgr_front_ptr = s->front_bufs[idx].addr; } else { - assert(idx < s->vision_bufs.num_bufs); + assert(idx < UI_BUF_COUNT); s->cur_vision_idx = idx; s->scene.bgr_ptr = s->bufs[idx].addr; // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); @@ -1087,7 +915,6 @@ static void ui_update(UIState *s) { 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); @@ -1128,20 +955,23 @@ static void ui_update(UIState *s) { s->scene.lead_y_rel = leaddatad.yRel; s->scene.lead_v_rel = leaddatad.vRel; } else if (eventd.which == cereal_Event_liveCalibration) { + s->scene.world_objects_visible = s->intrinsic_matrix_loaded; 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)); + capn_resolve(&warpl.p); // is this a bug? + for (int i = 0; i < 3 * 3; i++) { + s->scene.warp_matrix.v[i] = capn_to_f32(capn_get32(warpl, i)); } - // pthread_mutex_unlock(&s->transform_lock); - // printf("recv %f\n", datad.vEgo); + capn_list32 extrinsicl = datad.extrinsicMatrix; + capn_resolve(&extrinsicl.p); // is this a bug? + for (int i = 0; i < 3 * 4; i++) { + s->scene.extrinsic_matrix.v[i] = + capn_to_f32(capn_get32(extrinsicl, i)); + } } else if (eventd.which == cereal_Event_model) { s->scene.model_ts = eventd.logMonoTime; s->scene.model = read_model(eventd.model); @@ -1152,98 +982,6 @@ static void ui_update(UIState *s) { 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; - uint64_t tx_bytes_n = 0; - char *tx_bytes; - - // cellular bytes - tx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/tx_bytes"); - if (tx_bytes) { tx_bytes_n += atoll(tx_bytes); free(tx_bytes); } - - // wifi bytes - tx_bytes = read_file("/sys/class/net/wlan0/statistics/tx_bytes"); - if (tx_bytes) { tx_bytes_n += atoll(tx_bytes); free(tx_bytes); } - - tx_rate = tx_bytes_n - s->last_tx_bytes; - s->last_tx_bytes = tx_bytes_n; - - // TODO: do this properly - system("git rev-parse --abbrev-ref HEAD > /tmp/git_branch"); - char *git_branch = read_file("/tmp/git_branch"); - system("git rev-parse --short HEAD > /tmp/git_commit"); - char *git_commit = read_file("/tmp/git_commit"); - - 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), - "version: v%s %s (%s)\nserial: %s\n dongle id: %s\n battery: %s %s\npending: %d -> %.1f kb/s\nboard: %s", - openpilot_version, git_commit, git_branch, - s->serial, s->dongle_id, bat_cap ? bat_cap : "(null)", bat_stat ? bat_stat : "(null)", - pending, tx_rate / 1024.0, s->board_connected ? "found" : "NOT FOUND"); - - if (bat_cap) free(bat_cap); - if (bat_stat) free(bat_stat); - - if (git_branch) free(git_branch); - if (git_commit) free(git_commit); - - s->last_base_update = ts; - - if (!activity_running()) { - if (s->awake_timeout > 0) { - s->awake_timeout--; - } else { - set_awake(s, false); - } - } - } - - if (s->vision_connected) { - // always awake if vision is connected - set_awake(s, true); - } - - 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) { - if (s->awake) { - // 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; - } - } - } - } else { - set_awake(s, true); - } - } } } @@ -1268,30 +1006,52 @@ static void* vision_connect_thread(void *args) { int fd = vipc_connect(); if (fd < 0) continue; - VisionPacket p = { - .type = VISION_UI_SUBSCRIBE, + + + VisionPacket p1 = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { .type = VISION_STREAM_UI_BACK, .tbuffer = true, }, }, + }; + err = vipc_send(fd, &p1); + if (err < 0) { + close(fd); + continue; + } + VisionPacket p2 = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { .type = VISION_STREAM_UI_FRONT, .tbuffer = true, }, }, }; - err = vipc_send(fd, p); + err = vipc_send(fd, &p2); if (err < 0) { close(fd); continue; } // printf("init recv\n"); - VisionPacket rp; - err = vipc_recv(fd, &rp); + VisionPacket back_rp; + err = vipc_recv(fd, &back_rp); if (err <= 0) { close(fd); continue; } + assert(back_rp.type == VIPC_STREAM_BUFS); + VisionPacket front_rp; + err = vipc_recv(fd, &front_rp); + if (err <= 0) { + close(fd); + continue; + } + assert(front_rp.type == VIPC_STREAM_BUFS); - 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); + + ui_init_vision(s, + back_rp.d.stream_bufs, back_rp.num_fds, back_rp.fds, + front_rp.d.stream_bufs, front_rp.num_fds, front_rp.fds); + s->vision_connected = true; s->vision_connect_firstrun = true; pthread_mutex_unlock(&s->lock); @@ -1315,10 +1075,31 @@ int main() { assert(err == 0); while (!do_exit) { - pthread_mutex_lock(&s->lock); - ui_update(s); - ui_draw(s); - pthread_mutex_unlock(&s->lock); + if (s->awake) { + pthread_mutex_lock(&s->lock); + ui_update(s); + ui_draw(s); + pthread_mutex_unlock(&s->lock); + } + + // manage wakefulness + if (s->awake_timeout > 0) { + s->awake_timeout--; + } else { + set_awake(s, false); + } + + // always awake if vision is connected + if (s->vision_connected) { + set_awake(s, true); + } else { + int touch_x = -1, touch_y = -1; + err = touch_poll(&s->touch, &touch_x, &touch_y); + if (err == 1) { + // touch event will still happen :( + set_awake(s, true); + } + } // no simple way to do 30fps vsync with surfaceflinger... usleep(30000); diff --git a/selfdrive/version.py b/selfdrive/version.py new file mode 100644 index 0000000000..b5d667f39a --- /dev/null +++ b/selfdrive/version.py @@ -0,0 +1,3 @@ +import os +with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: + version = _versionf.read().split('"')[1] diff --git a/selfdrive/visiond/LICENSE.boringssl b/selfdrive/visiond/LICENSE.boringssl new file mode 100644 index 0000000000..a25996f720 --- /dev/null +++ b/selfdrive/visiond/LICENSE.boringssl @@ -0,0 +1,192 @@ +BoringSSL is a fork of OpenSSL. As such, large parts of it fall under OpenSSL +licensing. Files that are completely new have a Google copyright and an ISC +license. This license is reproduced at the bottom of this file. + +Contributors to BoringSSL are required to follow the CLA rules for Chromium: +https://cla.developers.google.com/clas + +Some files from Intel are under yet another license, which is also included +underneath. + +The OpenSSL toolkit stays under a dual license, i.e. both the conditions of the +OpenSSL License and the original SSLeay license apply to the toolkit. See below +for the actual license texts. Actually both licenses are BSD-style Open Source +licenses. In case of any license issues related to OpenSSL please contact +openssl-core@openssl.org. + +The following are Google-internal bug numbers where explicit permission from +some authors is recorded for use of their work. (This is purely for our own +record keeping.) + 27287199 + 27287880 + 27287883 + + OpenSSL License + --------------- + +/* ==================================================================== + * Copyright (c) 1998-2011 The OpenSSL Project. All rights reserved. + * + * 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. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED 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 OpenSSL PROJECT OR + * ITS 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. + * ==================================================================== + * + * This product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ + + Original SSLeay License + ----------------------- + +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * 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 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``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 AUTHOR 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. + * + * The licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + + +ISC license used for completely new code in BoringSSL: + +/* Copyright (c) 2015, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + + +Some files from Intel carry the following license: + +# Copyright (c) 2012, Intel Corporation +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are +# met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * 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. +# +# * Neither the name of the Intel Corporation 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 INTEL CORPORATION ""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 INTEL CORPORATION 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. diff --git a/selfdrive/visiond/LICENSE.libyuv b/selfdrive/visiond/LICENSE.libyuv new file mode 100644 index 0000000000..c911747a6b --- /dev/null +++ b/selfdrive/visiond/LICENSE.libyuv @@ -0,0 +1,29 @@ +Copyright 2011 The LibYuv Project Authors. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * 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. + + * Neither the name of Google 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. diff --git a/selfdrive/visiond/LICENSE.opencv b/selfdrive/visiond/LICENSE.opencv new file mode 100644 index 0000000000..fce70d7135 --- /dev/null +++ b/selfdrive/visiond/LICENSE.opencv @@ -0,0 +1,41 @@ +By downloading, copying, installing or using the software you agree to this license. +If you do not agree to this license, do not download, install, +copy or use the software. + + + License Agreement + For Open Source Computer Vision Library + (3-clause BSD License) + +Copyright (C) 2000-2016, Intel Corporation, all rights reserved. +Copyright (C) 2009-2011, Willow Garage Inc., all rights reserved. +Copyright (C) 2009-2016, NVIDIA Corporation, all rights reserved. +Copyright (C) 2010-2013, Advanced Micro Devices, Inc., all rights reserved. +Copyright (C) 2015-2016, OpenCV Foundation, all rights reserved. +Copyright (C) 2015-2016, Itseez Inc., all rights reserved. +Third party copyrights are property of their respective owners. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * 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. + + * Neither the names of the copyright holders nor the names of the 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 copyright holders 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. diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README index 488343bc1e..ae92bd4b3f 100644 --- a/selfdrive/visiond/README +++ b/selfdrive/visiond/README @@ -1,3 +1,3 @@ -visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs and video logs lives here. +visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs 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 index 8e68b39555..5f0f994162 100755 --- a/selfdrive/visiond/visiond +++ b/selfdrive/visiond/visiond @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a2753f355653ea7baf25bf4e64d46137e2a6b6bec36c660c4707b8f84b1e4015 -size 14736912 +oid sha256:bb6d9abbef0be0d91c425402a9d85b0192ba691ae80bcbf180ec946d73160068 +size 16364248