openpilot v0.2.4 release

old-commit-hash: ecc565aa3f
commatwo_master v0.2.4
Vehicle Researcher 8 years ago
parent ed1c0d5fec
commit 7609fa3b51
  1. 1
      .gitignore
  2. 6
      Makefile
  3. 11
      README.md
  4. 6
      RELEASES.md
  5. 9
      board/can.h
  6. 3
      board/inc/stm32f2xx_hal_def.h
  7. 3
      board/inc/stm32f2xx_hal_gpio_ex.h
  8. 41
      board/libc.h
  9. 80
      board/main.c
  10. 23
      board/spi.h
  11. 337
      cereal/gen/c/car.capnp.c
  12. 287
      cereal/gen/c/car.capnp.h
  13. 55
      cereal/gen/c/log.capnp.c
  14. 42
      cereal/gen/c/log.capnp.h
  15. 1504
      cereal/gen/cpp/car.capnp.c++
  16. 2032
      cereal/gen/cpp/car.capnp.h
  17. 554
      cereal/gen/cpp/log.capnp.c++
  18. 418
      cereal/gen/cpp/log.capnp.h
  19. 41
      cereal/log.capnp
  20. 3
      common/services.py
  21. 26
      installation/files/continue.sh
  22. 7
      installation/install.sh
  23. 3
      phonelibs/json/src/json.c
  24. 3
      phonelibs/json/src/json.h
  25. 29
      selfdrive/boardd/Makefile
  26. 53
      selfdrive/boardd/boardd.cc
  27. 51
      selfdrive/calibrationd/calibrationd.py
  28. 17
      selfdrive/common/cereal.mk
  29. 1
      selfdrive/common/framebuffer.cc
  30. 71
      selfdrive/common/glutil.c
  31. 8
      selfdrive/common/glutil.h
  32. 16
      selfdrive/common/swaglog.c
  33. 8
      selfdrive/common/swaglog.h
  34. 2
      selfdrive/common/version.h
  35. 7
      selfdrive/controls/controlsd.py
  36. 2
      selfdrive/controls/lib/alertmanager.py
  37. 7
      selfdrive/controls/lib/radar_helpers.py
  38. 2
      selfdrive/controls/radard.py
  39. 19
      selfdrive/logcatd/Makefile
  40. 46
      selfdrive/manager.py
  41. 21
      selfdrive/sensord/Makefile
  42. 1
      selfdrive/sensord/sensors.cc
  43. 1
      selfdrive/ui/Makefile
  44. 41
      selfdrive/ui/touch.c
  45. 73
      selfdrive/ui/ui.c
  46. 4
      selfdrive/visiond/visiond

1
.gitignore vendored

@ -1,5 +1,6 @@
.DS_Store .DS_Store
.tags .tags
.ipynb_checkpoints
*.pyc *.pyc
.*.swp .*.swp

@ -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

@ -10,15 +10,9 @@ The openpilot codebase has been written to be concise and enable rapid prototypi
Hardware 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: Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup.
```bash
# Requires working adb in PATH
cd installation
./install.sh
```
Supported Cars Supported Cars
------ ------
@ -36,7 +30,6 @@ Directory structure
- cereal -- The messaging spec used for all logs on the phone - cereal -- The messaging spec used for all logs on the phone
- common -- Library like functionality we've developed here - common -- Library like functionality we've developed here
- dbcs -- Files showing how to interpret data from cars - dbcs -- Files showing how to interpret data from cars
- installation -- Installation on the neo platform
- phonelibs -- Libraries used on the phone - phonelibs -- Libraries used on the phone
- selfdrive -- Code needed to drive the car - selfdrive -- Code needed to drive the car
- assets -- Fonts for ui - assets -- Fonts for ui

@ -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) Version 0.2.3 (2017-01-11)
=========================== ===========================
* Reduce space usage by 80% * Reduce space usage by 80%

@ -1,4 +1,13 @@
void can_init(CAN_TypeDef *CAN) { 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; CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
puts("CAN initting\n"); puts("CAN initting\n");

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:740f87930e67d4288d9e89186a89ca71254acd3981dc7231157a3c41305152b2
size 6017

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:99bd10a191f12b66e5a58fee1176f419785cb3c0ced16fc8f9c879682912aa64
size 11218

@ -13,19 +13,7 @@
#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) #define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100)
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F)) #define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F))
#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ #include "stm32f2xx_hal_gpio_ex.h"
#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */
#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */
#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */
#define GPIO_AF10_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */
#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS */
#ifdef OLD_BOARD
#define USART USART2
#else
#define USART USART3
#endif
// **** shitty libc **** // **** shitty libc ****
@ -68,15 +56,20 @@ void clock_init() {
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN; RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN; RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
RCC->APB1ENR |= RCC_APB1ENR_DACEN; RCC->APB1ENR |= RCC_APB1ENR_DACEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
//RCC->APB1ENR |= RCC_APB1ENR_TIM4EN;
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
//RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// turn on alt USB // turn on alt USB
RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN; RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN;
@ -101,7 +94,7 @@ void gpio_init() {
// IGNITION on C13 // IGNITION on C13
// set mode for LEDs and CAN // 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 // CAN 2
GPIOB->MODER |= GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1; GPIOB->MODER |= GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1;
// CAN 1 // CAN 1
@ -125,6 +118,12 @@ void gpio_init() {
GPIOA->PUPDR = GPIO_PUPDR_PUPDR2_0 | GPIO_PUPDR_PUPDR3_0; 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 // set mode for CAN / USB_HS pins
GPIOB->AFR[0] = GPIO_AF9_CAN1 << (5*4) | GPIO_AF9_CAN1 << (6*4); 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); 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; GPIOB->OSPEEDR = GPIO_OSPEEDER_OSPEEDR14 | GPIO_OSPEEDER_OSPEEDR15;
// enable CAN busses
GPIOB->ODR |= (1 << 3) | (1 << 4);
// enable OTG out tied to ground // enable OTG out tied to ground
GPIOA->ODR = 0; GPIOA->ODR = 0;
GPIOA->MODER |= GPIO_MODER_MODER1_0; GPIOA->MODER |= GPIO_MODER_MODER1_0;
@ -223,4 +219,13 @@ void *memcpy(void *dest, const void *src, unsigned int n) {
return dest; 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));
}
}

