diff --git a/.gitignore b/.gitignore index acbbe11c58..3731d8f749 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ .DS_Store .tags +.ipynb_checkpoints *.pyc .*.swp diff --git a/Makefile b/Makefile new file mode 100644 index 0000000000..14dcee805c --- /dev/null +++ b/Makefile @@ -0,0 +1,6 @@ +.PHONY: all + +# TODO: Add a global build system to openpilot +all: + cd /data/openpilot/selfdrive && PYTHONPATH=/data/openpilot PREPAREONLY=1 /data/openpilot/selfdrive/manager.py + diff --git a/README.md b/README.md index b0a808a64e..afa45fe2cb 100644 --- a/README.md +++ b/README.md @@ -10,15 +10,9 @@ The openpilot codebase has been written to be concise and enable rapid prototypi Hardware ------ -Right now openpilot supports the [neo research platform](http://github.com/commaai/neo) for vehicle control. We'd like to support [Open Source Car Control](https://github.com/PolySync/OSCC) as well. +Right now openpilot supports the [neo research platform](http://github.com/commaai/neo) for vehicle control. We'd like to support other platforms as well. -To install it on the NEO: - -```bash -# Requires working adb in PATH -cd installation -./install.sh -``` +Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup. Supported Cars ------ @@ -36,7 +30,6 @@ Directory structure - cereal -- The messaging spec used for all logs on the phone - common -- Library like functionality we've developed here - dbcs -- Files showing how to interpret data from cars -- installation -- Installation on the neo platform - phonelibs -- Libraries used on the phone - selfdrive -- Code needed to drive the car - assets -- Fonts for ui diff --git a/RELEASES.md b/RELEASES.md index 664ccd5c27..91166d1797 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,9 @@ +Version 0.2.4 (2017-01-27) +=========================== + * OnePlus 3T support + * Enable installation as NEOS app + * Various minor bugfixes + Version 0.2.3 (2017-01-11) =========================== * Reduce space usage by 80% diff --git a/board/can.h b/board/can.h index 02053bafb6..5cb5b7e5c2 100644 --- a/board/can.h +++ b/board/can.h @@ -1,4 +1,13 @@ 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"); diff --git a/board/inc/stm32f2xx_hal_def.h b/board/inc/stm32f2xx_hal_def.h new file mode 100644 index 0000000000..a20355fbf3 --- /dev/null +++ b/board/inc/stm32f2xx_hal_def.h @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * @file stm32f2xx_hal_def.h + * @author MCD Application Team + * @version V1.0.1 + * @date 25-March-2014 + * @brief This file contains HAL common defines, enumeration, macros and + * structures definitions. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 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. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F2xx_HAL_DEF +#define __STM32F2xx_HAL_DEF + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f2xx.h" + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief HAL Status structures definition + */ +typedef enum +{ + HAL_OK = 0x00, + HAL_ERROR = 0x01, + HAL_BUSY = 0x02, + HAL_TIMEOUT = 0x03 +} HAL_StatusTypeDef; + +/** + * @brief HAL Lock structures definition + */ +typedef enum +{ + HAL_UNLOCKED = 0x00, + HAL_LOCKED = 0x01 +} HAL_LockTypeDef; + +/* Exported macro ------------------------------------------------------------*/ +#ifndef NULL + #define NULL (void *) 0 +#endif + +#define HAL_MAX_DELAY 0xFFFFFFFF + +#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) +#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) + +#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD_, __DMA_HANDLE_) \ + do{ \ + (__HANDLE__)->__PPP_DMA_FIELD_ = &(__DMA_HANDLE_); \ + (__DMA_HANDLE_).Parent = (__HANDLE__); \ + } while(0) + +#if (USE_RTOS == 1) + /* Reserved for future use */ +#else + #define __HAL_LOCK(__HANDLE__) \ + do{ \ + if((__HANDLE__)->Lock == HAL_LOCKED) \ + { \ + return HAL_BUSY; \ + } \ + else \ + { \ + (__HANDLE__)->Lock = HAL_LOCKED; \ + } \ + }while (0) + + #define __HAL_UNLOCK(__HANDLE__) \ + do{ \ + (__HANDLE__)->Lock = HAL_UNLOCKED; \ + }while (0) +#endif /* USE_RTOS */ + +#if defined ( __GNUC__ ) + #ifndef __weak + #define __weak __attribute__((weak)) + #endif /* __weak */ + #ifndef __packed + #define __packed __attribute__((__packed__)) + #endif /* __packed */ +#endif /* __GNUC__ */ + + +/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ +#if defined (__GNUC__) /* GNU Compiler */ + #ifndef __ALIGN_END + #define __ALIGN_END __attribute__ ((aligned (4))) + #endif /* __ALIGN_END */ + #ifndef __ALIGN_BEGIN + #define __ALIGN_BEGIN + #endif /* __ALIGN_BEGIN */ +#else + #ifndef __ALIGN_END + #define __ALIGN_END + #endif /* __ALIGN_END */ + #ifndef __ALIGN_BEGIN + #if defined (__CC_ARM) /* ARM Compiler */ + #define __ALIGN_BEGIN __align(4) + #elif defined (__ICCARM__) /* IAR Compiler */ + #define __ALIGN_BEGIN + #elif defined (__TASKING__) /* TASKING Compiler */ + #define __ALIGN_BEGIN __align(4) + #endif /* __CC_ARM */ + #endif /* __ALIGN_BEGIN */ +#endif /* __GNUC__ */ + +#ifdef __cplusplus +} +#endif + +#endif /* ___STM32F2xx_HAL_DEF */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/board/inc/stm32f2xx_hal_gpio_ex.h b/board/inc/stm32f2xx_hal_gpio_ex.h new file mode 100644 index 0000000000..67e455eb5e --- /dev/null +++ b/board/inc/stm32f2xx_hal_gpio_ex.h @@ -0,0 +1,236 @@ +/** + ****************************************************************************** + * @file stm32f2xx_hal_gpio_ex.h + * @author MCD Application Team + * @version V1.0.1 + * @date 25-March-2014 + * @brief Header file of GPIO HAL Extension module. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 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. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F2xx_HAL_GPIO_EX_H +#define __STM32F2xx_HAL_GPIO_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f2xx_hal_def.h" + +/** @addtogroup STM32F2xx_HAL_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_Alternat_function_selection + * @{ + */ + +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0xA) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#if defined(STM32F207xx) || defined(STM32F217xx) +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FSMC ((uint8_t)0xC) /* FSMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0xC) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#if defined(STM32F207xx) || defined(STM32F217xx) +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ + +#if defined(STM32F207xx) || defined(STM32F217xx) +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) +#else /* STM32F207xx || STM32F217xx */ +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F2xx_HAL_GPIO_EX_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/board/libc.h b/board/libc.h index 4a2913b883..798de46c04 100644 --- a/board/libc.h +++ b/board/libc.h @@ -13,19 +13,7 @@ #define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) #define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F)) -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS */ - -#ifdef OLD_BOARD - #define USART USART2 -#else - #define USART USART3 -#endif - +#include "stm32f2xx_hal_gpio_ex.h" // **** shitty libc **** @@ -68,15 +56,20 @@ void clock_init() { 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_TIM1EN; RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; // turn on alt USB RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN; @@ -101,7 +94,7 @@ void gpio_init() { // IGNITION on C13 // set mode for LEDs and CAN - GPIOB->MODER = GPIO_MODER_MODER10_0 | GPIO_MODER_MODER11_0; + 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 @@ -125,6 +118,12 @@ void gpio_init() { 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); @@ -136,9 +135,6 @@ void gpio_init() { GPIOB->OSPEEDR = GPIO_OSPEEDER_OSPEEDR14 | GPIO_OSPEEDER_OSPEEDR15; - // enable CAN busses - GPIOB->ODR |= (1 << 3) | (1 << 4); - // enable OTG out tied to ground GPIOA->ODR = 0; GPIOA->MODER |= GPIO_MODER_MODER1_0; @@ -223,4 +219,13 @@ void *memcpy(void *dest, const void *src, unsigned int n) { return dest; } +void set_led(int led_num, int state) { + if (state) { + // turn on + GPIOB->ODR &= ~(1 << (10 + led_num)); + } else { + // turn off + GPIOB->ODR |= (1 << (10 + led_num)); + } +} diff --git a/board/main.c b/board/main.c index 19ed6c0c48..637fdf1c84 100644 --- a/board/main.c +++ b/board/main.c @@ -3,6 +3,11 @@ //#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 @@ -22,6 +27,7 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; #include "timer.h" #include "usb.h" #include "can.h" +#include "spi.h" // debug safety check: is controls allowed? int controls_allowed = 0; @@ -394,6 +400,48 @@ 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() { @@ -428,11 +476,6 @@ int main() { // init devices clock_init(); - // test the USB choice before GPIO init - if (GPIOA->IDR & (1 << 12)) { - USBx = USB_OTG_HS; - } - gpio_init(); uart_init(); usb_init(); @@ -440,6 +483,14 @@ int main() { 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; @@ -475,13 +526,21 @@ int main() { 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 - while (1) { + int cnt; + for (cnt=0;;cnt++) { can_live = pending_can_live; - pending_can_live = 0; + + // reset this every 16th pass + if ((cnt&0xF) == 0) pending_can_live = 0; #ifdef DEBUG puts("** blink "); @@ -504,6 +563,13 @@ int main() { 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; } diff --git a/board/spi.h b/board/spi.h new file mode 100644 index 0000000000..e725790d06 --- /dev/null +++ b/board/spi.h @@ -0,0 +1,23 @@ +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/cereal/gen/c/car.capnp.c b/cereal/gen/c/car.capnp.c new file mode 100644 index 0000000000..9cf47c5fb7 --- /dev/null +++ b/cereal/gen/c/car.capnp.c @@ -0,0 +1,337 @@ +#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 new file mode 100644 index 0000000000..0a9b010af0 --- /dev/null +++ b/cereal/gen/c/car.capnp.h @@ -0,0 +1,287 @@ +#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 index 59363044d6..a62a180aab 100644 --- a/cereal/gen/c/log.capnp.c +++ b/cereal/gen/c/log.capnp.c @@ -137,6 +137,7 @@ void cereal_read_SensorEventData(struct cereal_SensorEventData *s, cereal_Sensor 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); @@ -155,6 +156,7 @@ void cereal_write_SensorEventData(const struct cereal_SensorEventData *s, cereal 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; @@ -198,6 +200,49 @@ void cereal_set_SensorEventData_SensorVec(const struct cereal_SensorEventData_Se 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); @@ -253,6 +298,7 @@ void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_pt 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)); } void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { capn_resolve(&p.p); @@ -264,6 +310,7 @@ void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_Thermal 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)); } void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { cereal_ThermalData_ptr p; @@ -969,7 +1016,9 @@ void cereal_read_Event(struct cereal_Event *s, cereal_Event_ptr p) { case cereal_Event_sendcan: case cereal_Event_liveCalibration: case cereal_Event_androidLogEntry: - s->androidLogEntry.p = capn_getp(p.p, 0, 0); + case cereal_Event_gpsLocation: + case cereal_Event_carState: + s->carState.p = capn_getp(p.p, 0, 0); break; default: break; @@ -1002,7 +1051,9 @@ void cereal_write_Event(const struct cereal_Event *s, cereal_Event_ptr p) { case cereal_Event_sendcan: case cereal_Event_liveCalibration: case cereal_Event_androidLogEntry: - capn_setp(p.p, 0, s->androidLogEntry.p); + case cereal_Event_gpsLocation: + case cereal_Event_carState: + capn_setp(p.p, 0, s->carState.p); break; default: break; diff --git a/cereal/gen/c/log.capnp.h b/cereal/gen/c/log.capnp.h index 232ff9ab1f..24ad3e1ebe 100644 --- a/cereal/gen/c/log.capnp.h +++ b/cereal/gen/c/log.capnp.h @@ -8,6 +8,7 @@ #endif #include "c++.capnp.h" +#include "car.capnp.h" #ifdef __cplusplus extern "C" { @@ -18,6 +19,7 @@ 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; @@ -43,6 +45,7 @@ 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; @@ -68,6 +71,7 @@ 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; @@ -88,6 +92,13 @@ 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, @@ -153,6 +164,7 @@ struct cereal_SensorEventData { cereal_SensorEventData_SensorVec_ptr orientation; cereal_SensorEventData_SensorVec_ptr gyro; }; + enum cereal_SensorEventData_SensorSource source; }; static const size_t cereal_SensorEventData_word_count = 3; @@ -172,6 +184,23 @@ 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; @@ -194,6 +223,7 @@ struct cereal_ThermalData { uint16_t gpu; uint32_t bat; float freeSpace; + int16_t batteryPercent; }; static const size_t cereal_ThermalData_word_count = 3; @@ -477,7 +507,9 @@ enum cereal_Event_which { cereal_Event_sendcan = 16, cereal_Event_logMessage = 17, cereal_Event_liveCalibration = 18, - cereal_Event_androidLogEntry = 19 + cereal_Event_androidLogEntry = 19, + cereal_Event_gpsLocation = 20, + cereal_Event_carState = 21 }; struct cereal_Event { @@ -504,6 +536,8 @@ struct cereal_Event { capn_text logMessage; cereal_LiveCalibrationData_ptr liveCalibration; cereal_AndroidLogEntry_ptr androidLogEntry; + cereal_GpsLocationData_ptr gpsLocation; + cereal_CarState_ptr carState; }; }; @@ -518,6 +552,7 @@ 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*); @@ -543,6 +578,7 @@ 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); @@ -568,6 +604,7 @@ 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); @@ -593,6 +630,7 @@ 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); @@ -618,6 +656,7 @@ 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); @@ -643,6 +682,7 @@ void cereal_set_FrameData(const struct cereal_FrameData*, cereal_FrameData_list, 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); diff --git a/cereal/gen/cpp/car.capnp.c++ b/cereal/gen/cpp/car.capnp.c++ new file mode 100644 index 0000000000..10ccef31af --- /dev/null +++ b/cereal/gen/cpp/car.capnp.c++ @@ -0,0 +1,1504 @@ +// 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 new file mode 100644 index 0000000000..5f7cf8d6de --- /dev/null +++ b/cereal/gen/cpp/car.capnp.h @@ -0,0 +1,2032 @@ +// 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++ index 4ffc7516ca..99178add84 100644 --- a/cereal/gen/cpp/log.capnp.c++ +++ b/cereal/gen/cpp/log.capnp.c++ @@ -329,7 +329,7 @@ const ::capnp::_::RawSchema s_9d291d7813ba4a88 = { 0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { +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, @@ -337,77 +337,88 @@ static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { 1, 0, 7, 0, 0, 0, 4, 0, 6, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 210, 0, 0, 0, - 33, 0, 0, 0, 23, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 0, 0, 0, 199, 1, 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, - 4, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 1, 0, 252, 36, 252, 43, 189, 41, 52, 164, - 1, 0, 0, 0, 82, 0, 0, 0, + 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, - 32, 0, 0, 0, 3, 0, 4, 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, - 209, 0, 0, 0, 66, 0, 0, 0, + 237, 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, + 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, - 213, 0, 0, 0, 58, 0, 0, 0, + 241, 0, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 0, 0, 0, 3, 0, 1, 0, - 220, 0, 0, 0, 2, 0, 1, 0, + 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, - 217, 0, 0, 0, 42, 0, 0, 0, + 245, 0, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 0, 0, 0, 3, 0, 1, 0, - 224, 0, 0, 0, 2, 0, 1, 0, + 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, - 221, 0, 0, 0, 82, 0, 0, 0, + 249, 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, + 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, - 229, 0, 0, 0, 106, 0, 0, 0, + 1, 1, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 0, 0, 0, 3, 0, 1, 0, - 240, 0, 0, 0, 2, 0, 1, 0, + 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, - 237, 0, 0, 0, 74, 0, 0, 0, + 9, 1, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 0, 0, 0, 3, 0, 1, 0, - 248, 0, 0, 0, 2, 0, 1, 0, + 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, - 245, 0, 0, 0, 98, 0, 0, 0, + 17, 1, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 0, 0, 0, 3, 0, 1, 0, - 0, 1, 0, 0, 2, 0, 1, 0, + 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, - 253, 0, 0, 0, 42, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 0, 0, 0, 3, 0, 1, 0, - 4, 1, 0, 0, 2, 0, 1, 0, + 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, @@ -474,6 +485,14 @@ static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { 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, } }; @@ -481,12 +500,13 @@ static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { #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, 3, 2, 0}; -static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 0, 1, 2, 3}; +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, 146, d_a2b29a69d44529a1, m_a2b29a69d44529a1, - 1, 8, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr } + 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 = { @@ -553,6 +573,207 @@ const ::capnp::_::RawSchema s_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, @@ -641,7 +862,7 @@ const ::capnp::_::RawSchema s_8785009a964c7c59 = { 0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<138> b_8d8231a40b7fe6e0 = { +static const ::capnp::_::AlignedData<154> 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, @@ -651,70 +872,77 @@ static const ::capnp::_::AlignedData<138> b_8d8231a40b7fe6e0 = { 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, 199, 1, 0, 0, + 25, 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, 84, 104, 101, 114, 109, 97, 108, 68, 97, 116, 97, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 32, 0, 0, 0, 3, 0, 4, 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, - 209, 0, 0, 0, 42, 0, 0, 0, + 237, 0, 0, 0, 42, 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, + 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, - 213, 0, 0, 0, 42, 0, 0, 0, + 241, 0, 0, 0, 42, 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, + 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, - 217, 0, 0, 0, 42, 0, 0, 0, + 245, 0, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 0, 0, 0, 3, 0, 1, 0, - 224, 0, 0, 0, 2, 0, 1, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 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, - 221, 0, 0, 0, 42, 0, 0, 0, + 249, 0, 0, 0, 42, 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, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 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, - 225, 0, 0, 0, 34, 0, 0, 0, + 253, 0, 0, 0, 34, 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, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 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, - 229, 0, 0, 0, 34, 0, 0, 0, + 1, 1, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 0, 0, 0, 3, 0, 1, 0, - 236, 0, 0, 0, 2, 0, 1, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 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, - 233, 0, 0, 0, 34, 0, 0, 0, + 5, 1, 0, 0, 34, 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, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 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, - 237, 0, 0, 0, 82, 0, 0, 0, + 9, 1, 0, 0, 82, 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, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 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, + 17, 1, 0, 0, 122, 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, 99, 112, 117, 48, 0, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -778,16 +1006,25 @@ static const ::capnp::_::AlignedData<138> b_8d8231a40b7fe6e0 = { 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, } }; ::capnp::word const* const bp_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words; #if !CAPNP_LITE -static const uint16_t m_8d8231a40b7fe6e0[] = {6, 0, 1, 2, 3, 7, 5, 4}; -static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7}; +static const uint16_t m_8d8231a40b7fe6e0[] = {6, 8, 0, 1, 2, 3, 7, 5, 4}; +static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { - 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 138, nullptr, m_8d8231a40b7fe6e0, - 0, 8, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } + 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 154, nullptr, m_8d8231a40b7fe6e0, + 0, 9, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<112> b_cfa2b0c2c82af1e4 = { @@ -3102,170 +3339,184 @@ const ::capnp::_::RawSchema s_9811e1f38f62f2d1 = { 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<366> b_d314cfd957229c11 = { +static const ::capnp::_::AlignedData<398> b_d314cfd957229c11 = { { 0, 0, 0, 0, 5, 0, 6, 0, 17, 156, 34, 87, 217, 207, 20, 211, 10, 0, 0, 0, 1, 0, 2, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 1, 0, 7, 0, 0, 0, 20, 0, + 1, 0, 7, 0, 0, 0, 22, 0, 4, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 130, 0, 0, 0, 25, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 159, 4, 0, 0, + 21, 0, 0, 0, 15, 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, - 84, 0, 0, 0, 3, 0, 4, 0, + 92, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 2, 0, 0, 98, 0, 0, 0, + 117, 2, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 2, 0, 0, 3, 0, 1, 0, - 72, 2, 0, 0, 2, 0, 1, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, 1, 0, 255, 255, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 2, 0, 0, 74, 0, 0, 0, + 125, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 2, 0, 0, 3, 0, 1, 0, - 80, 2, 0, 0, 2, 0, 1, 0, + 124, 2, 0, 0, 3, 0, 1, 0, + 136, 2, 0, 0, 2, 0, 1, 0, 2, 0, 254, 255, 0, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 2, 0, 0, 50, 0, 0, 0, + 133, 2, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 2, 0, 0, 3, 0, 1, 0, - 84, 2, 0, 0, 2, 0, 1, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 140, 2, 0, 0, 2, 0, 1, 0, 3, 0, 253, 255, 0, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 2, 0, 0, 66, 0, 0, 0, + 137, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 76, 2, 0, 0, 3, 0, 1, 0, - 88, 2, 0, 0, 2, 0, 1, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 144, 2, 0, 0, 2, 0, 1, 0, 4, 0, 252, 255, 0, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 2, 0, 0, 178, 0, 0, 0, + 141, 2, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 2, 0, 0, 3, 0, 1, 0, - 100, 2, 0, 0, 2, 0, 1, 0, + 144, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, 5, 0, 251, 255, 0, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 97, 2, 0, 0, 34, 0, 0, 0, + 153, 2, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 2, 0, 0, 3, 0, 1, 0, - 120, 2, 0, 0, 2, 0, 1, 0, + 148, 2, 0, 0, 3, 0, 1, 0, + 176, 2, 0, 0, 2, 0, 1, 0, 6, 0, 250, 255, 0, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 2, 0, 0, 66, 0, 0, 0, + 173, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 2, 0, 0, 3, 0, 1, 0, - 124, 2, 0, 0, 2, 0, 1, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, 7, 0, 249, 255, 0, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 2, 0, 0, 66, 0, 0, 0, + 177, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 2, 0, 0, 3, 0, 1, 0, - 128, 2, 0, 0, 2, 0, 1, 0, + 172, 2, 0, 0, 3, 0, 1, 0, + 184, 2, 0, 0, 2, 0, 1, 0, 8, 0, 248, 255, 0, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 2, 0, 0, 162, 0, 0, 0, + 181, 2, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 2, 0, 0, 3, 0, 1, 0, - 156, 2, 0, 0, 2, 0, 1, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, 9, 0, 247, 255, 0, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 2, 0, 0, 50, 0, 0, 0, + 209, 2, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 2, 0, 0, 3, 0, 1, 0, - 160, 2, 0, 0, 2, 0, 1, 0, + 204, 2, 0, 0, 3, 0, 1, 0, + 216, 2, 0, 0, 2, 0, 1, 0, 10, 0, 246, 255, 0, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 2, 0, 0, 74, 0, 0, 0, + 213, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 2, 0, 0, 3, 0, 1, 0, - 168, 2, 0, 0, 2, 0, 1, 0, + 212, 2, 0, 0, 3, 0, 1, 0, + 224, 2, 0, 0, 2, 0, 1, 0, 11, 0, 245, 255, 0, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 2, 0, 0, 106, 0, 0, 0, + 221, 2, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 2, 0, 0, 3, 0, 1, 0, - 192, 2, 0, 0, 2, 0, 1, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 248, 2, 0, 0, 2, 0, 1, 0, 12, 0, 244, 255, 0, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 2, 0, 0, 58, 0, 0, 0, + 245, 2, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 2, 0, 0, 3, 0, 1, 0, - 196, 2, 0, 0, 2, 0, 1, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, 13, 0, 243, 255, 0, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 2, 0, 0, 58, 0, 0, 0, + 249, 2, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 2, 0, 0, 3, 0, 1, 0, - 200, 2, 0, 0, 2, 0, 1, 0, + 244, 2, 0, 0, 3, 0, 1, 0, + 0, 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, - 197, 2, 0, 0, 138, 0, 0, 0, + 253, 2, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 200, 2, 0, 0, 3, 0, 1, 0, - 212, 2, 0, 0, 2, 0, 1, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 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, - 209, 2, 0, 0, 82, 0, 0, 0, + 9, 3, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 2, 0, 0, 3, 0, 1, 0, - 220, 2, 0, 0, 2, 0, 1, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 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, - 217, 2, 0, 0, 90, 0, 0, 0, + 17, 3, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 2, 0, 0, 3, 0, 1, 0, - 244, 2, 0, 0, 2, 0, 1, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 44, 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, - 241, 2, 0, 0, 66, 0, 0, 0, + 41, 3, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 2, 0, 0, 3, 0, 1, 0, - 8, 3, 0, 0, 2, 0, 1, 0, + 36, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, 18, 0, 238, 255, 0, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 3, 0, 0, 90, 0, 0, 0, + 61, 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, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, 19, 0, 237, 255, 0, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 3, 0, 0, 130, 0, 0, 0, + 69, 3, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 3, 0, 0, 3, 0, 1, 0, - 24, 3, 0, 0, 2, 0, 1, 0, + 68, 3, 0, 0, 3, 0, 1, 0, + 80, 3, 0, 0, 2, 0, 1, 0, 20, 0, 236, 255, 0, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 3, 0, 0, 130, 0, 0, 0, + 77, 3, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 20, 3, 0, 0, 3, 0, 1, 0, - 32, 3, 0, 0, 2, 0, 1, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 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, + 85, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 234, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 3, 0, 0, 3, 0, 1, 0, + 104, 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, @@ -3466,6 +3717,24 @@ static const ::capnp::_::AlignedData<366> b_d314cfd957229c11 = { 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, } @@ -3483,19 +3752,21 @@ static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { &s_97ff69c53601abf1, &s_9a185389d6fdd05f, &s_9d291d7813ba4a88, + &s_9da4fa09e052903c, &s_a2b29a69d44529a1, &s_b8aad62cffef28a9, &s_c08240f996aefced, &s_cfa2b0c2c82af1e4, &s_e71008caeb3fb65c, + &s_e946524859add50e, &s_ea0245f695ae0a33, &s_ea095da1894f7d85, }; -static const uint16_t m_d314cfd957229c11[] = {20, 5, 15, 10, 2, 3, 12, 1, 7, 13, 19, 8, 16, 14, 18, 0, 9, 17, 4, 11, 6}; -static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 0}; +static const uint16_t m_d314cfd957229c11[] = {20, 5, 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, 0}; const ::capnp::_::RawSchema s_d314cfd957229c11 = { - 0xd314cfd957229c11, b_d314cfd957229c11.words, 366, d_d314cfd957229c11, m_d314cfd957229c11, - 17, 21, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } + 0xd314cfd957229c11, b_d314cfd957229c11.words, 398, d_d314cfd957229c11, m_d314cfd957229c11, + 19, 23, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE } // namespace schemas @@ -3560,6 +3831,17 @@ constexpr ::capnp::_::RawSchema const* SensorEventData::SensorVec::_capnpPrivate 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; diff --git a/cereal/gen/cpp/log.capnp.h b/cereal/gen/cpp/log.capnp.h index 8cd21c0c58..084d36aaed 100644 --- a/cereal/gen/cpp/log.capnp.h +++ b/cereal/gen/cpp/log.capnp.h @@ -10,6 +10,7 @@ #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 { @@ -20,6 +21,15 @@ 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); @@ -111,6 +121,8 @@ struct SensorEventData { GYRO, }; struct SensorVec; + typedef ::capnp::schemas::SensorSource_e49b3ce8f7f48d0d SensorSource; + struct _capnpPrivate { CAPNP_DECLARE_STRUCT_HEADER(a2b29a69d44529a1, 3, 1) @@ -135,6 +147,21 @@ struct SensorEventData::SensorVec { }; }; +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; @@ -438,6 +465,8 @@ struct Event { LOG_MESSAGE, LIVE_CALIBRATION, ANDROID_LOG_ENTRY, + GPS_LOCATION, + CAR_STATE, }; struct _capnpPrivate { @@ -796,6 +825,8 @@ public: inline bool hasGyro() const; inline ::cereal::SensorEventData::SensorVec::Reader getGyro() const; + inline ::cereal::SensorEventData::SensorSource getSource() const; + private: ::capnp::_::StructReader _reader; template @@ -869,6 +900,9 @@ public: 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 @@ -982,6 +1016,117 @@ private: }; #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; @@ -1111,6 +1256,8 @@ public: inline float getFreeSpace() const; + inline ::int16_t getBatteryPercent() const; + private: ::capnp::_::StructReader _reader; template @@ -1163,6 +1310,9 @@ public: inline float getFreeSpace(); inline void setFreeSpace(float value); + inline ::int16_t getBatteryPercent(); + inline void setBatteryPercent( ::int16_t value); + private: ::capnp::_::StructBuilder _builder; template @@ -3127,6 +3277,14 @@ public: 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; + private: ::capnp::_::StructReader _reader; template @@ -3319,6 +3477,22 @@ public: 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(); + private: ::capnp::_::StructBuilder _builder; template @@ -3894,6 +4068,20 @@ inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::B _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(); } @@ -3944,6 +4132,118 @@ inline void SensorEventData::SensorVec::Builder::setStatus( ::int8_t value) { 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); @@ -4130,6 +4430,20 @@ inline void ThermalData::Builder::setFreeSpace(float value) { 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 ::uint32_t HealthData::Reader::getVoltage() const { return _reader.getDataField< ::uint32_t>( 0 * ::capnp::ELEMENTS); @@ -7284,6 +7598,110 @@ inline ::capnp::Orphan< ::cereal::AndroidLogEntry> Event::Builder::disownAndroid _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)); +} + } // namespace #endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ diff --git a/cereal/log.capnp b/cereal/log.capnp index bc158976aa..17a879e6d8 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1,6 +1,8 @@ using Cxx = import "c++.capnp"; $Cxx.namespace("cereal"); +using Car = import "car.capnp"; + @0xf3b1f17e25a4285b; const logVersion :Int32 = 1; @@ -39,11 +41,47 @@ struct SensorEventData { orientation @6 :SensorVec; gyro @7 :SensorVec; } + source @8 :SensorSource; struct SensorVec { v @0 :List(Float32); status @1 :Int8; } + + enum SensorSource { + android @0; + iOS @1; + fiber @2; + velodyne @3; # Velodyne IMU + } +} + +# android struct GpsLocation +struct GpsLocationData { + # Contains GpsLocationFlags bits. + flags @0 :UInt16; + + # Represents latitude in degrees. + latitude @1 :Float64; + + # Represents longitude in degrees. + longitude @2 :Float64; + + # Represents altitude in meters above the WGS 84 reference ellipsoid. + altitude @3 :Float64; + + # Represents speed in meters per second. + speed @4 :Float32; + + # Represents heading in degrees. + bearing @5 :Float32; + + # Represents expected accuracy in meters. + accuracy @6 :Float32; + + # Timestamp for the location fix. + # Milliseconds since January 1, 1970. + timestamp @7 :Int64; } struct CanData { @@ -64,6 +102,7 @@ struct ThermalData { # not thermal freeSpace @7 :Float32; + batteryPercent @8 :Int16; } struct HealthData { @@ -272,5 +311,7 @@ struct Event { logMessage @18 :Text; liveCalibration @19 :LiveCalibrationData; androidLogEntry @20 :AndroidLogEntry; + gpsLocation @21 :GpsLocationData; + carState @22 :Car.CarState; } } diff --git a/common/services.py b/common/services.py index ffe592a335..9e9c6e11a1 100644 --- a/common/services.py +++ b/common/services.py @@ -33,6 +33,7 @@ service_list = { "logMessage": Service(8018, True), "liveCalibration": Service(8019, True), "androidLog": Service(8020, True), + "carState": Service(8021, True), } # manager -- base process to manage starting and stopping of all others @@ -56,7 +57,7 @@ service_list = { # controlsd -- actually drives the car # subscribes: can, thermal, model, live20 -# publishes: sendcan, live100 +# publishes: carState, sendcan, live100 # radard -- processes the radar data # subscribes: can, live100, model diff --git a/installation/files/continue.sh b/installation/files/continue.sh deleted file mode 100755 index adc05b3048..0000000000 --- a/installation/files/continue.sh +++ /dev/null @@ -1,26 +0,0 @@ -#!/usr/bin/bash - -# enable wifi access point for debugging only! -#service call wifi 37 i32 0 i32 1 # WifiService.setWifiApEnabled(null, true) - -# check out the openpilot repo -if [ ! -d /data/openpilot ]; then - cd /tmp - git clone https://github.com/commaai/openpilot.git -b release - mv /tmp/openpilot /data/openpilot -fi - -# enter openpilot directory -cd /data/openpilot - -# automatic update -git pull - -# start manager -cd selfdrive -mkdir -p /sdcard/realdata -PYTHONPATH=/data/openpilot ./manager.py - -# if broken, keep on screen error -while true; do sleep 1; done - diff --git a/installation/install.sh b/installation/install.sh deleted file mode 100755 index 85751cd508..0000000000 --- a/installation/install.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/bash -set -e - -# moving continue into place runs the continue script -adb push files/continue.sh /tmp/continue.sh -adb shell mv /tmp/continue.sh /data/data/com.termux/files/ - diff --git a/phonelibs/json/src/json.c b/phonelibs/json/src/json.c new file mode 100644 index 0000000000..2f0452aebe --- /dev/null +++ b/phonelibs/json/src/json.c @@ -0,0 +1,1381 @@ +/* + Copyright (C) 2011 Joseph A. Adams (joeyadams3.14159@gmail.com) + All rights reserved. + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in + all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + THE SOFTWARE. +*/ + +#include "json.h" + +#include +#include +#include +#include +#include + +#define out_of_memory() do { \ + fprintf(stderr, "Out of memory.\n"); \ + exit(EXIT_FAILURE); \ + } while (0) + +/* Sadly, strdup is not portable. */ +static char *json_strdup(const char *str) +{ + char *ret = (char*) malloc(strlen(str) + 1); + if (ret == NULL) + out_of_memory(); + strcpy(ret, str); + return ret; +} + +/* String buffer */ + +typedef struct +{ + char *cur; + char *end; + char *start; +} SB; + +static void sb_init(SB *sb) +{ + sb->start = (char*) malloc(17); + if (sb->start == NULL) + out_of_memory(); + sb->cur = sb->start; + sb->end = sb->start + 16; +} + +/* sb and need may be evaluated multiple times. */ +#define sb_need(sb, need) do { \ + if ((sb)->end - (sb)->cur < (need)) \ + sb_grow(sb, need); \ + } while (0) + +static void sb_grow(SB *sb, int need) +{ + size_t length = sb->cur - sb->start; + size_t alloc = sb->end - sb->start; + + do { + alloc *= 2; + } while (alloc < length + need); + + sb->start = (char*) realloc(sb->start, alloc + 1); + if (sb->start == NULL) + out_of_memory(); + sb->cur = sb->start + length; + sb->end = sb->start + alloc; +} + +static void sb_put(SB *sb, const char *bytes, int count) +{ + sb_need(sb, count); + memcpy(sb->cur, bytes, count); + sb->cur += count; +} + +#define sb_putc(sb, c) do { \ + if ((sb)->cur >= (sb)->end) \ + sb_grow(sb, 1); \ + *(sb)->cur++ = (c); \ + } while (0) + +static void sb_puts(SB *sb, const char *str) +{ + sb_put(sb, str, strlen(str)); +} + +static char *sb_finish(SB *sb) +{ + *sb->cur = 0; + assert(sb->start <= sb->cur && strlen(sb->start) == (size_t)(sb->cur - sb->start)); + return sb->start; +} + +static void sb_free(SB *sb) +{ + free(sb->start); +} + +/* + * Unicode helper functions + * + * These are taken from the ccan/charset module and customized a bit. + * Putting them here means the compiler can (choose to) inline them, + * and it keeps ccan/json from having a dependency. + */ + +/* + * Type for Unicode codepoints. + * We need our own because wchar_t might be 16 bits. + */ +typedef uint32_t uchar_t; + +/* + * Validate a single UTF-8 character starting at @s. + * The string must be null-terminated. + * + * If it's valid, return its length (1 thru 4). + * If it's invalid or clipped, return 0. + * + * This function implements the syntax given in RFC3629, which is + * the same as that given in The Unicode Standard, Version 6.0. + * + * It has the following properties: + * + * * All codepoints U+0000..U+10FFFF may be encoded, + * except for U+D800..U+DFFF, which are reserved + * for UTF-16 surrogate pair encoding. + * * UTF-8 byte sequences longer than 4 bytes are not permitted, + * as they exceed the range of Unicode. + * * The sixty-six Unicode "non-characters" are permitted + * (namely, U+FDD0..U+FDEF, U+xxFFFE, and U+xxFFFF). + */ +static int utf8_validate_cz(const char *s) +{ + unsigned char c = *s++; + + if (c <= 0x7F) { /* 00..7F */ + return 1; + } else if (c <= 0xC1) { /* 80..C1 */ + /* Disallow overlong 2-byte sequence. */ + return 0; + } else if (c <= 0xDF) { /* C2..DF */ + /* Make sure subsequent byte is in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 2; + } else if (c <= 0xEF) { /* E0..EF */ + /* Disallow overlong 3-byte sequence. */ + if (c == 0xE0 && (unsigned char)*s < 0xA0) + return 0; + + /* Disallow U+D800..U+DFFF. */ + if (c == 0xED && (unsigned char)*s > 0x9F) + return 0; + + /* Make sure subsequent bytes are in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 3; + } else if (c <= 0xF4) { /* F0..F4 */ + /* Disallow overlong 4-byte sequence. */ + if (c == 0xF0 && (unsigned char)*s < 0x90) + return 0; + + /* Disallow codepoints beyond U+10FFFF. */ + if (c == 0xF4 && (unsigned char)*s > 0x8F) + return 0; + + /* Make sure subsequent bytes are in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 4; + } else { /* F5..FF */ + return 0; + } +} + +/* Validate a null-terminated UTF-8 string. */ +static bool utf8_validate(const char *s) +{ + int len; + + for (; *s != 0; s += len) { + len = utf8_validate_cz(s); + if (len == 0) + return false; + } + + return true; +} + +/* + * Read a single UTF-8 character starting at @s, + * returning the length, in bytes, of the character read. + * + * This function assumes input is valid UTF-8, + * and that there are enough characters in front of @s. + */ +static int utf8_read_char(const char *s, uchar_t *out) +{ + const unsigned char *c = (const unsigned char*) s; + + assert(utf8_validate_cz(s)); + + if (c[0] <= 0x7F) { + /* 00..7F */ + *out = c[0]; + return 1; + } else if (c[0] <= 0xDF) { + /* C2..DF (unless input is invalid) */ + *out = ((uchar_t)c[0] & 0x1F) << 6 | + ((uchar_t)c[1] & 0x3F); + return 2; + } else if (c[0] <= 0xEF) { + /* E0..EF */ + *out = ((uchar_t)c[0] & 0xF) << 12 | + ((uchar_t)c[1] & 0x3F) << 6 | + ((uchar_t)c[2] & 0x3F); + return 3; + } else { + /* F0..F4 (unless input is invalid) */ + *out = ((uchar_t)c[0] & 0x7) << 18 | + ((uchar_t)c[1] & 0x3F) << 12 | + ((uchar_t)c[2] & 0x3F) << 6 | + ((uchar_t)c[3] & 0x3F); + return 4; + } +} + +/* + * Write a single UTF-8 character to @s, + * returning the length, in bytes, of the character written. + * + * @unicode must be U+0000..U+10FFFF, but not U+D800..U+DFFF. + * + * This function will write up to 4 bytes to @out. + */ +static int utf8_write_char(uchar_t unicode, char *out) +{ + unsigned char *o = (unsigned char*) out; + + assert(unicode <= 0x10FFFF && !(unicode >= 0xD800 && unicode <= 0xDFFF)); + + if (unicode <= 0x7F) { + /* U+0000..U+007F */ + *o++ = unicode; + return 1; + } else if (unicode <= 0x7FF) { + /* U+0080..U+07FF */ + *o++ = 0xC0 | unicode >> 6; + *o++ = 0x80 | (unicode & 0x3F); + return 2; + } else if (unicode <= 0xFFFF) { + /* U+0800..U+FFFF */ + *o++ = 0xE0 | unicode >> 12; + *o++ = 0x80 | (unicode >> 6 & 0x3F); + *o++ = 0x80 | (unicode & 0x3F); + return 3; + } else { + /* U+10000..U+10FFFF */ + *o++ = 0xF0 | unicode >> 18; + *o++ = 0x80 | (unicode >> 12 & 0x3F); + *o++ = 0x80 | (unicode >> 6 & 0x3F); + *o++ = 0x80 | (unicode & 0x3F); + return 4; + } +} + +/* + * Compute the Unicode codepoint of a UTF-16 surrogate pair. + * + * @uc should be 0xD800..0xDBFF, and @lc should be 0xDC00..0xDFFF. + * If they aren't, this function returns false. + */ +static bool from_surrogate_pair(uint16_t uc, uint16_t lc, uchar_t *unicode) +{ + if (uc >= 0xD800 && uc <= 0xDBFF && lc >= 0xDC00 && lc <= 0xDFFF) { + *unicode = 0x10000 + ((((uchar_t)uc & 0x3FF) << 10) | (lc & 0x3FF)); + return true; + } else { + return false; + } +} + +/* + * Construct a UTF-16 surrogate pair given a Unicode codepoint. + * + * @unicode must be U+10000..U+10FFFF. + */ +static void to_surrogate_pair(uchar_t unicode, uint16_t *uc, uint16_t *lc) +{ + uchar_t n; + + assert(unicode >= 0x10000 && unicode <= 0x10FFFF); + + n = unicode - 0x10000; + *uc = ((n >> 10) & 0x3FF) | 0xD800; + *lc = (n & 0x3FF) | 0xDC00; +} + +#define is_space(c) ((c) == '\t' || (c) == '\n' || (c) == '\r' || (c) == ' ') +#define is_digit(c) ((c) >= '0' && (c) <= '9') + +static bool parse_value (const char **sp, JsonNode **out); +static bool parse_string (const char **sp, char **out); +static bool parse_number (const char **sp, double *out); +static bool parse_array (const char **sp, JsonNode **out); +static bool parse_object (const char **sp, JsonNode **out); +static bool parse_hex16 (const char **sp, uint16_t *out); + +static bool expect_literal (const char **sp, const char *str); +static void skip_space (const char **sp); + +static void emit_value (SB *out, const JsonNode *node); +static void emit_value_indented (SB *out, const JsonNode *node, const char *space, int indent_level); +static void emit_string (SB *out, const char *str); +static void emit_number (SB *out, double num); +static void emit_array (SB *out, const JsonNode *array); +static void emit_array_indented (SB *out, const JsonNode *array, const char *space, int indent_level); +static void emit_object (SB *out, const JsonNode *object); +static void emit_object_indented (SB *out, const JsonNode *object, const char *space, int indent_level); + +static int write_hex16(char *out, uint16_t val); + +static JsonNode *mknode(JsonTag tag); +static void append_node(JsonNode *parent, JsonNode *child); +static void prepend_node(JsonNode *parent, JsonNode *child); +static void append_member(JsonNode *object, char *key, JsonNode *value); + +/* Assertion-friendly validity checks */ +static bool tag_is_valid(unsigned int tag); +static bool number_is_valid(const char *num); + +JsonNode *json_decode(const char *json) +{ + const char *s = json; + JsonNode *ret; + + skip_space(&s); + if (!parse_value(&s, &ret)) + return NULL; + + skip_space(&s); + if (*s != 0) { + json_delete(ret); + return NULL; + } + + return ret; +} + +char *json_encode(const JsonNode *node) +{ + return json_stringify(node, NULL); +} + +char *json_encode_string(const char *str) +{ + SB sb; + sb_init(&sb); + + emit_string(&sb, str); + + return sb_finish(&sb); +} + +char *json_stringify(const JsonNode *node, const char *space) +{ + SB sb; + sb_init(&sb); + + if (space != NULL) + emit_value_indented(&sb, node, space, 0); + else + emit_value(&sb, node); + + return sb_finish(&sb); +} + +void json_delete(JsonNode *node) +{ + if (node != NULL) { + json_remove_from_parent(node); + + switch (node->tag) { + case JSON_STRING: + free(node->string_); + break; + case JSON_ARRAY: + case JSON_OBJECT: + { + JsonNode *child, *next; + for (child = node->children.head; child != NULL; child = next) { + next = child->next; + json_delete(child); + } + break; + } + default:; + } + + free(node); + } +} + +bool json_validate(const char *json) +{ + const char *s = json; + + skip_space(&s); + if (!parse_value(&s, NULL)) + return false; + + skip_space(&s); + if (*s != 0) + return false; + + return true; +} + +JsonNode *json_find_element(JsonNode *array, int index) +{ + JsonNode *element; + int i = 0; + + if (array == NULL || array->tag != JSON_ARRAY) + return NULL; + + json_foreach(element, array) { + if (i == index) + return element; + i++; + } + + return NULL; +} + +JsonNode *json_find_member(JsonNode *object, const char *name) +{ + JsonNode *member; + + if (object == NULL || object->tag != JSON_OBJECT) + return NULL; + + json_foreach(member, object) + if (strcmp(member->key, name) == 0) + return member; + + return NULL; +} + +JsonNode *json_first_child(const JsonNode *node) +{ + if (node != NULL && (node->tag == JSON_ARRAY || node->tag == JSON_OBJECT)) + return node->children.head; + return NULL; +} + +static JsonNode *mknode(JsonTag tag) +{ + JsonNode *ret = (JsonNode*) calloc(1, sizeof(JsonNode)); + if (ret == NULL) + out_of_memory(); + ret->tag = tag; + return ret; +} + +JsonNode *json_mknull(void) +{ + return mknode(JSON_NULL); +} + +JsonNode *json_mkbool(bool b) +{ + JsonNode *ret = mknode(JSON_BOOL); + ret->bool_ = b; + return ret; +} + +static JsonNode *mkstring(char *s) +{ + JsonNode *ret = mknode(JSON_STRING); + ret->string_ = s; + return ret; +} + +JsonNode *json_mkstring(const char *s) +{ + return mkstring(json_strdup(s)); +} + +JsonNode *json_mknumber(double n) +{ + JsonNode *node = mknode(JSON_NUMBER); + node->number_ = n; + return node; +} + +JsonNode *json_mkarray(void) +{ + return mknode(JSON_ARRAY); +} + +JsonNode *json_mkobject(void) +{ + return mknode(JSON_OBJECT); +} + +static void append_node(JsonNode *parent, JsonNode *child) +{ + child->parent = parent; + child->prev = parent->children.tail; + child->next = NULL; + + if (parent->children.tail != NULL) + parent->children.tail->next = child; + else + parent->children.head = child; + parent->children.tail = child; +} + +static void prepend_node(JsonNode *parent, JsonNode *child) +{ + child->parent = parent; + child->prev = NULL; + child->next = parent->children.head; + + if (parent->children.head != NULL) + parent->children.head->prev = child; + else + parent->children.tail = child; + parent->children.head = child; +} + +static void append_member(JsonNode *object, char *key, JsonNode *value) +{ + value->key = key; + append_node(object, value); +} + +void json_append_element(JsonNode *array, JsonNode *element) +{ + assert(array->tag == JSON_ARRAY); + assert(element->parent == NULL); + + append_node(array, element); +} + +void json_prepend_element(JsonNode *array, JsonNode *element) +{ + assert(array->tag == JSON_ARRAY); + assert(element->parent == NULL); + + prepend_node(array, element); +} + +void json_append_member(JsonNode *object, const char *key, JsonNode *value) +{ + assert(object->tag == JSON_OBJECT); + assert(value->parent == NULL); + + append_member(object, json_strdup(key), value); +} + +void json_prepend_member(JsonNode *object, const char *key, JsonNode *value) +{ + assert(object->tag == JSON_OBJECT); + assert(value->parent == NULL); + + value->key = json_strdup(key); + prepend_node(object, value); +} + +void json_remove_from_parent(JsonNode *node) +{ + JsonNode *parent = node->parent; + + if (parent != NULL) { + if (node->prev != NULL) + node->prev->next = node->next; + else + parent->children.head = node->next; + if (node->next != NULL) + node->next->prev = node->prev; + else + parent->children.tail = node->prev; + + free(node->key); + + node->parent = NULL; + node->prev = node->next = NULL; + node->key = NULL; + } +} + +static bool parse_value(const char **sp, JsonNode **out) +{ + const char *s = *sp; + + switch (*s) { + case 'n': + if (expect_literal(&s, "null")) { + if (out) + *out = json_mknull(); + *sp = s; + return true; + } + return false; + + case 'f': + if (expect_literal(&s, "false")) { + if (out) + *out = json_mkbool(false); + *sp = s; + return true; + } + return false; + + case 't': + if (expect_literal(&s, "true")) { + if (out) + *out = json_mkbool(true); + *sp = s; + return true; + } + return false; + + case '"': { + char *str; + if (parse_string(&s, out ? &str : NULL)) { + if (out) + *out = mkstring(str); + *sp = s; + return true; + } + return false; + } + + case '[': + if (parse_array(&s, out)) { + *sp = s; + return true; + } + return false; + + case '{': + if (parse_object(&s, out)) { + *sp = s; + return true; + } + return false; + + default: { + double num; + if (parse_number(&s, out ? &num : NULL)) { + if (out) + *out = json_mknumber(num); + *sp = s; + return true; + } + return false; + } + } +} + +static bool parse_array(const char **sp, JsonNode **out) +{ + const char *s = *sp; + JsonNode *ret = out ? json_mkarray() : NULL; + JsonNode *element; + + if (*s++ != '[') + goto failure; + skip_space(&s); + + if (*s == ']') { + s++; + goto success; + } + + for (;;) { + if (!parse_value(&s, out ? &element : NULL)) + goto failure; + skip_space(&s); + + if (out) + json_append_element(ret, element); + + if (*s == ']') { + s++; + goto success; + } + + if (*s++ != ',') + goto failure; + skip_space(&s); + } + +success: + *sp = s; + if (out) + *out = ret; + return true; + +failure: + json_delete(ret); + return false; +} + +static bool parse_object(const char **sp, JsonNode **out) +{ + const char *s = *sp; + JsonNode *ret = out ? json_mkobject() : NULL; + char *key; + JsonNode *value; + + if (*s++ != '{') + goto failure; + skip_space(&s); + + if (*s == '}') { + s++; + goto success; + } + + for (;;) { + if (!parse_string(&s, out ? &key : NULL)) + goto failure; + skip_space(&s); + + if (*s++ != ':') + goto failure_free_key; + skip_space(&s); + + if (!parse_value(&s, out ? &value : NULL)) + goto failure_free_key; + skip_space(&s); + + if (out) + append_member(ret, key, value); + + if (*s == '}') { + s++; + goto success; + } + + if (*s++ != ',') + goto failure; + skip_space(&s); + } + +success: + *sp = s; + if (out) + *out = ret; + return true; + +failure_free_key: + if (out) + free(key); +failure: + json_delete(ret); + return false; +} + +bool parse_string(const char **sp, char **out) +{ + const char *s = *sp; + SB sb; + char throwaway_buffer[4]; + /* enough space for a UTF-8 character */ + char *b; + + if (*s++ != '"') + return false; + + if (out) { + sb_init(&sb); + sb_need(&sb, 4); + b = sb.cur; + } else { + b = throwaway_buffer; + } + + while (*s != '"') { + unsigned char c = *s++; + + /* Parse next character, and write it to b. */ + if (c == '\\') { + c = *s++; + switch (c) { + case '"': + case '\\': + case '/': + *b++ = c; + break; + case 'b': + *b++ = '\b'; + break; + case 'f': + *b++ = '\f'; + break; + case 'n': + *b++ = '\n'; + break; + case 'r': + *b++ = '\r'; + break; + case 't': + *b++ = '\t'; + break; + case 'u': + { + uint16_t uc, lc; + uchar_t unicode; + + if (!parse_hex16(&s, &uc)) + goto failed; + + if (uc >= 0xD800 && uc <= 0xDFFF) { + /* Handle UTF-16 surrogate pair. */ + if (*s++ != '\\' || *s++ != 'u' || !parse_hex16(&s, &lc)) + goto failed; /* Incomplete surrogate pair. */ + if (!from_surrogate_pair(uc, lc, &unicode)) + goto failed; /* Invalid surrogate pair. */ + } else if (uc == 0) { + /* Disallow "\u0000". */ + goto failed; + } else { + unicode = uc; + } + + b += utf8_write_char(unicode, b); + break; + } + default: + /* Invalid escape */ + goto failed; + } + } else if (c <= 0x1F) { + /* Control characters are not allowed in string literals. */ + goto failed; + } else { + /* Validate and echo a UTF-8 character. */ + int len; + + s--; + len = utf8_validate_cz(s); + if (len == 0) + goto failed; /* Invalid UTF-8 character. */ + + while (len--) + *b++ = *s++; + } + + /* + * Update sb to know about the new bytes, + * and set up b to write another character. + */ + if (out) { + sb.cur = b; + sb_need(&sb, 4); + b = sb.cur; + } else { + b = throwaway_buffer; + } + } + s++; + + if (out) + *out = sb_finish(&sb); + *sp = s; + return true; + +failed: + if (out) + sb_free(&sb); + return false; +} + +/* + * The JSON spec says that a number shall follow this precise pattern + * (spaces and quotes added for readability): + * '-'? (0 | [1-9][0-9]*) ('.' [0-9]+)? ([Ee] [+-]? [0-9]+)? + * + * However, some JSON parsers are more liberal. For instance, PHP accepts + * '.5' and '1.'. JSON.parse accepts '+3'. + * + * This function takes the strict approach. + */ +bool parse_number(const char **sp, double *out) +{ + const char *s = *sp; + + /* '-'? */ + if (*s == '-') + s++; + + /* (0 | [1-9][0-9]*) */ + if (*s == '0') { + s++; + } else { + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + /* ('.' [0-9]+)? */ + if (*s == '.') { + s++; + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + /* ([Ee] [+-]? [0-9]+)? */ + if (*s == 'E' || *s == 'e') { + s++; + if (*s == '+' || *s == '-') + s++; + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + if (out) + *out = strtod(*sp, NULL); + + *sp = s; + return true; +} + +static void skip_space(const char **sp) +{ + const char *s = *sp; + while (is_space(*s)) + s++; + *sp = s; +} + +static void emit_value(SB *out, const JsonNode *node) +{ + assert(tag_is_valid(node->tag)); + switch (node->tag) { + case JSON_NULL: + sb_puts(out, "null"); + break; + case JSON_BOOL: + sb_puts(out, node->bool_ ? "true" : "false"); + break; + case JSON_STRING: + emit_string(out, node->string_); + break; + case JSON_NUMBER: + emit_number(out, node->number_); + break; + case JSON_ARRAY: + emit_array(out, node); + break; + case JSON_OBJECT: + emit_object(out, node); + break; + default: + assert(false); + } +} + +void emit_value_indented(SB *out, const JsonNode *node, const char *space, int indent_level) +{ + assert(tag_is_valid(node->tag)); + switch (node->tag) { + case JSON_NULL: + sb_puts(out, "null"); + break; + case JSON_BOOL: + sb_puts(out, node->bool_ ? "true" : "false"); + break; + case JSON_STRING: + emit_string(out, node->string_); + break; + case JSON_NUMBER: + emit_number(out, node->number_); + break; + case JSON_ARRAY: + emit_array_indented(out, node, space, indent_level); + break; + case JSON_OBJECT: + emit_object_indented(out, node, space, indent_level); + break; + default: + assert(false); + } +} + +static void emit_array(SB *out, const JsonNode *array) +{ + const JsonNode *element; + + sb_putc(out, '['); + json_foreach(element, array) { + emit_value(out, element); + if (element->next != NULL) + sb_putc(out, ','); + } + sb_putc(out, ']'); +} + +static void emit_array_indented(SB *out, const JsonNode *array, const char *space, int indent_level) +{ + const JsonNode *element = array->children.head; + int i; + + if (element == NULL) { + sb_puts(out, "[]"); + return; + } + + sb_puts(out, "[\n"); + while (element != NULL) { + for (i = 0; i < indent_level + 1; i++) + sb_puts(out, space); + emit_value_indented(out, element, space, indent_level + 1); + + element = element->next; + sb_puts(out, element != NULL ? ",\n" : "\n"); + } + for (i = 0; i < indent_level; i++) + sb_puts(out, space); + sb_putc(out, ']'); +} + +static void emit_object(SB *out, const JsonNode *object) +{ + const JsonNode *member; + + sb_putc(out, '{'); + json_foreach(member, object) { + emit_string(out, member->key); + sb_putc(out, ':'); + emit_value(out, member); + if (member->next != NULL) + sb_putc(out, ','); + } + sb_putc(out, '}'); +} + +static void emit_object_indented(SB *out, const JsonNode *object, const char *space, int indent_level) +{ + const JsonNode *member = object->children.head; + int i; + + if (member == NULL) { + sb_puts(out, "{}"); + return; + } + + sb_puts(out, "{\n"); + while (member != NULL) { + for (i = 0; i < indent_level + 1; i++) + sb_puts(out, space); + emit_string(out, member->key); + sb_puts(out, ": "); + emit_value_indented(out, member, space, indent_level + 1); + + member = member->next; + sb_puts(out, member != NULL ? ",\n" : "\n"); + } + for (i = 0; i < indent_level; i++) + sb_puts(out, space); + sb_putc(out, '}'); +} + +void emit_string(SB *out, const char *str) +{ + bool escape_unicode = false; + const char *s = str; + char *b; + + assert(utf8_validate(str)); + + /* + * 14 bytes is enough space to write up to two + * \uXXXX escapes and two quotation marks. + */ + sb_need(out, 14); + b = out->cur; + + *b++ = '"'; + while (*s != 0) { + unsigned char c = *s++; + + /* Encode the next character, and write it to b. */ + switch (c) { + case '"': + *b++ = '\\'; + *b++ = '"'; + break; + case '\\': + *b++ = '\\'; + *b++ = '\\'; + break; + case '\b': + *b++ = '\\'; + *b++ = 'b'; + break; + case '\f': + *b++ = '\\'; + *b++ = 'f'; + break; + case '\n': + *b++ = '\\'; + *b++ = 'n'; + break; + case '\r': + *b++ = '\\'; + *b++ = 'r'; + break; + case '\t': + *b++ = '\\'; + *b++ = 't'; + break; + default: { + int len; + + s--; + len = utf8_validate_cz(s); + + if (len == 0) { + /* + * Handle invalid UTF-8 character gracefully in production + * by writing a replacement character (U+FFFD) + * and skipping a single byte. + * + * This should never happen when assertions are enabled + * due to the assertion at the beginning of this function. + */ + assert(false); + if (escape_unicode) { + strcpy(b, "\\uFFFD"); + b += 6; + } else { + *b++ = 0xEF; + *b++ = 0xBF; + *b++ = 0xBD; + } + s++; + } else if (c < 0x1F || (c >= 0x80 && escape_unicode)) { + /* Encode using \u.... */ + uint32_t unicode; + + s += utf8_read_char(s, &unicode); + + if (unicode <= 0xFFFF) { + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, unicode); + } else { + /* Produce a surrogate pair. */ + uint16_t uc, lc; + assert(unicode <= 0x10FFFF); + to_surrogate_pair(unicode, &uc, &lc); + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, uc); + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, lc); + } + } else { + /* Write the character directly. */ + while (len--) + *b++ = *s++; + } + + break; + } + } + + /* + * Update *out to know about the new bytes, + * and set up b to write another encoded character. + */ + out->cur = b; + sb_need(out, 14); + b = out->cur; + } + *b++ = '"'; + + out->cur = b; +} + +static void emit_number(SB *out, double num) +{ + /* + * This isn't exactly how JavaScript renders numbers, + * but it should produce valid JSON for reasonable numbers + * preserve precision well enough, and avoid some oddities + * like 0.3 -> 0.299999999999999988898 . + */ + char buf[64]; + sprintf(buf, "%.16g", num); + + if (number_is_valid(buf)) + sb_puts(out, buf); + else + sb_puts(out, "null"); +} + +static bool tag_is_valid(unsigned int tag) +{ + return (/* tag >= JSON_NULL && */ tag <= JSON_OBJECT); +} + +static bool number_is_valid(const char *num) +{ + return (parse_number(&num, NULL) && *num == '\0'); +} + +static bool expect_literal(const char **sp, const char *str) +{ + const char *s = *sp; + + while (*str != '\0') + if (*s++ != *str++) + return false; + + *sp = s; + return true; +} + +/* + * Parses exactly 4 hex characters (capital or lowercase). + * Fails if any input chars are not [0-9A-Fa-f]. + */ +static bool parse_hex16(const char **sp, uint16_t *out) +{ + const char *s = *sp; + uint16_t ret = 0; + uint16_t i; + uint16_t tmp; + char c; + + for (i = 0; i < 4; i++) { + c = *s++; + if (c >= '0' && c <= '9') + tmp = c - '0'; + else if (c >= 'A' && c <= 'F') + tmp = c - 'A' + 10; + else if (c >= 'a' && c <= 'f') + tmp = c - 'a' + 10; + else + return false; + + ret <<= 4; + ret += tmp; + } + + if (out) + *out = ret; + *sp = s; + return true; +} + +/* + * Encodes a 16-bit number into hexadecimal, + * writing exactly 4 hex chars. + */ +static int write_hex16(char *out, uint16_t val) +{ + const char *hex = "0123456789ABCDEF"; + + *out++ = hex[(val >> 12) & 0xF]; + *out++ = hex[(val >> 8) & 0xF]; + *out++ = hex[(val >> 4) & 0xF]; + *out++ = hex[ val & 0xF]; + + return 4; +} + +bool json_check(const JsonNode *node, char errmsg[256]) +{ + #define problem(...) do { \ + if (errmsg != NULL) \ + snprintf(errmsg, 256, __VA_ARGS__); \ + return false; \ + } while (0) + + if (node->key != NULL && !utf8_validate(node->key)) + problem("key contains invalid UTF-8"); + + if (!tag_is_valid(node->tag)) + problem("tag is invalid (%u)", node->tag); + + if (node->tag == JSON_BOOL) { + if (node->bool_ != false && node->bool_ != true) + problem("bool_ is neither false (%d) nor true (%d)", (int)false, (int)true); + } else if (node->tag == JSON_STRING) { + if (node->string_ == NULL) + problem("string_ is NULL"); + if (!utf8_validate(node->string_)) + problem("string_ contains invalid UTF-8"); + } else if (node->tag == JSON_ARRAY || node->tag == JSON_OBJECT) { + JsonNode *head = node->children.head; + JsonNode *tail = node->children.tail; + + if (head == NULL || tail == NULL) { + if (head != NULL) + problem("tail is NULL, but head is not"); + if (tail != NULL) + problem("head is NULL, but tail is not"); + } else { + JsonNode *child; + JsonNode *last = NULL; + + if (head->prev != NULL) + problem("First child's prev pointer is not NULL"); + + for (child = head; child != NULL; last = child, child = child->next) { + if (child == node) + problem("node is its own child"); + if (child->next == child) + problem("child->next == child (cycle)"); + if (child->next == head) + problem("child->next == head (cycle)"); + + if (child->parent != node) + problem("child does not point back to parent"); + if (child->next != NULL && child->next->prev != child) + problem("child->next does not point back to child"); + + if (node->tag == JSON_ARRAY && child->key != NULL) + problem("Array element's key is not NULL"); + if (node->tag == JSON_OBJECT && child->key == NULL) + problem("Object member's key is NULL"); + + if (!json_check(child, errmsg)) + return false; + } + + if (last != tail) + problem("tail does not match pointer found by starting at head and following next links"); + } + } + + return true; + + #undef problem +} diff --git a/phonelibs/json/src/json.h b/phonelibs/json/src/json.h new file mode 100644 index 0000000000..ed5255e682 --- /dev/null +++ b/phonelibs/json/src/json.h @@ -0,0 +1,117 @@ +/* + Copyright (C) 2011 Joseph A. Adams (joeyadams3.14159@gmail.com) + All rights reserved. + + 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. +*/ + +#ifndef CCAN_JSON_H +#define CCAN_JSON_H + +#include +#include + +typedef enum { + JSON_NULL, + JSON_BOOL, + JSON_STRING, + JSON_NUMBER, + JSON_ARRAY, + JSON_OBJECT, +} JsonTag; + +typedef struct JsonNode JsonNode; + +struct JsonNode +{ + /* only if parent is an object or array (NULL otherwise) */ + JsonNode *parent; + JsonNode *prev, *next; + + /* only if parent is an object (NULL otherwise) */ + char *key; /* Must be valid UTF-8. */ + + JsonTag tag; + union { + /* JSON_BOOL */ + bool bool_; + + /* JSON_STRING */ + char *string_; /* Must be valid UTF-8. */ + + /* JSON_NUMBER */ + double number_; + + /* JSON_ARRAY */ + /* JSON_OBJECT */ + struct { + JsonNode *head, *tail; + } children; + }; +}; + +/*** Encoding, decoding, and validation ***/ + +JsonNode *json_decode (const char *json); +char *json_encode (const JsonNode *node); +char *json_encode_string (const char *str); +char *json_stringify (const JsonNode *node, const char *space); +void json_delete (JsonNode *node); + +bool json_validate (const char *json); + +/*** Lookup and traversal ***/ + +JsonNode *json_find_element (JsonNode *array, int index); +JsonNode *json_find_member (JsonNode *object, const char *key); + +JsonNode *json_first_child (const JsonNode *node); + +#define json_foreach(i, object_or_array) \ + for ((i) = json_first_child(object_or_array); \ + (i) != NULL; \ + (i) = (i)->next) + +/*** Construction and manipulation ***/ + +JsonNode *json_mknull(void); +JsonNode *json_mkbool(bool b); +JsonNode *json_mkstring(const char *s); +JsonNode *json_mknumber(double n); +JsonNode *json_mkarray(void); +JsonNode *json_mkobject(void); + +void json_append_element(JsonNode *array, JsonNode *element); +void json_prepend_element(JsonNode *array, JsonNode *element); +void json_append_member(JsonNode *object, const char *key, JsonNode *value); +void json_prepend_member(JsonNode *object, const char *key, JsonNode *value); + +void json_remove_from_parent(JsonNode *node); + +/*** Debugging ***/ + +/* + * Look for structure and encoding problems in a JsonNode or its descendents. + * + * If a problem is detected, return false, writing a description of the problem + * to errmsg (unless errmsg is NULL). + */ +bool json_check(const JsonNode *node, char errmsg[256]); + +#endif diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile index 4e0c00c6c7..e27459dfb3 100644 --- a/selfdrive/boardd/Makefile +++ b/selfdrive/boardd/Makefile @@ -19,10 +19,7 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ -l:libczmq.a -l:libzmq.a \ -lgnustl_shared -CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include -CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ - -l:libcapnp.a -l:libkj.a -CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o +JSON_FLAGS = -I$(PHONELIBS)/json/src EXTRA_LIBS = -lusb @@ -34,14 +31,18 @@ CEREAL_LIBS = -L$(HOME)/drive/external/capnp/lib/ \ EXTRA_LIBS = -lusb-1.0 -lpthread endif +.PHONY: all +all: boardd + +-include ../common/cereal.mk OBJS = boardd.o \ - log.capnp.o + ../common/swaglog.o \ + $(PHONELIBS)/json/src/json.o \ + $(CEREAL_OBJS) DEPS := $(OBJS:.o=.d) -all: boardd - boardd: $(OBJS) @echo "[ LINK ] $@" $(CXX) -fPIC -o '$@' $^ \ @@ -53,18 +54,20 @@ boardd.o: boardd.cc @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) \ -I$(PHONELIBS)/android_system_core/include \ - $(CEREAL_FLAGS) \ + $(CEREAL_CFLAGS) \ $(ZMQ_FLAGS) \ -I../ \ -I../../ \ -c -o '$@' '$<' - -log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ - @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ - -c -o '$@' '$<' - +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(CEREAL_CFLAGS) \ + $(ZMQ_FLAGS) \ + $(JSON_FLAGS) \ + -c -o '$@' '$<' .PHONY: clean clean: diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index bc8378a519..117fee611b 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -20,6 +20,7 @@ #include #include "cereal/gen/cpp/log.capnp.h" +#include "common/swaglog.h" #include "common/timing.h" int do_exit = 0; @@ -29,18 +30,12 @@ libusb_device_handle *dev_handle; pthread_mutex_t usb_lock; bool spoofing_started = false; +bool fake_send = false; // double the FIFO size #define RECV_SIZE (0x1000) #define TIMEOUT 0 -#define DEBUG_BOARDD -#ifdef DEBUG_BOARDD -#define DPRINTF(fmt, ...) printf("boardd(%lu): " fmt, time(NULL), ## __VA_ARGS__) -#else -#define DPRINTF(fmt, ...) -#endif - bool usb_connect() { int err; @@ -56,11 +51,17 @@ bool usb_connect() { return true; } +void usb_retry_connect() { + LOG("attempting to connect"); + while (!usb_connect()) { usleep(100*1000); } + LOGW("connected to board"); +} void handle_usb_issue(int err, const char func[]) { - DPRINTF("usb error %d \"%s\" in %s\n", err, libusb_strerror((enum libusb_error)err), func); + LOGE("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); if (err == -4) { - while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } + LOGE("lost connection"); + usb_retry_connect(); } // TODO: check other errors, is simply retrying okay? } @@ -77,7 +78,7 @@ void can_recv(void *s) { do { err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); if (err != 0) { handle_usb_issue(err, __func__); } - if (err == -8) { DPRINTF("overflow got 0x%x\n", recv); }; + if (err == -8) { LOGE("overflow got 0x%x", recv); }; // timeout is okay to exit, recv still happened if (err == -7) { break; } @@ -199,8 +200,6 @@ void can_send(void *s) { memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); } - //DPRINTF("got send message: %d\n", msg_count); - // release msg zmq_msg_close(&msg); @@ -208,10 +207,12 @@ void can_send(void *s) { int sent; pthread_mutex_lock(&usb_lock); - do { - err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); - if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); } - } while(err != 0); + if (!fake_send) { + do { + err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); + if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); } + } while(err != 0); + } pthread_mutex_unlock(&usb_lock); @@ -223,7 +224,7 @@ void can_send(void *s) { // **** threads **** void *can_send_thread(void *crap) { - DPRINTF("start send thread\n"); + LOGD("start send thread"); // sendcan = 8017 void *context = zmq_ctx_new(); @@ -239,7 +240,7 @@ void *can_send_thread(void *crap) { } void *can_recv_thread(void *crap) { - DPRINTF("start recv thread\n"); + LOGD("start recv thread"); // can = 8006 void *context = zmq_ctx_new(); @@ -256,7 +257,7 @@ void *can_recv_thread(void *crap) { } void *can_health_thread(void *crap) { - DPRINTF("start health thread\n"); + LOGD("start health thread"); // health = 8011 void *context = zmq_ctx_new(); @@ -281,35 +282,31 @@ int set_realtime_priority(int level) { int main() { int err; - DPRINTF("starting boardd\n"); + LOGW("starting boardd"); // set process priority err = set_realtime_priority(4); - DPRINTF("setpriority returns %d\n", err); + LOG("setpriority returns %d", err); // check the environment if (getenv("STARTED")) { spoofing_started = true; } - // connect to the board + if (getenv("FAKESEND")) { + fake_send = true; + } + + // init libusb err = libusb_init(&ctx); assert(err == 0); libusb_set_debug(ctx, 3); - // TODO: duplicate code from error handling - while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } - - /*int config; - err = libusb_get_configuration(dev_handle, &config); - assert(err == 0); - DPRINTF("configuration is %d\n", config);*/ + // connect to the board + usb_retry_connect(); - /*err = libusb_set_interface_alt_setting(dev_handle, 0, 0); - assert(err == 0);*/ // create threads - pthread_t can_health_thread_handle; err = pthread_create(&can_health_thread_handle, NULL, can_health_thread, NULL); diff --git a/selfdrive/calibrationd/calibrationd.py b/selfdrive/calibrationd/calibrationd.py index 779cb4723f..9ae83da3f3 100755 --- a/selfdrive/calibrationd/calibrationd.py +++ b/selfdrive/calibrationd/calibrationd.py @@ -1,6 +1,9 @@ #!/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 @@ -8,6 +11,7 @@ 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): @@ -32,28 +36,33 @@ def load_calibration(gctx): # load calibration data if os.path.isfile(CALIBRATION_FILE): - # if the calibration file exist, start from the last cal values - with open(CALIBRATION_FILE, "r") as cal_file: - data = [float(l.strip()) for l in cal_file.readlines()] - calib = ViewCalibrator((I.X, I.Y), - big_box_size, - vp_img, - warp_matrix_start, - vp_f=[data[2], data[3]], - cal_cycle=data[0], - cal_status=data[1]) - - if calib.cal_status == CalibStatus.INCOMPLETE: - print "CALIBRATION IN PROGRESS", calib.cal_cycle - else: - print "NO CALIBRATION FILE" - calib = ViewCalibrator((I.X, I.Y), - big_box_size, - vp_img, - warp_matrix_start, - vp_f=vp_guess) - - return calib + 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() @@ -69,7 +78,7 @@ def calibrationd_thread(gctx): v_ego = None calib = load_calibration(gctx) - last_cal_cycle = calib.cal_cycle + last_write_cycle = calib.cal_cycle while 1: # calibration at the end so it does not delay radar processing above @@ -91,14 +100,10 @@ def calibrationd_thread(gctx): calib.calibration(p0, p1, st, v_ego, steer_angle, VP) # write a new calibration every 100 cal cycle - if calib.cal_cycle - last_cal_cycle >= 100: - print "writing cal", calib.cal_cycle - with open(CALIBRATION_FILE, "w") as cal_file: - cal_file.write(str(calib.cal_cycle)+'\n') - cal_file.write(str(calib.cal_status)+'\n') - cal_file.write(str(calib.vp_f[0])+'\n') - cal_file.write(str(calib.vp_f[1])+'\n') - last_cal_cycle = calib.cal_cycle + 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() diff --git a/selfdrive/common/cereal.mk b/selfdrive/common/cereal.mk new file mode 100644 index 0000000000..f09bfa7722 --- /dev/null +++ b/selfdrive/common/cereal.mk @@ -0,0 +1,17 @@ +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 +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) \ + -c -o '$@' '$<' + +car.capnp.o: ../../cereal/gen/cpp/car.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_CFLAGS) \ + -c -o '$@' '$<' + diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 4b13b644d4..25e5d5577a 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -53,6 +53,7 @@ extern "C" FramebufferState* framebuffer_init( assert(status == 0); int orientation = 3; // rotate framebuffer 270 degrees + //int orientation = 1; // rotate framebuffer 90 degrees if(orientation == 1 || orientation == 3) { int temp = s->dinfo.h; s->dinfo.h = s->dinfo.w; diff --git a/selfdrive/common/glutil.c b/selfdrive/common/glutil.c new file mode 100644 index 0000000000..d118dd8af6 --- /dev/null +++ b/selfdrive/common/glutil.c @@ -0,0 +1,71 @@ +#include +#include + +#include + +#include "glutil.h" + +GLuint load_shader(GLenum shaderType, const char *src) { + GLint status = 0, len = 0; + GLuint shader; + + if (!(shader = glCreateShader(shaderType))) + return 0; + + glShaderSource(shader, 1, &src, NULL); + glCompileShader(shader); + glGetShaderiv(shader, GL_COMPILE_STATUS, &status); + + if (status) + return shader; + + glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *msg = (char*)malloc(len); + if (msg) { + glGetShaderInfoLog(shader, len, NULL, msg); + msg[len-1] = 0; + fprintf(stderr, "error compiling shader:\n%s\n", msg); + free(msg); + } + } + glDeleteShader(shader); + return 0; +} + +GLuint load_program(const char *vert_src, const char *frag_src) { + GLuint vert, frag, prog; + GLint status = 0, len = 0; + + if (!(vert = load_shader(GL_VERTEX_SHADER, vert_src))) + return 0; + if (!(frag = load_shader(GL_FRAGMENT_SHADER, frag_src))) + goto fail_frag; + if (!(prog = glCreateProgram())) + goto fail_prog; + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + glLinkProgram(prog); + + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status) + return prog; + + glGetProgramiv(prog, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *buf = (char*) malloc(len); + if (buf) { + glGetProgramInfoLog(prog, len, NULL, buf); + buf[len-1] = 0; + fprintf(stderr, "error linking program:\n%s\n", buf); + free(buf); + } + } + glDeleteProgram(prog); +fail_prog: + glDeleteShader(frag); +fail_frag: + glDeleteShader(vert); + return 0; +} diff --git a/selfdrive/common/glutil.h b/selfdrive/common/glutil.h new file mode 100644 index 0000000000..68d6cfa630 --- /dev/null +++ b/selfdrive/common/glutil.h @@ -0,0 +1,8 @@ +#ifndef COMMON_GLUTIL_H +#define COMMON_GLUTIL_H + +#include +GLuint load_shader(GLenum shaderType, const char *src); +GLuint load_program(const char *vert_src, const char *frag_src); + +#endif diff --git a/selfdrive/common/swaglog.c b/selfdrive/common/swaglog.c index 8fc64aed8e..8d31e99522 100644 --- a/selfdrive/common/swaglog.c +++ b/selfdrive/common/swaglog.c @@ -19,6 +19,7 @@ typedef struct LogState { JsonNode *ctx_j; void *zctx; void *sock; + int print_level; } LogState; static LogState s = { @@ -31,6 +32,19 @@ static void cloudlog_init() { s.zctx = zmq_ctx_new(); s.sock = zmq_socket(s.zctx, ZMQ_PUSH); zmq_connect(s.sock, "ipc:///tmp/logmessage"); + + s.print_level = CLOUDLOG_WARNING; + const char* print_level = getenv("LOGPRINT"); + if (print_level) { + if (strcmp(print_level, "debug") == 0) { + s.print_level = CLOUDLOG_DEBUG; + } else if (strcmp(print_level, "info") == 0) { + s.print_level = CLOUDLOG_INFO; + } else if (strcmp(print_level, "warning") == 0) { + s.print_level = CLOUDLOG_WARNING; + } + } + s.inited = true; } @@ -50,7 +64,7 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func return; } - if (levelnum >= CLOUDLOG_PRINT_LEVEL) { + if (levelnum >= s.print_level) { printf("%s: %s\n", filename, msg_buf); } diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h index 50b01da66f..47f6af6e8b 100644 --- a/selfdrive/common/swaglog.h +++ b/selfdrive/common/swaglog.h @@ -7,13 +7,19 @@ #define CLOUDLOG_ERROR 40 #define CLOUDLOG_CRITICAL 50 -#define CLOUDLOG_PRINT_LEVEL CLOUDLOG_WARNING +#ifdef __cplusplus +extern "C" { +#endif void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; void cloudlog_bind(const char* k, const char* v); +#ifdef __cplusplus +} +#endif + #define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ __func__, __DATE__ " " __TIME__, \ fmt, ## __VA_ARGS__) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index fc442273c3..11b08e1f78 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -const char *openpilot_version = "0.2.3"; +const char *openpilot_version = "0.2.4"; diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 9b7ad903ed..51f52d1c56 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -38,6 +38,7 @@ def controlsd_thread(gctx, rate=100): #rate in Hz # *** log *** context = zmq.Context() live100 = messaging.pub_sock(context, service_list['live100'].port) + carstate = messaging.pub_sock(context, service_list['carState'].port) thermal = messaging.sub_sock(context, service_list['thermal'].port) live20 = messaging.sub_sock(context, service_list['live20'].port) @@ -88,6 +89,12 @@ def controlsd_thread(gctx, rate=100): #rate in Hz # read CAN CS = CI.update() + # broadcast carState + cs_send = messaging.new_message() + cs_send.init('carState') + cs_send.carState = CS # copy? + carstate.send(cs_send.to_bytes()) + prof.checkpoint("CarInterface") # did it request to enable? diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 0cf6ae180f..d30f46592d 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -57,10 +57,12 @@ class AlertManager(object): "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.), "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.), } def __init__(self): self.activealerts = [] self.current_alert = None + self.add("startup", False) def alertPresent(self): return len(self.activealerts) > 0 diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index ec3a68c464..9d2216ccf4 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -219,7 +219,7 @@ class Cluster(object): ret += " vision_cnt: %6.0f" % self.vision_cnt return ret - def is_potential_lead(self, v_ego, enabled): + def is_potential_lead(self, v_ego): # predict cut-ins by extrapolating lateral speed by a lookahead time # lookahead time depends on cut-in distance. more attentive for close cut-ins # also, above 50 meters the predicted path isn't very reliable @@ -233,12 +233,11 @@ class Cluster(object): # average dist d_path = self.dPath - if enabled: - t_lookahead = interp(self.dRel, t_lookahead_bp, t_lookahead_v) - # correct d_path for lookahead time, considering only cut-ins and no more than 1m impact - lat_corr = clip(t_lookahead * self.vLat, -1, 0) - else: - lat_corr = 0. + # lat_corr used to be gated on enabled, now always running + t_lookahead = interp(self.dRel, t_lookahead_bp, t_lookahead_v) + # correct d_path for lookahead time, considering only cut-ins and no more than 1m impact + lat_corr = clip(t_lookahead * self.vLat, -1, 0) + d_path = max(d_path + lat_corr, 0) if d_path < 1.5 and not self.stationary and not self.oncoming: diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index ae612f9aa9..8bd93186f5 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -196,7 +196,7 @@ def radard_thread(gctx=None): # *** extract the lead car *** lead_clusters = [c for c in clusters - if c.is_potential_lead(v_ego, enabled)] + if c.is_potential_lead(v_ego)] lead_clusters.sort(key=lambda x: x.dRel) lead_len = len(lead_clusters) diff --git a/selfdrive/logcatd/Makefile b/selfdrive/logcatd/Makefile index 610ca25676..b22ef1e1c6 100644 --- a/selfdrive/logcatd/Makefile +++ b/selfdrive/logcatd/Makefile @@ -17,18 +17,16 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ -l:libczmq.a -l:libzmq.a \ -lgnustl_shared -CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include -CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ - -l:libcapnp.a -l:libkj.a -CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o +.PHONY: all +all: logcatd + +-include ../common/cereal.mk OBJS = logcatd.o \ - log.capnp.o + $(CEREAL_OBJS) DEPS := $(OBJS:.o=.d) -all: logcatd - logcatd: $(OBJS) @echo "[ LINK ] $@" $(CXX) -fPIC -o '$@' $^ \ @@ -40,17 +38,12 @@ logcatd: $(OBJS) @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) \ -I$(PHONELIBS)/android_system_core/include \ - $(CEREAL_FLAGS) \ + $(CEREAL_CFLAGS) \ $(ZMQ_FLAGS) \ -I../ \ -I../../ \ -c -o '$@' '$<' -log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ - @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ - -c -o '$@' '$<' - .PHONY: clean clean: rm -f logcatd $(OBJS) $(DEPS) diff --git a/selfdrive/manager.py b/selfdrive/manager.py index ca2ef87345..ab3729454a 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -194,6 +194,10 @@ def manager_thread(): count = 0 + # set 5 second timeout on health socket + # 5x slower than expected + health_sock.RCVTIMEO = 5000 + while 1: # get health of board, log this in "thermal" td = messaging.recv_sock(health_sock, wait=True) @@ -208,6 +212,8 @@ def manager_thread(): # thermal message now also includes free space msg.thermal.freeSpace = avail + with open("/sys/class/power_supply/battery/capacity") as f: + msg.thermal.batteryPercent = int(f.read()) thermal_sock.send(msg.to_bytes()) print msg @@ -228,7 +234,7 @@ def manager_thread(): # 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.health.started and avail > 0.02: + 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) @@ -246,7 +252,14 @@ def manager_thread(): # report to server once per minute if (count%60) == 0: names, total_size = fake_uploader.get_data_stats() - cloudlog.info({"names": names, "total_size": total_size, "running": running.keys(), "count": count, "health": td.to_dict(), "thermal": msg.to_dict(), "version": version, "nonce": "THIS_STATUS_PACKET"}) + cloudlog.event("STATUS_PACKET", + names=names, + total_size=total_size, + running=running.keys(), + count=count, + health=(td.to_dict() if td else None), + thermal=msg.to_dict(), + version=version) count += 1 @@ -270,24 +283,6 @@ def manager_prepare(): subprocess.check_call(["make", "clean"], cwd=proc[0]) subprocess.check_call(["make", "-j4"], cwd=proc[0]) -def manager_test(): - global managed_processes - managed_processes = {} - managed_processes["test1"] = ("test", ["./test.py"]) - managed_processes["test2"] = ("test", ["./test.py"]) - managed_processes["test3"] = "selfdrive.test.test" - manager_prepare() - start_managed_process("test1") - start_managed_process("test2") - start_managed_process("test3") - print running - time.sleep(3) - kill_managed_process("test1") - kill_managed_process("test2") - kill_managed_process("test3") - print running - time.sleep(10) - def wait_for_device(): while 1: try: @@ -319,20 +314,23 @@ def main(): del managed_processes['loggerd'] del managed_processes['logmessaged'] del managed_processes['logcatd'] + if os.getenv("NOCONTROL") is not None: + del managed_processes['controlsd'] + del managed_processes['radard'] manager_init() + manager_prepare() + + if os.getenv("PREPAREONLY") is not None: + sys.exit(0) - if len(sys.argv) > 1 and sys.argv[1] == "test": - manager_test() - else: - manager_prepare() - try: - manager_thread() - except Exception: - traceback.print_exc() - common.crash.capture_exception() - finally: - cleanup_all_processes(None, None) + try: + manager_thread() + except Exception: + traceback.print_exc() + common.crash.capture_exception() + finally: + cleanup_all_processes(None, None) if __name__ == "__main__": main() diff --git a/selfdrive/sensord/Makefile b/selfdrive/sensord/Makefile index e6ad07817e..ac99cbcb23 100644 --- a/selfdrive/sensord/Makefile +++ b/selfdrive/sensord/Makefile @@ -17,18 +17,16 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ -l:libczmq.a -l:libzmq.a \ -lgnustl_shared -CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include -CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ - -l:libcapnp.a -l:libkj.a -CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o +.PHONY: all +all: sensord + +-include ../common/cereal.mk OBJS = sensors.o \ - log.capnp.o + $(CEREAL_OBJS) DEPS := $(OBJS:.o=.d) -all: sensord - sensord: $(OBJS) @echo "[ LINK ] $@" $(CXX) -fPIC -o '$@' $^ \ @@ -40,19 +38,12 @@ sensors.o: sensors.cc @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) \ -I$(PHONELIBS)/android_system_core/include \ - $(CEREAL_FLAGS) \ + $(CEREAL_CFLAGS) \ $(ZMQ_FLAGS) \ -I../ \ -I../../ \ -c -o '$@' '$<' - -log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ - @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ - -c -o '$@' '$<' - - .PHONY: clean clean: rm -f sensord $(OBJS) $(DEPS) diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors.cc index 774b9afc26..e8ce856225 100644 --- a/selfdrive/sensord/sensors.cc +++ b/selfdrive/sensord/sensors.cc @@ -83,6 +83,7 @@ void sensor_loop() { 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); diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile index e4549e1183..19b9bc7df6 100644 --- a/selfdrive/ui/Makefile +++ b/selfdrive/ui/Makefile @@ -30,6 +30,7 @@ FRAMEBUFFER_LIBS = -lutils -lgui -lEGL OBJS = ui.o \ touch.o \ + ../common/glutil.o \ ../common/visionipc.o \ ../common/framebuffer.o \ $(PHONELIBS)/nanovg/nanovg.o \ diff --git a/selfdrive/ui/touch.c b/selfdrive/ui/touch.c index a1b6a683af..a6dc226053 100644 --- a/selfdrive/ui/touch.c +++ b/selfdrive/ui/touch.c @@ -1,15 +1,50 @@ +#include +#include #include +#include #include #include -#include +#include #include #include #include "touch.h" +static int find_dev() { + int err; + + int ret = -1; + + DIR *dir = opendir("/dev/input"); + assert(dir); + struct dirent* de = NULL; + while ((de = readdir(dir))) { + if (strncmp(de->d_name, "event", 5)) continue; + + int fd = openat(dirfd(dir), de->d_name, O_RDONLY); + assert(fd >= 0); + + char name[128] = {0}; + err = ioctl(fd, EVIOCGNAME(sizeof(name) - 1), &name); + assert(err >= 0); + + unsigned long ev_bits[8] = {0}; + err = ioctl(fd, EVIOCGBIT(0, sizeof(ev_bits)), ev_bits); + assert(err >= 0); + + if (strncmp(name, "synaptics", 9) == 0 && ev_bits[0] == 0xb) { + ret = fd; + break; + } + close(fd); + } + closedir(dir); + + return ret; +} + void touch_init(TouchState *s) { - // synaptics touch screen on oneplus 3 - s->fd = open("/dev/input/event4", O_RDONLY); + s->fd = find_dev(); assert(s->fd >= 0); } diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index 4dfd18ff6b..a2b26b35e5 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -20,6 +20,7 @@ #include "common/timing.h" #include "common/util.h" #include "common/mat.h" +#include "common/glutil.h" #include "common/framebuffer.h" #include "common/visionipc.h" @@ -250,70 +251,6 @@ static const char line_fragment_shader[] = " gl_FragColor = vColor;\n" "}\n"; -static GLuint load_shader(GLenum shaderType, const char *src) { - GLint status = 0, len = 0; - GLuint shader; - - if (!(shader = glCreateShader(shaderType))) - return 0; - - glShaderSource(shader, 1, &src, NULL); - glCompileShader(shader); - glGetShaderiv(shader, GL_COMPILE_STATUS, &status); - - if (status) - return shader; - - glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &len); - if (len) { - char *msg = malloc(len); - if (msg) { - glGetShaderInfoLog(shader, len, NULL, msg); - msg[len-1] = 0; - fprintf(stderr, "error compiling shader:\n%s\n", msg); - free(msg); - } - } - glDeleteShader(shader); - return 0; -} - -static GLuint load_program(const char *vert_src, const char *frag_src) { - GLuint vert, frag, prog; - GLint status = 0, len = 0; - - if (!(vert = load_shader(GL_VERTEX_SHADER, vert_src))) - return 0; - if (!(frag = load_shader(GL_FRAGMENT_SHADER, frag_src))) - goto fail_frag; - if (!(prog = glCreateProgram())) - goto fail_prog; - - glAttachShader(prog, vert); - glAttachShader(prog, frag); - glLinkProgram(prog); - - glGetProgramiv(prog, GL_LINK_STATUS, &status); - if (status) - return prog; - - glGetProgramiv(prog, GL_INFO_LOG_LENGTH, &len); - if (len) { - char *buf = (char*) malloc(len); - if (buf) { - glGetProgramInfoLog(prog, len, NULL, buf); - buf[len-1] = 0; - fprintf(stderr, "error linking program:\n%s\n", buf); - free(buf); - } - } - glDeleteProgram(prog); -fail_prog: - glDeleteShader(frag); -fail_frag: - glDeleteShader(vert); - return 0; -} static const mat4 device_transform = {{ 1.0, 0.0, 0.0, 0.0, @@ -760,9 +697,9 @@ 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, + /*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); + 0xFF0000FF);*/ ui_draw_transformed_box(s, 0xFF00FF00); @@ -843,7 +780,7 @@ static void ui_draw_vision(UIState *s) { if (strlen(scene->alert_text2) > 0) { nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); nvgFontSize(s->vg, 100.0f); - nvgText(s->vg, 100+1700/2, 200+500, scene->alert_text2, NULL); + nvgText(s->vg, 100+1700/2, 200+550, scene->alert_text2, NULL); } } @@ -1271,10 +1208,12 @@ static void ui_update(UIState *s) { s->last_base_update = ts; - if (s->awake_timeout > 0) { - s->awake_timeout--; - } else { - set_awake(s, false); + if (!activity_running()) { + if (s->awake_timeout > 0) { + s->awake_timeout--; + } else { + set_awake(s, false); + } } } diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 127fe4d8de..77707ca4df 100755 Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