@ -3,6 +3,11 @@
//#define USE_INTERNAL_OSC //#define USE_INTERNAL_OSC
//#define OLD_BOARD //#define OLD_BOARD
//#define ENABLE_CURRENT_SENSOR //#define ENABLE_CURRENT_SENSOR
//#define ENABLE_SPI
// choose serial port for debugging
//#define USART USART2
#define USART USART3
#define USB_VID 0xbbaa #define USB_VID 0xbbaa
#define USB_PID 0xddcc #define USB_PID 0xddcc
@ -22,6 +27,7 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS;
#include "timer.h" #include "timer.h"
#include "usb.h" #include "usb.h"
#include "can.h" #include "can.h"
#include "spi.h"
// debug safety check: is controls allowed? // debug safety check: is controls allowed?
int controls_allowed = 0; int controls_allowed = 0;
@ -394,6 +400,48 @@ void ADC_IRQHandler(void) {
puts("ADC_IRQ\n"); 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 ***************************** // ***************************** main code *****************************
void __initialize_hardware_early() { void __initialize_hardware_early() {
@ -428,11 +476,6 @@ int main() {
// init devices // init devices
clock_init(); clock_init();
// test the USB choice before GPIO init
if (GPIOA->IDR & (1 << 12)) {
USBx = USB_OTG_HS;
}
gpio_init(); gpio_init();
uart_init(); uart_init();
usb_init(); usb_init();
@ -440,6 +483,14 @@ int main() {
can_init(CAN2); can_init(CAN2);
adc_init(); 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 // timer for fan PWM
#ifdef OLD_BOARD #ifdef OLD_BOARD
TIM3->CCMR2 = TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1; TIM3->CCMR2 = TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1;
@ -475,13 +526,21 @@ int main() {
NVIC_EnableIRQ(CAN2_TX_IRQn); NVIC_EnableIRQ(CAN2_TX_IRQn);
NVIC_EnableIRQ(CAN2_RX0_IRQn); NVIC_EnableIRQ(CAN2_RX0_IRQn);
NVIC_EnableIRQ(CAN2_SCE_IRQn); NVIC_EnableIRQ(CAN2_SCE_IRQn);
#ifdef ENABLE_SPI
NVIC_EnableIRQ(DMA2_Stream3_IRQn);
NVIC_EnableIRQ(SPI1_IRQn);
#endif
__enable_irq(); __enable_irq();
// LED should keep on blinking all the time // LED should keep on blinking all the time
while (1) { int cnt;
for (cnt=0;;cnt++) {
can_live = pending_can_live; can_live = pending_can_live;
pending_can_live = 0;
// reset this every 16th pass
if ((cnt&0xF) == 0) pending_can_live = 0;
#ifdef DEBUG #ifdef DEBUG
puts("** blink "); puts("** blink ");
@ -504,6 +563,13 @@ int main() {
GPIOB->ODR &= ~(1 << 10); GPIOB->ODR &= ~(1 << 10);
delay(1000000); delay(1000000);
#ifdef ENABLE_SPI
if (spi_buf_count > 0) {
hexdump(spi_buf, spi_buf_count);
spi_buf_count = 0;
}
#endif
// started logic // started logic
int started_signal = (GPIOC->IDR & (1 << 13)) != 0; int started_signal = (GPIOC->IDR & (1 << 13)) != 0;
if (started_signal) { started_signal_detected = 1; } if (started_signal) { started_signal_detected = 1; }

@ -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;
}

@ -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);
}

@ -0,0 +1,287 @@
#ifndef CAPN_8E2AF1E78AF8B8D
#define CAPN_8E2AF1E78AF8B8D
/* AUTO GENERATED - DO NOT EDIT */
#include <capnp_c.h>
#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

@ -137,6 +137,7 @@ void cereal_read_SensorEventData(struct cereal_SensorEventData *s, cereal_Sensor
default: default:
break; 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) { void cereal_write_SensorEventData(const struct cereal_SensorEventData *s, cereal_SensorEventData_ptr p) {
capn_resolve(&p.p); capn_resolve(&p.p);
@ -155,6 +156,7 @@ void cereal_write_SensorEventData(const struct cereal_SensorEventData *s, cereal
default: default:
break; break;
} }
capn_write16(p.p, 14, (uint16_t) (s->source));
} }
void cereal_get_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) { void cereal_get_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) {
cereal_SensorEventData_ptr p; 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_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 cereal_new_CanData(struct capn_segment *s) {
cereal_CanData_ptr p; cereal_CanData_ptr p;
p.p = capn_new_struct(s, 8, 1); 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->gpu = capn_read16(p.p, 10);
s->bat = capn_read32(p.p, 12); s->bat = capn_read32(p.p, 12);
s->freeSpace = capn_to_f32(capn_read32(p.p, 16)); 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) { void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) {
capn_resolve(&p.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_write16(p.p, 10, s->gpu);
capn_write32(p.p, 12, s->bat); capn_write32(p.p, 12, s->bat);
capn_write32(p.p, 16, capn_from_f32(s->freeSpace)); 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) { void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) {
cereal_ThermalData_ptr p; 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_sendcan:
case cereal_Event_liveCalibration: case cereal_Event_liveCalibration:
case cereal_Event_androidLogEntry: 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; break;
default: default:
break; 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_sendcan:
case cereal_Event_liveCalibration: case cereal_Event_liveCalibration:
case cereal_Event_androidLogEntry: 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; break;
default: default:
break; break;

@ -8,6 +8,7 @@
#endif #endif
#include "c++.capnp.h" #include "c++.capnp.h"
#include "car.capnp.h"
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
@ -18,6 +19,7 @@ struct cereal_FrameData;
struct cereal_GPSNMEAData; struct cereal_GPSNMEAData;
struct cereal_SensorEventData; struct cereal_SensorEventData;
struct cereal_SensorEventData_SensorVec; struct cereal_SensorEventData_SensorVec;
struct cereal_GpsLocationData;
struct cereal_CanData; struct cereal_CanData;
struct cereal_ThermalData; struct cereal_ThermalData;
struct cereal_HealthData; 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_GPSNMEAData_ptr;
typedef struct {capn_ptr p;} cereal_SensorEventData_ptr; typedef struct {capn_ptr p;} cereal_SensorEventData_ptr;
typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_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_CanData_ptr;
typedef struct {capn_ptr p;} cereal_ThermalData_ptr; typedef struct {capn_ptr p;} cereal_ThermalData_ptr;
typedef struct {capn_ptr p;} cereal_HealthData_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_GPSNMEAData_list;
typedef struct {capn_ptr p;} cereal_SensorEventData_list; typedef struct {capn_ptr p;} cereal_SensorEventData_list;
typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_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_CanData_list;
typedef struct {capn_ptr p;} cereal_ThermalData_list; typedef struct {capn_ptr p;} cereal_ThermalData_list;
typedef struct {capn_ptr p;} cereal_HealthData_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_LogRotate_list;
typedef struct {capn_ptr p;} cereal_Event_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 { enum cereal_EncodeIndex_Type {
cereal_EncodeIndex_Type_bigBoxLossless = 0, cereal_EncodeIndex_Type_bigBoxLossless = 0,
cereal_EncodeIndex_Type_fullHEVC = 1, cereal_EncodeIndex_Type_fullHEVC = 1,
@ -153,6 +164,7 @@ struct cereal_SensorEventData {
cereal_SensorEventData_SensorVec_ptr orientation; cereal_SensorEventData_SensorVec_ptr orientation;
cereal_SensorEventData_SensorVec_ptr gyro; cereal_SensorEventData_SensorVec_ptr gyro;
}; };
enum cereal_SensorEventData_SensorSource source;
}; };
static const size_t cereal_SensorEventData_word_count = 3; static const size_t cereal_SensorEventData_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; 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 { struct cereal_CanData {
uint32_t address; uint32_t address;
uint16_t busTime; uint16_t busTime;
@ -194,6 +223,7 @@ struct cereal_ThermalData {
uint16_t gpu; uint16_t gpu;
uint32_t bat; uint32_t bat;
float freeSpace; float freeSpace;
int16_t batteryPercent;
}; };
static const size_t cereal_ThermalData_word_count = 3; static const size_t cereal_ThermalData_word_count = 3;
@ -477,7 +507,9 @@ enum cereal_Event_which {
cereal_Event_sendcan = 16, cereal_Event_sendcan = 16,
cereal_Event_logMessage = 17, cereal_Event_logMessage = 17,
cereal_Event_liveCalibration = 18, cereal_Event_liveCalibration = 18,
cereal_Event_androidLogEntry = 19 cereal_Event_androidLogEntry = 19,
cereal_Event_gpsLocation = 20,
cereal_Event_carState = 21
}; };
struct cereal_Event { struct cereal_Event {
@ -504,6 +536,8 @@ struct cereal_Event {
capn_text logMessage; capn_text logMessage;
cereal_LiveCalibrationData_ptr liveCalibration; cereal_LiveCalibrationData_ptr liveCalibration;
cereal_AndroidLogEntry_ptr androidLogEntry; 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_GPSNMEAData_ptr cereal_new_GPSNMEAData(struct capn_segment*);
cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment*); cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment*);
cereal_SensorEventData_SensorVec_ptr cereal_new_SensorEventData_SensorVec(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_CanData_ptr cereal_new_CanData(struct capn_segment*);
cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment*); cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment*);
cereal_HealthData_ptr cereal_new_HealthData(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_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_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_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_CanData_list cereal_new_CanData_list(struct capn_segment*, int len);
cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment*, int len); cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment*, int len);
cereal_HealthData_list cereal_new_HealthData_list(struct capn_segment*, int len); cereal_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_GPSNMEAData(struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr);
void cereal_read_SensorEventData(struct cereal_SensorEventData*, cereal_SensorEventData_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_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_CanData(struct cereal_CanData*, cereal_CanData_ptr);
void cereal_read_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_ptr); void cereal_read_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_ptr);
void cereal_read_HealthData(struct cereal_HealthData*, cereal_HealthData_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_GPSNMEAData(const struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr);
void cereal_write_SensorEventData(const struct cereal_SensorEventData*, cereal_SensorEventData_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_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_CanData(const struct cereal_CanData*, cereal_CanData_ptr);
void cereal_write_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_ptr); void cereal_write_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_ptr);
void cereal_write_HealthData(const struct cereal_HealthData*, cereal_HealthData_ptr); void cereal_write_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_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(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_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_CanData(struct cereal_CanData*, cereal_CanData_list, int i);
void cereal_get_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_list, int i); void cereal_get_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_list, int i);
void cereal_get_HealthData(struct cereal_HealthData*, cereal_HealthData_list, int i); void cereal_get_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_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(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_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_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_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_list, int i);
void cereal_set_HealthData(const struct cereal_HealthData*, cereal_HealthData_list, int i); void cereal_set_HealthData(const struct cereal_HealthData*, cereal_HealthData_list, int i);

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

@ -329,7 +329,7 @@ const ::capnp::_::RawSchema s_9d291d7813ba4a88 = {
0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr } 0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #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, { 0, 0, 0, 0, 5, 0, 6, 0,
161, 41, 69, 212, 105, 154, 178, 162, 161, 41, 69, 212, 105, 154, 178, 162,
10, 0, 0, 0, 1, 0, 3, 0, 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, 1, 0, 7, 0, 0, 0, 4, 0,
6, 0, 0, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0,
21, 0, 0, 0, 210, 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, 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,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
108, 111, 103, 46, 99, 97, 112, 110, 108, 111, 103, 46, 99, 97, 112, 110,
112, 58, 83, 101, 110, 115, 111, 114, 112, 58, 83, 101, 110, 115, 111, 114,
69, 118, 101, 110, 116, 68, 97, 116, 69, 118, 101, 110, 116, 68, 97, 116,
97, 0, 0, 0, 0, 0, 0, 0, 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, 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, 83, 101, 110, 115, 111, 114, 86, 101,
99, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0,
0, 0, 1, 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,
209, 0, 0, 0, 66, 0, 0, 0, 237, 0, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
204, 0, 0, 0, 3, 0, 1, 0, 232, 0, 0, 0, 3, 0, 1, 0,
216, 0, 0, 0, 2, 0, 1, 0, 244, 0, 0, 0, 2, 0, 1, 0,
1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0,
0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
208, 0, 0, 0, 3, 0, 1, 0, 236, 0, 0, 0, 3, 0, 1, 0,
220, 0, 0, 0, 2, 0, 1, 0, 248, 0, 0, 0, 2, 0, 1, 0,
2, 0, 0, 0, 2, 0, 0, 0, 2, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
212, 0, 0, 0, 3, 0, 1, 0, 240, 0, 0, 0, 3, 0, 1, 0,
224, 0, 0, 0, 2, 0, 1, 0, 252, 0, 0, 0, 2, 0, 1, 0,
3, 0, 0, 0, 2, 0, 0, 0, 3, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
220, 0, 0, 0, 3, 0, 1, 0, 248, 0, 0, 0, 3, 0, 1, 0,
232, 0, 0, 0, 2, 0, 1, 0, 4, 1, 0, 0, 2, 0, 1, 0,
4, 0, 255, 255, 0, 0, 0, 0, 4, 0, 255, 255, 0, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
228, 0, 0, 0, 3, 0, 1, 0, 0, 1, 0, 0, 3, 0, 1, 0,
240, 0, 0, 0, 2, 0, 1, 0, 12, 1, 0, 0, 2, 0, 1, 0,
5, 0, 254, 255, 0, 0, 0, 0, 5, 0, 254, 255, 0, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
236, 0, 0, 0, 3, 0, 1, 0, 8, 1, 0, 0, 3, 0, 1, 0,
248, 0, 0, 0, 2, 0, 1, 0, 20, 1, 0, 0, 2, 0, 1, 0,
6, 0, 253, 255, 0, 0, 0, 0, 6, 0, 253, 255, 0, 0, 0, 0,
0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
244, 0, 0, 0, 3, 0, 1, 0, 16, 1, 0, 0, 3, 0, 1, 0,
0, 1, 0, 0, 2, 0, 1, 0, 28, 1, 0, 0, 2, 0, 1, 0,
7, 0, 252, 255, 0, 0, 0, 0, 7, 0, 252, 255, 0, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
248, 0, 0, 0, 3, 0, 1, 0, 20, 1, 0, 0, 3, 0, 1, 0,
4, 1, 0, 0, 2, 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, 118, 101, 114, 115, 105, 111, 110, 0,
4, 0, 0, 0, 0, 0, 0, 0, 4, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
@ -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,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
16, 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,
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 #if !CAPNP_LITE
static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = { static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = {
&s_a43429bd2bfc24fc, &s_a43429bd2bfc24fc,
&s_e49b3ce8f7f48d0d,
}; };
static const uint16_t m_a2b29a69d44529a1[] = {4, 7, 5, 6, 1, 3, 2, 0}; 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}; static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 0, 1, 2, 3, 8};
const ::capnp::_::RawSchema s_a2b29a69d44529a1 = { const ::capnp::_::RawSchema s_a2b29a69d44529a1 = {
0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 146, d_a2b29a69d44529a1, m_a2b29a69d44529a1, 0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 165, d_a2b29a69d44529a1, m_a2b29a69d44529a1,
1, 8, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr } 2, 9, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<53> b_a43429bd2bfc24fc = { 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 } 0, 2, i_a43429bd2bfc24fc, nullptr, nullptr, { &s_a43429bd2bfc24fc, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #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 = { static const ::capnp::_::AlignedData<77> b_8785009a964c7c59 = {
{ 0, 0, 0, 0, 5, 0, 6, 0, { 0, 0, 0, 0, 5, 0, 6, 0,
89, 124, 76, 150, 154, 0, 133, 135, 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 } 0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #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, { 0, 0, 0, 0, 5, 0, 6, 0,
224, 230, 127, 11, 164, 49, 130, 141, 224, 230, 127, 11, 164, 49, 130, 141,
10, 0, 0, 0, 1, 0, 3, 0, 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, 21, 0, 0, 0, 178, 0, 0, 0,
29, 0, 0, 0, 7, 0, 0, 0, 29, 0, 0, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 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,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
108, 111, 103, 46, 99, 97, 112, 110, 108, 111, 103, 46, 99, 97, 112, 110,
112, 58, 84, 104, 101, 114, 109, 97, 112, 58, 84, 104, 101, 114, 109, 97,
108, 68, 97, 116, 97, 0, 0, 0, 108, 68, 97, 116, 97, 0, 0, 0,
0, 0, 0, 0, 1, 0, 1, 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, 0, 0, 0, 0, 0, 0,
0, 0, 1, 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,
209, 0, 0, 0, 42, 0, 0, 0, 237, 0, 0, 0, 42, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
204, 0, 0, 0, 3, 0, 1, 0, 232, 0, 0, 0, 3, 0, 1, 0,
216, 0, 0, 0, 2, 0, 1, 0, 244, 0, 0, 0, 2, 0, 1, 0,
1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0,
0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
208, 0, 0, 0, 3, 0, 1, 0, 236, 0, 0, 0, 3, 0, 1, 0,
220, 0, 0, 0, 2, 0, 1, 0, 248, 0, 0, 0, 2, 0, 1, 0,
2, 0, 0, 0, 2, 0, 0, 0, 2, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
212, 0, 0, 0, 3, 0, 1, 0, 240, 0, 0, 0, 3, 0, 1, 0,
224, 0, 0, 0, 2, 0, 1, 0, 252, 0, 0, 0, 2, 0, 1, 0,
3, 0, 0, 0, 3, 0, 0, 0, 3, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
216, 0, 0, 0, 3, 0, 1, 0, 244, 0, 0, 0, 3, 0, 1, 0,
228, 0, 0, 0, 2, 0, 1, 0, 0, 1, 0, 0, 2, 0, 1, 0,
4, 0, 0, 0, 4, 0, 0, 0, 4, 0, 0, 0, 4, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
220, 0, 0, 0, 3, 0, 1, 0, 248, 0, 0, 0, 3, 0, 1, 0,
232, 0, 0, 0, 2, 0, 1, 0, 4, 1, 0, 0, 2, 0, 1, 0,
5, 0, 0, 0, 5, 0, 0, 0, 5, 0, 0, 0, 5, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
224, 0, 0, 0, 3, 0, 1, 0, 252, 0, 0, 0, 3, 0, 1, 0,
236, 0, 0, 0, 2, 0, 1, 0, 8, 1, 0, 0, 2, 0, 1, 0,
6, 0, 0, 0, 3, 0, 0, 0, 6, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
228, 0, 0, 0, 3, 0, 1, 0, 0, 1, 0, 0, 3, 0, 1, 0,
240, 0, 0, 0, 2, 0, 1, 0, 12, 1, 0, 0, 2, 0, 1, 0,
7, 0, 0, 0, 4, 0, 0, 0, 7, 0, 0, 0, 4, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
236, 0, 0, 0, 3, 0, 1, 0, 8, 1, 0, 0, 3, 0, 1, 0,
248, 0, 0, 0, 2, 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, 99, 112, 117, 48, 0, 0, 0, 0,
7, 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,
@ -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,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
10, 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,
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; ::capnp::word const* const bp_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words;
#if !CAPNP_LITE #if !CAPNP_LITE
static const uint16_t m_8d8231a40b7fe6e0[] = {6, 0, 1, 2, 3, 7, 5, 4}; 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}; static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8};
const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = {
0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 138, nullptr, m_8d8231a40b7fe6e0, 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 154, nullptr, m_8d8231a40b7fe6e0,
0, 8, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } 0, 9, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<112> b_cfa2b0c2c82af1e4 = { 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 } 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #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, { 0, 0, 0, 0, 5, 0, 6, 0,
17, 156, 34, 87, 217, 207, 20, 211, 17, 156, 34, 87, 217, 207, 20, 211,
10, 0, 0, 0, 1, 0, 2, 0, 10, 0, 0, 0, 1, 0, 2, 0,
91, 40, 164, 37, 126, 241, 177, 243, 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, 4, 0, 0, 0, 0, 0, 0, 0,
21, 0, 0, 0, 130, 0, 0, 0, 21, 0, 0, 0, 130, 0, 0, 0,
25, 0, 0, 0, 7, 0, 0, 0, 25, 0, 0, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 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,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
108, 111, 103, 46, 99, 97, 112, 110, 108, 111, 103, 46, 99, 97, 112, 110,
112, 58, 69, 118, 101, 110, 116, 0, 112, 58, 69, 118, 101, 110, 116, 0,
0, 0, 0, 0, 1, 0, 1, 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, 0, 0, 0, 0, 0, 0,
0, 0, 1, 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,
61, 2, 0, 0, 98, 0, 0, 0, 117, 2, 0, 0, 98, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
60, 2, 0, 0, 3, 0, 1, 0, 116, 2, 0, 0, 3, 0, 1, 0,
72, 2, 0, 0, 2, 0, 1, 0, 128, 2, 0, 0, 2, 0, 1, 0,
1, 0, 255, 255, 0, 0, 0, 0, 1, 0, 255, 255, 0, 0, 0, 0,
0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
68, 2, 0, 0, 3, 0, 1, 0, 124, 2, 0, 0, 3, 0, 1, 0,
80, 2, 0, 0, 2, 0, 1, 0, 136, 2, 0, 0, 2, 0, 1, 0,
2, 0, 254, 255, 0, 0, 0, 0, 2, 0, 254, 255, 0, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
72, 2, 0, 0, 3, 0, 1, 0, 128, 2, 0, 0, 3, 0, 1, 0,
84, 2, 0, 0, 2, 0, 1, 0, 140, 2, 0, 0, 2, 0, 1, 0,
3, 0, 253, 255, 0, 0, 0, 0, 3, 0, 253, 255, 0, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
76, 2, 0, 0, 3, 0, 1, 0, 132, 2, 0, 0, 3, 0, 1, 0,
88, 2, 0, 0, 2, 0, 1, 0, 144, 2, 0, 0, 2, 0, 1, 0,
4, 0, 252, 255, 0, 0, 0, 0, 4, 0, 252, 255, 0, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
88, 2, 0, 0, 3, 0, 1, 0, 144, 2, 0, 0, 3, 0, 1, 0,
100, 2, 0, 0, 2, 0, 1, 0, 156, 2, 0, 0, 2, 0, 1, 0,
5, 0, 251, 255, 0, 0, 0, 0, 5, 0, 251, 255, 0, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
92, 2, 0, 0, 3, 0, 1, 0, 148, 2, 0, 0, 3, 0, 1, 0,
120, 2, 0, 0, 2, 0, 1, 0, 176, 2, 0, 0, 2, 0, 1, 0,
6, 0, 250, 255, 0, 0, 0, 0, 6, 0, 250, 255, 0, 0, 0, 0,
0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
112, 2, 0, 0, 3, 0, 1, 0, 168, 2, 0, 0, 3, 0, 1, 0,
124, 2, 0, 0, 2, 0, 1, 0, 180, 2, 0, 0, 2, 0, 1, 0,
7, 0, 249, 255, 0, 0, 0, 0, 7, 0, 249, 255, 0, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
116, 2, 0, 0, 3, 0, 1, 0, 172, 2, 0, 0, 3, 0, 1, 0,
128, 2, 0, 0, 2, 0, 1, 0, 184, 2, 0, 0, 2, 0, 1, 0,
8, 0, 248, 255, 0, 0, 0, 0, 8, 0, 248, 255, 0, 0, 0, 0,
0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
128, 2, 0, 0, 3, 0, 1, 0, 184, 2, 0, 0, 3, 0, 1, 0,
156, 2, 0, 0, 2, 0, 1, 0, 212, 2, 0, 0, 2, 0, 1, 0,
9, 0, 247, 255, 0, 0, 0, 0, 9, 0, 247, 255, 0, 0, 0, 0,
0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
148, 2, 0, 0, 3, 0, 1, 0, 204, 2, 0, 0, 3, 0, 1, 0,
160, 2, 0, 0, 2, 0, 1, 0, 216, 2, 0, 0, 2, 0, 1, 0,
10, 0, 246, 255, 0, 0, 0, 0, 10, 0, 246, 255, 0, 0, 0, 0,
0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
156, 2, 0, 0, 3, 0, 1, 0, 212, 2, 0, 0, 3, 0, 1, 0,
168, 2, 0, 0, 2, 0, 1, 0, 224, 2, 0, 0, 2, 0, 1, 0,
11, 0, 245, 255, 0, 0, 0, 0, 11, 0, 245, 255, 0, 0, 0, 0,
0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
164, 2, 0, 0, 3, 0, 1, 0, 220, 2, 0, 0, 3, 0, 1, 0,
192, 2, 0, 0, 2, 0, 1, 0, 248, 2, 0, 0, 2, 0, 1, 0,
12, 0, 244, 255, 0, 0, 0, 0, 12, 0, 244, 255, 0, 0, 0, 0,
0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
184, 2, 0, 0, 3, 0, 1, 0, 240, 2, 0, 0, 3, 0, 1, 0,
196, 2, 0, 0, 2, 0, 1, 0, 252, 2, 0, 0, 2, 0, 1, 0,
13, 0, 243, 255, 0, 0, 0, 0, 13, 0, 243, 255, 0, 0, 0, 0,
0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
188, 2, 0, 0, 3, 0, 1, 0, 244, 2, 0, 0, 3, 0, 1, 0,
200, 2, 0, 0, 2, 0, 1, 0, 0, 3, 0, 0, 2, 0, 1, 0,
14, 0, 242, 255, 0, 0, 0, 0, 14, 0, 242, 255, 0, 0, 0, 0,
0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
200, 2, 0, 0, 3, 0, 1, 0, 0, 3, 0, 0, 3, 0, 1, 0,
212, 2, 0, 0, 2, 0, 1, 0, 12, 3, 0, 0, 2, 0, 1, 0,
15, 0, 241, 255, 0, 0, 0, 0, 15, 0, 241, 255, 0, 0, 0, 0,
0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
208, 2, 0, 0, 3, 0, 1, 0, 8, 3, 0, 0, 3, 0, 1, 0,
220, 2, 0, 0, 2, 0, 1, 0, 20, 3, 0, 0, 2, 0, 1, 0,
16, 0, 240, 255, 0, 0, 0, 0, 16, 0, 240, 255, 0, 0, 0, 0,
0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
216, 2, 0, 0, 3, 0, 1, 0, 16, 3, 0, 0, 3, 0, 1, 0,
244, 2, 0, 0, 2, 0, 1, 0, 44, 3, 0, 0, 2, 0, 1, 0,
17, 0, 239, 255, 0, 0, 0, 0, 17, 0, 239, 255, 0, 0, 0, 0,
0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
236, 2, 0, 0, 3, 0, 1, 0, 36, 3, 0, 0, 3, 0, 1, 0,
8, 3, 0, 0, 2, 0, 1, 0, 64, 3, 0, 0, 2, 0, 1, 0,
18, 0, 238, 255, 0, 0, 0, 0, 18, 0, 238, 255, 0, 0, 0, 0,
0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
4, 3, 0, 0, 3, 0, 1, 0, 60, 3, 0, 0, 3, 0, 1, 0,
16, 3, 0, 0, 2, 0, 1, 0, 72, 3, 0, 0, 2, 0, 1, 0,
19, 0, 237, 255, 0, 0, 0, 0, 19, 0, 237, 255, 0, 0, 0, 0,
0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
12, 3, 0, 0, 3, 0, 1, 0, 68, 3, 0, 0, 3, 0, 1, 0,
24, 3, 0, 0, 2, 0, 1, 0, 80, 3, 0, 0, 2, 0, 1, 0,
20, 0, 236, 255, 0, 0, 0, 0, 20, 0, 236, 255, 0, 0, 0, 0,
0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0,
0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0,
20, 3, 0, 0, 3, 0, 1, 0, 76, 3, 0, 0, 3, 0, 1, 0,
32, 3, 0, 0, 2, 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, 108, 111, 103, 77, 111, 110, 111, 84,
105, 109, 101, 0, 0, 0, 0, 0, 105, 109, 101, 0, 0, 0, 0, 0,
9, 0, 0, 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, 133, 125, 79, 137, 161, 93, 9, 234,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
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, 16, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 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_97ff69c53601abf1,
&s_9a185389d6fdd05f, &s_9a185389d6fdd05f,
&s_9d291d7813ba4a88, &s_9d291d7813ba4a88,
&s_9da4fa09e052903c,
&s_a2b29a69d44529a1, &s_a2b29a69d44529a1,
&s_b8aad62cffef28a9, &s_b8aad62cffef28a9,
&s_c08240f996aefced, &s_c08240f996aefced,
&s_cfa2b0c2c82af1e4, &s_cfa2b0c2c82af1e4,
&s_e71008caeb3fb65c, &s_e71008caeb3fb65c,
&s_e946524859add50e,
&s_ea0245f695ae0a33, &s_ea0245f695ae0a33,
&s_ea095da1894f7d85, &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 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, 0}; 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 = { const ::capnp::_::RawSchema s_d314cfd957229c11 = {
0xd314cfd957229c11, b_d314cfd957229c11.words, 366, d_d314cfd957229c11, m_d314cfd957229c11, 0xd314cfd957229c11, b_d314cfd957229c11.words, 398, d_d314cfd957229c11, m_d314cfd957229c11,
17, 21, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } 19, 23, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr }
}; };
#endif // !CAPNP_LITE #endif // !CAPNP_LITE
} // namespace schemas } // namespace schemas
@ -3560,6 +3831,17 @@ constexpr ::capnp::_::RawSchema const* SensorEventData::SensorVec::_capnpPrivate
constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::SensorVec::_capnpPrivate::brand; constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::SensorVec::_capnpPrivate::brand;
#endif // !CAPNP_LITE #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 // CanData
#ifndef _MSC_VER #ifndef _MSC_VER
constexpr uint16_t CanData::_capnpPrivate::dataWordSize; constexpr uint16_t CanData::_capnpPrivate::dataWordSize;

@ -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." #error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library."
#endif #endif
#include "car.capnp.h"
namespace capnp { namespace capnp {
namespace schemas { namespace schemas {
@ -20,6 +21,15 @@ CAPNP_DECLARE_SCHEMA(ea0245f695ae0a33);
CAPNP_DECLARE_SCHEMA(9d291d7813ba4a88); CAPNP_DECLARE_SCHEMA(9d291d7813ba4a88);
CAPNP_DECLARE_SCHEMA(a2b29a69d44529a1); CAPNP_DECLARE_SCHEMA(a2b29a69d44529a1);
CAPNP_DECLARE_SCHEMA(a43429bd2bfc24fc); 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(8785009a964c7c59);
CAPNP_DECLARE_SCHEMA(8d8231a40b7fe6e0); CAPNP_DECLARE_SCHEMA(8d8231a40b7fe6e0);
CAPNP_DECLARE_SCHEMA(cfa2b0c2c82af1e4); CAPNP_DECLARE_SCHEMA(cfa2b0c2c82af1e4);
@ -111,6 +121,8 @@ struct SensorEventData {
GYRO, GYRO,
}; };
struct SensorVec; struct SensorVec;
typedef ::capnp::schemas::SensorSource_e49b3ce8f7f48d0d SensorSource;
struct _capnpPrivate { struct _capnpPrivate {
CAPNP_DECLARE_STRUCT_HEADER(a2b29a69d44529a1, 3, 1) 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 { struct CanData {
CanData() = delete; CanData() = delete;
@ -438,6 +465,8 @@ struct Event {
LOG_MESSAGE, LOG_MESSAGE,
LIVE_CALIBRATION, LIVE_CALIBRATION,
ANDROID_LOG_ENTRY, ANDROID_LOG_ENTRY,
GPS_LOCATION,
CAR_STATE,
}; };
struct _capnpPrivate { struct _capnpPrivate {
@ -796,6 +825,8 @@ public:
inline bool hasGyro() const; inline bool hasGyro() const;
inline ::cereal::SensorEventData::SensorVec::Reader getGyro() const; inline ::cereal::SensorEventData::SensorVec::Reader getGyro() const;
inline ::cereal::SensorEventData::SensorSource getSource() const;
private: private:
::capnp::_::StructReader _reader; ::capnp::_::StructReader _reader;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -869,6 +900,9 @@ public:
inline void adoptGyro(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); inline void adoptGyro(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value);
inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownGyro(); inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownGyro();
inline ::cereal::SensorEventData::SensorSource getSource();
inline void setSource( ::cereal::SensorEventData::SensorSource value);
private: private:
::capnp::_::StructBuilder _builder; ::capnp::_::StructBuilder _builder;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -982,6 +1016,117 @@ private:
}; };
#endif // !CAPNP_LITE #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 <typename, ::capnp::Kind>
friend struct ::capnp::ToDynamic_;
template <typename, ::capnp::Kind>
friend struct ::capnp::_::PointerHelpers;
template <typename, ::capnp::Kind>
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 <typename, ::capnp::Kind>
friend struct ::capnp::ToDynamic_;
friend class ::capnp::Orphanage;
template <typename, ::capnp::Kind>
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 <typename, ::capnp::Kind>
friend struct ::capnp::ToDynamic_;
};
#endif // !CAPNP_LITE
class CanData::Reader { class CanData::Reader {
public: public:
typedef CanData Reads; typedef CanData Reads;
@ -1111,6 +1256,8 @@ public:
inline float getFreeSpace() const; inline float getFreeSpace() const;
inline ::int16_t getBatteryPercent() const;
private: private:
::capnp::_::StructReader _reader; ::capnp::_::StructReader _reader;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -1163,6 +1310,9 @@ public:
inline float getFreeSpace(); inline float getFreeSpace();
inline void setFreeSpace(float value); inline void setFreeSpace(float value);
inline ::int16_t getBatteryPercent();
inline void setBatteryPercent( ::int16_t value);
private: private:
::capnp::_::StructBuilder _builder; ::capnp::_::StructBuilder _builder;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -3127,6 +3277,14 @@ public:
inline bool hasAndroidLogEntry() const; inline bool hasAndroidLogEntry() const;
inline ::cereal::AndroidLogEntry::Reader getAndroidLogEntry() 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: private:
::capnp::_::StructReader _reader; ::capnp::_::StructReader _reader;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -3319,6 +3477,22 @@ public:
inline void adoptAndroidLogEntry(::capnp::Orphan< ::cereal::AndroidLogEntry>&& value); inline void adoptAndroidLogEntry(::capnp::Orphan< ::cereal::AndroidLogEntry>&& value);
inline ::capnp::Orphan< ::cereal::AndroidLogEntry> disownAndroidLogEntry(); 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: private:
::capnp::_::StructBuilder _builder; ::capnp::_::StructBuilder _builder;
template <typename, ::capnp::Kind> template <typename, ::capnp::Kind>
@ -3894,6 +4068,20 @@ inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::B
_builder.getPointerField(0 * ::capnp::POINTERS)); _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 { inline bool SensorEventData::SensorVec::Reader::hasV() const {
return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull();
} }
@ -3944,6 +4132,118 @@ inline void SensorEventData::SensorVec::Builder::setStatus( ::int8_t value) {
0 * ::capnp::ELEMENTS, 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<double>(
1 * ::capnp::ELEMENTS);
}
inline double GpsLocationData::Builder::getLatitude() {
return _builder.getDataField<double>(
1 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setLatitude(double value) {
_builder.setDataField<double>(
1 * ::capnp::ELEMENTS, value);
}
inline double GpsLocationData::Reader::getLongitude() const {
return _reader.getDataField<double>(
2 * ::capnp::ELEMENTS);
}
inline double GpsLocationData::Builder::getLongitude() {
return _builder.getDataField<double>(
2 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setLongitude(double value) {
_builder.setDataField<double>(
2 * ::capnp::ELEMENTS, value);
}
inline double GpsLocationData::Reader::getAltitude() const {
return _reader.getDataField<double>(
3 * ::capnp::ELEMENTS);
}
inline double GpsLocationData::Builder::getAltitude() {
return _builder.getDataField<double>(
3 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setAltitude(double value) {
_builder.setDataField<double>(
3 * ::capnp::ELEMENTS, value);
}
inline float GpsLocationData::Reader::getSpeed() const {
return _reader.getDataField<float>(
1 * ::capnp::ELEMENTS);
}
inline float GpsLocationData::Builder::getSpeed() {
return _builder.getDataField<float>(
1 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setSpeed(float value) {
_builder.setDataField<float>(
1 * ::capnp::ELEMENTS, value);
}
inline float GpsLocationData::Reader::getBearing() const {
return _reader.getDataField<float>(
8 * ::capnp::ELEMENTS);
}
inline float GpsLocationData::Builder::getBearing() {
return _builder.getDataField<float>(
8 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setBearing(float value) {
_builder.setDataField<float>(
8 * ::capnp::ELEMENTS, value);
}
inline float GpsLocationData::Reader::getAccuracy() const {
return _reader.getDataField<float>(
9 * ::capnp::ELEMENTS);
}
inline float GpsLocationData::Builder::getAccuracy() {
return _builder.getDataField<float>(
9 * ::capnp::ELEMENTS);
}
inline void GpsLocationData::Builder::setAccuracy(float value) {
_builder.setDataField<float>(
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 { inline ::uint32_t CanData::Reader::getAddress() const {
return _reader.getDataField< ::uint32_t>( return _reader.getDataField< ::uint32_t>(
0 * ::capnp::ELEMENTS); 0 * ::capnp::ELEMENTS);
@ -4130,6 +4430,20 @@ inline void ThermalData::Builder::setFreeSpace(float value) {
4 * ::capnp::ELEMENTS, 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 { inline ::uint32_t HealthData::Reader::getVoltage() const {
return _reader.getDataField< ::uint32_t>( return _reader.getDataField< ::uint32_t>(
0 * ::capnp::ELEMENTS); 0 * ::capnp::ELEMENTS);
@ -7284,6 +7598,110 @@ inline ::capnp::Orphan< ::cereal::AndroidLogEntry> Event::Builder::disownAndroid
_builder.getPointerField(0 * ::capnp::POINTERS)); _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<Event::Which>(
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<Event::Which>(
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<Event::Which>(
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<Event::Which>(
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<Event::Which>(
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<Event::Which>(
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 } // namespace
#endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ #endif // CAPNP_INCLUDED_f3b1f17e25a4285b_

@ -1,6 +1,8 @@
using Cxx = import "c++.capnp"; using Cxx = import "c++.capnp";
$Cxx.namespace("cereal"); $Cxx.namespace("cereal");
using Car = import "car.capnp";
@0xf3b1f17e25a4285b; @0xf3b1f17e25a4285b;
const logVersion :Int32 = 1; const logVersion :Int32 = 1;
@ -39,11 +41,47 @@ struct SensorEventData {
orientation @6 :SensorVec; orientation @6 :SensorVec;
gyro @7 :SensorVec; gyro @7 :SensorVec;
} }
source @8 :SensorSource;
struct SensorVec { struct SensorVec {
v @0 :List(Float32); v @0 :List(Float32);
status @1 :Int8; 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 { struct CanData {
@ -64,6 +102,7 @@ struct ThermalData {
# not thermal # not thermal
freeSpace @7 :Float32; freeSpace @7 :Float32;
batteryPercent @8 :Int16;
} }
struct HealthData { struct HealthData {
@ -272,5 +311,7 @@ struct Event {
logMessage @18 :Text; logMessage @18 :Text;
liveCalibration @19 :LiveCalibrationData; liveCalibration @19 :LiveCalibrationData;
androidLogEntry @20 :AndroidLogEntry; androidLogEntry @20 :AndroidLogEntry;
gpsLocation @21 :GpsLocationData;
carState @22 :Car.CarState;
} }
} }

@ -33,6 +33,7 @@ service_list = {
"logMessage": Service(8018, True), "logMessage": Service(8018, True),
"liveCalibration": Service(8019, True), "liveCalibration": Service(8019, True),
"androidLog": Service(8020, True), "androidLog": Service(8020, True),
"carState": Service(8021, True),
} }
# manager -- base process to manage starting and stopping of all others # manager -- base process to manage starting and stopping of all others
@ -56,7 +57,7 @@ service_list = {
# controlsd -- actually drives the car # controlsd -- actually drives the car
# subscribes: can, thermal, model, live20 # subscribes: can, thermal, model, live20
# publishes: sendcan, live100 # publishes: carState, sendcan, live100
# radard -- processes the radar data # radard -- processes the radar data
# subscribes: can, live100, model # subscribes: can, live100, model

@ -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

@ -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/

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:1e39e76315aa470f9a3f8b3bd0dfa56dd07bb9aa2daf36a6b37e7d84b9165e21
size 29298

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:8e647e8960b76dd9b022132d9fb9aa115f07ba004ed41b7704add69fd8da5b66
size 3492

@ -19,10 +19,7 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \
-l:libczmq.a -l:libzmq.a \ -l:libczmq.a -l:libzmq.a \
-lgnustl_shared -lgnustl_shared
CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include JSON_FLAGS = -I$(PHONELIBS)/json/src
CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \
-l:libcapnp.a -l:libkj.a
CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o
EXTRA_LIBS = -lusb EXTRA_LIBS = -lusb
@ -34,14 +31,18 @@ CEREAL_LIBS = -L$(HOME)/drive/external/capnp/lib/ \
EXTRA_LIBS = -lusb-1.0 -lpthread EXTRA_LIBS = -lusb-1.0 -lpthread
endif endif
.PHONY: all
all: boardd
-include ../common/cereal.mk
OBJS = boardd.o \ OBJS = boardd.o \
log.capnp.o ../common/swaglog.o \
$(PHONELIBS)/json/src/json.o \
$(CEREAL_OBJS)
DEPS := $(OBJS:.o=.d) DEPS := $(OBJS:.o=.d)
all: boardd
boardd: $(OBJS) boardd: $(OBJS)
@echo "[ LINK ] $@" @echo "[ LINK ] $@"
$(CXX) -fPIC -o '$@' $^ \ $(CXX) -fPIC -o '$@' $^ \
@ -53,19 +54,21 @@ boardd.o: boardd.cc
@echo "[ CXX ] $@" @echo "[ CXX ] $@"
$(CXX) $(CXXFLAGS) \ $(CXX) $(CXXFLAGS) \
-I$(PHONELIBS)/android_system_core/include \ -I$(PHONELIBS)/android_system_core/include \
$(CEREAL_FLAGS) \ $(CEREAL_CFLAGS) \
$(ZMQ_FLAGS) \ $(ZMQ_FLAGS) \
-I../ \ -I../ \
-I../../ \ -I../../ \
-c -o '$@' '$<' -c -o '$@' '$<'
%.o: %.c
log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ @echo "[ CC ] $@"
@echo "[ CXX ] $@" $(CC) $(CFLAGS) -MMD \
$(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ -Iinclude -I.. -I../.. \
$(CEREAL_CFLAGS) \
$(ZMQ_FLAGS) \
$(JSON_FLAGS) \
-c -o '$@' '$<' -c -o '$@' '$<'
.PHONY: clean .PHONY: clean
clean: clean:
rm -f boardd $(OBJS) $(DEPS) rm -f boardd $(OBJS) $(DEPS)

@ -20,6 +20,7 @@
#include <capnp/serialize.h> #include <capnp/serialize.h>
#include "cereal/gen/cpp/log.capnp.h" #include "cereal/gen/cpp/log.capnp.h"
#include "common/swaglog.h"
#include "common/timing.h" #include "common/timing.h"
int do_exit = 0; int do_exit = 0;
@ -29,18 +30,12 @@ libusb_device_handle *dev_handle;
pthread_mutex_t usb_lock; pthread_mutex_t usb_lock;
bool spoofing_started = false; bool spoofing_started = false;
bool fake_send = false;
// double the FIFO size // double the FIFO size
#define RECV_SIZE (0x1000) #define RECV_SIZE (0x1000)
#define TIMEOUT 0 #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() { bool usb_connect() {
int err; int err;
@ -56,11 +51,17 @@ bool usb_connect() {
return true; 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[]) { 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) { 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? // TODO: check other errors, is simply retrying okay?
} }
@ -77,7 +78,7 @@ void can_recv(void *s) {
do { do {
err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT);
if (err != 0) { handle_usb_issue(err, __func__); } 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 // timeout is okay to exit, recv still happened
if (err == -7) { break; } if (err == -7) { break; }
@ -199,8 +200,6 @@ void can_send(void *s) {
memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size());
} }
//DPRINTF("got send message: %d\n", msg_count);
// release msg // release msg
zmq_msg_close(&msg); zmq_msg_close(&msg);
@ -208,10 +207,12 @@ void can_send(void *s) {
int sent; int sent;
pthread_mutex_lock(&usb_lock); pthread_mutex_lock(&usb_lock);
if (!fake_send) {
do { do {
err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); 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__); } if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); }
} while(err != 0); } while(err != 0);
}
pthread_mutex_unlock(&usb_lock); pthread_mutex_unlock(&usb_lock);
@ -223,7 +224,7 @@ void can_send(void *s) {
// **** threads **** // **** threads ****
void *can_send_thread(void *crap) { void *can_send_thread(void *crap) {
DPRINTF("start send thread\n"); LOGD("start send thread");
// sendcan = 8017 // sendcan = 8017
void *context = zmq_ctx_new(); void *context = zmq_ctx_new();
@ -239,7 +240,7 @@ void *can_send_thread(void *crap) {
} }
void *can_recv_thread(void *crap) { void *can_recv_thread(void *crap) {
DPRINTF("start recv thread\n"); LOGD("start recv thread");
// can = 8006 // can = 8006
void *context = zmq_ctx_new(); void *context = zmq_ctx_new();
@ -256,7 +257,7 @@ void *can_recv_thread(void *crap) {
} }
void *can_health_thread(void *crap) { void *can_health_thread(void *crap) {
DPRINTF("start health thread\n"); LOGD("start health thread");
// health = 8011 // health = 8011
void *context = zmq_ctx_new(); void *context = zmq_ctx_new();
@ -281,35 +282,31 @@ int set_realtime_priority(int level) {
int main() { int main() {
int err; int err;
DPRINTF("starting boardd\n"); LOGW("starting boardd");
// set process priority // set process priority
err = set_realtime_priority(4); err = set_realtime_priority(4);
DPRINTF("setpriority returns %d\n", err); LOG("setpriority returns %d", err);
// check the environment // check the environment
if (getenv("STARTED")) { if (getenv("STARTED")) {
spoofing_started = true; spoofing_started = true;
} }
// connect to the board if (getenv("FAKESEND")) {
fake_send = true;
}
// init libusb
err = libusb_init(&ctx); err = libusb_init(&ctx);
assert(err == 0); assert(err == 0);
libusb_set_debug(ctx, 3); libusb_set_debug(ctx, 3);
// TODO: duplicate code from error handling // connect to the board
while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } usb_retry_connect();
/*int config;
err = libusb_get_configuration(dev_handle, &config);
assert(err == 0);
DPRINTF("configuration is %d\n", config);*/
/*err = libusb_set_interface_alt_setting(dev_handle, 0, 0);
assert(err == 0);*/
// create threads // create threads
pthread_t can_health_thread_handle; pthread_t can_health_thread_handle;
err = pthread_create(&can_health_thread_handle, NULL, err = pthread_create(&can_health_thread_handle, NULL,
can_health_thread, NULL); can_health_thread, NULL);

@ -1,6 +1,9 @@
#!/usr/bin/env python #!/usr/bin/env python
from __future__ import print_function
import os import os
import numpy as np import numpy as np
import tempfile
import zmq import zmq
from common.services import service_list from common.services import service_list
@ -8,6 +11,7 @@ import selfdrive.messaging as messaging
from selfdrive.config import ImageParams, VehicleParams from selfdrive.config import ImageParams, VehicleParams
from selfdrive.calibrationd.calibration import ViewCalibrator, CalibStatus from selfdrive.calibrationd.calibration import ViewCalibrator, CalibStatus
CALIBRATION_TMP_DIR = "/sdcard"
CALIBRATION_FILE = "/sdcard/calibration_param" CALIBRATION_FILE = "/sdcard/calibration_param"
def load_calibration(gctx): def load_calibration(gctx):
@ -32,28 +36,33 @@ def load_calibration(gctx):
# load calibration data # load calibration data
if os.path.isfile(CALIBRATION_FILE): if os.path.isfile(CALIBRATION_FILE):
# if the calibration file exist, start from the last cal values try:
# If the calibration file exist, start from the last cal values
with open(CALIBRATION_FILE, "r") as cal_file: with open(CALIBRATION_FILE, "r") as cal_file:
data = [float(l.strip()) for l in cal_file.readlines()] data = [float(l.strip()) for l in cal_file.readlines()]
calib = ViewCalibrator((I.X, I.Y), return ViewCalibrator(
(I.X, I.Y),
big_box_size, big_box_size,
vp_img, vp_img,
warp_matrix_start, warp_matrix_start,
vp_f=[data[2], data[3]], vp_f=[data[2], data[3]],
cal_cycle=data[0], cal_cycle=data[0],
cal_status=data[1]) cal_status=data[1])
except Exception as e:
if calib.cal_status == CalibStatus.INCOMPLETE: print("Could not load calibration file: {}".format(e))
print "CALIBRATION IN PROGRESS", calib.cal_cycle
else: return ViewCalibrator(
print "NO CALIBRATION FILE" (I.X, I.Y), big_box_size, vp_img, warp_matrix_start, vp_f=vp_guess)
calib = ViewCalibrator((I.X, I.Y),
big_box_size, def store_calibration(calib):
vp_img, # Tempfile needs to be on the same device as the calbration file.
warp_matrix_start, with tempfile.NamedTemporaryFile(delete=False, dir=CALIBRATION_TMP_DIR) as cal_file:
vp_f=vp_guess) print(calib.cal_cycle, file=cal_file)
print(calib.cal_status, file=cal_file)
return calib 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): def calibrationd_thread(gctx):
context = zmq.Context() context = zmq.Context()
@ -69,7 +78,7 @@ def calibrationd_thread(gctx):
v_ego = None v_ego = None
calib = load_calibration(gctx) calib = load_calibration(gctx)
last_cal_cycle = calib.cal_cycle last_write_cycle = calib.cal_cycle
while 1: while 1:
# calibration at the end so it does not delay radar processing above # 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) calib.calibration(p0, p1, st, v_ego, steer_angle, VP)
# write a new calibration every 100 cal cycle # write a new calibration every 100 cal cycle
if calib.cal_cycle - last_cal_cycle >= 100: if calib.cal_cycle - last_write_cycle >= 100:
print "writing cal", calib.cal_cycle print("writing cal", calib.cal_cycle)
with open(CALIBRATION_FILE, "w") as cal_file: store_calibration(calib)
cal_file.write(str(calib.cal_cycle)+'\n') last_write_cycle = calib.cal_cycle
cal_file.write(str(calib.cal_status)+'\n')
cal_file.write(str(calib.vp_f[0])+'\n')
cal_file.write(str(calib.vp_f[1])+'\n')
last_cal_cycle = calib.cal_cycle
warp_matrix = map(float, calib.warp_matrix.reshape(9).tolist()) warp_matrix = map(float, calib.warp_matrix.reshape(9).tolist())
dat = messaging.new_message() dat = messaging.new_message()

@ -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 '$@' '$<'

@ -53,6 +53,7 @@ extern "C" FramebufferState* framebuffer_init(
assert(status == 0); assert(status == 0);
int orientation = 3; // rotate framebuffer 270 degrees int orientation = 3; // rotate framebuffer 270 degrees
//int orientation = 1; // rotate framebuffer 90 degrees
if(orientation == 1 || orientation == 3) { if(orientation == 1 || orientation == 3) {
int temp = s->dinfo.h; int temp = s->dinfo.h;
s->dinfo.h = s->dinfo.w; s->dinfo.h = s->dinfo.w;

@ -0,0 +1,71 @@
#include <stdlib.h>
#include <stdio.h>
#include <GLES3/gl3.h>
#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;
}

@ -0,0 +1,8 @@
#ifndef COMMON_GLUTIL_H
#define COMMON_GLUTIL_H
#include <GLES3/gl3.h>
GLuint load_shader(GLenum shaderType, const char *src);
GLuint load_program(const char *vert_src, const char *frag_src);
#endif

@ -19,6 +19,7 @@ typedef struct LogState {
JsonNode *ctx_j; JsonNode *ctx_j;
void *zctx; void *zctx;
void *sock; void *sock;
int print_level;
} LogState; } LogState;
static LogState s = { static LogState s = {
@ -31,6 +32,19 @@ static void cloudlog_init() {
s.zctx = zmq_ctx_new(); s.zctx = zmq_ctx_new();
s.sock = zmq_socket(s.zctx, ZMQ_PUSH); s.sock = zmq_socket(s.zctx, ZMQ_PUSH);
zmq_connect(s.sock, "ipc:///tmp/logmessage"); 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; s.inited = true;
} }
@ -50,7 +64,7 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func
return; return;
} }
if (levelnum >= CLOUDLOG_PRINT_LEVEL) { if (levelnum >= s.print_level) {
printf("%s: %s\n", filename, msg_buf); printf("%s: %s\n", filename, msg_buf);
} }

@ -7,13 +7,19 @@
#define CLOUDLOG_ERROR 40 #define CLOUDLOG_ERROR 40
#define CLOUDLOG_CRITICAL 50 #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, void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime,
const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/;
void cloudlog_bind(const char* k, const char* v); void cloudlog_bind(const char* k, const char* v);
#ifdef __cplusplus
}
#endif
#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ #define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \
__func__, __DATE__ " " __TIME__, \ __func__, __DATE__ " " __TIME__, \
fmt, ## __VA_ARGS__) fmt, ## __VA_ARGS__)

@ -1 +1 @@
const char *openpilot_version = "0.2.3"; const char *openpilot_version = "0.2.4";

@ -38,6 +38,7 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
# *** log *** # *** log ***
context = zmq.Context() context = zmq.Context()
live100 = messaging.pub_sock(context, service_list['live100'].port) 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) thermal = messaging.sub_sock(context, service_list['thermal'].port)
live20 = messaging.sub_sock(context, service_list['live20'].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 # read CAN
CS = CI.update() 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") prof.checkpoint("CarInterface")
# did it request to enable? # did it request to enable?

@ -57,10 +57,12 @@ class AlertManager(object):
"wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), "wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.),
"outOfSpace": alert("Comma Unavailable","Out of Space", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.), "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.), "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): def __init__(self):
self.activealerts = [] self.activealerts = []
self.current_alert = None self.current_alert = None
self.add("startup", False)
def alertPresent(self): def alertPresent(self):
return len(self.activealerts) > 0 return len(self.activealerts) > 0

@ -219,7 +219,7 @@ class Cluster(object):
ret += " vision_cnt: %6.0f" % self.vision_cnt ret += " vision_cnt: %6.0f" % self.vision_cnt
return ret 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 # predict cut-ins by extrapolating lateral speed by a lookahead time
# lookahead time depends on cut-in distance. more attentive for close cut-ins # lookahead time depends on cut-in distance. more attentive for close cut-ins
# also, above 50 meters the predicted path isn't very reliable # also, above 50 meters the predicted path isn't very reliable
@ -233,12 +233,11 @@ class Cluster(object):
# average dist # average dist
d_path = self.dPath d_path = self.dPath
if enabled: # lat_corr used to be gated on enabled, now always running
t_lookahead = interp(self.dRel, t_lookahead_bp, t_lookahead_v) 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 # 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) lat_corr = clip(t_lookahead * self.vLat, -1, 0)
else:
lat_corr = 0.
d_path = max(d_path + lat_corr, 0) d_path = max(d_path + lat_corr, 0)
if d_path < 1.5 and not self.stationary and not self.oncoming: if d_path < 1.5 and not self.stationary and not self.oncoming:

@ -196,7 +196,7 @@ def radard_thread(gctx=None):
# *** extract the lead car *** # *** extract the lead car ***
lead_clusters = [c for c in clusters 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_clusters.sort(key=lambda x: x.dRel)
lead_len = len(lead_clusters) lead_len = len(lead_clusters)

@ -17,18 +17,16 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \
-l:libczmq.a -l:libzmq.a \ -l:libczmq.a -l:libzmq.a \
-lgnustl_shared -lgnustl_shared
CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include .PHONY: all
CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ all: logcatd
-l:libcapnp.a -l:libkj.a
CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o -include ../common/cereal.mk
OBJS = logcatd.o \ OBJS = logcatd.o \
log.capnp.o $(CEREAL_OBJS)
DEPS := $(OBJS:.o=.d) DEPS := $(OBJS:.o=.d)
all: logcatd
logcatd: $(OBJS) logcatd: $(OBJS)
@echo "[ LINK ] $@" @echo "[ LINK ] $@"
$(CXX) -fPIC -o '$@' $^ \ $(CXX) -fPIC -o '$@' $^ \
@ -40,17 +38,12 @@ logcatd: $(OBJS)
@echo "[ CXX ] $@" @echo "[ CXX ] $@"
$(CXX) $(CXXFLAGS) \ $(CXX) $(CXXFLAGS) \
-I$(PHONELIBS)/android_system_core/include \ -I$(PHONELIBS)/android_system_core/include \
$(CEREAL_FLAGS) \ $(CEREAL_CFLAGS) \
$(ZMQ_FLAGS) \ $(ZMQ_FLAGS) \
-I../ \ -I../ \
-I../../ \ -I../../ \
-c -o '$@' '$<' -c -o '$@' '$<'
log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++
@echo "[ CXX ] $@"
$(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \
-c -o '$@' '$<'
.PHONY: clean .PHONY: clean
clean: clean:
rm -f logcatd $(OBJS) $(DEPS) rm -f logcatd $(OBJS) $(DEPS)

@ -194,6 +194,10 @@ def manager_thread():
count = 0 count = 0
# set 5 second timeout on health socket
# 5x slower than expected
health_sock.RCVTIMEO = 5000
while 1: while 1:
# get health of board, log this in "thermal" # get health of board, log this in "thermal"
td = messaging.recv_sock(health_sock, wait=True) td = messaging.recv_sock(health_sock, wait=True)
@ -208,6 +212,8 @@ def manager_thread():
# thermal message now also includes free space # thermal message now also includes free space
msg.thermal.freeSpace = avail 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()) thermal_sock.send(msg.to_bytes())
print msg print msg
@ -228,7 +234,7 @@ def manager_thread():
# start constellation of processes when the car starts # start constellation of processes when the car starts
if not os.getenv("STARTALL"): if not os.getenv("STARTALL"):
# with 2% left, we killall, otherwise the phone is bricked # 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: for p in car_started_processes:
if p == "loggerd" and logger_dead: if p == "loggerd" and logger_dead:
kill_managed_process(p) kill_managed_process(p)
@ -246,7 +252,14 @@ def manager_thread():
# report to server once per minute # report to server once per minute
if (count%60) == 0: if (count%60) == 0:
names, total_size = fake_uploader.get_data_stats() 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 count += 1
@ -270,24 +283,6 @@ def manager_prepare():
subprocess.check_call(["make", "clean"], cwd=proc[0]) subprocess.check_call(["make", "clean"], cwd=proc[0])
subprocess.check_call(["make", "-j4"], 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(): def wait_for_device():
while 1: while 1:
try: try:
@ -319,13 +314,16 @@ def main():
del managed_processes['loggerd'] del managed_processes['loggerd']
del managed_processes['logmessaged'] del managed_processes['logmessaged']
del managed_processes['logcatd'] del managed_processes['logcatd']
if os.getenv("NOCONTROL") is not None:
del managed_processes['controlsd']
del managed_processes['radard']
manager_init() manager_init()
if len(sys.argv) > 1 and sys.argv[1] == "test":
manager_test()
else:
manager_prepare() manager_prepare()
if os.getenv("PREPAREONLY") is not None:
sys.exit(0)
try: try:
manager_thread() manager_thread()
except Exception: except Exception:

@ -17,18 +17,16 @@ ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \
-l:libczmq.a -l:libzmq.a \ -l:libczmq.a -l:libzmq.a \
-lgnustl_shared -lgnustl_shared
CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include .PHONY: all
CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ all: sensord
-l:libcapnp.a -l:libkj.a
CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o -include ../common/cereal.mk
OBJS = sensors.o \ OBJS = sensors.o \
log.capnp.o $(CEREAL_OBJS)
DEPS := $(OBJS:.o=.d) DEPS := $(OBJS:.o=.d)
all: sensord
sensord: $(OBJS) sensord: $(OBJS)
@echo "[ LINK ] $@" @echo "[ LINK ] $@"
$(CXX) -fPIC -o '$@' $^ \ $(CXX) -fPIC -o '$@' $^ \
@ -40,19 +38,12 @@ sensors.o: sensors.cc
@echo "[ CXX ] $@" @echo "[ CXX ] $@"
$(CXX) $(CXXFLAGS) \ $(CXX) $(CXXFLAGS) \
-I$(PHONELIBS)/android_system_core/include \ -I$(PHONELIBS)/android_system_core/include \
$(CEREAL_FLAGS) \ $(CEREAL_CFLAGS) \
$(ZMQ_FLAGS) \ $(ZMQ_FLAGS) \
-I../ \ -I../ \
-I../../ \ -I../../ \
-c -o '$@' '$<' -c -o '$@' '$<'
log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++
@echo "[ CXX ] $@"
$(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \
-c -o '$@' '$<'
.PHONY: clean .PHONY: clean
clean: clean:
rm -f sensord $(OBJS) $(DEPS) rm -f sensord $(OBJS) $(DEPS)

@ -83,6 +83,7 @@ void sensor_loop() {
const sensors_event_t& data = buffer[i]; const sensors_event_t& data = buffer[i];
sensorEvents[i].setSource(cereal::SensorEventData::SensorSource::ANDROID);
sensorEvents[i].setVersion(data.version); sensorEvents[i].setVersion(data.version);
sensorEvents[i].setSensor(data.sensor); sensorEvents[i].setSensor(data.sensor);
sensorEvents[i].setType(data.type); sensorEvents[i].setType(data.type);

@ -30,6 +30,7 @@ FRAMEBUFFER_LIBS = -lutils -lgui -lEGL
OBJS = ui.o \ OBJS = ui.o \
touch.o \ touch.o \
../common/glutil.o \
../common/visionipc.o \ ../common/visionipc.o \
../common/framebuffer.o \ ../common/framebuffer.o \
$(PHONELIBS)/nanovg/nanovg.o \ $(PHONELIBS)/nanovg/nanovg.o \

@ -1,15 +1,50 @@
#include <stdio.h>
#include <stdlib.h>
#include <stdbool.h> #include <stdbool.h>
#include <assert.h>
#include <unistd.h> #include <unistd.h>
#include <fcntl.h> #include <fcntl.h>
#include <assert.h> #include <dirent.h>
#include <sys/poll.h> #include <sys/poll.h>
#include <linux/input.h> #include <linux/input.h>
#include "touch.h" #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) { void touch_init(TouchState *s) {
// synaptics touch screen on oneplus 3 s->fd = find_dev();
s->fd = open("/dev/input/event4", O_RDONLY);
assert(s->fd >= 0); assert(s->fd >= 0);
} }

@ -20,6 +20,7 @@
#include "common/timing.h" #include "common/timing.h"
#include "common/util.h" #include "common/util.h"
#include "common/mat.h" #include "common/mat.h"
#include "common/glutil.h"
#include "common/framebuffer.h" #include "common/framebuffer.h"
#include "common/visionipc.h" #include "common/visionipc.h"
@ -250,70 +251,6 @@ static const char line_fragment_shader[] =
" gl_FragColor = vColor;\n" " gl_FragColor = vColor;\n"
"}\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 = {{ static const mat4 device_transform = {{
1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0,
@ -760,9 +697,9 @@ static void ui_draw_vision(UIState *s) {
draw_frame(s); draw_frame(s);
if (!scene->frontview) { 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, scene->big_box_width, scene->big_box_height,
0xFF0000FF); 0xFF0000FF);*/
ui_draw_transformed_box(s, 0xFF00FF00); ui_draw_transformed_box(s, 0xFF00FF00);
@ -843,7 +780,7 @@ static void ui_draw_vision(UIState *s) {
if (strlen(scene->alert_text2) > 0) { if (strlen(scene->alert_text2) > 0) {
nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); nvgFillColor(s->vg, nvgRGBA(255,255,255,255));
nvgFontSize(s->vg, 100.0f); 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,12 +1208,14 @@ static void ui_update(UIState *s) {
s->last_base_update = ts; s->last_base_update = ts;
if (!activity_running()) {
if (s->awake_timeout > 0) { if (s->awake_timeout > 0) {
s->awake_timeout--; s->awake_timeout--;
} else { } else {
set_awake(s, false); set_awake(s, false);
} }
} }
}
if (s->vision_connected) { if (s->vision_connected) {
// always awake if vision is connected // always awake if vision is connected

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:fa55f398631e8831c45a93e32e00909d2464c80a263fdede974fcf030e5085cc oid sha256:6f627ba11b5b9bff1b620bda632c4648378c0232d3725f8b0a5052fae13a02d9
size 14723648 size 14737936

Loading…
Cancel
Save