commit e94a30bec07e719c5a7b037ca1f4db8312702cce Author: Vehicle Researcher Date: Tue Nov 29 18:34:21 2016 -0800 openpilot release diff --git a/LICENSE.openpilot b/LICENSE.openpilot new file mode 100644 index 0000000000..d1b0147269 --- /dev/null +++ b/LICENSE.openpilot @@ -0,0 +1,7 @@ +Copyright (c) 2016, comma.ai + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. diff --git a/README.md b/README.md new file mode 100644 index 0000000000..6c018638f5 --- /dev/null +++ b/README.md @@ -0,0 +1,93 @@ +Welcome to openpilot +====== + +[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. + +Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas and Acuras. It's about on par with Tesla Autopilot at launch, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). + +The openpilot codebase has been written to be concise and enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier. + +Hardware +------ + +Right now openpilot supports the [neo research platform](http://github.com/commaai/neo) for vehicle control. We'd like to support [Open Source Car Control](https://github.com/PolySync/OSCC) as well. + +To install it on the NEO: + +```bash +# Requires working adb in PATH +cd installation +./install.sh +``` + +Supported Cars +------ + +- Acura ILX 2016 with AcuraWatch Plus + - Limitations: Due to use of the cruise control for gas, it can only be enabled above 25 mph + +- Honda Civic 2016 Touring Edition + - Limitations: Due to limitations in steering firmware, steering is disabled below 18 mph + +Directory structure +------ + +- board -- Code that runs on the USB interface board +- cereal -- The messaging spec used for all logs on the phone +- common -- Library like functionality we've developed here +- dbcs -- Files showing how to interpret data from cars +- installation -- Installation on the neo platform +- phonelibs -- Libraries used on the phone +- selfdrive -- Code needed to drive the car + - assets -- Fonts for ui + - boardd -- Daemon to talk to the board + - calibrationd -- Camera calibration server + - common -- Shared C/C++ code for the daemons + - controls -- Python controls (PID loops etc) for the car + - logcatd -- Android logcat as a service + - loggerd -- Logger and uploader of car data + - sensord -- IMU / GPS interface code + - ui -- The UI + - visiond -- embedded vision pipeline + +To understand how the services interact, see `common/services.py` + +Adding Car Support +------ + +It should be relatively easy to add support for the Honda CR-V Touring. The brake message is the same. Steering has a slightly different message with a different message id. Sniff CAN while using LKAS to find it. + +The Honda Accord uses different signalling for the steering and probably requires new hardware. + +Adding other manufacturers besides Honda/Acura is doable but will be more of an undertaking. + + +User Data / chffr Account / Crash Reporting +------ + +By default openpilot creates an account and includes a client for chffr, our dashcam app. We use your data to train better models and improve openpilot for everyone. + +It's open source software, so you are free to disable it if you wish. + +It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +It does not log the user facing camera or the microphone. + +By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. + +Contributing +------ + +We welcome both pull requests and issues on +[github](http://github.com/commaai/openpilot). See the TODO file for a list of +good places to start. + + + +Licensing +------ + +openpilot is released under the MIT license. + +**THIS IS ALPHA QUALITY SOFTWARE FOR RESEARCH PURPOSES ONLY. THIS IS NOT A PRODUCT. +YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. +NO WARRANTY EXPRESSED OR IMPLIED.** diff --git a/SAFETY.md b/SAFETY.md new file mode 100644 index 0000000000..72297d8d7c --- /dev/null +++ b/SAFETY.md @@ -0,0 +1,36 @@ +openpilot Safety +====== + +openpilot is an Adaptive Cruise Control and Lane Keeping Assist System. Like +other ACC and LKAS systems, openpilot requires the driver to be alert and to pay +attention at all times. We repeat, **driver alertness is necessary, but not +sufficient, for openpilot to be used safely**. + +Even with an attentive driver, we must make further efforts for the system to be +safe. We have designed openpilot with two other safety considerations. + +1. The vehicle must always be controllable by the driver. +2. The vehicle must not alter its trajectory too quickly for the driver to safely + react. + +To address these, we came up with two safety principles. + +1. Enforced disengagements. Step on either pedal or press the cancel button to + retake manual control of the car immediately. + - These are hard enforced by the board, and soft enforced by the software. The + green led on the board signifies if the board is allowing control messages. + - Honda CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +2. Actuation limits. While the system is engaged, the actuators are constrained + to operate within reasonable limits; the same limits used by the stock system on + the Honda. + - Without an interceptor, the gas is controlled by the PCM. The PCM limits + acceleration to what is reasonable for a cruise control system. With an + interceptor, the gas is clipped to 60% in longcontrol.py + - The brake is controlled by the 0x1FA CAN message. This message allows full + braking, although the board and the software clip it to 1/4th of the max. + This is around .3g of braking. + - Steering is controlled by the 0xE4 CAN message. The EPS controller in the + car limits the torque to a very small amount, so regardless of the message, + the controller cannot jerk the wheel. diff --git a/TODO.md b/TODO.md new file mode 100644 index 0000000000..b7b842c609 --- /dev/null +++ b/TODO.md @@ -0,0 +1,14 @@ +TODO +====== + +An incomplete list of known issues and desired featues. + +- TX and RX amounts on UI are wrong for a few frames at startup because we + subtract (total sent - 0). We should initialize sent bytes before displaying. + +- Rewrite common/dbc.py to be faster and cleaner, potentially in C++. + +- Add module and class level documentation where appropriate. + +- Fix lock file cleanup so there isn't always 1 pending upload when the vehicle + shuts off. diff --git a/board/Makefile b/board/Makefile new file mode 100644 index 0000000000..4c0b6d38ac --- /dev/null +++ b/board/Makefile @@ -0,0 +1,43 @@ +# :set noet +PROJ_NAME = comma + +CFLAGS = -g -O0 -Wall +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 +CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx +CFLAGS += -I inc -nostdlib +CFLAGS += -Tstm32_flash.ld + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy +OBJDUMP = arm-none-eabi-objdump + +MACHINE = $(shell uname -m) + +all: obj/$(PROJ_NAME).bin + #$(OBJDUMP) -d obj/$(PROJ_NAME).elf + ./tools/enter_download_mode.py + ./tools/dfu-util-$(MACHINE) -a 0 -s 0x08000000 -D $< + ./tools/dfu-util-$(MACHINE) --reset-stm32 -a 0 -s 0x08000000 + +ifneq ($(wildcard ../.git/HEAD),) +obj/gitversion.h: ../.git/HEAD ../.git/index + echo "const uint8_t gitversion[] = \"$(shell git rev-parse HEAD)\";" > $@ +else +obj/gitversion.h: + echo "const uint8_t gitversion[] = \"RELEASE\";" > $@ +endif + +obj/main.o: main.c *.h obj/gitversion.h + $(CC) $(CFLAGS) -o $@ -c $< + +obj/startup_stm32f205xx.o: startup_stm32f205xx.s + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(PROJ_NAME).bin: obj/startup_stm32f205xx.o obj/main.o + $(CC) $(CFLAGS) -o obj/$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf $@ + +clean: + rm -f obj/* + diff --git a/board/adc.h b/board/adc.h new file mode 100644 index 0000000000..3ac2fe4fe4 --- /dev/null +++ b/board/adc.h @@ -0,0 +1,38 @@ +// ACCEL1 = ADC10 +// ACCEL2 = ADC11 +// VOLT_S = ADC12 +// CURR_S = ADC13 + +#define ADCCHAN_ACCEL0 10 +#define ADCCHAN_ACCEL1 11 +#define ADCCHAN_VOLTAGE 12 +#define ADCCHAN_CURRENT 13 + +void adc_init() { + // global setup + ADC->CCR = ADC_CCR_TSVREFE | ADC_CCR_VBATE; + //ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_EOCS | ADC_CR2_DDS; + ADC1->CR2 = ADC_CR2_ADON; + + // long + ADC1->SMPR1 = ADC_SMPR1_SMP10 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13; +} + +uint32_t adc_get(int channel) { + + // includes length + //ADC1->SQR1 = 0; + + // select channel + ADC1->JSQR = channel << 15; + + //ADC1->CR1 = ADC_CR1_DISCNUM_0; + //ADC1->CR1 = ADC_CR1_EOCIE; + + ADC1->SR &= ~(ADC_SR_JEOC); + ADC1->CR2 |= ADC_CR2_JSWSTART; + while (!(ADC1->SR & ADC_SR_JEOC)); + + return ADC1->JDR1; +} + diff --git a/board/can.h b/board/can.h new file mode 100644 index 0000000000..02053bafb6 --- /dev/null +++ b/board/can.h @@ -0,0 +1,75 @@ +void can_init(CAN_TypeDef *CAN) { + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ; + while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); + puts("CAN initting\n"); + + // PCLK = 24000000, 500000 is 48 clocks + // from http://www.bittiming.can-wiki.ino/ + CAN->BTR = 0x001c0002; + + // loopback mode for debugging + #ifdef CAN_LOOPBACK_MODE + CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; + #endif + + // reset + CAN->MCR = CAN_MCR_TTCM; + while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK); + puts("CAN init done\n"); + + // accept all filter + CAN->FMR |= CAN_FMR_FINIT; + + // no mask + CAN->sFilterRegister[0].FR1 = 0; + CAN->sFilterRegister[0].FR2 = 0; + CAN->sFilterRegister[14].FR1 = 0; + CAN->sFilterRegister[14].FR2 = 0; + CAN->FA1R |= 1 | (1 << 14); + + CAN->FMR &= ~(CAN_FMR_FINIT); + + // enable all CAN interrupts + CAN->IER = 0xFFFFFFFF; + //CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_FMPIE1; +} + +// CAN error +void can_sce(CAN_TypeDef *CAN) { + #ifdef DEBUG + puts("MSR:"); + puth(CAN->MSR); + puts(" TSR:"); + puth(CAN->TSR); + puts(" RF0R:"); + puth(CAN->RF0R); + puts(" RF1R:"); + puth(CAN->RF1R); + puts(" ESR:"); + puth(CAN->ESR); + puts("\n"); + #endif + + // clear + //CAN->sTxMailBox[0].TIR &= ~(CAN_TI0R_TXRQ); + CAN->TSR |= CAN_TSR_ABRQ0; + //CAN->ESR |= CAN_ESR_LEC; + //CAN->MSR &= ~(CAN_MSR_ERRI); + CAN->MSR = CAN->MSR; +} + +int can_cksum(uint8_t *dat, int len, int addr, int idx) { + int i; + int s = 0; + for (i = 0; i < len; i++) { + s += (dat[i] >> 4); + s += dat[i] & 0xF; + } + s += (addr>>0)&0xF; + s += (addr>>4)&0xF; + s += (addr>>8)&0xF; + s += idx; + s = 8-s; + return s&0xF; +} + diff --git a/board/dac.h b/board/dac.h new file mode 100644 index 0000000000..b8833dc4a6 --- /dev/null +++ b/board/dac.h @@ -0,0 +1,16 @@ +void dac_init() { + // no buffers required since we have an opamp + //DAC->CR = DAC_CR_EN1 | DAC_CR_BOFF1 | DAC_CR_EN2 | DAC_CR_BOFF2; + DAC->DHR12R1 = 0; + DAC->DHR12R2 = 0; + DAC->CR = DAC_CR_EN1 | DAC_CR_EN2; +} + +void dac_set(int channel, uint32_t value) { + if (channel == 0) { + DAC->DHR12R1 = value; + } else if (channel == 1) { + DAC->DHR12R2 = value; + } +} + diff --git a/board/inc/core_cm3.h b/board/inc/core_cm3.h new file mode 100644 index 0000000000..2a1b8454a7 --- /dev/null +++ b/board/inc/core_cm3.h @@ -0,0 +1,1211 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM3_H_GENERIC +#define __CORE_CM3_H_GENERIC + + + + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \defgroup CMSIS_core_definitions CMSIS Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core + - Cortex-M core Revision Number + @{ + */ + +/* CMSIS CM3 definitions */ +#define __CM3_CMSIS_VERSION_MAIN (0x02) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x10) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + +/*!< __FPU_USED to be checked prior to making use of FPU specific registers and functions */ +#define __FPU_USED 0 + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + /* add preprocessor checks */ +#endif + +#include /*!< standard types definitions */ +#include "core_cmInstr.h" /*!< Core Instruction Access */ +#include "core_cmFunc.h" /*!< Core Function Access */ + +#endif /* __CORE_CM3_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM3_H_DEPENDANT +#define __CORE_CM3_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM3_REV + #define __CM3_REV 0x0200 + #warning "__CM3_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0 + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + +/*@} end of group CMSIS_core_definitions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** \defgroup CMSIS_core_register CMSIS Core Register + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE CMSIS Core + Type definitions for the Cortex-M Core Registers + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + unsigned int _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + unsigned int Q:1; /*!< bit: 27 Saturation condition flag */ + unsigned int V:1; /*!< bit: 28 Overflow condition code flag */ + unsigned int C:1; /*!< bit: 29 Carry condition code flag */ + unsigned int Z:1; /*!< bit: 30 Zero condition code flag */ + unsigned int N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + unsigned int ISR:9; /*!< bit: 0.. 8 Exception number */ + unsigned int _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + unsigned int ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + unsigned int _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + unsigned int T:1; /*!< bit: 24 Thumb bit (read 0) */ + unsigned int IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + unsigned int Q:1; /*!< bit: 27 Saturation condition flag */ + unsigned int V:1; /*!< bit: 28 Overflow condition code flag */ + unsigned int C:1; /*!< bit: 29 Carry condition code flag */ + unsigned int Z:1; /*!< bit: 30 Zero condition code flag */ + unsigned int N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + unsigned int nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + unsigned int SPSEL:1; /*!< bit: 1 Stack to be used */ + unsigned int FPCA:1; /*!< bit: 2 FP extension active flag */ + unsigned int _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC CMSIS NVIC + Type definitions for the Cortex-M NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB CMSIS SCB + Type definitions for the Cortex-M System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB CMSIS System Control and ID Register not in the SCB + Type definitions for the Cortex-M System Control and ID Register not in the SCB + @{ + */ + +/** \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +#else + uint32_t RESERVED1[1]; +#endif +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick CMSIS SysTick + Type definitions for the Cortex-M System Timer Registers + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_ITM CMSIS ITM + Type definitions for the Cortex-M Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_TXENA_Pos 3 /*!< ITM TCR: TXENA Position */ +#define ITM_TCR_TXENA_Msk (1UL << ITM_TCR_TXENA_Pos) /*!< ITM TCR: TXENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +#if (__MPU_PRESENT == 1) +/** \ingroup CMSIS_core_register + \defgroup CMSIS_MPU CMSIS MPU + Type definitions for the Cortex-M Memory Protection Unit (MPU) + @{ + */ + +/** \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug CMSIS Core Debug + Type definitions for the Cortex-M Core Debug Registers + @{ + */ + +/** \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + @{ + */ + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface CMSIS Core Function Interface + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions CMSIS Core NVIC Functions + @{ + */ + +/** \brief Set Priority Grouping + + This function sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + + \param [in] PriorityGroup Priority grouping field + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** \brief Get Priority Grouping + + This function gets the priority grouping from NVIC Interrupt Controller. + Priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + + \return Priority grouping field + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + + +/** \brief Enable External Interrupt + + This function enables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to enable + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)); /* enable interrupt */ +} + + +/** \brief Disable External Interrupt + + This function disables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to disable + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)); /* disable interrupt */ +} + + +/** \brief Get Pending Interrupt + + This function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Number of the interrupt for get pending + \return 0 Interrupt status is not pending + \return 1 Interrupt status is pending + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) (((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)))!=0)?1:0)); /* Return 1 if pending else 0 */ +} + + +/** \brief Set Pending Interrupt + + This function sets the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for set pending + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)); /* set interrupt pending */ +} + + +/** \brief Clear Pending Interrupt + + This function clears the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for clear pending + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Get Active Interrupt + + This function reads the active register in NVIC and returns the active bit. + \param [in] IRQn Number of the interrupt for get active + \return 0 Interrupt status is not active + \return 1 Interrupt status is active + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)(((NVIC->IABR[(uint32_t)(IRQn) >> 5] & ((uint32_t)1 << ((uint32_t)(IRQn) & (uint32_t)0x1F)))!=0)?1:0)); /* Return 1 if active else 0 */ +} + + +/** \brief Set Interrupt Priority + + This function sets the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + Note: The priority cannot be set for every core interrupt. + + \param [in] IRQn Number of the interrupt for set priority + \param [in] priority Priority to set + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + + +/** \brief Get Interrupt Priority + + This function reads the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + The returned priority value is automatically aligned to the implemented + priority bits of the microcontroller. + + \param [in] IRQn Number of the interrupt for get priority + \return Interrupt Priority + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief Encode Priority + + This function encodes the priority for an interrupt with the given priority group, + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The returned priority value can be used for NVIC_SetPriority(...) function + + \param [in] PriorityGroup Used priority group + \param [in] PreemptPriority Preemptive priority value (starting from 0) + \param [in] SubPriority Sub priority value (starting from 0) + \return Encoded priority for the interrupt + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & (((uint32_t)1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & (((uint32_t)1 << (SubPriorityBits )) - 1))) + ); +} + + +/** \brief Decode Priority + + This function decodes an interrupt priority value with the given priority group to + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The priority value can be retrieved with NVIC_GetPriority(...) function + + \param [in] Priority Priority value + \param [in] PriorityGroup Used priority group + \param [out] pPreemptPriority Preemptive priority value (starting from 0) + \param [out] pSubPriority Sub priority value (starting from 0) + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & (((uint32_t)1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & (((uint32_t)1 << (SubPriorityBits )) - 1); +} + + +/** \brief System Reset + + This function initiate a system reset request to reset the MCU. + */ +static __INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions CMSIS Core SysTick Functions + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + This function initialises the system tick timer and its interrupt and start the system tick timer. + Counter is in free running mode to generate periodical interrupts. + + \param [in] ticks Number of ticks between two interrupts + \return 0 Function succeeded + \return 1 Function failed + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions CMSIS Core Debug Functions + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< external variable to receive characters */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ + + +/** \brief ITM Send Character + + This function transmits a character via the ITM channel 0. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \param [in] ch Character to transmit + \return Character to transmit + */ +static __INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ + (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** \brief ITM Receive Character + + This function inputs a character via external variable ITM_RxBuffer. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \return Received character + \return -1 No character received + */ +static __INLINE int32_t ITM_ReceiveChar (void) { + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** \brief ITM Check Character + + This function checks external variable ITM_RxBuffer whether a character is available or not. + It returns '1' if a character is available and '0' if no character is available. + + \return 0 No character available + \return 1 Character available + */ +static __INLINE int32_t ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + +#endif /* __CORE_CM3_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif diff --git a/board/inc/core_cmFunc.h b/board/inc/core_cmFunc.h new file mode 100644 index 0000000000..c999b1c83b --- /dev/null +++ b/board/inc/core_cmFunc.h @@ -0,0 +1,609 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V2.10 + * @date 26. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** \brief Get ISPR Register + + This function returns the content of the ISPR Register. + + \return ISPR Register value + */ +static __INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +static __INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +static __INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief Enable IRQ Interrupts + + This function enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i"); +} + + +/** \brief Disable IRQ Interrupts + + This function disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i"); +} + + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** \brief Get ISPR Register + + This function returns the content of the ISPR Register. + + \return ISPR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f"); +} + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f"); +} + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +#endif /* __CORE_CMFUNC_H */ diff --git a/board/inc/core_cmInstr.h b/board/inc/core_cmInstr.h new file mode 100644 index 0000000000..399327004f --- /dev/null +++ b/board/inc/core_cmInstr.h @@ -0,0 +1,585 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +static __INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +static __INLINE __ASM int32_t __REVSH(int32_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __rbit + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW(value, ptr) __strex(value, ptr) + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +#define __CLREX __clrex + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + +#endif /* (__CORTEX_M >= 0x03) */ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__( ( always_inline ) ) static __INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +__attribute__( ( always_inline ) ) static __INLINE void __ISB(void) +{ + __ASM volatile ("isb"); +} + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DSB(void) +{ + __ASM volatile ("dsb"); +} + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DMB(void) +{ + __ASM volatile ("dmb"); +} + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value) +{ + uint32_t result; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return((int32_t)result); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint8_t result; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint16_t result; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +__attribute__( ( always_inline ) ) static __INLINE void __CLREX(void) +{ + __ASM volatile ("clrex"); +} + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value) +{ + uint8_t result; + + __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */ diff --git a/board/inc/stm32f205xx.h b/board/inc/stm32f205xx.h new file mode 100644 index 0000000000..ec812fbb54 --- /dev/null +++ b/board/inc/stm32f205xx.h @@ -0,0 +1,7185 @@ +/** + ****************************************************************************** + * @file stm32f205xx.h + * @author MCD Application Team + * @version V2.0.1 + * @date 25-March-2014 + * @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File. + * This file contains : + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral's registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2014 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f205xx + * @{ + */ + +#ifndef __STM32F205xx_H +#define __STM32F205xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M3 Processor and Core Peripherals + */ +#define __CM3_REV 0x0200 /*!< Core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< STM32F2XX provides an MPU */ +#define __NVIC_PRIO_BITS 4 /*!< STM32F2XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F2XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M3 Processor Exceptions Numbers ****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ + DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ + DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ + DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ + DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ + DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ + DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ + ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ + CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ + CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global interrupt */ + DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ + DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ + DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ + DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ + DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + HASH_RNG_IRQn = 80 /*!< Hash and Rng global interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm3.h" +#include "system_stm32f2xx.h" +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ + __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ + __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ + __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ + __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ + __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ + __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ + __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + __IO uint32_t TDLR; /*!< CAN mailbox data low register */ + __IO uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ + __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CAN_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA stream x configuration register */ + __IO uint32_t NDTR; /*!< DMA stream x number of data register */ + __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ + __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ + __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ + __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ +} DMA_Stream_TypeDef; + +typedef struct +{ + __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ + __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ + __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ + __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ +} DMA_TypeDef; + + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ + __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ + __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ + __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ + __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ + __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ + __IO uint32_t OPTCR; /*!< FLASH option control register, Address offset: 0x14 */ +} FLASH_TypeDef; + + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ + uint32_t RESERVED1; /*!< Reserved, 0x78 */ + uint32_t RESERVED2; /*!< Reserved, 0x7C */ + __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED3; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FSMC_Bank2_3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ + __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ + __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ + __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ + __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ +} FSMC_Bank4_TypeDef; + + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint16_t BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ + __IO uint16_t BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ +} GPIO_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ + __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ +} SYSCFG_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ + __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ + __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ + __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ + __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ + __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ + __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ + __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved, 0x3C */ + __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ + uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, 0x5C */ + __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ + uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ + __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ + __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ + __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ + +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ + __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + uint32_t RESERVED1; /*!< Reserved, 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + uint32_t RESERVED3; /*!< Reserved, 0x38 */ + uint32_t RESERVED4; /*!< Reserved, 0x3C */ + __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ + uint32_t RESERVED5; /*!< Reserved, 0x44 */ + uint32_t RESERVED6; /*!< Reserved, 0x48 */ + uint32_t RESERVED7; /*!< Reserved, 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ + __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ + __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ + __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ + __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ + __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ + __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ + __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ + __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ + __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ + __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ + __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ + __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ + __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ + __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ + __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ + __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ + __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ + __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ + __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ +} RTC_TypeDef; + + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ + __I uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ + __I uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ + __I uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ + __I uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ + __I uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ + __I uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ + __I uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ + __I uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ + uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ + __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ + __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ + __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ + __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ + __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ + __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ + __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ + __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ + __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ + __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + + +/** + * @brief RNG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + + + +/** + * @brief __USB_OTG_Core_register + */ +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h*/ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h*/ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h*/ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch*/ + __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h*/ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h*/ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h*/ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch*/ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h*/ + __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register 024h*/ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h*/ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch*/ + uint32_t Reserved30[2]; /* Reserved 030h*/ + __IO uint32_t GCCFG; /* General Purpose IO Register 038h*/ + __IO uint32_t CID; /* User ID Register 03Ch*/ + uint32_t Reserved40[48]; /* Reserved 040h-0FFh*/ + __IO uint32_t HPTXFSIZ; /* Host Periodic Tx FIFO Size Reg 100h*/ + __IO uint32_t DIEPTXF[0x0F];/* dev Periodic Transmit FIFO */ +} +USB_OTG_GlobalTypeDef; + + + +/** + * @brief __device_Registers + */ +typedef struct +{ + __IO uint32_t DCFG; /* dev Configuration Register 800h*/ + __IO uint32_t DCTL; /* dev Control Register 804h*/ + __IO uint32_t DSTS; /* dev Status Register (RO) 808h*/ + uint32_t Reserved0C; /* Reserved 80Ch*/ + __IO uint32_t DIEPMSK; /* dev IN Endpoint Mask 810h*/ + __IO uint32_t DOEPMSK; /* dev OUT Endpoint Mask 814h*/ + __IO uint32_t DAINT; /* dev All Endpoints Itr Reg 818h*/ + __IO uint32_t DAINTMSK; /* dev All Endpoints Itr Mask 81Ch*/ + uint32_t Reserved20; /* Reserved 820h*/ + uint32_t Reserved9; /* Reserved 824h*/ + __IO uint32_t DVBUSDIS; /* dev VBUS discharge Register 828h*/ + __IO uint32_t DVBUSPULSE; /* dev VBUS Pulse Register 82Ch*/ + __IO uint32_t DTHRCTL; /* dev thr 830h*/ + __IO uint32_t DIEPEMPMSK; /* dev empty msk 834h*/ + __IO uint32_t DEACHINT; /* dedicated EP interrupt 838h*/ + __IO uint32_t DEACHMSK; /* dedicated EP msk 83Ch*/ + uint32_t Reserved40; /* dedicated EP mask 840h*/ + __IO uint32_t DINEP1MSK; /* dedicated EP mask 844h*/ + uint32_t Reserved44[15]; /* Reserved 844-87Ch*/ + __IO uint32_t DOUTEP1MSK; /* dedicated EP msk 884h*/ +} +USB_OTG_DeviceTypeDef; + + +/** + * @brief __IN_Endpoint-Specific_Register + */ +typedef struct +{ + __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h*/ + __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h*/ + __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h*/ + __IO uint32_t DTXFSTS;/*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h*/ + uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch*/ +} +USB_OTG_INEndpointTypeDef; + + +/** + * @brief __OUT_Endpoint-Specific_Registers + */ +typedef struct +{ + __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ +} +USB_OTG_OUTEndpointTypeDef; + + +/** + * @brief __Host_Mode_Register_Structures + */ +typedef struct +{ + __IO uint32_t HCFG; /* Host Configuration Register 400h*/ + __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ + __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ + uint32_t Reserved40C; /* Reserved 40Ch*/ + __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ + __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ + __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ +} +USB_OTG_HostTypeDef; + + +/** + * @brief __Host_Channel_Specific_Registers + */ +typedef struct +{ + __IO uint32_t HCCHAR; + __IO uint32_t HCSPLT; + __IO uint32_t HCINT; + __IO uint32_t HCINTMSK; + __IO uint32_t HCTSIZ; + __IO uint32_t HCDMA; + uint32_t Reserved[2]; +} +USB_OTG_HostChannelTypeDef; + + +/** + * @brief Peripheral_memory_map + */ +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH(up to 1 MB) base address in the alias region */ +#define CCMDATARAM_BASE ((uint32_t)0x10000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region */ +#define SRAM1_BASE ((uint32_t)0x20000000) /*!< SRAM1(112 KB) base address in the alias region */ +#define SRAM2_BASE ((uint32_t)0x2001C000) /*!< SRAM2(16 KB) base address in the alias region */ +#define SRAM3_BASE ((uint32_t)0x20020000) /*!< SRAM3(64 KB) base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ +#define BKPSRAM_BASE ((uint32_t)0x40024000) /*!< Backup SRAM(4 KB) base address in the alias region */ +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ +#define CCMDATARAM_BB_BASE ((uint32_t)0x12000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the bit-band region */ +#define SRAM1_BB_BASE ((uint32_t)0x22000000) /*!< SRAM1(112 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE ((uint32_t)0x2201C000) /*!< SRAM2(16 KB) base address in the bit-band region */ +#define SRAM3_BB_BASE ((uint32_t)0x22020000) /*!< SRAM3(64 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ +#define BKPSRAM_BB_BASE ((uint32_t)0x42024000) /*!< Backup SRAM(4 KB) base address in the bit-band region */ + +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000) + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) + +/*!< APB2 peripherals */ +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADC_BASE (APB2PERIPH_BASE + 0x2300) +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800) + +/*!< AHB1 peripherals */ +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00) +#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8) + +/*!< AHB2 peripherals */ +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800) + +/*!< FSMC Bankx registers base address */ +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) +#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060) +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE ((uint32_t )0xE0042000) + +/*!< USB registers base address */ +#define USB_OTG_HS_PERIPH_BASE ((uint32_t )0x40040000) +#define USB_OTG_FS_PERIPH_BASE ((uint32_t )0x50000000) + +#define USB_OTG_GLOBAL_BASE ((uint32_t )0x000) +#define USB_OTG_DEVICE_BASE ((uint32_t )0x800) +#define USB_OTG_IN_ENDPOINT_BASE ((uint32_t )0x900) +#define USB_OTG_OUT_ENDPOINT_BASE ((uint32_t )0xB00) +#define USB_OTG_EP_REG_SIZE ((uint32_t )0x20) +#define USB_OTG_HOST_BASE ((uint32_t )0x400) +#define USB_OTG_HOST_PORT_BASE ((uint32_t )0x440) +#define USB_OTG_HOST_CHANNEL_BASE ((uint32_t )0x500) +#define USB_OTG_HOST_CHANNEL_SIZE ((uint32_t )0x20) +#define USB_OTG_PCGCCTL_BASE ((uint32_t )0xE00) +#define USB_OTG_FIFO_BASE ((uint32_t )0x1000) +#define USB_OTG_FIFO_SIZE ((uint32_t )0x1000) + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define ADC ((ADC_Common_TypeDef *) ADC_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) +#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) +#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) +#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) +#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) +#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) +#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) +#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) +#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) +#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) +#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) +#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) +#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) +#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) +#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) +#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) +#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD ((uint32_t)0x00000001) /*!
© COPYRIGHT(c) 2014 STMicroelectronics
+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f2xx + * @{ + */ + +#ifndef __STM32F2xx_H +#define __STM32F2xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ + +#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) + + /* #define STM32F205xx */ /*!< STM32Fxx Devices */ + /* #define STM32F215xx */ /*!< STM32Fxx Devices */ + /* #define STM32F207xx */ /*!< STM32Fxx Devices */ + /* #define STM32F217xx */ /*!< STM32Fxx Devices */ + +#endif + +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + */ +#if !defined (USE_HAL_DRIVER) +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_HAL_DRIVER */ +#endif /* USE_HAL_DRIVER */ + +/** + * @brief CMSIS Device version number V2.0.1 + */ +#define __STM32F2xx_CMSIS_DEVICE_VERSION_MAIN (0x02) /*!< [31:24] main version */ +#define __STM32F2xx_CMSIS_DEVICE_VERSION_SUB1 (0x00) /*!< [23:16] sub1 version */ +#define __STM32F2xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32F2xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32F2xx_CMSIS_DEVICE_VERSION ((__CMSIS_DEVICE_VERSION_MAIN << 24)\ + |(__CMSIS_DEVICE_HAL_VERSION_SUB1 << 16)\ + |(__CMSIS_DEVICE_HAL_VERSION_SUB2 << 8 )\ + |(__CMSIS_DEVICE_HAL_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Device_Included + * @{ + */ + +#if defined(STM32F205xx) + #include "stm32f205xx.h" +#elif defined(STM32F215xx) + #include "stm32f215xx.h" +#elif defined(STM32F207xx) + #include "stm32f207xx.h" +#elif defined(STM32F217xx) + #include "stm32f217xx.h" +#else + #error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)" +#endif + +/** + * @} + */ + +/** @addtogroup Exported_types + * @{ + */ +typedef enum +{ + RESET = 0, + SET = !RESET +} FlagStatus, ITStatus; + +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum +{ + ERROR = 0, + SUCCESS = !ERROR +} ErrorStatus; + +/** + * @} + */ + + +/** @addtogroup Exported_macro + * @{ + */ +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + +#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) + + +/** + * @} + */ + + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __STM32F2xx_H */ + +/** + * @} + */ + +/** + * @} + */ + + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/board/inc/system_stm32f2xx.h b/board/inc/system_stm32f2xx.h new file mode 100644 index 0000000000..6c251c34e0 --- /dev/null +++ b/board/inc/system_stm32f2xx.h @@ -0,0 +1,99 @@ +/** + ****************************************************************************** + * @file system_stm32f2xx.h + * @author MCD Application Team + * @version V1.0.0 + * @date 18-April-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f2xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F2XX_H +#define __SYSTEM_STM32F2XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F2xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F2xx_System_Exported_types + * @{ + */ + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F2XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/board/libc.h b/board/libc.h new file mode 100644 index 0000000000..4a2913b883 --- /dev/null +++ b/board/libc.h @@ -0,0 +1,226 @@ +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_))) +#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100) +#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) +#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F)) + +#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF10_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS */ + +#ifdef OLD_BOARD + #define USART USART2 +#else + #define USART USART3 +#endif + + +// **** shitty libc **** + +void clock_init() { + #ifdef USE_INTERNAL_OSC + // enable internal oscillator + RCC->CR |= RCC_CR_HSION; + while ((RCC->CR & RCC_CR_HSIRDY) == 0); + #else + // enable external oscillator + RCC->CR |= RCC_CR_HSEON; + while ((RCC->CR & RCC_CR_HSERDY) == 0); + #endif + + // divide shit + RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4; + #ifdef USE_INTERNAL_OSC + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSI; + #else + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE; + #endif + + // start PLL + RCC->CR |= RCC_CR_PLLON; + while ((RCC->CR & RCC_CR_PLLRDY) == 0); + + // Configure Flash prefetch, Instruction cache, Data cache and wait state + // *** without this, it breaks *** + FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS; + + // switch to PLL + RCC->CFGR |= RCC_CFGR_SW_PLL; + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); + + // *** running on PLL *** + + // enable GPIOB, UART2, CAN, USB clock + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + RCC->APB1ENR |= RCC_APB1ENR_USART3EN; + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; + RCC->APB1ENR |= RCC_APB1ENR_DACEN; + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + //RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; + + // turn on alt USB + RCC->AHB1ENR |= RCC_AHB1ENR_OTGHSEN; + + // fix interrupt vectors +} + +// board specific +void gpio_init() { + // analog mode + GPIOC->MODER = GPIO_MODER_MODER3 | GPIO_MODER_MODER2 | + GPIO_MODER_MODER1 | GPIO_MODER_MODER0; + + // FAN on C9, aka TIM3_CH4 + #ifdef OLD_BOARD + GPIOC->MODER |= GPIO_MODER_MODER9_1; + GPIOC->AFR[1] = GPIO_AF2_TIM3 << ((9-8)*4); + #else + GPIOC->MODER |= GPIO_MODER_MODER8_1; + GPIOC->AFR[1] = GPIO_AF2_TIM3 << ((8-8)*4); + #endif + // IGNITION on C13 + + // set mode for LEDs and CAN + GPIOB->MODER = GPIO_MODER_MODER10_0 | GPIO_MODER_MODER11_0; + // CAN 2 + GPIOB->MODER |= GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1; + // CAN 1 + GPIOB->MODER |= GPIO_MODER_MODER8_1 | GPIO_MODER_MODER9_1; + // CAN enables + GPIOB->MODER |= GPIO_MODER_MODER3_0 | GPIO_MODER_MODER4_0; + + // set mode for SERIAL and USB (DAC should be configured to in) + GPIOA->MODER = GPIO_MODER_MODER2_1 | GPIO_MODER_MODER3_1; + GPIOA->AFR[0] = GPIO_AF7_USART2 << (2*4) | GPIO_AF7_USART2 << (3*4); + + // GPIOC USART3 + GPIOC->MODER |= GPIO_MODER_MODER10_1 | GPIO_MODER_MODER11_1; + GPIOC->AFR[1] |= GPIO_AF7_USART3 << ((10-8)*4) | GPIO_AF7_USART3 << ((11-8)*4); + + if (USBx == USB_OTG_FS) { + GPIOA->MODER |= GPIO_MODER_MODER11_1 | GPIO_MODER_MODER12_1; + GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; + GPIOA->AFR[1] = GPIO_AF10_OTG_FS << ((11-8)*4) | GPIO_AF10_OTG_FS << ((12-8)*4); + } + + GPIOA->PUPDR = GPIO_PUPDR_PUPDR2_0 | GPIO_PUPDR_PUPDR3_0; + + // set mode for CAN / USB_HS pins + GPIOB->AFR[0] = GPIO_AF9_CAN1 << (5*4) | GPIO_AF9_CAN1 << (6*4); + GPIOB->AFR[1] = GPIO_AF9_CAN1 << ((8-8)*4) | GPIO_AF9_CAN1 << ((9-8)*4); + + if (USBx == USB_OTG_HS) { + GPIOB->AFR[1] |= GPIO_AF12_OTG_HS_FS << ((15-8)*4) | GPIO_AF12_OTG_HS_FS << ((14-8)*4); + GPIOB->MODER |= GPIO_MODER_MODER14_1 | GPIO_MODER_MODER15_1; + } + + GPIOB->OSPEEDR = GPIO_OSPEEDER_OSPEEDR14 | GPIO_OSPEEDER_OSPEEDR15; + + // enable CAN busses + GPIOB->ODR |= (1 << 3) | (1 << 4); + + // enable OTG out tied to ground + GPIOA->ODR = 0; + GPIOA->MODER |= GPIO_MODER_MODER1_0; + + // enable USB power tied to + + GPIOA->ODR |= 1; + GPIOA->MODER |= GPIO_MODER_MODER0_0; +} + +void uart_init() { + // enable uart and tx+rx mode + USART->CR1 = USART_CR1_UE; + USART->BRR = __USART_BRR(24000000, 115200); + USART->CR1 |= USART_CR1_TE | USART_CR1_RE; + USART->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1; + // ** UART is ready to work ** + + // enable interrupts + USART->CR1 |= USART_CR1_RXNEIE; +} + +void delay(int a) { + volatile int i; + for (i=0;iSR & USART_SR_TXE)); + USART->DR = a; +} + +int puts(const char *a) { + for (;*a;a++) { + if (*a == '\n') putch('\r'); + putch(*a); + } + return 0; +} + +void puth(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 28; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void puth2(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 4; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void hexdump(void *a, int l) { + int i; + for (i=0;iw_ptr != q->r_ptr) { + *elem = q->elems[q->r_ptr]; + q->r_ptr += 1; + return 1; + } + return 0; +} + +inline int push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + uint8_t next_w_ptr = q->w_ptr + 1; + if (next_w_ptr != q->r_ptr) { + q->elems[q->w_ptr] = *elem; + q->w_ptr = next_w_ptr; + return 1; + } + return 0; +} + +// ***************************** CAN ***************************** + +void process_can(CAN_TypeDef *CAN, can_ring *can_q, int can_number) { + #ifdef DEBUG + puts("process CAN TX\n"); + #endif + + // add successfully transmitted message to my fifo + if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) { + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sTxMailBox[0].TIR; + to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) | ((can_number+2) << 4); + to_push.RDLR = CAN->sTxMailBox[0].TDLR; + to_push.RDHR = CAN->sTxMailBox[0].TDHR; + push(&can_rx_q, &to_push); + } + + // check for empty mailbox + CAN_FIFOMailBox_TypeDef to_send; + if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { + if (pop(can_q, &to_send)) { + + // BRAKE: safety check + if ((to_send.RIR>>21) == 0x1FA) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFF3F; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // STEER: safety check + if ((to_send.RIR>>21) == 0xE4) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFFFF; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // GAS: safety check + if ((to_send.RIR>>21) == 0x200) { + if (controls_allowed) { + to_send.RDLR &= 0xFFFFFFFF; + } else { + to_send.RDLR &= 0xFFFF0000; + } + } + + // only send if we have received a packet + CAN->sTxMailBox[0].TDLR = to_send.RDLR; + CAN->sTxMailBox[0].TDHR = to_send.RDHR; + CAN->sTxMailBox[0].TDTR = to_send.RDTR; + CAN->sTxMailBox[0].TIR = to_send.RIR; + } + } + + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +// send more, possible for these to not trigger? +void CAN1_TX_IRQHandler() { + process_can(CAN1, &can_tx1_q, 1); +} + +void CAN2_TX_IRQHandler() { + process_can(CAN2, &can_tx2_q, 0); +} + +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button + + +// all commands: brake and steering +// if controls_allowed +// allow all commands up to limit +// else +// block all commands that produce actuation + +// CAN receive handlers +void can_rx(CAN_TypeDef *CAN, int can_number) { + while (CAN->RF0R & CAN_RF0R_FMP0) { + // add to my fifo + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sFIFOMailBox[0].RIR; + // top 16-bits is the timestamp + to_push.RDTR = (CAN->sFIFOMailBox[0].RDTR & 0xFFFF000F) | (can_number << 4); + to_push.RDLR = CAN->sFIFOMailBox[0].RDLR; + to_push.RDHR = CAN->sFIFOMailBox[0].RDHR; + + // state machine to enter and exit controls + // 0x1A6 for the ILX, 0x296 for the Civic Touring + if ((to_push.RIR>>21) == 0x1A6 || (to_push.RIR>>21) == 0x296) { + int buttons = (to_push.RDLR & 0xE0) >> 5; + if (buttons == 4 || buttons == 3) { + controls_allowed = 1; + } else if (buttons == 2) { + controls_allowed = 0; + } + } + + // exit controls on brake press + if ((to_push.RIR>>21) == 0x17C) { + // bit 50 + if (to_push.RDHR & 0x200000) { + controls_allowed = 0; + } + } + + // exit controls on gas press if interceptor + if ((to_push.RIR>>21) == 0x201) { + gas_interceptor_detected = 1; + int gas = ((to_push.RDLR & 0xFF) << 8) | ((to_push.RDLR & 0xFF00) >> 8); + if (gas > 328) { + controls_allowed = 0; + } + } + + // exit controls on gas press if no interceptor + if (!gas_interceptor_detected) { + if ((to_push.RIR>>21) == 0x17C) { + if (to_push.RDLR & 0xFF) { + controls_allowed = 0; + } + } + } + + push(&can_rx_q, &to_push); + + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_RX0_IRQHandler() { + //puts("CANRX1"); + //delay(10000); + can_rx(CAN1, 1); +} + +void CAN2_RX0_IRQHandler() { + //puts("CANRX0"); + //delay(10000); + can_rx(CAN2, 0); +} + +void CAN1_SCE_IRQHandler() { + //puts("CAN1_SCE\n"); + can_sce(CAN1); +} + +void CAN2_SCE_IRQHandler() { + //puts("CAN2_SCE\n"); + can_sce(CAN2); +} + +// ***************************** serial port ***************************** + +void USART_IRQHandler(void) { + puts("S"); + + // echo characters + if (USART->SR & USART_SR_RXNE) { + char rcv = USART->DR; + putch(rcv); + + // jump to DFU flash + if (rcv == 'z') { + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + } +} + +void USART2_IRQHandler(void) { + USART_IRQHandler(); +} + +void USART3_IRQHandler(void) { + USART_IRQHandler(); +} + +// ***************************** USB port ***************************** + +int get_health_pkt(void *dat) { + struct { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + } *health = dat; + health->voltage = adc_get(ADCCHAN_VOLTAGE); + health->current = adc_get(ADCCHAN_CURRENT); + health->started = (GPIOC->IDR & (1 << 13)) != 0; + health->controls_allowed = controls_allowed; + health->gas_interceptor_detected = gas_interceptor_detected; + return sizeof(*health); +} + +void set_fan_speed(int fan_speed) { + #ifdef OLD_BOARD + TIM3->CCR4 = fan_speed; + #else + TIM3->CCR3 = fan_speed; + #endif +} + +void usb_cb_ep1_in(int len) { + CAN_FIFOMailBox_TypeDef reply[4]; + + int ilen = 0; + while (ilen < min(len/0x10, 4) && pop(&can_rx_q, &reply[ilen])) ilen++; + + #ifdef DEBUG + puts("FIFO SENDING "); + puth(ilen); + puts("\n"); + #endif + + USB_WritePacket((void *)reply, ilen*0x10, 1); +} + +void usb_cb_ep2_out(uint8_t *usbdata, int len) { +} + +// send on CAN +void usb_cb_ep3_out(uint8_t *usbdata, int len) { + int dpkt = 0; + for (dpkt = 0; dpkt < len; dpkt += 0x10) { + uint32_t *tf = (uint32_t*)(&usbdata[dpkt]); + + int flags = tf[1] >> 4; + CAN_TypeDef *CAN; + can_ring *can_q; + int can_number = 0; + if (flags & 1) { + CAN=CAN1; + can_q = &can_tx1_q; + can_number = 1; + } else { + CAN=CAN2; + can_q = &can_tx2_q; + } + + // add CAN packet to send queue + CAN_FIFOMailBox_TypeDef to_push; + to_push.RDHR = tf[3]; + to_push.RDLR = tf[2]; + to_push.RDTR = tf[1] & 0xF; + to_push.RIR = tf[0]; + push(can_q, &to_push); + + process_can(CAN, can_q, can_number); + } +} + + +void usb_cb_control_msg() { + uint8_t resp[0x20]; + int resp_len; + switch (setup.b.bRequest) { + case 0xd1: + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + break; + case 0xd2: + resp_len = get_health_pkt(resp); + USB_WritePacket(resp, resp_len, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd3: + set_fan_speed(setup.b.wValue.w); + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd6: // GET_VERSION + USB_WritePacket(gitversion, min(sizeof(gitversion), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case 0xd8: // RESET + NVIC_SystemReset(); + break; + default: + puts("NO HANDLER "); + puth(setup.b.bRequest); + puts("\n"); + break; + } +} + + +void OTG_FS_IRQHandler(void) { + NVIC_DisableIRQ(OTG_FS_IRQn); + //__disable_irq(); + usb_irqhandler(); + //__enable_irq(); + NVIC_EnableIRQ(OTG_FS_IRQn); +} + +void OTG_HS_IRQHandler(void) { + //puts("HS_IRQ\n"); + NVIC_DisableIRQ(OTG_FS_IRQn); + //__disable_irq(); + usb_irqhandler(); + //__enable_irq(); + NVIC_EnableIRQ(OTG_FS_IRQn); +} + +void ADC_IRQHandler(void) { + puts("ADC_IRQ\n"); +} + +// ***************************** main code ***************************** + +void __initialize_hardware_early() { + // set USB power + and OTG mode + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + + // enable OTG out tied to ground + GPIOA->ODR = 0; + GPIOA->MODER |= GPIO_MODER_MODER1_0; + + // enable USB power tied to + + GPIOA->ODR |= 1; + GPIOA->MODER |= GPIO_MODER_MODER0_0; + + // enable pull DOWN on OTG_FS_DP + // must be done a while before reading it + GPIOA->PUPDR = GPIO_PUPDR_PUPDR12_1; + + if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { + enter_bootloader_mode = 0; + void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004)); + + // jump to bootloader + bootloader(); + + // LOOP + while(1); + } +} + +int main() { + // init devices + clock_init(); + + // test the USB choice before GPIO init + if (GPIOA->IDR & (1 << 12)) { + USBx = USB_OTG_HS; + } + + gpio_init(); + uart_init(); + usb_init(); + can_init(CAN1); + can_init(CAN2); + adc_init(); + + // timer for fan PWM + #ifdef OLD_BOARD + TIM3->CCMR2 = TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1; + TIM3->CCER = TIM_CCER_CC4E; + #else + TIM3->CCMR2 = TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1; + TIM3->CCER = TIM_CCER_CC3E; + #endif + + // max value of the timer + // 64 makes it above the audible range + //TIM3->ARR = 64; + + // 10 prescale makes it below the audible range + timer_init(TIM3, 10); + + // set PWM + set_fan_speed(65535); + + puts("**** INTERRUPTS ON ****\n"); + __disable_irq(); + NVIC_EnableIRQ(USART2_IRQn); + NVIC_EnableIRQ(USART3_IRQn); + NVIC_EnableIRQ(OTG_FS_IRQn); + NVIC_EnableIRQ(OTG_HS_IRQn); + NVIC_EnableIRQ(ADC_IRQn); + // CAN has so many interrupts! + + NVIC_EnableIRQ(CAN1_TX_IRQn); + NVIC_EnableIRQ(CAN1_RX0_IRQn); + NVIC_EnableIRQ(CAN1_SCE_IRQn); + + NVIC_EnableIRQ(CAN2_TX_IRQn); + NVIC_EnableIRQ(CAN2_RX0_IRQn); + NVIC_EnableIRQ(CAN2_SCE_IRQn); + __enable_irq(); + + + // LED should keep on blinking all the time + while (1) { + #ifdef DEBUG + puts("** blink "); + puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); + puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); + puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); + #endif + + /*puts("voltage: "); puth(adc_get(ADCCHAN_VOLTAGE)); puts(" "); + puts("current: "); puth(adc_get(ADCCHAN_CURRENT)); puts("\n");*/ + + // set LED to be controls allowed + GPIOB->ODR = (GPIOB->ODR | (1 << 11)) & ~(controls_allowed << 11); + + // blink the other LED if in FS mode + if (USBx == USB_OTG_FS) { + GPIOB->ODR |= (1 << 10); + } + delay(1000000); + GPIOB->ODR &= ~(1 << 10); + delay(1000000); + + if (GPIOC->IDR & (1 << 13)) { + // turn on fan at half speed + set_fan_speed(32768); + } else { + // turn off fan + set_fan_speed(0); + } + + } + + return 0; +} + diff --git a/board/startup_stm32f205xx.s b/board/startup_stm32f205xx.s new file mode 100644 index 0000000000..6fb1d22fbb --- /dev/null +++ b/board/startup_stm32f205xx.s @@ -0,0 +1,511 @@ +/** + ****************************************************************************** + * @file startup_stm32f205xx.s + * @author MCD Application Team + * @version V2.0.1 + * @date 25-March-2014 + * @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + bl __initialize_hardware_early + ldr sp, =_estack /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + /* bl SystemInit */ +/* Call static constructors */ + /* bl __libc_init_array */ +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FSMC_IRQHandler /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/board/stm32_flash.ld b/board/stm32_flash.ld new file mode 100644 index 0000000000..3d3c4c4540 --- /dev/null +++ b/board/stm32_flash.ld @@ -0,0 +1,163 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F407VG Device with +** 1024KByte FLASH, 192KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Environment : Atollic TrueSTUDIO(R) +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +** (c)Copyright Atollic AB. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the Atollic TrueSTUDIO(R) toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of 128K RAM on AHB bus*/ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + _exit = .; + } >FLASH + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/board/timer.h b/board/timer.h new file mode 100644 index 0000000000..a14b619e4b --- /dev/null +++ b/board/timer.h @@ -0,0 +1,7 @@ +void timer_init(TIM_TypeDef *TIM, int psc) { + TIM->PSC = psc-1; + TIM->DIER = TIM_DIER_UIE; + TIM->CR1 = TIM_CR1_CEN; + TIM->SR = 0; +} + diff --git a/board/tools/dfu-util-aarch64 b/board/tools/dfu-util-aarch64 new file mode 100755 index 0000000000..250c592ada Binary files /dev/null and b/board/tools/dfu-util-aarch64 differ diff --git a/board/tools/dfu-util-x86_64 b/board/tools/dfu-util-x86_64 new file mode 100755 index 0000000000..7be3dc3a7e Binary files /dev/null and b/board/tools/dfu-util-x86_64 differ diff --git a/board/tools/enter_download_mode.py b/board/tools/enter_download_mode.py new file mode 100755 index 0000000000..2b3d906f6f --- /dev/null +++ b/board/tools/enter_download_mode.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python +import usb1 +import time +import traceback + +if __name__ == "__main__": + context = usb1.USBContext() + + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID()&0xFF00 == 0xdd00: + print "found device" + handle = device.open() + handle.claimInterface(0) + + try: + handle.controlWrite(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd1, 0, 0, '') + except Exception: + traceback.print_exc() + print "expected error, exiting cleanly" + time.sleep(1) diff --git a/board/usb.h b/board/usb.h new file mode 100644 index 0000000000..65799a7936 --- /dev/null +++ b/board/usb.h @@ -0,0 +1,510 @@ +// **** supporting defines **** + +typedef struct +{ + __IO uint32_t HPRT; +} +USB_OTG_HostPortTypeDef; + +#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) +#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) +#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) +#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + (i)*USB_OTG_EP_REG_SIZE)) +#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + (i)*USB_OTG_EP_REG_SIZE)) +#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + (i) * USB_OTG_FIFO_SIZE) +#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) + +#define USB_REQ_GET_STATUS 0x00 +#define USB_REQ_CLEAR_FEATURE 0x01 +#define USB_REQ_SET_FEATURE 0x03 +#define USB_REQ_SET_ADDRESS 0x05 +#define USB_REQ_GET_DESCRIPTOR 0x06 +#define USB_REQ_SET_DESCRIPTOR 0x07 +#define USB_REQ_GET_CONFIGURATION 0x08 +#define USB_REQ_SET_CONFIGURATION 0x09 +#define USB_REQ_GET_INTERFACE 0x0A +#define USB_REQ_SET_INTERFACE 0x0B +#define USB_REQ_SYNCH_FRAME 0x0C + +#define USB_DESC_TYPE_DEVICE 1 +#define USB_DESC_TYPE_CONFIGURATION 2 +#define USB_DESC_TYPE_STRING 3 +#define USB_DESC_TYPE_INTERFACE 4 +#define USB_DESC_TYPE_ENDPOINT 5 +#define USB_DESC_TYPE_DEVICE_QUALIFIER 6 +#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7 + +#define STS_GOUT_NAK 1 +#define STS_DATA_UPDT 2 +#define STS_XFER_COMP 3 +#define STS_SETUP_COMP 4 +#define STS_SETUP_UPDT 6 + +#define USBD_FS_TRDT_VALUE 5 + +// interfaces +void usb_cb_control_msg(); +void usb_cb_ep1_in(int len); +void usb_cb_ep2_out(uint8_t *usbdata, int len); +void usb_cb_ep3_out(uint8_t *usbdata, int len); + +uint8_t device_desc[] = { + 0x12,0x01,0x00,0x01, + 0xFF,0xFF,0xFF,0x40, + (USB_VID>>0)&0xFF,(USB_VID>>8)&0xFF, + (USB_PID>>0)&0xFF,(USB_PID>>8)&0xFF, + 0x00,0x22,0x00,0x00, + 0x00,0x01}; + +uint8_t configuration_desc[] = { + 0x09, 0x02, 0x27, 0x00, + 0x01, 0x01, 0x00, 0xc0, + 0x32, + // interface 0 + 0x09, 0x04, 0x00, 0x00, + 0x03, 0xff, 0xFF, 0xFF, + 0x00, + // endpoint 1, read CAN + 0x07, 0x05, 0x81, 0x02, 0x40, 0x00, 0x00, + // endpoint 2, AES load + 0x07, 0x05, 0x02, 0x02, 0x10, 0x00, 0x00, + // endpoint 3, send CAN + 0x07, 0x05, 0x03, 0x02, 0x40, 0x00, 0x00, +}; + +typedef union +{ + uint16_t w; + struct BW + { + uint8_t msb; + uint8_t lsb; + } + bw; +} +uint16_t_uint8_t; + + +typedef union _USB_Setup +{ + uint32_t d8[2]; + + struct _SetupPkt_Struc + { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t_uint8_t wValue; + uint16_t_uint8_t wIndex; + uint16_t_uint8_t wLength; + } b; +} +USB_Setup_TypeDef; + +// current packet +USB_Setup_TypeDef setup; +uint8_t usbdata[0x100]; + +// packet read and write + +void *USB_ReadPacket(void *dest, uint16_t len) { + uint32_t i=0; + uint32_t count32b = (len + 3) / 4; + + for ( i = 0; i < count32b; i++, dest += 4 ) { + // packed? + *(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0); + } + return ((void *)dest); +} + +void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) { + #ifdef DEBUG + puts("writing "); + hexdump(src, len); + #endif + uint32_t count32b = 0, i = 0; + count32b = (len + 3) / 4; + + // bullshit + USBx_INEP(ep)->DIEPTSIZ = (USB_OTG_DIEPTSIZ_PKTCNT & (1 << 19)) | (len & USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + // load the FIFO + for (i = 0; i < count32b; i++, src += 4) { + USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src); + } +} + +void usb_reset() { + // unmask endpoint interrupts, so many sets + USBx_DEVICE->DAINT = 0xFFFFFFFF; + USBx_DEVICE->DAINTMSK = 0xFFFFFFFF; + //USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM); + + // all interrupts for debugging + USBx_DEVICE->DIEPMSK = 0xFFFFFFFF; + USBx_DEVICE->DOEPMSK = 0xFFFFFFFF; + + // clear interrupts + USBx_INEP(0)->DIEPINT = 0xFF; + USBx_OUTEP(0)->DOEPINT = 0xFF; + + // unset the address + USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; + + // set up USB FIFOs + // RX start address is fixed to 0 + USBx->GRXFSIZ = 0x40; + + // 0x100 to offset past GRXFSIZ + USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40; + + // EP1, massive + USBx->DIEPTXF[0] = (0x40 << 16) | 0x80; + + // flush TX fifo + USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + // flush RX FIFO + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + // no global NAK + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; + + // ready to receive setup packets + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8); +} + +void usb_setup() { + uint8_t resp[0x20]; + // setup packet is ready + switch (setup.b.bRequest) { + case USB_REQ_SET_CONFIGURATION: + // enable other endpoints, has to be here? + USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP; + USBx_INEP(1)->DIEPINT = 0xFF; + + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x10; + USBx_OUTEP(2)->DOEPCTL = (0x10 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(2)->DOEPINT = 0xFF; + + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(3)->DOEPINT = 0xFF; + + // mark ready to receive + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_REQ_SET_ADDRESS: + // set now? + USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4); + + #ifdef DEBUG + puts(" set address\n"); + #endif + + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + break; + case USB_REQ_GET_DESCRIPTOR: + switch (setup.b.wValue.bw.lsb) { + case USB_DESC_TYPE_DEVICE: + //puts(" writing device descriptor\n"); + + // setup transfer + USB_WritePacket(device_desc, min(sizeof(device_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + //puts("D"); + break; + case USB_DESC_TYPE_CONFIGURATION: + USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + // nothing here? + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + } + break; + case USB_REQ_GET_STATUS: + // empty resp? + resp[0] = 0; + resp[1] = 0; + USB_WritePacket((void*)&resp, 2, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + usb_cb_control_msg(); + } +} + +void usb_init() { + // internal PHY set before reset + USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + + // full speed PHY, do reset and remove power down + puth(USBx->GRSTCTL); + puts(" resetting PHY\n"); + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); + puts("AHB idle\n"); + + // reset PHY here? + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + puts("reset done\n"); + + // power up the PHY + USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS; + + // be a device, slowest timings + //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL; + USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); + //USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + + // **** for debugging, doesn't seem to work **** + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT; + + // reset PHY clock + USBx_PCGCCTL = 0; + + // enable the fancy OTG things + USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP; + + USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD; + //USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD; + + // setup USB interrupts + // all interrupts except TXFIFO EMPTY + //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); + USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM); + + USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT; + USBx->GINTSTS = 0; +} + +// ***************************** USB port ***************************** + +void usb_irqhandler(void) { + USBx->GINTMSK = 0; + + unsigned int gintsts = USBx->GINTSTS; + + // gintsts SUSPEND? 04008428 + #ifdef DEBUG + unsigned int daint = USBx_DEVICE->DAINT; + puth(gintsts); + puts(" ep "); + puth(daint); + puts(" USB interrupt!\n"); + #endif + + if (gintsts & USB_OTG_GINTSTS_ESUSP) { + puts("ESUSP detected\n"); + } + + if (gintsts & USB_OTG_GINTSTS_USBRST) { + puts("USB reset\n"); + usb_reset(); + } + + if (gintsts & USB_OTG_GINTSTS_ENUMDNE) { + puts("enumeration done "); + // Full speed, ENUMSPD + puth(USBx_DEVICE->DSTS); + puts("\n"); + } + + if (gintsts & USB_OTG_GINTSTS_OTGINT) { + puts("OTG int:"); + puth(USBx->GOTGINT); + puts("\n"); + + // getting ADTOCHG + USBx->GOTGINT = USBx->GOTGINT; + } + + // RX FIFO first + if (gintsts & USB_OTG_GINTSTS_RXFLVL) { + // 1. Read the Receive status pop register + volatile unsigned int rxst = USBx->GRXSTSP; + + #ifdef DEBUG + puts(" RX FIFO:"); + puth(rxst); + puts(" status: "); + puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17); + puts(" len: "); + puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4); + puts("\n"); + #endif + + + if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) { + int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM); + int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4; + USB_ReadPacket(&usbdata, len); + #ifdef DEBUG + puts(" data "); + puth(len); + puts("\n"); + hexdump(&usbdata, len); + #endif + + if (endpoint == 2) { + usb_cb_ep2_out(usbdata, len); + } + + if (endpoint == 3) { + usb_cb_ep3_out(usbdata, len); + } + } else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) { + USB_ReadPacket(&setup, 8); + #ifdef DEBUG + puts(" setup "); + hexdump(&setup, 8); + puts("\n"); + #endif + } + } + + if (gintsts & USB_OTG_GINTSTS_HPRTINT) { + // host + puts("HPRT:"); + puth(USBx_HOST_PORT->HPRT); + puts("\n"); + if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) { + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST; + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET; + } + + } + + if (gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) { + // no global NAK, why is this getting set? + #ifdef DEBUG + puts("GLOBAL NAK\n"); + #endif + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK; + } + + if (gintsts & USB_OTG_GINTSTS_SRQINT) { + // we want to do "A-device host negotiation protocol" since we are the A-device + puts("start request\n"); + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + //USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA; + } + + // out endpoint hit + if (gintsts & USB_OTG_GINTSTS_OEPINT) { + #ifdef DEBUG + puts(" 0:"); + puth(USBx_OUTEP(0)->DOEPINT); + puts(" 2:"); + puth(USBx_OUTEP(2)->DOEPINT); + puts(" 3:"); + puth(USBx_OUTEP(3)->DOEPINT); + puts(" "); + puth(USBx_OUTEP(3)->DOEPCTL); + puts(" 4:"); + puth(USBx_OUTEP(4)->DOEPINT); + puts(" OUT ENDPOINT\n"); + #endif + + if (USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG + puts(" OUT2 PACKET XFRC\n"); + #endif + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x10; + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } + + if (USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG + puts(" OUT3 PACKET XFRC\n"); + #endif + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT & 0x2000) { + #ifdef DEBUG + puts(" OUT3 PACKET WTF\n"); + #endif + // if NAK was set trigger this, unknown interrupt + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT) { + puts("OUTEP3 error "); + puth(USBx_OUTEP(3)->DOEPINT); + puts("\n"); + } + + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) { + // ready for next packet + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8); + } + + // respond to setup packets + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) { + usb_setup(); + } + + USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT; + USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT; + USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT; + } + + + // in endpoint hit + if (gintsts & USB_OTG_GINTSTS_IEPINT) { + #ifdef DEBUG + puts(" "); + puth(USBx_INEP(0)->DIEPINT); + puts(" "); + puth(USBx_INEP(1)->DIEPINT); + puts(" IN ENDPOINT\n"); + #endif + + // this happens first + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPINT_XFRC) { + #ifdef DEBUG + puts(" IN PACKET SEND\n"); + #endif + //USBx_DEVICE->DIEPEMPMSK = ~(1 << 1); + } + + // *** IN token received when TxFIFO is empty + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG + puts(" IN PACKET QUEUE\n"); + #endif + // TODO: always assuming max len, can we get the length? + usb_cb_ep1_in(0x40); + } + + // clear interrupts + USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; + USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT; + } + + + // clear all interrupts + USBx_DEVICE->DAINT = USBx_DEVICE->DAINT; + USBx->GINTSTS = USBx->GINTSTS; + + USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); +} + diff --git a/cereal/__init__.py b/cereal/__init__.py new file mode 100644 index 0000000000..b083b67399 --- /dev/null +++ b/cereal/__init__.py @@ -0,0 +1,7 @@ +import os +import capnp +capnp.remove_import_hook() + +CEREAL_PATH = os.path.dirname(os.path.abspath(__file__)) +log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) + diff --git a/cereal/c++.capnp b/cereal/c++.capnp new file mode 100644 index 0000000000..2bda547179 --- /dev/null +++ b/cereal/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/cereal/gen/c/c++.capnp.h b/cereal/gen/c/c++.capnp.h new file mode 100644 index 0000000000..e69de29bb2 diff --git a/cereal/gen/c/log.capnp.c b/cereal/gen/c/log.capnp.c new file mode 100644 index 0000000000..b7b8692ff4 --- /dev/null +++ b/cereal/gen/c/log.capnp.c @@ -0,0 +1,1016 @@ +#include "log.capnp.h" +/* AUTO GENERATED - DO NOT EDIT */ +static const capn_text capn_val0 = {0,""}; +int32_t cereal_logVersion = 1; + +cereal_InitData_ptr cereal_new_InitData(struct capn_segment *s) { + cereal_InitData_ptr p; + p.p = capn_new_struct(s, 0, 3); + return p; +} +cereal_InitData_list cereal_new_InitData_list(struct capn_segment *s, int len) { + cereal_InitData_list p; + p.p = capn_new_list(s, len, 0, 3); + return p; +} +void cereal_read_InitData(struct cereal_InitData *s, cereal_InitData_ptr p) { + capn_resolve(&p.p); + s->kernelArgs = capn_getp(p.p, 0, 0); + s->gctx = capn_get_text(p.p, 1, capn_val0); + s->dongleId = capn_get_text(p.p, 2, capn_val0); +} +void cereal_write_InitData(const struct cereal_InitData *s, cereal_InitData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->kernelArgs); + capn_set_text(p.p, 1, s->gctx); + capn_set_text(p.p, 2, s->dongleId); +} +void cereal_get_InitData(struct cereal_InitData *s, cereal_InitData_list l, int i) { + cereal_InitData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_InitData(s, p); +} +void cereal_set_InitData(const struct cereal_InitData *s, cereal_InitData_list l, int i) { + cereal_InitData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_InitData(s, p); +} + +cereal_FrameData_ptr cereal_new_FrameData(struct capn_segment *s) { + cereal_FrameData_ptr p; + p.p = capn_new_struct(s, 32, 1); + return p; +} +cereal_FrameData_list cereal_new_FrameData_list(struct capn_segment *s, int len) { + cereal_FrameData_list p; + p.p = capn_new_list(s, len, 32, 1); + return p; +} +void cereal_read_FrameData(struct cereal_FrameData *s, cereal_FrameData_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->encodeId = capn_read32(p.p, 4); + s->timestampEof = capn_read64(p.p, 8); + s->frameLength = (int32_t) ((int32_t)capn_read32(p.p, 16)); + s->integLines = (int32_t) ((int32_t)capn_read32(p.p, 20)); + s->globalGain = (int32_t) ((int32_t)capn_read32(p.p, 24)); + s->image = capn_get_data(p.p, 0); +} +void cereal_write_FrameData(const struct cereal_FrameData *s, cereal_FrameData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_write32(p.p, 4, s->encodeId); + capn_write64(p.p, 8, s->timestampEof); + capn_write32(p.p, 16, (uint32_t) (s->frameLength)); + capn_write32(p.p, 20, (uint32_t) (s->integLines)); + capn_write32(p.p, 24, (uint32_t) (s->globalGain)); + capn_setp(p.p, 0, s->image.p); +} +void cereal_get_FrameData(struct cereal_FrameData *s, cereal_FrameData_list l, int i) { + cereal_FrameData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_FrameData(s, p); +} +void cereal_set_FrameData(const struct cereal_FrameData *s, cereal_FrameData_list l, int i) { + cereal_FrameData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_FrameData(s, p); +} + +cereal_GPSNMEAData_ptr cereal_new_GPSNMEAData(struct capn_segment *s) { + cereal_GPSNMEAData_ptr p; + p.p = capn_new_struct(s, 16, 1); + return p; +} +cereal_GPSNMEAData_list cereal_new_GPSNMEAData_list(struct capn_segment *s, int len) { + cereal_GPSNMEAData_list p; + p.p = capn_new_list(s, len, 16, 1); + return p; +} +void cereal_read_GPSNMEAData(struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_ptr p) { + capn_resolve(&p.p); + s->timestamp = (int64_t) ((int64_t)(capn_read64(p.p, 0))); + s->localWallTime = capn_read64(p.p, 8); + s->nmea = capn_get_text(p.p, 0, capn_val0); +} +void cereal_write_GPSNMEAData(const struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 0, (uint64_t) (s->timestamp)); + capn_write64(p.p, 8, s->localWallTime); + capn_set_text(p.p, 0, s->nmea); +} +void cereal_get_GPSNMEAData(struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_list l, int i) { + cereal_GPSNMEAData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_GPSNMEAData(s, p); +} +void cereal_set_GPSNMEAData(const struct cereal_GPSNMEAData *s, cereal_GPSNMEAData_list l, int i) { + cereal_GPSNMEAData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_GPSNMEAData(s, p); +} + +cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment *s) { + cereal_SensorEventData_ptr p; + p.p = capn_new_struct(s, 24, 1); + return p; +} +cereal_SensorEventData_list cereal_new_SensorEventData_list(struct capn_segment *s, int len) { + cereal_SensorEventData_list p; + p.p = capn_new_list(s, len, 24, 1); + return p; +} +void cereal_read_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_ptr p) { + capn_resolve(&p.p); + s->version = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->sensor = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->type = (int32_t) ((int32_t)capn_read32(p.p, 8)); + s->timestamp = (int64_t) ((int64_t)(capn_read64(p.p, 16))); + s->which = (enum cereal_SensorEventData_which)(int) capn_read16(p.p, 12); + switch (s->which) { + case cereal_SensorEventData_acceleration: + case cereal_SensorEventData_magnetic: + case cereal_SensorEventData_orientation: + case cereal_SensorEventData_gyro: + s->gyro.p = capn_getp(p.p, 0, 0); + break; + default: + break; + } +} +void cereal_write_SensorEventData(const struct cereal_SensorEventData *s, cereal_SensorEventData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->version)); + capn_write32(p.p, 4, (uint32_t) (s->sensor)); + capn_write32(p.p, 8, (uint32_t) (s->type)); + capn_write64(p.p, 16, (uint64_t) (s->timestamp)); + capn_write16(p.p, 12, s->which); + switch (s->which) { + case cereal_SensorEventData_acceleration: + case cereal_SensorEventData_magnetic: + case cereal_SensorEventData_orientation: + case cereal_SensorEventData_gyro: + capn_setp(p.p, 0, s->gyro.p); + break; + default: + break; + } +} +void cereal_get_SensorEventData(struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) { + cereal_SensorEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_SensorEventData(s, p); +} +void cereal_set_SensorEventData(const struct cereal_SensorEventData *s, cereal_SensorEventData_list l, int i) { + cereal_SensorEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_SensorEventData(s, p); +} + +cereal_SensorEventData_SensorVec_ptr cereal_new_SensorEventData_SensorVec(struct capn_segment *s) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_SensorEventData_SensorVec_list cereal_new_SensorEventData_SensorVec_list(struct capn_segment *s, int len) { + cereal_SensorEventData_SensorVec_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_ptr p) { + capn_resolve(&p.p); + s->v.p = capn_getp(p.p, 0, 0); + s->status = (int8_t) ((int8_t)capn_read8(p.p, 0)); +} +void cereal_write_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->v.p); + capn_write8(p.p, 0, (uint8_t) (s->status)); +} +void cereal_get_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_list l, int i) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_SensorEventData_SensorVec(s, p); +} +void cereal_set_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec *s, cereal_SensorEventData_SensorVec_list l, int i) { + cereal_SensorEventData_SensorVec_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_SensorEventData_SensorVec(s, p); +} + +cereal_CanData_ptr cereal_new_CanData(struct capn_segment *s) { + cereal_CanData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_CanData_list cereal_new_CanData_list(struct capn_segment *s, int len) { + cereal_CanData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_CanData(struct cereal_CanData *s, cereal_CanData_ptr p) { + capn_resolve(&p.p); + s->address = capn_read32(p.p, 0); + s->busTime = capn_read16(p.p, 4); + s->dat = capn_get_data(p.p, 0); + s->src = (int8_t) ((int8_t)capn_read8(p.p, 6)); +} +void cereal_write_CanData(const struct cereal_CanData *s, cereal_CanData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->address); + capn_write16(p.p, 4, s->busTime); + capn_setp(p.p, 0, s->dat.p); + capn_write8(p.p, 6, (uint8_t) (s->src)); +} +void cereal_get_CanData(struct cereal_CanData *s, cereal_CanData_list l, int i) { + cereal_CanData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_CanData(s, p); +} +void cereal_set_CanData(const struct cereal_CanData *s, cereal_CanData_list l, int i) { + cereal_CanData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_CanData(s, p); +} + +cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment *s) { + cereal_ThermalData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment *s, int len) { + cereal_ThermalData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { + capn_resolve(&p.p); + s->cpu0 = capn_read16(p.p, 0); + s->cpu1 = capn_read16(p.p, 2); + s->cpu2 = capn_read16(p.p, 4); + s->cpu3 = capn_read16(p.p, 6); + s->mem = capn_read16(p.p, 8); + s->gpu = capn_read16(p.p, 10); + s->bat = capn_read32(p.p, 12); +} +void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { + capn_resolve(&p.p); + capn_write16(p.p, 0, s->cpu0); + capn_write16(p.p, 2, s->cpu1); + capn_write16(p.p, 4, s->cpu2); + capn_write16(p.p, 6, s->cpu3); + capn_write16(p.p, 8, s->mem); + capn_write16(p.p, 10, s->gpu); + capn_write32(p.p, 12, s->bat); +} +void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { + cereal_ThermalData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ThermalData(s, p); +} +void cereal_set_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { + cereal_ThermalData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ThermalData(s, p); +} + +cereal_HealthData_ptr cereal_new_HealthData(struct capn_segment *s) { + cereal_HealthData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_HealthData_list cereal_new_HealthData_list(struct capn_segment *s, int len) { + cereal_HealthData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_HealthData(struct cereal_HealthData *s, cereal_HealthData_ptr p) { + capn_resolve(&p.p); + s->voltage = capn_read32(p.p, 0); + s->current = capn_read32(p.p, 4); + s->started = (capn_read8(p.p, 8) & 1) != 0; + s->controlsAllowed = (capn_read8(p.p, 8) & 2) != 0; + s->gasInterceptorDetected = (capn_read8(p.p, 8) & 4) != 0; +} +void cereal_write_HealthData(const struct cereal_HealthData *s, cereal_HealthData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->voltage); + capn_write32(p.p, 4, s->current); + capn_write1(p.p, 64, s->started != 0); + capn_write1(p.p, 65, s->controlsAllowed != 0); + capn_write1(p.p, 66, s->gasInterceptorDetected != 0); +} +void cereal_get_HealthData(struct cereal_HealthData *s, cereal_HealthData_list l, int i) { + cereal_HealthData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_HealthData(s, p); +} +void cereal_set_HealthData(const struct cereal_HealthData *s, cereal_HealthData_list l, int i) { + cereal_HealthData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_HealthData(s, p); +} + +cereal_LiveUI_ptr cereal_new_LiveUI(struct capn_segment *s) { + cereal_LiveUI_ptr p; + p.p = capn_new_struct(s, 8, 2); + return p; +} +cereal_LiveUI_list cereal_new_LiveUI_list(struct capn_segment *s, int len) { + cereal_LiveUI_list p; + p.p = capn_new_list(s, len, 8, 2); + return p; +} +void cereal_read_LiveUI(struct cereal_LiveUI *s, cereal_LiveUI_ptr p) { + capn_resolve(&p.p); + s->rearViewCam = (capn_read8(p.p, 0) & 1) != 0; + s->alertText1 = capn_get_text(p.p, 0, capn_val0); + s->alertText2 = capn_get_text(p.p, 1, capn_val0); + s->awarenessStatus = capn_to_f32(capn_read32(p.p, 4)); +} +void cereal_write_LiveUI(const struct cereal_LiveUI *s, cereal_LiveUI_ptr p) { + capn_resolve(&p.p); + capn_write1(p.p, 0, s->rearViewCam != 0); + capn_set_text(p.p, 0, s->alertText1); + capn_set_text(p.p, 1, s->alertText2); + capn_write32(p.p, 4, capn_from_f32(s->awarenessStatus)); +} +void cereal_get_LiveUI(struct cereal_LiveUI *s, cereal_LiveUI_list l, int i) { + cereal_LiveUI_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveUI(s, p); +} +void cereal_set_LiveUI(const struct cereal_LiveUI *s, cereal_LiveUI_list l, int i) { + cereal_LiveUI_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveUI(s, p); +} + +cereal_Live20Data_ptr cereal_new_Live20Data(struct capn_segment *s) { + cereal_Live20Data_ptr p; + p.p = capn_new_struct(s, 32, 4); + return p; +} +cereal_Live20Data_list cereal_new_Live20Data_list(struct capn_segment *s, int len) { + cereal_Live20Data_list p; + p.p = capn_new_list(s, len, 32, 4); + return p; +} +void cereal_read_Live20Data(struct cereal_Live20Data *s, cereal_Live20Data_ptr p) { + capn_resolve(&p.p); + s->canMonoTimes.p = capn_getp(p.p, 3, 0); + s->mdMonoTime = capn_read64(p.p, 16); + s->ftMonoTime = capn_read64(p.p, 24); + s->warpMatrix.p = capn_getp(p.p, 0, 0); + s->angleOffset = capn_to_f32(capn_read32(p.p, 0)); + s->calStatus = (int8_t) ((int8_t)capn_read8(p.p, 4)); + s->calCycle = (int32_t) ((int32_t)capn_read32(p.p, 12)); + s->calPerc = (int8_t) ((int8_t)capn_read8(p.p, 5)); + s->leadOne.p = capn_getp(p.p, 1, 0); + s->leadTwo.p = capn_getp(p.p, 2, 0); + s->cumLagMs = capn_to_f32(capn_read32(p.p, 8)); +} +void cereal_write_Live20Data(const struct cereal_Live20Data *s, cereal_Live20Data_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 3, s->canMonoTimes.p); + capn_write64(p.p, 16, s->mdMonoTime); + capn_write64(p.p, 24, s->ftMonoTime); + capn_setp(p.p, 0, s->warpMatrix.p); + capn_write32(p.p, 0, capn_from_f32(s->angleOffset)); + capn_write8(p.p, 4, (uint8_t) (s->calStatus)); + capn_write32(p.p, 12, (uint32_t) (s->calCycle)); + capn_write8(p.p, 5, (uint8_t) (s->calPerc)); + capn_setp(p.p, 1, s->leadOne.p); + capn_setp(p.p, 2, s->leadTwo.p); + capn_write32(p.p, 8, capn_from_f32(s->cumLagMs)); +} +void cereal_get_Live20Data(struct cereal_Live20Data *s, cereal_Live20Data_list l, int i) { + cereal_Live20Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live20Data(s, p); +} +void cereal_set_Live20Data(const struct cereal_Live20Data *s, cereal_Live20Data_list l, int i) { + cereal_Live20Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live20Data(s, p); +} + +cereal_Live20Data_LeadData_ptr cereal_new_Live20Data_LeadData(struct capn_segment *s) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_new_struct(s, 48, 0); + return p; +} +cereal_Live20Data_LeadData_list cereal_new_Live20Data_LeadData_list(struct capn_segment *s, int len) { + cereal_Live20Data_LeadData_list p; + p.p = capn_new_list(s, len, 48, 0); + return p; +} +void cereal_read_Live20Data_LeadData(struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_ptr p) { + capn_resolve(&p.p); + s->dRel = capn_to_f32(capn_read32(p.p, 0)); + s->yRel = capn_to_f32(capn_read32(p.p, 4)); + s->vRel = capn_to_f32(capn_read32(p.p, 8)); + s->aRel = capn_to_f32(capn_read32(p.p, 12)); + s->vLead = capn_to_f32(capn_read32(p.p, 16)); + s->aLead = capn_to_f32(capn_read32(p.p, 20)); + s->dPath = capn_to_f32(capn_read32(p.p, 24)); + s->vLat = capn_to_f32(capn_read32(p.p, 28)); + s->vLeadK = capn_to_f32(capn_read32(p.p, 32)); + s->aLeadK = capn_to_f32(capn_read32(p.p, 36)); + s->fcw = (capn_read8(p.p, 40) & 1) != 0; + s->status = (capn_read8(p.p, 40) & 2) != 0; +} +void cereal_write_Live20Data_LeadData(const struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, capn_from_f32(s->dRel)); + capn_write32(p.p, 4, capn_from_f32(s->yRel)); + capn_write32(p.p, 8, capn_from_f32(s->vRel)); + capn_write32(p.p, 12, capn_from_f32(s->aRel)); + capn_write32(p.p, 16, capn_from_f32(s->vLead)); + capn_write32(p.p, 20, capn_from_f32(s->aLead)); + capn_write32(p.p, 24, capn_from_f32(s->dPath)); + capn_write32(p.p, 28, capn_from_f32(s->vLat)); + capn_write32(p.p, 32, capn_from_f32(s->vLeadK)); + capn_write32(p.p, 36, capn_from_f32(s->aLeadK)); + capn_write1(p.p, 320, s->fcw != 0); + capn_write1(p.p, 321, s->status != 0); +} +void cereal_get_Live20Data_LeadData(struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_list l, int i) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live20Data_LeadData(s, p); +} +void cereal_set_Live20Data_LeadData(const struct cereal_Live20Data_LeadData *s, cereal_Live20Data_LeadData_list l, int i) { + cereal_Live20Data_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live20Data_LeadData(s, p); +} + +cereal_LiveCalibrationData_ptr cereal_new_LiveCalibrationData(struct capn_segment *s) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LiveCalibrationData_list cereal_new_LiveCalibrationData_list(struct capn_segment *s, int len) { + cereal_LiveCalibrationData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LiveCalibrationData(struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_ptr p) { + capn_resolve(&p.p); + s->warpMatrix.p = capn_getp(p.p, 0, 0); + s->calStatus = (int8_t) ((int8_t)capn_read8(p.p, 0)); + s->calCycle = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->calPerc = (int8_t) ((int8_t)capn_read8(p.p, 1)); +} +void cereal_write_LiveCalibrationData(const struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->warpMatrix.p); + capn_write8(p.p, 0, (uint8_t) (s->calStatus)); + capn_write32(p.p, 4, (uint32_t) (s->calCycle)); + capn_write8(p.p, 1, (uint8_t) (s->calPerc)); +} +void cereal_get_LiveCalibrationData(struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_list l, int i) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveCalibrationData(s, p); +} +void cereal_set_LiveCalibrationData(const struct cereal_LiveCalibrationData *s, cereal_LiveCalibrationData_list l, int i) { + cereal_LiveCalibrationData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveCalibrationData(s, p); +} + +cereal_LiveTracks_ptr cereal_new_LiveTracks(struct capn_segment *s) { + cereal_LiveTracks_ptr p; + p.p = capn_new_struct(s, 40, 0); + return p; +} +cereal_LiveTracks_list cereal_new_LiveTracks_list(struct capn_segment *s, int len) { + cereal_LiveTracks_list p; + p.p = capn_new_list(s, len, 40, 0); + return p; +} +void cereal_read_LiveTracks(struct cereal_LiveTracks *s, cereal_LiveTracks_ptr p) { + capn_resolve(&p.p); + s->trackId = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->dRel = capn_to_f32(capn_read32(p.p, 4)); + s->yRel = capn_to_f32(capn_read32(p.p, 8)); + s->vRel = capn_to_f32(capn_read32(p.p, 12)); + s->aRel = capn_to_f32(capn_read32(p.p, 16)); + s->timeStamp = capn_to_f32(capn_read32(p.p, 20)); + s->status = capn_to_f32(capn_read32(p.p, 24)); + s->currentTime = capn_to_f32(capn_read32(p.p, 28)); + s->stationary = (capn_read8(p.p, 32) & 1) != 0; + s->oncoming = (capn_read8(p.p, 32) & 2) != 0; +} +void cereal_write_LiveTracks(const struct cereal_LiveTracks *s, cereal_LiveTracks_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->trackId)); + capn_write32(p.p, 4, capn_from_f32(s->dRel)); + capn_write32(p.p, 8, capn_from_f32(s->yRel)); + capn_write32(p.p, 12, capn_from_f32(s->vRel)); + capn_write32(p.p, 16, capn_from_f32(s->aRel)); + capn_write32(p.p, 20, capn_from_f32(s->timeStamp)); + capn_write32(p.p, 24, capn_from_f32(s->status)); + capn_write32(p.p, 28, capn_from_f32(s->currentTime)); + capn_write1(p.p, 256, s->stationary != 0); + capn_write1(p.p, 257, s->oncoming != 0); +} +void cereal_get_LiveTracks(struct cereal_LiveTracks *s, cereal_LiveTracks_list l, int i) { + cereal_LiveTracks_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveTracks(s, p); +} +void cereal_set_LiveTracks(const struct cereal_LiveTracks *s, cereal_LiveTracks_list l, int i) { + cereal_LiveTracks_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveTracks(s, p); +} + +cereal_Live100Data_ptr cereal_new_Live100Data(struct capn_segment *s) { + cereal_Live100Data_ptr p; + p.p = capn_new_struct(s, 104, 3); + return p; +} +cereal_Live100Data_list cereal_new_Live100Data_list(struct capn_segment *s, int len) { + cereal_Live100Data_list p; + p.p = capn_new_list(s, len, 104, 3); + return p; +} +void cereal_read_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_ptr p) { + capn_resolve(&p.p); + s->canMonoTime = capn_read64(p.p, 64); + s->canMonoTimes.p = capn_getp(p.p, 0, 0); + s->l20MonoTime = capn_read64(p.p, 72); + s->mdMonoTime = capn_read64(p.p, 80); + s->vEgo = capn_to_f32(capn_read32(p.p, 0)); + s->aEgo = capn_to_f32(capn_read32(p.p, 4)); + s->vPid = capn_to_f32(capn_read32(p.p, 8)); + s->vTargetLead = capn_to_f32(capn_read32(p.p, 12)); + s->upAccelCmd = capn_to_f32(capn_read32(p.p, 16)); + s->uiAccelCmd = capn_to_f32(capn_read32(p.p, 20)); + s->yActual = capn_to_f32(capn_read32(p.p, 24)); + s->yDes = capn_to_f32(capn_read32(p.p, 28)); + s->upSteer = capn_to_f32(capn_read32(p.p, 32)); + s->uiSteer = capn_to_f32(capn_read32(p.p, 36)); + s->aTargetMin = capn_to_f32(capn_read32(p.p, 40)); + s->aTargetMax = capn_to_f32(capn_read32(p.p, 44)); + s->jerkFactor = capn_to_f32(capn_read32(p.p, 48)); + s->angleSteers = capn_to_f32(capn_read32(p.p, 52)); + s->hudLead = (int32_t) ((int32_t)capn_read32(p.p, 56)); + s->cumLagMs = capn_to_f32(capn_read32(p.p, 60)); + s->enabled = (capn_read8(p.p, 88) & 1) != 0; + s->steerOverride = (capn_read8(p.p, 88) & 2) != 0; + s->vCruise = capn_to_f32(capn_read32(p.p, 92)); + s->rearViewCam = (capn_read8(p.p, 88) & 4) != 0; + s->alertText1 = capn_get_text(p.p, 1, capn_val0); + s->alertText2 = capn_get_text(p.p, 2, capn_val0); + s->awarenessStatus = capn_to_f32(capn_read32(p.p, 96)); +} +void cereal_write_Live100Data(const struct cereal_Live100Data *s, cereal_Live100Data_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 64, s->canMonoTime); + capn_setp(p.p, 0, s->canMonoTimes.p); + capn_write64(p.p, 72, s->l20MonoTime); + capn_write64(p.p, 80, s->mdMonoTime); + capn_write32(p.p, 0, capn_from_f32(s->vEgo)); + capn_write32(p.p, 4, capn_from_f32(s->aEgo)); + capn_write32(p.p, 8, capn_from_f32(s->vPid)); + capn_write32(p.p, 12, capn_from_f32(s->vTargetLead)); + capn_write32(p.p, 16, capn_from_f32(s->upAccelCmd)); + capn_write32(p.p, 20, capn_from_f32(s->uiAccelCmd)); + capn_write32(p.p, 24, capn_from_f32(s->yActual)); + capn_write32(p.p, 28, capn_from_f32(s->yDes)); + capn_write32(p.p, 32, capn_from_f32(s->upSteer)); + capn_write32(p.p, 36, capn_from_f32(s->uiSteer)); + capn_write32(p.p, 40, capn_from_f32(s->aTargetMin)); + capn_write32(p.p, 44, capn_from_f32(s->aTargetMax)); + capn_write32(p.p, 48, capn_from_f32(s->jerkFactor)); + capn_write32(p.p, 52, capn_from_f32(s->angleSteers)); + capn_write32(p.p, 56, (uint32_t) (s->hudLead)); + capn_write32(p.p, 60, capn_from_f32(s->cumLagMs)); + capn_write1(p.p, 704, s->enabled != 0); + capn_write1(p.p, 705, s->steerOverride != 0); + capn_write32(p.p, 92, capn_from_f32(s->vCruise)); + capn_write1(p.p, 706, s->rearViewCam != 0); + capn_set_text(p.p, 1, s->alertText1); + capn_set_text(p.p, 2, s->alertText2); + capn_write32(p.p, 96, capn_from_f32(s->awarenessStatus)); +} +void cereal_get_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_list l, int i) { + cereal_Live100Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Live100Data(s, p); +} +void cereal_set_Live100Data(const struct cereal_Live100Data *s, cereal_Live100Data_list l, int i) { + cereal_Live100Data_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Live100Data(s, p); +} + +cereal_LiveEventData_ptr cereal_new_LiveEventData(struct capn_segment *s) { + cereal_LiveEventData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LiveEventData_list cereal_new_LiveEventData_list(struct capn_segment *s, int len) { + cereal_LiveEventData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LiveEventData(struct cereal_LiveEventData *s, cereal_LiveEventData_ptr p) { + capn_resolve(&p.p); + s->name = capn_get_text(p.p, 0, capn_val0); + s->value = (int32_t) ((int32_t)capn_read32(p.p, 0)); +} +void cereal_write_LiveEventData(const struct cereal_LiveEventData *s, cereal_LiveEventData_ptr p) { + capn_resolve(&p.p); + capn_set_text(p.p, 0, s->name); + capn_write32(p.p, 0, (uint32_t) (s->value)); +} +void cereal_get_LiveEventData(struct cereal_LiveEventData *s, cereal_LiveEventData_list l, int i) { + cereal_LiveEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LiveEventData(s, p); +} +void cereal_set_LiveEventData(const struct cereal_LiveEventData *s, cereal_LiveEventData_list l, int i) { + cereal_LiveEventData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LiveEventData(s, p); +} + +cereal_ModelData_ptr cereal_new_ModelData(struct capn_segment *s) { + cereal_ModelData_ptr p; + p.p = capn_new_struct(s, 8, 5); + return p; +} +cereal_ModelData_list cereal_new_ModelData_list(struct capn_segment *s, int len) { + cereal_ModelData_list p; + p.p = capn_new_list(s, len, 8, 5); + return p; +} +void cereal_read_ModelData(struct cereal_ModelData *s, cereal_ModelData_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->path.p = capn_getp(p.p, 0, 0); + s->leftLane.p = capn_getp(p.p, 1, 0); + s->rightLane.p = capn_getp(p.p, 2, 0); + s->lead.p = capn_getp(p.p, 3, 0); + s->settings.p = capn_getp(p.p, 4, 0); +} +void cereal_write_ModelData(const struct cereal_ModelData *s, cereal_ModelData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_setp(p.p, 0, s->path.p); + capn_setp(p.p, 1, s->leftLane.p); + capn_setp(p.p, 2, s->rightLane.p); + capn_setp(p.p, 3, s->lead.p); + capn_setp(p.p, 4, s->settings.p); +} +void cereal_get_ModelData(struct cereal_ModelData *s, cereal_ModelData_list l, int i) { + cereal_ModelData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData(s, p); +} +void cereal_set_ModelData(const struct cereal_ModelData *s, cereal_ModelData_list l, int i) { + cereal_ModelData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData(s, p); +} + +cereal_ModelData_PathData_ptr cereal_new_ModelData_PathData(struct capn_segment *s) { + cereal_ModelData_PathData_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_ModelData_PathData_list cereal_new_ModelData_PathData_list(struct capn_segment *s, int len) { + cereal_ModelData_PathData_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_ModelData_PathData(struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_ptr p) { + capn_resolve(&p.p); + s->points.p = capn_getp(p.p, 0, 0); + s->prob = capn_to_f32(capn_read32(p.p, 0)); + s->std = capn_to_f32(capn_read32(p.p, 4)); +} +void cereal_write_ModelData_PathData(const struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_ptr p) { + capn_resolve(&p.p); + capn_setp(p.p, 0, s->points.p); + capn_write32(p.p, 0, capn_from_f32(s->prob)); + capn_write32(p.p, 4, capn_from_f32(s->std)); +} +void cereal_get_ModelData_PathData(struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_list l, int i) { + cereal_ModelData_PathData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_PathData(s, p); +} +void cereal_set_ModelData_PathData(const struct cereal_ModelData_PathData *s, cereal_ModelData_PathData_list l, int i) { + cereal_ModelData_PathData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_PathData(s, p); +} + +cereal_ModelData_LeadData_ptr cereal_new_ModelData_LeadData(struct capn_segment *s) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_new_struct(s, 16, 0); + return p; +} +cereal_ModelData_LeadData_list cereal_new_ModelData_LeadData_list(struct capn_segment *s, int len) { + cereal_ModelData_LeadData_list p; + p.p = capn_new_list(s, len, 16, 0); + return p; +} +void cereal_read_ModelData_LeadData(struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_ptr p) { + capn_resolve(&p.p); + s->dist = capn_to_f32(capn_read32(p.p, 0)); + s->prob = capn_to_f32(capn_read32(p.p, 4)); + s->std = capn_to_f32(capn_read32(p.p, 8)); +} +void cereal_write_ModelData_LeadData(const struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, capn_from_f32(s->dist)); + capn_write32(p.p, 4, capn_from_f32(s->prob)); + capn_write32(p.p, 8, capn_from_f32(s->std)); +} +void cereal_get_ModelData_LeadData(struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_list l, int i) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_LeadData(s, p); +} +void cereal_set_ModelData_LeadData(const struct cereal_ModelData_LeadData *s, cereal_ModelData_LeadData_list l, int i) { + cereal_ModelData_LeadData_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_LeadData(s, p); +} + +cereal_ModelData_ModelSettings_ptr cereal_new_ModelData_ModelSettings(struct capn_segment *s) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_new_struct(s, 8, 2); + return p; +} +cereal_ModelData_ModelSettings_list cereal_new_ModelData_ModelSettings_list(struct capn_segment *s, int len) { + cereal_ModelData_ModelSettings_list p; + p.p = capn_new_list(s, len, 8, 2); + return p; +} +void cereal_read_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_ptr p) { + capn_resolve(&p.p); + s->bigBoxX = capn_read16(p.p, 0); + s->bigBoxY = capn_read16(p.p, 2); + s->bigBoxWidth = capn_read16(p.p, 4); + s->bigBoxHeight = capn_read16(p.p, 6); + s->boxProjection.p = capn_getp(p.p, 0, 0); + s->yuvCorrection.p = capn_getp(p.p, 1, 0); +} +void cereal_write_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_ptr p) { + capn_resolve(&p.p); + capn_write16(p.p, 0, s->bigBoxX); + capn_write16(p.p, 2, s->bigBoxY); + capn_write16(p.p, 4, s->bigBoxWidth); + capn_write16(p.p, 6, s->bigBoxHeight); + capn_setp(p.p, 0, s->boxProjection.p); + capn_setp(p.p, 1, s->yuvCorrection.p); +} +void cereal_get_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_list l, int i) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_ModelData_ModelSettings(s, p); +} +void cereal_set_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings *s, cereal_ModelData_ModelSettings_list l, int i) { + cereal_ModelData_ModelSettings_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_ModelData_ModelSettings(s, p); +} + +cereal_CalibrationFeatures_ptr cereal_new_CalibrationFeatures(struct capn_segment *s) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_new_struct(s, 8, 3); + return p; +} +cereal_CalibrationFeatures_list cereal_new_CalibrationFeatures_list(struct capn_segment *s, int len) { + cereal_CalibrationFeatures_list p; + p.p = capn_new_list(s, len, 8, 3); + return p; +} +void cereal_read_CalibrationFeatures(struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->p0.p = capn_getp(p.p, 0, 0); + s->p1.p = capn_getp(p.p, 1, 0); + s->status.p = capn_getp(p.p, 2, 0); +} +void cereal_write_CalibrationFeatures(const struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_setp(p.p, 0, s->p0.p); + capn_setp(p.p, 1, s->p1.p); + capn_setp(p.p, 2, s->status.p); +} +void cereal_get_CalibrationFeatures(struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_list l, int i) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_CalibrationFeatures(s, p); +} +void cereal_set_CalibrationFeatures(const struct cereal_CalibrationFeatures *s, cereal_CalibrationFeatures_list l, int i) { + cereal_CalibrationFeatures_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_CalibrationFeatures(s, p); +} + +cereal_EncodeIndex_ptr cereal_new_EncodeIndex(struct capn_segment *s) { + cereal_EncodeIndex_ptr p; + p.p = capn_new_struct(s, 24, 0); + return p; +} +cereal_EncodeIndex_list cereal_new_EncodeIndex_list(struct capn_segment *s, int len) { + cereal_EncodeIndex_list p; + p.p = capn_new_list(s, len, 24, 0); + return p; +} +void cereal_read_EncodeIndex(struct cereal_EncodeIndex *s, cereal_EncodeIndex_ptr p) { + capn_resolve(&p.p); + s->frameId = capn_read32(p.p, 0); + s->type = (enum cereal_EncodeIndex_Type)(int) capn_read16(p.p, 4); + s->encodeId = capn_read32(p.p, 8); + s->segmentNum = (int32_t) ((int32_t)capn_read32(p.p, 12)); + s->segmentId = capn_read32(p.p, 16); +} +void cereal_write_EncodeIndex(const struct cereal_EncodeIndex *s, cereal_EncodeIndex_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, s->frameId); + capn_write16(p.p, 4, (uint16_t) (s->type)); + capn_write32(p.p, 8, s->encodeId); + capn_write32(p.p, 12, (uint32_t) (s->segmentNum)); + capn_write32(p.p, 16, s->segmentId); +} +void cereal_get_EncodeIndex(struct cereal_EncodeIndex *s, cereal_EncodeIndex_list l, int i) { + cereal_EncodeIndex_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_EncodeIndex(s, p); +} +void cereal_set_EncodeIndex(const struct cereal_EncodeIndex *s, cereal_EncodeIndex_list l, int i) { + cereal_EncodeIndex_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_EncodeIndex(s, p); +} + +cereal_AndroidLogEntry_ptr cereal_new_AndroidLogEntry(struct capn_segment *s) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_new_struct(s, 24, 2); + return p; +} +cereal_AndroidLogEntry_list cereal_new_AndroidLogEntry_list(struct capn_segment *s, int len) { + cereal_AndroidLogEntry_list p; + p.p = capn_new_list(s, len, 24, 2); + return p; +} +void cereal_read_AndroidLogEntry(struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_ptr p) { + capn_resolve(&p.p); + s->id = capn_read8(p.p, 0); + s->ts = capn_read64(p.p, 8); + s->priority = capn_read8(p.p, 1); + s->pid = (int32_t) ((int32_t)capn_read32(p.p, 4)); + s->tid = (int32_t) ((int32_t)capn_read32(p.p, 16)); + s->tag = capn_get_text(p.p, 0, capn_val0); + s->message = capn_get_text(p.p, 1, capn_val0); +} +void cereal_write_AndroidLogEntry(const struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_ptr p) { + capn_resolve(&p.p); + capn_write8(p.p, 0, s->id); + capn_write64(p.p, 8, s->ts); + capn_write8(p.p, 1, s->priority); + capn_write32(p.p, 4, (uint32_t) (s->pid)); + capn_write32(p.p, 16, (uint32_t) (s->tid)); + capn_set_text(p.p, 0, s->tag); + capn_set_text(p.p, 1, s->message); +} +void cereal_get_AndroidLogEntry(struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_list l, int i) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_AndroidLogEntry(s, p); +} +void cereal_set_AndroidLogEntry(const struct cereal_AndroidLogEntry *s, cereal_AndroidLogEntry_list l, int i) { + cereal_AndroidLogEntry_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_AndroidLogEntry(s, p); +} + +cereal_LogRotate_ptr cereal_new_LogRotate(struct capn_segment *s) { + cereal_LogRotate_ptr p; + p.p = capn_new_struct(s, 8, 1); + return p; +} +cereal_LogRotate_list cereal_new_LogRotate_list(struct capn_segment *s, int len) { + cereal_LogRotate_list p; + p.p = capn_new_list(s, len, 8, 1); + return p; +} +void cereal_read_LogRotate(struct cereal_LogRotate *s, cereal_LogRotate_ptr p) { + capn_resolve(&p.p); + s->segmentNum = (int32_t) ((int32_t)capn_read32(p.p, 0)); + s->path = capn_get_text(p.p, 0, capn_val0); +} +void cereal_write_LogRotate(const struct cereal_LogRotate *s, cereal_LogRotate_ptr p) { + capn_resolve(&p.p); + capn_write32(p.p, 0, (uint32_t) (s->segmentNum)); + capn_set_text(p.p, 0, s->path); +} +void cereal_get_LogRotate(struct cereal_LogRotate *s, cereal_LogRotate_list l, int i) { + cereal_LogRotate_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_LogRotate(s, p); +} +void cereal_set_LogRotate(const struct cereal_LogRotate *s, cereal_LogRotate_list l, int i) { + cereal_LogRotate_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_LogRotate(s, p); +} + +cereal_Event_ptr cereal_new_Event(struct capn_segment *s) { + cereal_Event_ptr p; + p.p = capn_new_struct(s, 16, 1); + return p; +} +cereal_Event_list cereal_new_Event_list(struct capn_segment *s, int len) { + cereal_Event_list p; + p.p = capn_new_list(s, len, 16, 1); + return p; +} +void cereal_read_Event(struct cereal_Event *s, cereal_Event_ptr p) { + capn_resolve(&p.p); + s->logMonoTime = capn_read64(p.p, 0); + s->which = (enum cereal_Event_which)(int) capn_read16(p.p, 8); + switch (s->which) { + case cereal_Event_logMessage: + s->logMessage = capn_get_text(p.p, 0, capn_val0); + break; + case cereal_Event_initData: + case cereal_Event_frame: + case cereal_Event_gpsNMEA: + case cereal_Event_sensorEventDEPRECATED: + case cereal_Event_can: + case cereal_Event_thermal: + case cereal_Event_live100: + case cereal_Event_liveEventDEPRECATED: + case cereal_Event_model: + case cereal_Event_features: + case cereal_Event_sensorEvents: + case cereal_Event_health: + case cereal_Event_live20: + case cereal_Event_liveUIDEPRECATED: + case cereal_Event_encodeIdx: + case cereal_Event_liveTracks: + case cereal_Event_sendcan: + case cereal_Event_liveCalibration: + case cereal_Event_androidLogEntry: + s->androidLogEntry.p = capn_getp(p.p, 0, 0); + break; + default: + break; + } +} +void cereal_write_Event(const struct cereal_Event *s, cereal_Event_ptr p) { + capn_resolve(&p.p); + capn_write64(p.p, 0, s->logMonoTime); + capn_write16(p.p, 8, s->which); + switch (s->which) { + case cereal_Event_logMessage: + capn_set_text(p.p, 0, s->logMessage); + break; + case cereal_Event_initData: + case cereal_Event_frame: + case cereal_Event_gpsNMEA: + case cereal_Event_sensorEventDEPRECATED: + case cereal_Event_can: + case cereal_Event_thermal: + case cereal_Event_live100: + case cereal_Event_liveEventDEPRECATED: + case cereal_Event_model: + case cereal_Event_features: + case cereal_Event_sensorEvents: + case cereal_Event_health: + case cereal_Event_live20: + case cereal_Event_liveUIDEPRECATED: + case cereal_Event_encodeIdx: + case cereal_Event_liveTracks: + case cereal_Event_sendcan: + case cereal_Event_liveCalibration: + case cereal_Event_androidLogEntry: + capn_setp(p.p, 0, s->androidLogEntry.p); + break; + default: + break; + } +} +void cereal_get_Event(struct cereal_Event *s, cereal_Event_list l, int i) { + cereal_Event_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_read_Event(s, p); +} +void cereal_set_Event(const struct cereal_Event *s, cereal_Event_list l, int i) { + cereal_Event_ptr p; + p.p = capn_getp(l.p, i, 0); + cereal_write_Event(s, p); +} diff --git a/cereal/gen/c/log.capnp.h b/cereal/gen/c/log.capnp.h new file mode 100644 index 0000000000..865e4d0ff9 --- /dev/null +++ b/cereal/gen/c/log.capnp.h @@ -0,0 +1,667 @@ +#ifndef CAPN_F3B1F17E25A4285B +#define CAPN_F3B1F17E25A4285B +/* AUTO GENERATED - DO NOT EDIT */ +#include + +#if CAPN_VERSION != 1 +#error "version mismatch between capnp_c.h and generated code" +#endif + +#include "c++.capnp.h" + +#ifdef __cplusplus +extern "C" { +#endif + +struct cereal_InitData; +struct cereal_FrameData; +struct cereal_GPSNMEAData; +struct cereal_SensorEventData; +struct cereal_SensorEventData_SensorVec; +struct cereal_CanData; +struct cereal_ThermalData; +struct cereal_HealthData; +struct cereal_LiveUI; +struct cereal_Live20Data; +struct cereal_Live20Data_LeadData; +struct cereal_LiveCalibrationData; +struct cereal_LiveTracks; +struct cereal_Live100Data; +struct cereal_LiveEventData; +struct cereal_ModelData; +struct cereal_ModelData_PathData; +struct cereal_ModelData_LeadData; +struct cereal_ModelData_ModelSettings; +struct cereal_CalibrationFeatures; +struct cereal_EncodeIndex; +struct cereal_AndroidLogEntry; +struct cereal_LogRotate; +struct cereal_Event; + +typedef struct {capn_ptr p;} cereal_InitData_ptr; +typedef struct {capn_ptr p;} cereal_FrameData_ptr; +typedef struct {capn_ptr p;} cereal_GPSNMEAData_ptr; +typedef struct {capn_ptr p;} cereal_SensorEventData_ptr; +typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_ptr; +typedef struct {capn_ptr p;} cereal_CanData_ptr; +typedef struct {capn_ptr p;} cereal_ThermalData_ptr; +typedef struct {capn_ptr p;} cereal_HealthData_ptr; +typedef struct {capn_ptr p;} cereal_LiveUI_ptr; +typedef struct {capn_ptr p;} cereal_Live20Data_ptr; +typedef struct {capn_ptr p;} cereal_Live20Data_LeadData_ptr; +typedef struct {capn_ptr p;} cereal_LiveCalibrationData_ptr; +typedef struct {capn_ptr p;} cereal_LiveTracks_ptr; +typedef struct {capn_ptr p;} cereal_Live100Data_ptr; +typedef struct {capn_ptr p;} cereal_LiveEventData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_PathData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_LeadData_ptr; +typedef struct {capn_ptr p;} cereal_ModelData_ModelSettings_ptr; +typedef struct {capn_ptr p;} cereal_CalibrationFeatures_ptr; +typedef struct {capn_ptr p;} cereal_EncodeIndex_ptr; +typedef struct {capn_ptr p;} cereal_AndroidLogEntry_ptr; +typedef struct {capn_ptr p;} cereal_LogRotate_ptr; +typedef struct {capn_ptr p;} cereal_Event_ptr; + +typedef struct {capn_ptr p;} cereal_InitData_list; +typedef struct {capn_ptr p;} cereal_FrameData_list; +typedef struct {capn_ptr p;} cereal_GPSNMEAData_list; +typedef struct {capn_ptr p;} cereal_SensorEventData_list; +typedef struct {capn_ptr p;} cereal_SensorEventData_SensorVec_list; +typedef struct {capn_ptr p;} cereal_CanData_list; +typedef struct {capn_ptr p;} cereal_ThermalData_list; +typedef struct {capn_ptr p;} cereal_HealthData_list; +typedef struct {capn_ptr p;} cereal_LiveUI_list; +typedef struct {capn_ptr p;} cereal_Live20Data_list; +typedef struct {capn_ptr p;} cereal_Live20Data_LeadData_list; +typedef struct {capn_ptr p;} cereal_LiveCalibrationData_list; +typedef struct {capn_ptr p;} cereal_LiveTracks_list; +typedef struct {capn_ptr p;} cereal_Live100Data_list; +typedef struct {capn_ptr p;} cereal_LiveEventData_list; +typedef struct {capn_ptr p;} cereal_ModelData_list; +typedef struct {capn_ptr p;} cereal_ModelData_PathData_list; +typedef struct {capn_ptr p;} cereal_ModelData_LeadData_list; +typedef struct {capn_ptr p;} cereal_ModelData_ModelSettings_list; +typedef struct {capn_ptr p;} cereal_CalibrationFeatures_list; +typedef struct {capn_ptr p;} cereal_EncodeIndex_list; +typedef struct {capn_ptr p;} cereal_AndroidLogEntry_list; +typedef struct {capn_ptr p;} cereal_LogRotate_list; +typedef struct {capn_ptr p;} cereal_Event_list; + +enum cereal_EncodeIndex_Type { + cereal_EncodeIndex_Type_bigBoxLossless = 0, + cereal_EncodeIndex_Type_fullHEVC = 1, + cereal_EncodeIndex_Type_bigBoxHEVC = 2 +}; +extern int32_t cereal_logVersion; + +struct cereal_InitData { + capn_ptr kernelArgs; + capn_text gctx; + capn_text dongleId; +}; + +static const size_t cereal_InitData_word_count = 0; + +static const size_t cereal_InitData_pointer_count = 3; + +static const size_t cereal_InitData_struct_bytes_count = 24; + +struct cereal_FrameData { + uint32_t frameId; + uint32_t encodeId; + uint64_t timestampEof; + int32_t frameLength; + int32_t integLines; + int32_t globalGain; + capn_data image; +}; + +static const size_t cereal_FrameData_word_count = 4; + +static const size_t cereal_FrameData_pointer_count = 1; + +static const size_t cereal_FrameData_struct_bytes_count = 40; + +struct cereal_GPSNMEAData { + int64_t timestamp; + uint64_t localWallTime; + capn_text nmea; +}; + +static const size_t cereal_GPSNMEAData_word_count = 2; + +static const size_t cereal_GPSNMEAData_pointer_count = 1; + +static const size_t cereal_GPSNMEAData_struct_bytes_count = 24; +enum cereal_SensorEventData_which { + cereal_SensorEventData_acceleration = 0, + cereal_SensorEventData_magnetic = 1, + cereal_SensorEventData_orientation = 2, + cereal_SensorEventData_gyro = 3 +}; + +struct cereal_SensorEventData { + int32_t version; + int32_t sensor; + int32_t type; + int64_t timestamp; + enum cereal_SensorEventData_which which; + union { + cereal_SensorEventData_SensorVec_ptr acceleration; + cereal_SensorEventData_SensorVec_ptr magnetic; + cereal_SensorEventData_SensorVec_ptr orientation; + cereal_SensorEventData_SensorVec_ptr gyro; + }; +}; + +static const size_t cereal_SensorEventData_word_count = 3; + +static const size_t cereal_SensorEventData_pointer_count = 1; + +static const size_t cereal_SensorEventData_struct_bytes_count = 32; + +struct cereal_SensorEventData_SensorVec { + capn_list32 v; + int8_t status; +}; + +static const size_t cereal_SensorEventData_SensorVec_word_count = 1; + +static const size_t cereal_SensorEventData_SensorVec_pointer_count = 1; + +static const size_t cereal_SensorEventData_SensorVec_struct_bytes_count = 16; + +struct cereal_CanData { + uint32_t address; + uint16_t busTime; + capn_data dat; + int8_t src; +}; + +static const size_t cereal_CanData_word_count = 1; + +static const size_t cereal_CanData_pointer_count = 1; + +static const size_t cereal_CanData_struct_bytes_count = 16; + +struct cereal_ThermalData { + uint16_t cpu0; + uint16_t cpu1; + uint16_t cpu2; + uint16_t cpu3; + uint16_t mem; + uint16_t gpu; + uint32_t bat; +}; + +static const size_t cereal_ThermalData_word_count = 2; + +static const size_t cereal_ThermalData_pointer_count = 0; + +static const size_t cereal_ThermalData_struct_bytes_count = 16; + +struct cereal_HealthData { + uint32_t voltage; + uint32_t current; + unsigned started : 1; + unsigned controlsAllowed : 1; + unsigned gasInterceptorDetected : 1; +}; + +static const size_t cereal_HealthData_word_count = 2; + +static const size_t cereal_HealthData_pointer_count = 0; + +static const size_t cereal_HealthData_struct_bytes_count = 16; + +struct cereal_LiveUI { + unsigned rearViewCam : 1; + capn_text alertText1; + capn_text alertText2; + float awarenessStatus; +}; + +static const size_t cereal_LiveUI_word_count = 1; + +static const size_t cereal_LiveUI_pointer_count = 2; + +static const size_t cereal_LiveUI_struct_bytes_count = 24; + +struct cereal_Live20Data { + capn_list64 canMonoTimes; + uint64_t mdMonoTime; + uint64_t ftMonoTime; + capn_list32 warpMatrix; + float angleOffset; + int8_t calStatus; + int32_t calCycle; + int8_t calPerc; + cereal_Live20Data_LeadData_ptr leadOne; + cereal_Live20Data_LeadData_ptr leadTwo; + float cumLagMs; +}; + +static const size_t cereal_Live20Data_word_count = 4; + +static const size_t cereal_Live20Data_pointer_count = 4; + +static const size_t cereal_Live20Data_struct_bytes_count = 64; + +struct cereal_Live20Data_LeadData { + float dRel; + float yRel; + float vRel; + float aRel; + float vLead; + float aLead; + float dPath; + float vLat; + float vLeadK; + float aLeadK; + unsigned fcw : 1; + unsigned status : 1; +}; + +static const size_t cereal_Live20Data_LeadData_word_count = 6; + +static const size_t cereal_Live20Data_LeadData_pointer_count = 0; + +static const size_t cereal_Live20Data_LeadData_struct_bytes_count = 48; + +struct cereal_LiveCalibrationData { + capn_list32 warpMatrix; + int8_t calStatus; + int32_t calCycle; + int8_t calPerc; +}; + +static const size_t cereal_LiveCalibrationData_word_count = 1; + +static const size_t cereal_LiveCalibrationData_pointer_count = 1; + +static const size_t cereal_LiveCalibrationData_struct_bytes_count = 16; + +struct cereal_LiveTracks { + int32_t trackId; + float dRel; + float yRel; + float vRel; + float aRel; + float timeStamp; + float status; + float currentTime; + unsigned stationary : 1; + unsigned oncoming : 1; +}; + +static const size_t cereal_LiveTracks_word_count = 5; + +static const size_t cereal_LiveTracks_pointer_count = 0; + +static const size_t cereal_LiveTracks_struct_bytes_count = 40; + +struct cereal_Live100Data { + uint64_t canMonoTime; + capn_list64 canMonoTimes; + uint64_t l20MonoTime; + uint64_t mdMonoTime; + float vEgo; + float aEgo; + float vPid; + float vTargetLead; + float upAccelCmd; + float uiAccelCmd; + float yActual; + float yDes; + float upSteer; + float uiSteer; + float aTargetMin; + float aTargetMax; + float jerkFactor; + float angleSteers; + int32_t hudLead; + float cumLagMs; + unsigned enabled : 1; + unsigned steerOverride : 1; + float vCruise; + unsigned rearViewCam : 1; + capn_text alertText1; + capn_text alertText2; + float awarenessStatus; +}; + +static const size_t cereal_Live100Data_word_count = 13; + +static const size_t cereal_Live100Data_pointer_count = 3; + +static const size_t cereal_Live100Data_struct_bytes_count = 128; + +struct cereal_LiveEventData { + capn_text name; + int32_t value; +}; + +static const size_t cereal_LiveEventData_word_count = 1; + +static const size_t cereal_LiveEventData_pointer_count = 1; + +static const size_t cereal_LiveEventData_struct_bytes_count = 16; + +struct cereal_ModelData { + uint32_t frameId; + cereal_ModelData_PathData_ptr path; + cereal_ModelData_PathData_ptr leftLane; + cereal_ModelData_PathData_ptr rightLane; + cereal_ModelData_LeadData_ptr lead; + cereal_ModelData_ModelSettings_ptr settings; +}; + +static const size_t cereal_ModelData_word_count = 1; + +static const size_t cereal_ModelData_pointer_count = 5; + +static const size_t cereal_ModelData_struct_bytes_count = 48; + +struct cereal_ModelData_PathData { + capn_list32 points; + float prob; + float std; +}; + +static const size_t cereal_ModelData_PathData_word_count = 1; + +static const size_t cereal_ModelData_PathData_pointer_count = 1; + +static const size_t cereal_ModelData_PathData_struct_bytes_count = 16; + +struct cereal_ModelData_LeadData { + float dist; + float prob; + float std; +}; + +static const size_t cereal_ModelData_LeadData_word_count = 2; + +static const size_t cereal_ModelData_LeadData_pointer_count = 0; + +static const size_t cereal_ModelData_LeadData_struct_bytes_count = 16; + +struct cereal_ModelData_ModelSettings { + uint16_t bigBoxX; + uint16_t bigBoxY; + uint16_t bigBoxWidth; + uint16_t bigBoxHeight; + capn_list32 boxProjection; + capn_list32 yuvCorrection; +}; + +static const size_t cereal_ModelData_ModelSettings_word_count = 1; + +static const size_t cereal_ModelData_ModelSettings_pointer_count = 2; + +static const size_t cereal_ModelData_ModelSettings_struct_bytes_count = 24; + +struct cereal_CalibrationFeatures { + uint32_t frameId; + capn_list32 p0; + capn_list32 p1; + capn_list8 status; +}; + +static const size_t cereal_CalibrationFeatures_word_count = 1; + +static const size_t cereal_CalibrationFeatures_pointer_count = 3; + +static const size_t cereal_CalibrationFeatures_struct_bytes_count = 32; + +struct cereal_EncodeIndex { + uint32_t frameId; + enum cereal_EncodeIndex_Type type; + uint32_t encodeId; + int32_t segmentNum; + uint32_t segmentId; +}; + +static const size_t cereal_EncodeIndex_word_count = 3; + +static const size_t cereal_EncodeIndex_pointer_count = 0; + +static const size_t cereal_EncodeIndex_struct_bytes_count = 24; + +struct cereal_AndroidLogEntry { + uint8_t id; + uint64_t ts; + uint8_t priority; + int32_t pid; + int32_t tid; + capn_text tag; + capn_text message; +}; + +static const size_t cereal_AndroidLogEntry_word_count = 3; + +static const size_t cereal_AndroidLogEntry_pointer_count = 2; + +static const size_t cereal_AndroidLogEntry_struct_bytes_count = 40; + +struct cereal_LogRotate { + int32_t segmentNum; + capn_text path; +}; + +static const size_t cereal_LogRotate_word_count = 1; + +static const size_t cereal_LogRotate_pointer_count = 1; + +static const size_t cereal_LogRotate_struct_bytes_count = 16; +enum cereal_Event_which { + cereal_Event_initData = 0, + cereal_Event_frame = 1, + cereal_Event_gpsNMEA = 2, + cereal_Event_sensorEventDEPRECATED = 3, + cereal_Event_can = 4, + cereal_Event_thermal = 5, + cereal_Event_live100 = 6, + cereal_Event_liveEventDEPRECATED = 7, + cereal_Event_model = 8, + cereal_Event_features = 9, + cereal_Event_sensorEvents = 10, + cereal_Event_health = 11, + cereal_Event_live20 = 12, + cereal_Event_liveUIDEPRECATED = 13, + cereal_Event_encodeIdx = 14, + cereal_Event_liveTracks = 15, + cereal_Event_sendcan = 16, + cereal_Event_logMessage = 17, + cereal_Event_liveCalibration = 18, + cereal_Event_androidLogEntry = 19 +}; + +struct cereal_Event { + uint64_t logMonoTime; + enum cereal_Event_which which; + union { + cereal_InitData_ptr initData; + cereal_FrameData_ptr frame; + cereal_GPSNMEAData_ptr gpsNMEA; + cereal_SensorEventData_ptr sensorEventDEPRECATED; + cereal_CanData_list can; + cereal_ThermalData_ptr thermal; + cereal_Live100Data_ptr live100; + cereal_LiveEventData_list liveEventDEPRECATED; + cereal_ModelData_ptr model; + cereal_CalibrationFeatures_ptr features; + cereal_SensorEventData_list sensorEvents; + cereal_HealthData_ptr health; + cereal_Live20Data_ptr live20; + cereal_LiveUI_ptr liveUIDEPRECATED; + cereal_EncodeIndex_ptr encodeIdx; + cereal_LiveTracks_list liveTracks; + cereal_CanData_list sendcan; + capn_text logMessage; + cereal_LiveCalibrationData_ptr liveCalibration; + cereal_AndroidLogEntry_ptr androidLogEntry; + }; +}; + +static const size_t cereal_Event_word_count = 2; + +static const size_t cereal_Event_pointer_count = 1; + +static const size_t cereal_Event_struct_bytes_count = 24; + +cereal_InitData_ptr cereal_new_InitData(struct capn_segment*); +cereal_FrameData_ptr cereal_new_FrameData(struct capn_segment*); +cereal_GPSNMEAData_ptr cereal_new_GPSNMEAData(struct capn_segment*); +cereal_SensorEventData_ptr cereal_new_SensorEventData(struct capn_segment*); +cereal_SensorEventData_SensorVec_ptr cereal_new_SensorEventData_SensorVec(struct capn_segment*); +cereal_CanData_ptr cereal_new_CanData(struct capn_segment*); +cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment*); +cereal_HealthData_ptr cereal_new_HealthData(struct capn_segment*); +cereal_LiveUI_ptr cereal_new_LiveUI(struct capn_segment*); +cereal_Live20Data_ptr cereal_new_Live20Data(struct capn_segment*); +cereal_Live20Data_LeadData_ptr cereal_new_Live20Data_LeadData(struct capn_segment*); +cereal_LiveCalibrationData_ptr cereal_new_LiveCalibrationData(struct capn_segment*); +cereal_LiveTracks_ptr cereal_new_LiveTracks(struct capn_segment*); +cereal_Live100Data_ptr cereal_new_Live100Data(struct capn_segment*); +cereal_LiveEventData_ptr cereal_new_LiveEventData(struct capn_segment*); +cereal_ModelData_ptr cereal_new_ModelData(struct capn_segment*); +cereal_ModelData_PathData_ptr cereal_new_ModelData_PathData(struct capn_segment*); +cereal_ModelData_LeadData_ptr cereal_new_ModelData_LeadData(struct capn_segment*); +cereal_ModelData_ModelSettings_ptr cereal_new_ModelData_ModelSettings(struct capn_segment*); +cereal_CalibrationFeatures_ptr cereal_new_CalibrationFeatures(struct capn_segment*); +cereal_EncodeIndex_ptr cereal_new_EncodeIndex(struct capn_segment*); +cereal_AndroidLogEntry_ptr cereal_new_AndroidLogEntry(struct capn_segment*); +cereal_LogRotate_ptr cereal_new_LogRotate(struct capn_segment*); +cereal_Event_ptr cereal_new_Event(struct capn_segment*); + +cereal_InitData_list cereal_new_InitData_list(struct capn_segment*, int len); +cereal_FrameData_list cereal_new_FrameData_list(struct capn_segment*, int len); +cereal_GPSNMEAData_list cereal_new_GPSNMEAData_list(struct capn_segment*, int len); +cereal_SensorEventData_list cereal_new_SensorEventData_list(struct capn_segment*, int len); +cereal_SensorEventData_SensorVec_list cereal_new_SensorEventData_SensorVec_list(struct capn_segment*, int len); +cereal_CanData_list cereal_new_CanData_list(struct capn_segment*, int len); +cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment*, int len); +cereal_HealthData_list cereal_new_HealthData_list(struct capn_segment*, int len); +cereal_LiveUI_list cereal_new_LiveUI_list(struct capn_segment*, int len); +cereal_Live20Data_list cereal_new_Live20Data_list(struct capn_segment*, int len); +cereal_Live20Data_LeadData_list cereal_new_Live20Data_LeadData_list(struct capn_segment*, int len); +cereal_LiveCalibrationData_list cereal_new_LiveCalibrationData_list(struct capn_segment*, int len); +cereal_LiveTracks_list cereal_new_LiveTracks_list(struct capn_segment*, int len); +cereal_Live100Data_list cereal_new_Live100Data_list(struct capn_segment*, int len); +cereal_LiveEventData_list cereal_new_LiveEventData_list(struct capn_segment*, int len); +cereal_ModelData_list cereal_new_ModelData_list(struct capn_segment*, int len); +cereal_ModelData_PathData_list cereal_new_ModelData_PathData_list(struct capn_segment*, int len); +cereal_ModelData_LeadData_list cereal_new_ModelData_LeadData_list(struct capn_segment*, int len); +cereal_ModelData_ModelSettings_list cereal_new_ModelData_ModelSettings_list(struct capn_segment*, int len); +cereal_CalibrationFeatures_list cereal_new_CalibrationFeatures_list(struct capn_segment*, int len); +cereal_EncodeIndex_list cereal_new_EncodeIndex_list(struct capn_segment*, int len); +cereal_AndroidLogEntry_list cereal_new_AndroidLogEntry_list(struct capn_segment*, int len); +cereal_LogRotate_list cereal_new_LogRotate_list(struct capn_segment*, int len); +cereal_Event_list cereal_new_Event_list(struct capn_segment*, int len); + +void cereal_read_InitData(struct cereal_InitData*, cereal_InitData_ptr); +void cereal_read_FrameData(struct cereal_FrameData*, cereal_FrameData_ptr); +void cereal_read_GPSNMEAData(struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr); +void cereal_read_SensorEventData(struct cereal_SensorEventData*, cereal_SensorEventData_ptr); +void cereal_read_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_ptr); +void cereal_read_CanData(struct cereal_CanData*, cereal_CanData_ptr); +void cereal_read_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_ptr); +void cereal_read_HealthData(struct cereal_HealthData*, cereal_HealthData_ptr); +void cereal_read_LiveUI(struct cereal_LiveUI*, cereal_LiveUI_ptr); +void cereal_read_Live20Data(struct cereal_Live20Data*, cereal_Live20Data_ptr); +void cereal_read_Live20Data_LeadData(struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_ptr); +void cereal_read_LiveCalibrationData(struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_ptr); +void cereal_read_LiveTracks(struct cereal_LiveTracks*, cereal_LiveTracks_ptr); +void cereal_read_Live100Data(struct cereal_Live100Data*, cereal_Live100Data_ptr); +void cereal_read_LiveEventData(struct cereal_LiveEventData*, cereal_LiveEventData_ptr); +void cereal_read_ModelData(struct cereal_ModelData*, cereal_ModelData_ptr); +void cereal_read_ModelData_PathData(struct cereal_ModelData_PathData*, cereal_ModelData_PathData_ptr); +void cereal_read_ModelData_LeadData(struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_ptr); +void cereal_read_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_ptr); +void cereal_read_CalibrationFeatures(struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_ptr); +void cereal_read_EncodeIndex(struct cereal_EncodeIndex*, cereal_EncodeIndex_ptr); +void cereal_read_AndroidLogEntry(struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_ptr); +void cereal_read_LogRotate(struct cereal_LogRotate*, cereal_LogRotate_ptr); +void cereal_read_Event(struct cereal_Event*, cereal_Event_ptr); + +void cereal_write_InitData(const struct cereal_InitData*, cereal_InitData_ptr); +void cereal_write_FrameData(const struct cereal_FrameData*, cereal_FrameData_ptr); +void cereal_write_GPSNMEAData(const struct cereal_GPSNMEAData*, cereal_GPSNMEAData_ptr); +void cereal_write_SensorEventData(const struct cereal_SensorEventData*, cereal_SensorEventData_ptr); +void cereal_write_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_ptr); +void cereal_write_CanData(const struct cereal_CanData*, cereal_CanData_ptr); +void cereal_write_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_ptr); +void cereal_write_HealthData(const struct cereal_HealthData*, cereal_HealthData_ptr); +void cereal_write_LiveUI(const struct cereal_LiveUI*, cereal_LiveUI_ptr); +void cereal_write_Live20Data(const struct cereal_Live20Data*, cereal_Live20Data_ptr); +void cereal_write_Live20Data_LeadData(const struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_ptr); +void cereal_write_LiveCalibrationData(const struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_ptr); +void cereal_write_LiveTracks(const struct cereal_LiveTracks*, cereal_LiveTracks_ptr); +void cereal_write_Live100Data(const struct cereal_Live100Data*, cereal_Live100Data_ptr); +void cereal_write_LiveEventData(const struct cereal_LiveEventData*, cereal_LiveEventData_ptr); +void cereal_write_ModelData(const struct cereal_ModelData*, cereal_ModelData_ptr); +void cereal_write_ModelData_PathData(const struct cereal_ModelData_PathData*, cereal_ModelData_PathData_ptr); +void cereal_write_ModelData_LeadData(const struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_ptr); +void cereal_write_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_ptr); +void cereal_write_CalibrationFeatures(const struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_ptr); +void cereal_write_EncodeIndex(const struct cereal_EncodeIndex*, cereal_EncodeIndex_ptr); +void cereal_write_AndroidLogEntry(const struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_ptr); +void cereal_write_LogRotate(const struct cereal_LogRotate*, cereal_LogRotate_ptr); +void cereal_write_Event(const struct cereal_Event*, cereal_Event_ptr); + +void cereal_get_InitData(struct cereal_InitData*, cereal_InitData_list, int i); +void cereal_get_FrameData(struct cereal_FrameData*, cereal_FrameData_list, int i); +void cereal_get_GPSNMEAData(struct cereal_GPSNMEAData*, cereal_GPSNMEAData_list, int i); +void cereal_get_SensorEventData(struct cereal_SensorEventData*, cereal_SensorEventData_list, int i); +void cereal_get_SensorEventData_SensorVec(struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_list, int i); +void cereal_get_CanData(struct cereal_CanData*, cereal_CanData_list, int i); +void cereal_get_ThermalData(struct cereal_ThermalData*, cereal_ThermalData_list, int i); +void cereal_get_HealthData(struct cereal_HealthData*, cereal_HealthData_list, int i); +void cereal_get_LiveUI(struct cereal_LiveUI*, cereal_LiveUI_list, int i); +void cereal_get_Live20Data(struct cereal_Live20Data*, cereal_Live20Data_list, int i); +void cereal_get_Live20Data_LeadData(struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_list, int i); +void cereal_get_LiveCalibrationData(struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_list, int i); +void cereal_get_LiveTracks(struct cereal_LiveTracks*, cereal_LiveTracks_list, int i); +void cereal_get_Live100Data(struct cereal_Live100Data*, cereal_Live100Data_list, int i); +void cereal_get_LiveEventData(struct cereal_LiveEventData*, cereal_LiveEventData_list, int i); +void cereal_get_ModelData(struct cereal_ModelData*, cereal_ModelData_list, int i); +void cereal_get_ModelData_PathData(struct cereal_ModelData_PathData*, cereal_ModelData_PathData_list, int i); +void cereal_get_ModelData_LeadData(struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_list, int i); +void cereal_get_ModelData_ModelSettings(struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_list, int i); +void cereal_get_CalibrationFeatures(struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_list, int i); +void cereal_get_EncodeIndex(struct cereal_EncodeIndex*, cereal_EncodeIndex_list, int i); +void cereal_get_AndroidLogEntry(struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_list, int i); +void cereal_get_LogRotate(struct cereal_LogRotate*, cereal_LogRotate_list, int i); +void cereal_get_Event(struct cereal_Event*, cereal_Event_list, int i); + +void cereal_set_InitData(const struct cereal_InitData*, cereal_InitData_list, int i); +void cereal_set_FrameData(const struct cereal_FrameData*, cereal_FrameData_list, int i); +void cereal_set_GPSNMEAData(const struct cereal_GPSNMEAData*, cereal_GPSNMEAData_list, int i); +void cereal_set_SensorEventData(const struct cereal_SensorEventData*, cereal_SensorEventData_list, int i); +void cereal_set_SensorEventData_SensorVec(const struct cereal_SensorEventData_SensorVec*, cereal_SensorEventData_SensorVec_list, int i); +void cereal_set_CanData(const struct cereal_CanData*, cereal_CanData_list, int i); +void cereal_set_ThermalData(const struct cereal_ThermalData*, cereal_ThermalData_list, int i); +void cereal_set_HealthData(const struct cereal_HealthData*, cereal_HealthData_list, int i); +void cereal_set_LiveUI(const struct cereal_LiveUI*, cereal_LiveUI_list, int i); +void cereal_set_Live20Data(const struct cereal_Live20Data*, cereal_Live20Data_list, int i); +void cereal_set_Live20Data_LeadData(const struct cereal_Live20Data_LeadData*, cereal_Live20Data_LeadData_list, int i); +void cereal_set_LiveCalibrationData(const struct cereal_LiveCalibrationData*, cereal_LiveCalibrationData_list, int i); +void cereal_set_LiveTracks(const struct cereal_LiveTracks*, cereal_LiveTracks_list, int i); +void cereal_set_Live100Data(const struct cereal_Live100Data*, cereal_Live100Data_list, int i); +void cereal_set_LiveEventData(const struct cereal_LiveEventData*, cereal_LiveEventData_list, int i); +void cereal_set_ModelData(const struct cereal_ModelData*, cereal_ModelData_list, int i); +void cereal_set_ModelData_PathData(const struct cereal_ModelData_PathData*, cereal_ModelData_PathData_list, int i); +void cereal_set_ModelData_LeadData(const struct cereal_ModelData_LeadData*, cereal_ModelData_LeadData_list, int i); +void cereal_set_ModelData_ModelSettings(const struct cereal_ModelData_ModelSettings*, cereal_ModelData_ModelSettings_list, int i); +void cereal_set_CalibrationFeatures(const struct cereal_CalibrationFeatures*, cereal_CalibrationFeatures_list, int i); +void cereal_set_EncodeIndex(const struct cereal_EncodeIndex*, cereal_EncodeIndex_list, int i); +void cereal_set_AndroidLogEntry(const struct cereal_AndroidLogEntry*, cereal_AndroidLogEntry_list, int i); +void cereal_set_LogRotate(const struct cereal_LogRotate*, cereal_LogRotate_list, int i); +void cereal_set_Event(const struct cereal_Event*, cereal_Event_list, int i); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ new file mode 100644 index 0000000000..b981eedac1 --- /dev/null +++ b/cereal/gen/cpp/log.capnp.c++ @@ -0,0 +1,3732 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: log.capnp + +#include "log.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<23> b_d578fb3372ed5043 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 80, 237, 114, 51, 251, 120, 213, + 10, 0, 0, 0, 4, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 108, 111, 103, 86, 101, 114, + 115, 105, 111, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d578fb3372ed5043 = b_d578fb3372ed5043.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d578fb3372ed5043 = { + 0xd578fb3372ed5043, b_d578fb3372ed5043.words, 23, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d578fb3372ed5043, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<68> b_e71008caeb3fb65c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 107, 101, 114, 110, 101, 108, 65, 114, + 103, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 99, 116, 120, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 110, 103, 108, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e71008caeb3fb65c = b_e71008caeb3fb65c.words; +#if !CAPNP_LITE +static const uint16_t m_e71008caeb3fb65c[] = {2, 1, 0}; +static const uint16_t i_e71008caeb3fb65c[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e71008caeb3fb65c = { + 0xe71008caeb3fb65c, b_e71008caeb3fb65c.words, 68, nullptr, m_e71008caeb3fb65c, + 0, 3, i_e71008caeb3fb65c, nullptr, nullptr, { &s_e71008caeb3fb65c, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<127> b_ea0245f695ae0a33 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 76, 101, 110, + 103, 116, 104, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 103, 76, 105, 110, + 101, 115, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 98, 97, 108, 71, 97, + 105, 110, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 97, 103, 101, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea0245f695ae0a33 = b_ea0245f695ae0a33.words; +#if !CAPNP_LITE +static const uint16_t m_ea0245f695ae0a33[] = {1, 0, 3, 5, 6, 4, 2}; +static const uint16_t i_ea0245f695ae0a33[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ea0245f695ae0a33 = { + 0xea0245f695ae0a33, b_ea0245f695ae0a33.words, 127, nullptr, m_ea0245f695ae0a33, + 0, 7, i_ea0245f695ae0a33, nullptr, nullptr, { &s_ea0245f695ae0a33, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_9d291d7813ba4a88 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 80, 83, 78, 77, 69, + 65, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 108, 87, 97, 108, + 108, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 109, 101, 97, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d291d7813ba4a88 = b_9d291d7813ba4a88.words; +#if !CAPNP_LITE +static const uint16_t m_9d291d7813ba4a88[] = {1, 2, 0}; +static const uint16_t i_9d291d7813ba4a88[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_9d291d7813ba4a88 = { + 0x9d291d7813ba4a88, b_9d291d7813ba4a88.words, 64, nullptr, m_9d291d7813ba4a88, + 0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<146> b_a2b29a69d44529a1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 4, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 1, 0, 0, 0, 82, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 86, 101, + 99, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2b29a69d44529a1 = b_a2b29a69d44529a1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = { + &s_a43429bd2bfc24fc, +}; +static const uint16_t m_a2b29a69d44529a1[] = {4, 7, 5, 6, 1, 3, 2, 0}; +static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 0, 1, 2, 3}; +const ::capnp::_::RawSchema s_a2b29a69d44529a1 = { + 0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 146, d_a2b29a69d44529a1, m_a2b29a69d44529a1, + 1, 8, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a43429bd2bfc24fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 26, 0, 0, 0, 1, 0, 1, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 46, 83, 101, 110, 115, 111, 114, + 86, 101, 99, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 118, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a43429bd2bfc24fc = b_a43429bd2bfc24fc.words; +#if !CAPNP_LITE +static const uint16_t m_a43429bd2bfc24fc[] = {1, 0}; +static const uint16_t i_a43429bd2bfc24fc[] = {0, 1}; +const ::capnp::_::RawSchema s_a43429bd2bfc24fc = { + 0xa43429bd2bfc24fc, b_a43429bd2bfc24fc.words, 53, nullptr, m_a43429bd2bfc24fc, + 0, 2, i_a43429bd2bfc24fc, nullptr, nullptr, { &s_a43429bd2bfc24fc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<77> b_8785009a964c7c59 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 110, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 97, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 115, 84, 105, 109, 101, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 114, 99, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8785009a964c7c59 = b_8785009a964c7c59.words; +#if !CAPNP_LITE +static const uint16_t m_8785009a964c7c59[] = {0, 1, 2, 3}; +static const uint16_t i_8785009a964c7c59[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8785009a964c7c59 = { + 0x8785009a964c7c59, b_8785009a964c7c59.words, 77, nullptr, m_8785009a964c7c59, + 0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<122> b_8d8231a40b7fe6e0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 224, 230, 127, 11, 164, 49, 130, 141, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 84, 104, 101, 114, 109, 97, + 108, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 99, 112, 117, 48, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 49, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 50, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 51, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words; +#if !CAPNP_LITE +static const uint16_t m_8d8231a40b7fe6e0[] = {6, 0, 1, 2, 3, 5, 4}; +static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { + 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 122, nullptr, m_8d8231a40b7fe6e0, + 0, 7, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 228, 241, 42, 200, 194, 176, 162, 207, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 72, 101, 97, 108, 116, 104, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 118, 111, 108, 116, 97, 103, 101, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 65, 108, 108, 111, 119, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 73, 110, 116, 101, 114, + 99, 101, 112, 116, 111, 114, 68, 101, + 116, 101, 99, 116, 101, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cfa2b0c2c82af1e4 = b_cfa2b0c2c82af1e4.words; +#if !CAPNP_LITE +static const uint16_t m_cfa2b0c2c82af1e4[] = {3, 1, 4, 2, 0}; +static const uint16_t i_cfa2b0c2c82af1e4[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_cfa2b0c2c82af1e4 = { + 0xcfa2b0c2c82af1e4, b_cfa2b0c2c82af1e4.words, 95, nullptr, m_cfa2b0c2c82af1e4, + 0, 5, i_cfa2b0c2c82af1e4, nullptr, nullptr, { &s_cfa2b0c2c82af1e4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<81> b_c08240f996aefced = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 85, 73, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c08240f996aefced = b_c08240f996aefced.words; +#if !CAPNP_LITE +static const uint16_t m_c08240f996aefced[] = {1, 2, 3, 0}; +static const uint16_t i_c08240f996aefced[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c08240f996aefced = { + 0xc08240f996aefced, b_c08240f996aefced.words, 81, nullptr, m_c08240f996aefced, + 0, 4, i_c08240f996aefced, nullptr, nullptr, { &s_c08240f996aefced, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 50, 48, + 68, 97, 116, 97, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 1, 0, 0, 0, 74, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 79, 110, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 84, 119, 111, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 116, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9a185389d6fdd05f = b_9a185389d6fdd05f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9a185389d6fdd05f[] = { + &s_b96f3ad9170cf085, +}; +static const uint16_t m_9a185389d6fdd05f[] = {1, 8, 9, 2, 10, 5, 7, 3, 4, 6, 0}; +static const uint16_t i_9a185389d6fdd05f[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_9a185389d6fdd05f = { + 0x9a185389d6fdd05f, b_9a185389d6fdd05f.words, 202, d_9a185389d6fdd05f, m_9a185389d6fdd05f, + 1, 11, i_9a185389d6fdd05f, nullptr, nullptr, { &s_9a185389d6fdd05f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<198> b_b96f3ad9170cf085 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 21, 0, 0, 0, 1, 0, 6, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 167, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 50, 48, + 68, 97, 116, 97, 46, 76, 101, 97, + 100, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 64, 1, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 65, 1, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 97, 116, 104, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 97, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b96f3ad9170cf085 = b_b96f3ad9170cf085.words; +#if !CAPNP_LITE +static const uint16_t m_b96f3ad9170cf085[] = {5, 9, 3, 6, 0, 10, 11, 7, 4, 8, 2, 1}; +static const uint16_t i_b96f3ad9170cf085[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; +const ::capnp::_::RawSchema s_b96f3ad9170cf085 = { + 0xb96f3ad9170cf085, b_b96f3ad9170cf085.words, 198, nullptr, m_b96f3ad9170cf085, + 0, 12, i_b96f3ad9170cf085, nullptr, nullptr, { &s_b96f3ad9170cf085, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<85> b_96df70754d8390bc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 67, 97, + 108, 105, 98, 114, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_96df70754d8390bc = b_96df70754d8390bc.words; +#if !CAPNP_LITE +static const uint16_t m_96df70754d8390bc[] = {2, 3, 1, 0}; +static const uint16_t i_96df70754d8390bc[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_96df70754d8390bc = { + 0x96df70754d8390bc, b_96df70754d8390bc.words, 85, nullptr, m_96df70754d8390bc, + 0, 4, i_96df70754d8390bc, nullptr, nullptr, { &s_96df70754d8390bc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<171> b_8faa644732dec251 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 84, 114, + 97, 99, 107, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 0, 1, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 1, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 99, 107, 73, 100, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 83, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 105, 111, 110, 97, + 114, 121, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 110, 99, 111, 109, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8faa644732dec251 = b_8faa644732dec251.words; +#if !CAPNP_LITE +static const uint16_t m_8faa644732dec251[] = {4, 7, 1, 9, 8, 6, 5, 0, 3, 2}; +static const uint16_t i_8faa644732dec251[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_8faa644732dec251 = { + 0x8faa644732dec251, b_8faa644732dec251.words, 171, nullptr, m_8faa644732dec251, + 0, 10, i_8faa644732dec251, nullptr, nullptr, { &s_8faa644732dec251, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 10, 0, 0, 0, 1, 0, 13, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 239, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 49, 48, + 48, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 108, 0, 0, 0, 3, 0, 4, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 3, 0, 0, 3, 0, 1, 0, + 80, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 192, 2, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 193, 2, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 132, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 194, 2, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 3, 0, 0, 3, 0, 1, 0, + 168, 3, 0, 0, 2, 0, 1, 0, + 118, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 80, 105, 100, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 84, 97, 114, 103, 101, 116, 76, + 101, 97, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 65, 99, 116, 117, 97, 108, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 68, 101, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 83, 116, 101, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 83, 116, 101, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 105, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 97, 120, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 101, 114, 107, 70, 97, 99, 116, + 111, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 83, 116, 101, + 101, 114, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 117, 100, 76, 101, 97, 100, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 50, 48, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_97ff69c53601abf1 = b_97ff69c53601abf1.words; +#if !CAPNP_LITE +static const uint16_t m_97ff69c53601abf1[] = {1, 11, 10, 24, 25, 13, 26, 16, 21, 15, 19, 14, 12, 17, 18, 23, 20, 5, 9, 4, 8, 22, 0, 2, 3, 6, 7}; +static const uint16_t i_97ff69c53601abf1[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26}; +const ::capnp::_::RawSchema s_97ff69c53601abf1 = { + 0x97ff69c53601abf1, b_97ff69c53601abf1.words, 443, nullptr, m_97ff69c53601abf1, + 0, 27, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<47> b_94b7baa90c5c321e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 69, 118, + 101, 110, 116, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_94b7baa90c5c321e = b_94b7baa90c5c321e.words; +#if !CAPNP_LITE +static const uint16_t m_94b7baa90c5c321e[] = {0, 1}; +static const uint16_t i_94b7baa90c5c321e[] = {0, 1}; +const ::capnp::_::RawSchema s_94b7baa90c5c321e = { + 0x94b7baa90c5c321e, b_94b7baa90c5c321e.words, 47, nullptr, m_94b7baa90c5c321e, + 0, 2, i_94b7baa90c5c321e, nullptr, nullptr, { &s_94b7baa90c5c321e, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<122> b_b8aad62cffef28a9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 17, 0, 0, 0, 74, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 17, 0, 0, 0, 74, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 17, 0, 0, 0, 114, 0, 0, 0, + 80, 97, 116, 104, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 111, 100, 101, 108, 83, 101, 116, + 116, 105, 110, 103, 115, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 76, 97, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 76, 97, 110, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 116, 116, 105, 110, 103, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b8aad62cffef28a9 = b_b8aad62cffef28a9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b8aad62cffef28a9[] = { + &s_8817eeea389e9f08, + &s_a26e3710efd3e914, + &s_d1c9bef96d26fa91, +}; +static const uint16_t m_b8aad62cffef28a9[] = {0, 4, 2, 1, 3, 5}; +static const uint16_t i_b8aad62cffef28a9[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_b8aad62cffef28a9 = { + 0xb8aad62cffef28a9, b_b8aad62cffef28a9.words, 122, d_b8aad62cffef28a9, m_b8aad62cffef28a9, + 3, 6, i_b8aad62cffef28a9, nullptr, nullptr, { &s_b8aad62cffef28a9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_8817eeea389e9f08 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 20, 0, 0, 0, 1, 0, 1, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 80, 97, 116, 104, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8817eeea389e9f08 = b_8817eeea389e9f08.words; +#if !CAPNP_LITE +static const uint16_t m_8817eeea389e9f08[] = {0, 1, 2}; +static const uint16_t i_8817eeea389e9f08[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_8817eeea389e9f08 = { + 0x8817eeea389e9f08, b_8817eeea389e9f08.words, 67, nullptr, m_8817eeea389e9f08, + 0, 3, i_8817eeea389e9f08, nullptr, nullptr, { &s_8817eeea389e9f08, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_d1c9bef96d26fa91 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 20, 0, 0, 0, 1, 0, 2, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 76, 101, 97, 100, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 100, 105, 115, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d1c9bef96d26fa91 = b_d1c9bef96d26fa91.words; +#if !CAPNP_LITE +static const uint16_t m_d1c9bef96d26fa91[] = {0, 1, 2}; +static const uint16_t i_d1c9bef96d26fa91[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d1c9bef96d26fa91 = { + 0xd1c9bef96d26fa91, b_d1c9bef96d26fa91.words, 63, nullptr, m_d1c9bef96d26fa91, + 0, 3, i_d1c9bef96d26fa91, nullptr, nullptr, { &s_d1c9bef96d26fa91, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<121> b_a26e3710efd3e914 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 20, 0, 0, 0, 1, 0, 1, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 46, 77, 111, 100, 101, + 108, 83, 101, 116, 116, 105, 110, 103, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 98, 105, 103, 66, 111, 120, 88, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 89, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 87, 105, + 100, 116, 104, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 101, + 105, 103, 104, 116, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 111, 120, 80, 114, 111, 106, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 117, 118, 67, 111, 114, 114, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a26e3710efd3e914 = b_a26e3710efd3e914.words; +#if !CAPNP_LITE +static const uint16_t m_a26e3710efd3e914[] = {3, 2, 0, 1, 4, 5}; +static const uint16_t i_a26e3710efd3e914[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_a26e3710efd3e914 = { + 0xa26e3710efd3e914, b_a26e3710efd3e914.words, 121, nullptr, m_a26e3710efd3e914, + 0, 6, i_a26e3710efd3e914, nullptr, nullptr, { &s_a26e3710efd3e914, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<90> b_8fdfadb254ea867a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 108, 105, 98, 114, + 97, 116, 105, 111, 110, 70, 101, 97, + 116, 117, 114, 101, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 48, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 49, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8fdfadb254ea867a = b_8fdfadb254ea867a.words; +#if !CAPNP_LITE +static const uint16_t m_8fdfadb254ea867a[] = {0, 1, 2, 3}; +static const uint16_t i_8fdfadb254ea867a[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8fdfadb254ea867a = { + 0x8fdfadb254ea867a, b_8fdfadb254ea867a.words, 90, nullptr, m_8fdfadb254ea867a, + 0, 4, i_8fdfadb254ea867a, nullptr, nullptr, { &s_8fdfadb254ea867a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<98> b_89d394e3541735fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 1, 0, 0, 0, 42, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 73, + 100, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_89d394e3541735fc = b_89d394e3541735fc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_89d394e3541735fc[] = { + &s_c0ad259ec157ccd3, +}; +static const uint16_t m_89d394e3541735fc[] = {2, 0, 4, 3, 1}; +static const uint16_t i_89d394e3541735fc[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_89d394e3541735fc = { + 0x89d394e3541735fc, b_89d394e3541735fc.words, 98, d_89d394e3541735fc, m_89d394e3541735fc, + 1, 5, i_89d394e3541735fc, nullptr, nullptr, { &s_89d394e3541735fc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_c0ad259ec157ccd3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 22, 0, 0, 0, 2, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 46, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 76, 111, + 115, 115, 108, 101, 115, 115, 0, 0, + 102, 117, 108, 108, 72, 69, 86, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 69, + 86, 67, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0ad259ec157ccd3 = b_c0ad259ec157ccd3.words; +#if !CAPNP_LITE +static const uint16_t m_c0ad259ec157ccd3[] = {2, 0, 1}; +const ::capnp::_::RawSchema s_c0ad259ec157ccd3 = { + 0xc0ad259ec157ccd3, b_c0ad259ec157ccd3.words, 33, nullptr, m_c0ad259ec157ccd3, + 0, 3, nullptr, nullptr, nullptr, { &s_c0ad259ec157ccd3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_c0ad259ec157ccd3, c0ad259ec157ccd3); +static const ::capnp::_::AlignedData<124> b_ea095da1894f7d85 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 65, 110, 100, 114, 111, 105, + 100, 76, 111, 103, 69, 110, 116, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 115, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 105, 111, 114, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 103, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 115, 97, 103, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea095da1894f7d85 = b_ea095da1894f7d85.words; +#if !CAPNP_LITE +static const uint16_t m_ea095da1894f7d85[] = {0, 6, 3, 2, 5, 4, 1}; +static const uint16_t i_ea095da1894f7d85[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ea095da1894f7d85 = { + 0xea095da1894f7d85, b_ea095da1894f7d85.words, 124, nullptr, m_ea095da1894f7d85, + 0, 7, i_ea095da1894f7d85, nullptr, nullptr, { &s_ea095da1894f7d85, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_9811e1f38f62f2d1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 209, 242, 98, 143, 243, 225, 17, 152, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 103, 82, 111, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9811e1f38f62f2d1 = b_9811e1f38f62f2d1.words; +#if !CAPNP_LITE +static const uint16_t m_9811e1f38f62f2d1[] = {1, 0}; +static const uint16_t i_9811e1f38f62f2d1[] = {0, 1}; +const ::capnp::_::RawSchema s_9811e1f38f62f2d1 = { + 0x9811e1f38f62f2d1, b_9811e1f38f62f2d1.words, 48, nullptr, m_9811e1f38f62f2d1, + 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<366> b_d314cfd957229c11 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 17, 156, 34, 87, 217, 207, 20, 211, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 20, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 0, 0, 0, + 25, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 159, 4, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 118, 101, 110, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 84, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 72, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 2, 0, 0, 3, 0, 1, 0, + 80, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 2, 0, 0, 3, 0, 1, 0, + 84, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 2, 0, 0, 3, 0, 1, 0, + 100, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 2, 0, 0, 3, 0, 1, 0, + 120, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 250, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 249, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 248, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 247, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 2, 0, 0, 3, 0, 1, 0, + 160, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 246, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 2, 0, 0, 3, 0, 1, 0, + 168, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 245, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 2, 0, 0, 3, 0, 1, 0, + 192, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 244, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 243, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 2, 0, 0, 3, 0, 1, 0, + 200, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 242, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 241, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 240, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 239, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 238, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 237, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 236, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 3, 0, 0, 3, 0, 1, 0, + 32, 3, 0, 0, 2, 0, 1, 0, + 108, 111, 103, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 105, 116, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 78, 77, 69, 65, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 114, 109, 97, 108, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 224, 230, 127, 11, 164, 49, 130, 141, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 49, 48, 48, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 69, 118, 101, 110, + 116, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 97, 116, 117, 114, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 108, 116, 104, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 228, 241, 42, 200, 194, 176, 162, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 50, 48, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 85, 73, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 120, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 84, 114, 97, 99, + 107, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 100, 99, 97, 110, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 77, 101, 115, 115, 97, + 103, 101, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 67, 97, 108, 105, + 98, 114, 97, 116, 105, 111, 110, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 76, + 111, 103, 69, 110, 116, 114, 121, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d314cfd957229c11 = b_d314cfd957229c11.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { + &s_8785009a964c7c59, + &s_89d394e3541735fc, + &s_8d8231a40b7fe6e0, + &s_8faa644732dec251, + &s_8fdfadb254ea867a, + &s_94b7baa90c5c321e, + &s_96df70754d8390bc, + &s_97ff69c53601abf1, + &s_9a185389d6fdd05f, + &s_9d291d7813ba4a88, + &s_a2b29a69d44529a1, + &s_b8aad62cffef28a9, + &s_c08240f996aefced, + &s_cfa2b0c2c82af1e4, + &s_e71008caeb3fb65c, + &s_ea0245f695ae0a33, + &s_ea095da1894f7d85, +}; +static const uint16_t m_d314cfd957229c11[] = {20, 5, 15, 10, 2, 3, 12, 1, 7, 13, 19, 8, 16, 14, 18, 0, 9, 17, 4, 11, 6}; +static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 0}; +const ::capnp::_::RawSchema s_d314cfd957229c11 = { + 0xd314cfd957229c11, b_d314cfd957229c11.words, 366, d_d314cfd957229c11, m_d314cfd957229c11, + 17, 21, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// InitData +#ifndef _MSC_VER +constexpr uint16_t InitData::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind InitData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* InitData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// FrameData +#ifndef _MSC_VER +constexpr uint16_t FrameData::_capnpPrivate::dataWordSize; +constexpr uint16_t FrameData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind FrameData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrameData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* FrameData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// GPSNMEAData +#ifndef _MSC_VER +constexpr uint16_t GPSNMEAData::_capnpPrivate::dataWordSize; +constexpr uint16_t GPSNMEAData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind GPSNMEAData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GPSNMEAData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* GPSNMEAData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// SensorEventData +#ifndef _MSC_VER +constexpr uint16_t SensorEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind SensorEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// SensorEventData::SensorVec +#ifndef _MSC_VER +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind SensorEventData::SensorVec::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::SensorVec::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* SensorEventData::SensorVec::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// CanData +#ifndef _MSC_VER +constexpr uint16_t CanData::_capnpPrivate::dataWordSize; +constexpr uint16_t CanData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind CanData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CanData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* CanData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ThermalData +#ifndef _MSC_VER +constexpr uint16_t ThermalData::_capnpPrivate::dataWordSize; +constexpr uint16_t ThermalData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ThermalData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ThermalData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ThermalData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// HealthData +#ifndef _MSC_VER +constexpr uint16_t HealthData::_capnpPrivate::dataWordSize; +constexpr uint16_t HealthData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind HealthData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* HealthData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* HealthData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveUI +#ifndef _MSC_VER +constexpr uint16_t LiveUI::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveUI::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveUI::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveUI::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveUI::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live20Data +#ifndef _MSC_VER +constexpr uint16_t Live20Data::_capnpPrivate::dataWordSize; +constexpr uint16_t Live20Data::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live20Data::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live20Data::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live20Data::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live20Data::LeadData +#ifndef _MSC_VER +constexpr uint16_t Live20Data::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t Live20Data::LeadData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live20Data::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live20Data::LeadData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live20Data::LeadData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveCalibrationData +#ifndef _MSC_VER +constexpr uint16_t LiveCalibrationData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveCalibrationData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveCalibrationData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveCalibrationData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveCalibrationData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveTracks +#ifndef _MSC_VER +constexpr uint16_t LiveTracks::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveTracks::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveTracks::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveTracks::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveTracks::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Live100Data +#ifndef _MSC_VER +constexpr uint16_t Live100Data::_capnpPrivate::dataWordSize; +constexpr uint16_t Live100Data::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Live100Data::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Live100Data::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Live100Data::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LiveEventData +#ifndef _MSC_VER +constexpr uint16_t LiveEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveEventData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LiveEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveEventData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LiveEventData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData +#ifndef _MSC_VER +constexpr uint16_t ModelData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::PathData +#ifndef _MSC_VER +constexpr uint16_t ModelData::PathData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::PathData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::PathData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::PathData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::PathData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::LeadData +#ifndef _MSC_VER +constexpr uint16_t ModelData::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::LeadData::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::LeadData::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::LeadData::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// ModelData::ModelSettings +#ifndef _MSC_VER +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind ModelData::ModelSettings::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::ModelSettings::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* ModelData::ModelSettings::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// CalibrationFeatures +#ifndef _MSC_VER +constexpr uint16_t CalibrationFeatures::_capnpPrivate::dataWordSize; +constexpr uint16_t CalibrationFeatures::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind CalibrationFeatures::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CalibrationFeatures::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* CalibrationFeatures::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// EncodeIndex +#ifndef _MSC_VER +constexpr uint16_t EncodeIndex::_capnpPrivate::dataWordSize; +constexpr uint16_t EncodeIndex::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind EncodeIndex::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* EncodeIndex::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* EncodeIndex::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// AndroidLogEntry +#ifndef _MSC_VER +constexpr uint16_t AndroidLogEntry::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidLogEntry::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind AndroidLogEntry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidLogEntry::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* AndroidLogEntry::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// LogRotate +#ifndef _MSC_VER +constexpr uint16_t LogRotate::_capnpPrivate::dataWordSize; +constexpr uint16_t LogRotate::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind LogRotate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LogRotate::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* LogRotate::_capnpPrivate::brand; +#endif // !CAPNP_LITE + +// Event +#ifndef _MSC_VER +constexpr uint16_t Event::_capnpPrivate::dataWordSize; +constexpr uint16_t Event::_capnpPrivate::pointerCount; +#endif +#if !CAPNP_LITE +constexpr ::capnp::Kind Event::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Event::_capnpPrivate::schema; +constexpr ::capnp::_::RawBrandedSchema const* Event::_capnpPrivate::brand; +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/gen/cpp/log.capnp.h b/cereal/gen/cpp/log.capnp.h new file mode 100644 index 0000000000..d5a4456386 --- /dev/null +++ b/cereal/gen/cpp/log.capnp.h @@ -0,0 +1,7251 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: log.capnp + +#ifndef CAPNP_INCLUDED_f3b1f17e25a4285b_ +#define CAPNP_INCLUDED_f3b1f17e25a4285b_ + +#include + +#if CAPNP_VERSION != 5003 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(d578fb3372ed5043); +CAPNP_DECLARE_SCHEMA(e71008caeb3fb65c); +CAPNP_DECLARE_SCHEMA(ea0245f695ae0a33); +CAPNP_DECLARE_SCHEMA(9d291d7813ba4a88); +CAPNP_DECLARE_SCHEMA(a2b29a69d44529a1); +CAPNP_DECLARE_SCHEMA(a43429bd2bfc24fc); +CAPNP_DECLARE_SCHEMA(8785009a964c7c59); +CAPNP_DECLARE_SCHEMA(8d8231a40b7fe6e0); +CAPNP_DECLARE_SCHEMA(cfa2b0c2c82af1e4); +CAPNP_DECLARE_SCHEMA(c08240f996aefced); +CAPNP_DECLARE_SCHEMA(9a185389d6fdd05f); +CAPNP_DECLARE_SCHEMA(b96f3ad9170cf085); +CAPNP_DECLARE_SCHEMA(96df70754d8390bc); +CAPNP_DECLARE_SCHEMA(8faa644732dec251); +CAPNP_DECLARE_SCHEMA(97ff69c53601abf1); +CAPNP_DECLARE_SCHEMA(94b7baa90c5c321e); +CAPNP_DECLARE_SCHEMA(b8aad62cffef28a9); +CAPNP_DECLARE_SCHEMA(8817eeea389e9f08); +CAPNP_DECLARE_SCHEMA(d1c9bef96d26fa91); +CAPNP_DECLARE_SCHEMA(a26e3710efd3e914); +CAPNP_DECLARE_SCHEMA(8fdfadb254ea867a); +CAPNP_DECLARE_SCHEMA(89d394e3541735fc); +CAPNP_DECLARE_SCHEMA(c0ad259ec157ccd3); +enum class Type_c0ad259ec157ccd3: uint16_t { + BIG_BOX_LOSSLESS, + FULL_H_E_V_C, + BIG_BOX_H_E_V_C, +}; +CAPNP_DECLARE_ENUM(Type, c0ad259ec157ccd3); +CAPNP_DECLARE_SCHEMA(ea095da1894f7d85); +CAPNP_DECLARE_SCHEMA(9811e1f38f62f2d1); +CAPNP_DECLARE_SCHEMA(d314cfd957229c11); + +} // namespace schemas +} // namespace capnp + +namespace cereal { + +static constexpr ::int32_t LOG_VERSION = 1; +struct InitData { + InitData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e71008caeb3fb65c, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct FrameData { + FrameData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ea0245f695ae0a33, 4, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct GPSNMEAData { + GPSNMEAData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9d291d7813ba4a88, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct SensorEventData { + SensorEventData() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + ACCELERATION, + MAGNETIC, + ORIENTATION, + GYRO, + }; + struct SensorVec; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a2b29a69d44529a1, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct SensorEventData::SensorVec { + SensorVec() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a43429bd2bfc24fc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct CanData { + CanData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8785009a964c7c59, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ThermalData { + ThermalData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct HealthData { + HealthData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cfa2b0c2c82af1e4, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveUI { + LiveUI() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c08240f996aefced, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live20Data { + Live20Data() = delete; + + class Reader; + class Builder; + class Pipeline; + struct LeadData; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9a185389d6fdd05f, 4, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live20Data::LeadData { + LeadData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b96f3ad9170cf085, 6, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveCalibrationData { + LiveCalibrationData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(96df70754d8390bc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveTracks { + LiveTracks() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8faa644732dec251, 5, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Live100Data { + Live100Data() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(97ff69c53601abf1, 13, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LiveEventData { + LiveEventData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(94b7baa90c5c321e, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData { + ModelData() = delete; + + class Reader; + class Builder; + class Pipeline; + struct PathData; + struct LeadData; + struct ModelSettings; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b8aad62cffef28a9, 1, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::PathData { + PathData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8817eeea389e9f08, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::LeadData { + LeadData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d1c9bef96d26fa91, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct ModelData::ModelSettings { + ModelSettings() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a26e3710efd3e914, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct CalibrationFeatures { + CalibrationFeatures() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8fdfadb254ea867a, 1, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct EncodeIndex { + EncodeIndex() = delete; + + class Reader; + class Builder; + class Pipeline; + typedef ::capnp::schemas::Type_c0ad259ec157ccd3 Type; + + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(89d394e3541735fc, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct AndroidLogEntry { + AndroidLogEntry() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ea095da1894f7d85, 3, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct LogRotate { + LogRotate() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9811e1f38f62f2d1, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +struct Event { + Event() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + INIT_DATA, + FRAME, + GPS_N_M_E_A, + SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + CAN, + THERMAL, + LIVE100, + LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + MODEL, + FEATURES, + SENSOR_EVENTS, + HEALTH, + LIVE20, + LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + ENCODE_IDX, + LIVE_TRACKS, + SENDCAN, + LOG_MESSAGE, + LIVE_CALIBRATION, + ANDROID_LOG_ENTRY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d314cfd957229c11, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class InitData::Reader { +public: + typedef InitData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasKernelArgs() const; + inline ::capnp::List< ::capnp::Text>::Reader getKernelArgs() const; + + inline bool hasGctx() const; + inline ::capnp::Text::Reader getGctx() const; + + inline bool hasDongleId() const; + inline ::capnp::Text::Reader getDongleId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InitData::Builder { +public: + typedef InitData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasKernelArgs(); + inline ::capnp::List< ::capnp::Text>::Builder getKernelArgs(); + inline void setKernelArgs( ::capnp::List< ::capnp::Text>::Reader value); + inline void setKernelArgs(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text>::Builder initKernelArgs(unsigned int size); + inline void adoptKernelArgs(::capnp::Orphan< ::capnp::List< ::capnp::Text>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text>> disownKernelArgs(); + + inline bool hasGctx(); + inline ::capnp::Text::Builder getGctx(); + inline void setGctx( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initGctx(unsigned int size); + inline void adoptGctx(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownGctx(); + + inline bool hasDongleId(); + inline ::capnp::Text::Builder getDongleId(); + inline void setDongleId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDongleId(unsigned int size); + inline void adoptDongleId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDongleId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InitData::Pipeline { +public: + typedef InitData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class FrameData::Reader { +public: + typedef FrameData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline ::uint32_t getEncodeId() const; + + inline ::uint64_t getTimestampEof() const; + + inline ::int32_t getFrameLength() const; + + inline ::int32_t getIntegLines() const; + + inline ::int32_t getGlobalGain() const; + + inline bool hasImage() const; + inline ::capnp::Data::Reader getImage() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class FrameData::Builder { +public: + typedef FrameData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline ::uint32_t getEncodeId(); + inline void setEncodeId( ::uint32_t value); + + inline ::uint64_t getTimestampEof(); + inline void setTimestampEof( ::uint64_t value); + + inline ::int32_t getFrameLength(); + inline void setFrameLength( ::int32_t value); + + inline ::int32_t getIntegLines(); + inline void setIntegLines( ::int32_t value); + + inline ::int32_t getGlobalGain(); + inline void setGlobalGain( ::int32_t value); + + inline bool hasImage(); + inline ::capnp::Data::Builder getImage(); + inline void setImage( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initImage(unsigned int size); + inline void adoptImage(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownImage(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class FrameData::Pipeline { +public: + typedef FrameData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GPSNMEAData::Reader { +public: + typedef GPSNMEAData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int64_t getTimestamp() const; + + inline ::uint64_t getLocalWallTime() const; + + inline bool hasNmea() const; + inline ::capnp::Text::Reader getNmea() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GPSNMEAData::Builder { +public: + typedef GPSNMEAData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int64_t getTimestamp(); + inline void setTimestamp( ::int64_t value); + + inline ::uint64_t getLocalWallTime(); + inline void setLocalWallTime( ::uint64_t value); + + inline bool hasNmea(); + inline ::capnp::Text::Builder getNmea(); + inline void setNmea( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initNmea(unsigned int size); + inline void adoptNmea(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownNmea(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GPSNMEAData::Pipeline { +public: + typedef GPSNMEAData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class SensorEventData::Reader { +public: + typedef SensorEventData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::int32_t getVersion() const; + + inline ::int32_t getSensor() const; + + inline ::int32_t getType() const; + + inline ::int64_t getTimestamp() const; + + inline bool isAcceleration() const; + inline bool hasAcceleration() const; + inline ::cereal::SensorEventData::SensorVec::Reader getAcceleration() const; + + inline bool isMagnetic() const; + inline bool hasMagnetic() const; + inline ::cereal::SensorEventData::SensorVec::Reader getMagnetic() const; + + inline bool isOrientation() const; + inline bool hasOrientation() const; + inline ::cereal::SensorEventData::SensorVec::Reader getOrientation() const; + + inline bool isGyro() const; + inline bool hasGyro() const; + inline ::cereal::SensorEventData::SensorVec::Reader getGyro() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class SensorEventData::Builder { +public: + typedef SensorEventData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::int32_t getVersion(); + inline void setVersion( ::int32_t value); + + inline ::int32_t getSensor(); + inline void setSensor( ::int32_t value); + + inline ::int32_t getType(); + inline void setType( ::int32_t value); + + inline ::int64_t getTimestamp(); + inline void setTimestamp( ::int64_t value); + + inline bool isAcceleration(); + inline bool hasAcceleration(); + inline ::cereal::SensorEventData::SensorVec::Builder getAcceleration(); + inline void setAcceleration( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initAcceleration(); + inline void adoptAcceleration(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownAcceleration(); + + inline bool isMagnetic(); + inline bool hasMagnetic(); + inline ::cereal::SensorEventData::SensorVec::Builder getMagnetic(); + inline void setMagnetic( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initMagnetic(); + inline void adoptMagnetic(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownMagnetic(); + + inline bool isOrientation(); + inline bool hasOrientation(); + inline ::cereal::SensorEventData::SensorVec::Builder getOrientation(); + inline void setOrientation( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initOrientation(); + inline void adoptOrientation(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownOrientation(); + + inline bool isGyro(); + inline bool hasGyro(); + inline ::cereal::SensorEventData::SensorVec::Builder getGyro(); + inline void setGyro( ::cereal::SensorEventData::SensorVec::Reader value); + inline ::cereal::SensorEventData::SensorVec::Builder initGyro(); + inline void adoptGyro(::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> disownGyro(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class SensorEventData::Pipeline { +public: + typedef SensorEventData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class SensorEventData::SensorVec::Reader { +public: + typedef SensorVec Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasV() const; + inline ::capnp::List::Reader getV() const; + + inline ::int8_t getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class SensorEventData::SensorVec::Builder { +public: + typedef SensorVec Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasV(); + inline ::capnp::List::Builder getV(); + inline void setV( ::capnp::List::Reader value); + inline void setV(::kj::ArrayPtr value); + inline ::capnp::List::Builder initV(unsigned int size); + inline void adoptV(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownV(); + + inline ::int8_t getStatus(); + inline void setStatus( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class SensorEventData::SensorVec::Pipeline { +public: + typedef SensorVec Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CanData::Reader { +public: + typedef CanData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getAddress() const; + + inline ::uint16_t getBusTime() const; + + inline bool hasDat() const; + inline ::capnp::Data::Reader getDat() const; + + inline ::int8_t getSrc() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CanData::Builder { +public: + typedef CanData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getAddress(); + inline void setAddress( ::uint32_t value); + + inline ::uint16_t getBusTime(); + inline void setBusTime( ::uint16_t value); + + inline bool hasDat(); + inline ::capnp::Data::Builder getDat(); + inline void setDat( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initDat(unsigned int size); + inline void adoptDat(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownDat(); + + inline ::int8_t getSrc(); + inline void setSrc( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CanData::Pipeline { +public: + typedef CanData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThermalData::Reader { +public: + typedef ThermalData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getCpu0() const; + + inline ::uint16_t getCpu1() const; + + inline ::uint16_t getCpu2() const; + + inline ::uint16_t getCpu3() const; + + inline ::uint16_t getMem() const; + + inline ::uint16_t getGpu() const; + + inline ::uint32_t getBat() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThermalData::Builder { +public: + typedef ThermalData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getCpu0(); + inline void setCpu0( ::uint16_t value); + + inline ::uint16_t getCpu1(); + inline void setCpu1( ::uint16_t value); + + inline ::uint16_t getCpu2(); + inline void setCpu2( ::uint16_t value); + + inline ::uint16_t getCpu3(); + inline void setCpu3( ::uint16_t value); + + inline ::uint16_t getMem(); + inline void setMem( ::uint16_t value); + + inline ::uint16_t getGpu(); + inline void setGpu( ::uint16_t value); + + inline ::uint32_t getBat(); + inline void setBat( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThermalData::Pipeline { +public: + typedef ThermalData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class HealthData::Reader { +public: + typedef HealthData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getVoltage() const; + + inline ::uint32_t getCurrent() const; + + inline bool getStarted() const; + + inline bool getControlsAllowed() const; + + inline bool getGasInterceptorDetected() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class HealthData::Builder { +public: + typedef HealthData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getVoltage(); + inline void setVoltage( ::uint32_t value); + + inline ::uint32_t getCurrent(); + inline void setCurrent( ::uint32_t value); + + inline bool getStarted(); + inline void setStarted(bool value); + + inline bool getControlsAllowed(); + inline void setControlsAllowed(bool value); + + inline bool getGasInterceptorDetected(); + inline void setGasInterceptorDetected(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class HealthData::Pipeline { +public: + typedef HealthData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveUI::Reader { +public: + typedef LiveUI Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool getRearViewCam() const; + + inline bool hasAlertText1() const; + inline ::capnp::Text::Reader getAlertText1() const; + + inline bool hasAlertText2() const; + inline ::capnp::Text::Reader getAlertText2() const; + + inline float getAwarenessStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveUI::Builder { +public: + typedef LiveUI Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool getRearViewCam(); + inline void setRearViewCam(bool value); + + inline bool hasAlertText1(); + inline ::capnp::Text::Builder getAlertText1(); + inline void setAlertText1( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText1(unsigned int size); + inline void adoptAlertText1(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText1(); + + inline bool hasAlertText2(); + inline ::capnp::Text::Builder getAlertText2(); + inline void setAlertText2( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText2(unsigned int size); + inline void adoptAlertText2(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText2(); + + inline float getAwarenessStatus(); + inline void setAwarenessStatus(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveUI::Pipeline { +public: + typedef LiveUI Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live20Data::Reader { +public: + typedef Live20Data Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix() const; + inline ::capnp::List::Reader getWarpMatrix() const; + + inline float getAngleOffset() const; + + inline ::int8_t getCalStatus() const; + + inline bool hasLeadOne() const; + inline ::cereal::Live20Data::LeadData::Reader getLeadOne() const; + + inline bool hasLeadTwo() const; + inline ::cereal::Live20Data::LeadData::Reader getLeadTwo() const; + + inline float getCumLagMs() const; + + inline ::uint64_t getMdMonoTime() const; + + inline ::uint64_t getFtMonoTime() const; + + inline ::int32_t getCalCycle() const; + + inline ::int8_t getCalPerc() const; + + inline bool hasCanMonoTimes() const; + inline ::capnp::List< ::uint64_t>::Reader getCanMonoTimes() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live20Data::Builder { +public: + typedef Live20Data Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix(); + inline ::capnp::List::Builder getWarpMatrix(); + inline void setWarpMatrix( ::capnp::List::Reader value); + inline void setWarpMatrix(::kj::ArrayPtr value); + inline ::capnp::List::Builder initWarpMatrix(unsigned int size); + inline void adoptWarpMatrix(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownWarpMatrix(); + + inline float getAngleOffset(); + inline void setAngleOffset(float value); + + inline ::int8_t getCalStatus(); + inline void setCalStatus( ::int8_t value); + + inline bool hasLeadOne(); + inline ::cereal::Live20Data::LeadData::Builder getLeadOne(); + inline void setLeadOne( ::cereal::Live20Data::LeadData::Reader value); + inline ::cereal::Live20Data::LeadData::Builder initLeadOne(); + inline void adoptLeadOne(::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> disownLeadOne(); + + inline bool hasLeadTwo(); + inline ::cereal::Live20Data::LeadData::Builder getLeadTwo(); + inline void setLeadTwo( ::cereal::Live20Data::LeadData::Reader value); + inline ::cereal::Live20Data::LeadData::Builder initLeadTwo(); + inline void adoptLeadTwo(::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> disownLeadTwo(); + + inline float getCumLagMs(); + inline void setCumLagMs(float value); + + inline ::uint64_t getMdMonoTime(); + inline void setMdMonoTime( ::uint64_t value); + + inline ::uint64_t getFtMonoTime(); + inline void setFtMonoTime( ::uint64_t value); + + inline ::int32_t getCalCycle(); + inline void setCalCycle( ::int32_t value); + + inline ::int8_t getCalPerc(); + inline void setCalPerc( ::int8_t value); + + inline bool hasCanMonoTimes(); + inline ::capnp::List< ::uint64_t>::Builder getCanMonoTimes(); + inline void setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value); + inline void setCanMonoTimes(::kj::ArrayPtr value); + inline ::capnp::List< ::uint64_t>::Builder initCanMonoTimes(unsigned int size); + inline void adoptCanMonoTimes(::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> disownCanMonoTimes(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live20Data::Pipeline { +public: + typedef Live20Data Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::cereal::Live20Data::LeadData::Pipeline getLeadOne(); + inline ::cereal::Live20Data::LeadData::Pipeline getLeadTwo(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live20Data::LeadData::Reader { +public: + typedef LeadData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getDRel() const; + + inline float getYRel() const; + + inline float getVRel() const; + + inline float getARel() const; + + inline float getVLead() const; + + inline float getALead() const; + + inline float getDPath() const; + + inline float getVLat() const; + + inline float getVLeadK() const; + + inline float getALeadK() const; + + inline bool getFcw() const; + + inline bool getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live20Data::LeadData::Builder { +public: + typedef LeadData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getDRel(); + inline void setDRel(float value); + + inline float getYRel(); + inline void setYRel(float value); + + inline float getVRel(); + inline void setVRel(float value); + + inline float getARel(); + inline void setARel(float value); + + inline float getVLead(); + inline void setVLead(float value); + + inline float getALead(); + inline void setALead(float value); + + inline float getDPath(); + inline void setDPath(float value); + + inline float getVLat(); + inline void setVLat(float value); + + inline float getVLeadK(); + inline void setVLeadK(float value); + + inline float getALeadK(); + inline void setALeadK(float value); + + inline bool getFcw(); + inline void setFcw(bool value); + + inline bool getStatus(); + inline void setStatus(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live20Data::LeadData::Pipeline { +public: + typedef LeadData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveCalibrationData::Reader { +public: + typedef LiveCalibrationData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix() const; + inline ::capnp::List::Reader getWarpMatrix() const; + + inline ::int8_t getCalStatus() const; + + inline ::int32_t getCalCycle() const; + + inline ::int8_t getCalPerc() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveCalibrationData::Builder { +public: + typedef LiveCalibrationData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasWarpMatrix(); + inline ::capnp::List::Builder getWarpMatrix(); + inline void setWarpMatrix( ::capnp::List::Reader value); + inline void setWarpMatrix(::kj::ArrayPtr value); + inline ::capnp::List::Builder initWarpMatrix(unsigned int size); + inline void adoptWarpMatrix(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownWarpMatrix(); + + inline ::int8_t getCalStatus(); + inline void setCalStatus( ::int8_t value); + + inline ::int32_t getCalCycle(); + inline void setCalCycle( ::int32_t value); + + inline ::int8_t getCalPerc(); + inline void setCalPerc( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveCalibrationData::Pipeline { +public: + typedef LiveCalibrationData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveTracks::Reader { +public: + typedef LiveTracks Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int32_t getTrackId() const; + + inline float getDRel() const; + + inline float getYRel() const; + + inline float getVRel() const; + + inline float getARel() const; + + inline float getTimeStamp() const; + + inline float getStatus() const; + + inline float getCurrentTime() const; + + inline bool getStationary() const; + + inline bool getOncoming() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveTracks::Builder { +public: + typedef LiveTracks Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int32_t getTrackId(); + inline void setTrackId( ::int32_t value); + + inline float getDRel(); + inline void setDRel(float value); + + inline float getYRel(); + inline void setYRel(float value); + + inline float getVRel(); + inline void setVRel(float value); + + inline float getARel(); + inline void setARel(float value); + + inline float getTimeStamp(); + inline void setTimeStamp(float value); + + inline float getStatus(); + inline void setStatus(float value); + + inline float getCurrentTime(); + inline void setCurrentTime(float value); + + inline bool getStationary(); + inline void setStationary(bool value); + + inline bool getOncoming(); + inline void setOncoming(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveTracks::Pipeline { +public: + typedef LiveTracks Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Live100Data::Reader { +public: + typedef Live100Data Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getVEgo() const; + + inline float getAEgo() const; + + inline float getVPid() const; + + inline float getVTargetLead() const; + + inline float getUpAccelCmd() const; + + inline float getUiAccelCmd() const; + + inline float getYActual() const; + + inline float getYDes() const; + + inline float getUpSteer() const; + + inline float getUiSteer() const; + + inline float getATargetMin() const; + + inline float getATargetMax() const; + + inline float getJerkFactor() const; + + inline float getAngleSteers() const; + + inline ::int32_t getHudLead() const; + + inline float getCumLagMs() const; + + inline ::uint64_t getCanMonoTime() const; + + inline ::uint64_t getL20MonoTime() const; + + inline ::uint64_t getMdMonoTime() const; + + inline bool getEnabled() const; + + inline bool getSteerOverride() const; + + inline bool hasCanMonoTimes() const; + inline ::capnp::List< ::uint64_t>::Reader getCanMonoTimes() const; + + inline float getVCruise() const; + + inline bool getRearViewCam() const; + + inline bool hasAlertText1() const; + inline ::capnp::Text::Reader getAlertText1() const; + + inline bool hasAlertText2() const; + inline ::capnp::Text::Reader getAlertText2() const; + + inline float getAwarenessStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Live100Data::Builder { +public: + typedef Live100Data Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getVEgo(); + inline void setVEgo(float value); + + inline float getAEgo(); + inline void setAEgo(float value); + + inline float getVPid(); + inline void setVPid(float value); + + inline float getVTargetLead(); + inline void setVTargetLead(float value); + + inline float getUpAccelCmd(); + inline void setUpAccelCmd(float value); + + inline float getUiAccelCmd(); + inline void setUiAccelCmd(float value); + + inline float getYActual(); + inline void setYActual(float value); + + inline float getYDes(); + inline void setYDes(float value); + + inline float getUpSteer(); + inline void setUpSteer(float value); + + inline float getUiSteer(); + inline void setUiSteer(float value); + + inline float getATargetMin(); + inline void setATargetMin(float value); + + inline float getATargetMax(); + inline void setATargetMax(float value); + + inline float getJerkFactor(); + inline void setJerkFactor(float value); + + inline float getAngleSteers(); + inline void setAngleSteers(float value); + + inline ::int32_t getHudLead(); + inline void setHudLead( ::int32_t value); + + inline float getCumLagMs(); + inline void setCumLagMs(float value); + + inline ::uint64_t getCanMonoTime(); + inline void setCanMonoTime( ::uint64_t value); + + inline ::uint64_t getL20MonoTime(); + inline void setL20MonoTime( ::uint64_t value); + + inline ::uint64_t getMdMonoTime(); + inline void setMdMonoTime( ::uint64_t value); + + inline bool getEnabled(); + inline void setEnabled(bool value); + + inline bool getSteerOverride(); + inline void setSteerOverride(bool value); + + inline bool hasCanMonoTimes(); + inline ::capnp::List< ::uint64_t>::Builder getCanMonoTimes(); + inline void setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value); + inline void setCanMonoTimes(::kj::ArrayPtr value); + inline ::capnp::List< ::uint64_t>::Builder initCanMonoTimes(unsigned int size); + inline void adoptCanMonoTimes(::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> disownCanMonoTimes(); + + inline float getVCruise(); + inline void setVCruise(float value); + + inline bool getRearViewCam(); + inline void setRearViewCam(bool value); + + inline bool hasAlertText1(); + inline ::capnp::Text::Builder getAlertText1(); + inline void setAlertText1( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText1(unsigned int size); + inline void adoptAlertText1(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText1(); + + inline bool hasAlertText2(); + inline ::capnp::Text::Builder getAlertText2(); + inline void setAlertText2( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initAlertText2(unsigned int size); + inline void adoptAlertText2(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownAlertText2(); + + inline float getAwarenessStatus(); + inline void setAwarenessStatus(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Live100Data::Pipeline { +public: + typedef Live100Data Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LiveEventData::Reader { +public: + typedef LiveEventData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::int32_t getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LiveEventData::Builder { +public: + typedef LiveEventData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::int32_t getValue(); + inline void setValue( ::int32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LiveEventData::Pipeline { +public: + typedef LiveEventData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::Reader { +public: + typedef ModelData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline bool hasPath() const; + inline ::cereal::ModelData::PathData::Reader getPath() const; + + inline bool hasLeftLane() const; + inline ::cereal::ModelData::PathData::Reader getLeftLane() const; + + inline bool hasRightLane() const; + inline ::cereal::ModelData::PathData::Reader getRightLane() const; + + inline bool hasLead() const; + inline ::cereal::ModelData::LeadData::Reader getLead() const; + + inline bool hasSettings() const; + inline ::cereal::ModelData::ModelSettings::Reader getSettings() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::Builder { +public: + typedef ModelData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline bool hasPath(); + inline ::cereal::ModelData::PathData::Builder getPath(); + inline void setPath( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initPath(); + inline void adoptPath(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownPath(); + + inline bool hasLeftLane(); + inline ::cereal::ModelData::PathData::Builder getLeftLane(); + inline void setLeftLane( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initLeftLane(); + inline void adoptLeftLane(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownLeftLane(); + + inline bool hasRightLane(); + inline ::cereal::ModelData::PathData::Builder getRightLane(); + inline void setRightLane( ::cereal::ModelData::PathData::Reader value); + inline ::cereal::ModelData::PathData::Builder initRightLane(); + inline void adoptRightLane(::capnp::Orphan< ::cereal::ModelData::PathData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::PathData> disownRightLane(); + + inline bool hasLead(); + inline ::cereal::ModelData::LeadData::Builder getLead(); + inline void setLead( ::cereal::ModelData::LeadData::Reader value); + inline ::cereal::ModelData::LeadData::Builder initLead(); + inline void adoptLead(::capnp::Orphan< ::cereal::ModelData::LeadData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::LeadData> disownLead(); + + inline bool hasSettings(); + inline ::cereal::ModelData::ModelSettings::Builder getSettings(); + inline void setSettings( ::cereal::ModelData::ModelSettings::Reader value); + inline ::cereal::ModelData::ModelSettings::Builder initSettings(); + inline void adoptSettings(::capnp::Orphan< ::cereal::ModelData::ModelSettings>&& value); + inline ::capnp::Orphan< ::cereal::ModelData::ModelSettings> disownSettings(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::Pipeline { +public: + typedef ModelData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::cereal::ModelData::PathData::Pipeline getPath(); + inline ::cereal::ModelData::PathData::Pipeline getLeftLane(); + inline ::cereal::ModelData::PathData::Pipeline getRightLane(); + inline ::cereal::ModelData::LeadData::Pipeline getLead(); + inline ::cereal::ModelData::ModelSettings::Pipeline getSettings(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::PathData::Reader { +public: + typedef PathData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline bool hasPoints() const; + inline ::capnp::List::Reader getPoints() const; + + inline float getProb() const; + + inline float getStd() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::PathData::Builder { +public: + typedef PathData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPoints(); + inline ::capnp::List::Builder getPoints(); + inline void setPoints( ::capnp::List::Reader value); + inline void setPoints(::kj::ArrayPtr value); + inline ::capnp::List::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownPoints(); + + inline float getProb(); + inline void setProb(float value); + + inline float getStd(); + inline void setStd(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::PathData::Pipeline { +public: + typedef PathData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::LeadData::Reader { +public: + typedef LeadData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline float getDist() const; + + inline float getProb() const; + + inline float getStd() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::LeadData::Builder { +public: + typedef LeadData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getDist(); + inline void setDist(float value); + + inline float getProb(); + inline void setProb(float value); + + inline float getStd(); + inline void setStd(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::LeadData::Pipeline { +public: + typedef LeadData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ModelData::ModelSettings::Reader { +public: + typedef ModelSettings Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getBigBoxX() const; + + inline ::uint16_t getBigBoxY() const; + + inline ::uint16_t getBigBoxWidth() const; + + inline ::uint16_t getBigBoxHeight() const; + + inline bool hasBoxProjection() const; + inline ::capnp::List::Reader getBoxProjection() const; + + inline bool hasYuvCorrection() const; + inline ::capnp::List::Reader getYuvCorrection() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ModelData::ModelSettings::Builder { +public: + typedef ModelSettings Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getBigBoxX(); + inline void setBigBoxX( ::uint16_t value); + + inline ::uint16_t getBigBoxY(); + inline void setBigBoxY( ::uint16_t value); + + inline ::uint16_t getBigBoxWidth(); + inline void setBigBoxWidth( ::uint16_t value); + + inline ::uint16_t getBigBoxHeight(); + inline void setBigBoxHeight( ::uint16_t value); + + inline bool hasBoxProjection(); + inline ::capnp::List::Builder getBoxProjection(); + inline void setBoxProjection( ::capnp::List::Reader value); + inline void setBoxProjection(::kj::ArrayPtr value); + inline ::capnp::List::Builder initBoxProjection(unsigned int size); + inline void adoptBoxProjection(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownBoxProjection(); + + inline bool hasYuvCorrection(); + inline ::capnp::List::Builder getYuvCorrection(); + inline void setYuvCorrection( ::capnp::List::Reader value); + inline void setYuvCorrection(::kj::ArrayPtr value); + inline ::capnp::List::Builder initYuvCorrection(unsigned int size); + inline void adoptYuvCorrection(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownYuvCorrection(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ModelData::ModelSettings::Pipeline { +public: + typedef ModelSettings Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CalibrationFeatures::Reader { +public: + typedef CalibrationFeatures Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline bool hasP0() const; + inline ::capnp::List::Reader getP0() const; + + inline bool hasP1() const; + inline ::capnp::List::Reader getP1() const; + + inline bool hasStatus() const; + inline ::capnp::List< ::int8_t>::Reader getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CalibrationFeatures::Builder { +public: + typedef CalibrationFeatures Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline bool hasP0(); + inline ::capnp::List::Builder getP0(); + inline void setP0( ::capnp::List::Reader value); + inline void setP0(::kj::ArrayPtr value); + inline ::capnp::List::Builder initP0(unsigned int size); + inline void adoptP0(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownP0(); + + inline bool hasP1(); + inline ::capnp::List::Builder getP1(); + inline void setP1( ::capnp::List::Reader value); + inline void setP1(::kj::ArrayPtr value); + inline ::capnp::List::Builder initP1(unsigned int size); + inline void adoptP1(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownP1(); + + inline bool hasStatus(); + inline ::capnp::List< ::int8_t>::Builder getStatus(); + inline void setStatus( ::capnp::List< ::int8_t>::Reader value); + inline void setStatus(::kj::ArrayPtr value); + inline ::capnp::List< ::int8_t>::Builder initStatus(unsigned int size); + inline void adoptStatus(::capnp::Orphan< ::capnp::List< ::int8_t>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int8_t>> disownStatus(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CalibrationFeatures::Pipeline { +public: + typedef CalibrationFeatures Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class EncodeIndex::Reader { +public: + typedef EncodeIndex Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId() const; + + inline ::cereal::EncodeIndex::Type getType() const; + + inline ::uint32_t getEncodeId() const; + + inline ::int32_t getSegmentNum() const; + + inline ::uint32_t getSegmentId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class EncodeIndex::Builder { +public: + typedef EncodeIndex Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getFrameId(); + inline void setFrameId( ::uint32_t value); + + inline ::cereal::EncodeIndex::Type getType(); + inline void setType( ::cereal::EncodeIndex::Type value); + + inline ::uint32_t getEncodeId(); + inline void setEncodeId( ::uint32_t value); + + inline ::int32_t getSegmentNum(); + inline void setSegmentNum( ::int32_t value); + + inline ::uint32_t getSegmentId(); + inline void setSegmentId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class EncodeIndex::Pipeline { +public: + typedef EncodeIndex Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class AndroidLogEntry::Reader { +public: + typedef AndroidLogEntry Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getId() const; + + inline ::uint64_t getTs() const; + + inline ::uint8_t getPriority() const; + + inline ::int32_t getPid() const; + + inline ::int32_t getTid() const; + + inline bool hasTag() const; + inline ::capnp::Text::Reader getTag() const; + + inline bool hasMessage() const; + inline ::capnp::Text::Reader getMessage() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class AndroidLogEntry::Builder { +public: + typedef AndroidLogEntry Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getId(); + inline void setId( ::uint8_t value); + + inline ::uint64_t getTs(); + inline void setTs( ::uint64_t value); + + inline ::uint8_t getPriority(); + inline void setPriority( ::uint8_t value); + + inline ::int32_t getPid(); + inline void setPid( ::int32_t value); + + inline ::int32_t getTid(); + inline void setTid( ::int32_t value); + + inline bool hasTag(); + inline ::capnp::Text::Builder getTag(); + inline void setTag( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initTag(unsigned int size); + inline void adoptTag(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownTag(); + + inline bool hasMessage(); + inline ::capnp::Text::Builder getMessage(); + inline void setMessage( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initMessage(unsigned int size); + inline void adoptMessage(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownMessage(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class AndroidLogEntry::Pipeline { +public: + typedef AndroidLogEntry Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LogRotate::Reader { +public: + typedef LogRotate Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline ::int32_t getSegmentNum() const; + + inline bool hasPath() const; + inline ::capnp::Text::Reader getPath() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LogRotate::Builder { +public: + typedef LogRotate Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int32_t getSegmentNum(); + inline void setSegmentNum( ::int32_t value); + + inline bool hasPath(); + inline ::capnp::Text::Builder getPath(); + inline void setPath( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initPath(unsigned int size); + inline void adoptPath(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownPath(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LogRotate::Pipeline { +public: + typedef LogRotate Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Event::Reader { +public: + typedef Event Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getLogMonoTime() const; + + inline bool isInitData() const; + inline bool hasInitData() const; + inline ::cereal::InitData::Reader getInitData() const; + + inline bool isFrame() const; + inline bool hasFrame() const; + inline ::cereal::FrameData::Reader getFrame() const; + + inline bool isGpsNMEA() const; + inline bool hasGpsNMEA() const; + inline ::cereal::GPSNMEAData::Reader getGpsNMEA() const; + + inline bool isSensorEventDEPRECATED() const; + inline bool hasSensorEventDEPRECATED() const; + inline ::cereal::SensorEventData::Reader getSensorEventDEPRECATED() const; + + inline bool isCan() const; + inline bool hasCan() const; + inline ::capnp::List< ::cereal::CanData>::Reader getCan() const; + + inline bool isThermal() const; + inline bool hasThermal() const; + inline ::cereal::ThermalData::Reader getThermal() const; + + inline bool isLive100() const; + inline bool hasLive100() const; + inline ::cereal::Live100Data::Reader getLive100() const; + + inline bool isLiveEventDEPRECATED() const; + inline bool hasLiveEventDEPRECATED() const; + inline ::capnp::List< ::cereal::LiveEventData>::Reader getLiveEventDEPRECATED() const; + + inline bool isModel() const; + inline bool hasModel() const; + inline ::cereal::ModelData::Reader getModel() const; + + inline bool isFeatures() const; + inline bool hasFeatures() const; + inline ::cereal::CalibrationFeatures::Reader getFeatures() const; + + inline bool isSensorEvents() const; + inline bool hasSensorEvents() const; + inline ::capnp::List< ::cereal::SensorEventData>::Reader getSensorEvents() const; + + inline bool isHealth() const; + inline bool hasHealth() const; + inline ::cereal::HealthData::Reader getHealth() const; + + inline bool isLive20() const; + inline bool hasLive20() const; + inline ::cereal::Live20Data::Reader getLive20() const; + + inline bool isLiveUIDEPRECATED() const; + inline bool hasLiveUIDEPRECATED() const; + inline ::cereal::LiveUI::Reader getLiveUIDEPRECATED() const; + + inline bool isEncodeIdx() const; + inline bool hasEncodeIdx() const; + inline ::cereal::EncodeIndex::Reader getEncodeIdx() const; + + inline bool isLiveTracks() const; + inline bool hasLiveTracks() const; + inline ::capnp::List< ::cereal::LiveTracks>::Reader getLiveTracks() const; + + inline bool isSendcan() const; + inline bool hasSendcan() const; + inline ::capnp::List< ::cereal::CanData>::Reader getSendcan() const; + + inline bool isLogMessage() const; + inline bool hasLogMessage() const; + inline ::capnp::Text::Reader getLogMessage() const; + + inline bool isLiveCalibration() const; + inline bool hasLiveCalibration() const; + inline ::cereal::LiveCalibrationData::Reader getLiveCalibration() const; + + inline bool isAndroidLogEntry() const; + inline bool hasAndroidLogEntry() const; + inline ::cereal::AndroidLogEntry::Reader getAndroidLogEntry() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Event::Builder { +public: + typedef Event Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getLogMonoTime(); + inline void setLogMonoTime( ::uint64_t value); + + inline bool isInitData(); + inline bool hasInitData(); + inline ::cereal::InitData::Builder getInitData(); + inline void setInitData( ::cereal::InitData::Reader value); + inline ::cereal::InitData::Builder initInitData(); + inline void adoptInitData(::capnp::Orphan< ::cereal::InitData>&& value); + inline ::capnp::Orphan< ::cereal::InitData> disownInitData(); + + inline bool isFrame(); + inline bool hasFrame(); + inline ::cereal::FrameData::Builder getFrame(); + inline void setFrame( ::cereal::FrameData::Reader value); + inline ::cereal::FrameData::Builder initFrame(); + inline void adoptFrame(::capnp::Orphan< ::cereal::FrameData>&& value); + inline ::capnp::Orphan< ::cereal::FrameData> disownFrame(); + + inline bool isGpsNMEA(); + inline bool hasGpsNMEA(); + inline ::cereal::GPSNMEAData::Builder getGpsNMEA(); + inline void setGpsNMEA( ::cereal::GPSNMEAData::Reader value); + inline ::cereal::GPSNMEAData::Builder initGpsNMEA(); + inline void adoptGpsNMEA(::capnp::Orphan< ::cereal::GPSNMEAData>&& value); + inline ::capnp::Orphan< ::cereal::GPSNMEAData> disownGpsNMEA(); + + inline bool isSensorEventDEPRECATED(); + inline bool hasSensorEventDEPRECATED(); + inline ::cereal::SensorEventData::Builder getSensorEventDEPRECATED(); + inline void setSensorEventDEPRECATED( ::cereal::SensorEventData::Reader value); + inline ::cereal::SensorEventData::Builder initSensorEventDEPRECATED(); + inline void adoptSensorEventDEPRECATED(::capnp::Orphan< ::cereal::SensorEventData>&& value); + inline ::capnp::Orphan< ::cereal::SensorEventData> disownSensorEventDEPRECATED(); + + inline bool isCan(); + inline bool hasCan(); + inline ::capnp::List< ::cereal::CanData>::Builder getCan(); + inline void setCan( ::capnp::List< ::cereal::CanData>::Reader value); + inline ::capnp::List< ::cereal::CanData>::Builder initCan(unsigned int size); + inline void adoptCan(::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> disownCan(); + + inline bool isThermal(); + inline bool hasThermal(); + inline ::cereal::ThermalData::Builder getThermal(); + inline void setThermal( ::cereal::ThermalData::Reader value); + inline ::cereal::ThermalData::Builder initThermal(); + inline void adoptThermal(::capnp::Orphan< ::cereal::ThermalData>&& value); + inline ::capnp::Orphan< ::cereal::ThermalData> disownThermal(); + + inline bool isLive100(); + inline bool hasLive100(); + inline ::cereal::Live100Data::Builder getLive100(); + inline void setLive100( ::cereal::Live100Data::Reader value); + inline ::cereal::Live100Data::Builder initLive100(); + inline void adoptLive100(::capnp::Orphan< ::cereal::Live100Data>&& value); + inline ::capnp::Orphan< ::cereal::Live100Data> disownLive100(); + + inline bool isLiveEventDEPRECATED(); + inline bool hasLiveEventDEPRECATED(); + inline ::capnp::List< ::cereal::LiveEventData>::Builder getLiveEventDEPRECATED(); + inline void setLiveEventDEPRECATED( ::capnp::List< ::cereal::LiveEventData>::Reader value); + inline ::capnp::List< ::cereal::LiveEventData>::Builder initLiveEventDEPRECATED(unsigned int size); + inline void adoptLiveEventDEPRECATED(::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>> disownLiveEventDEPRECATED(); + + inline bool isModel(); + inline bool hasModel(); + inline ::cereal::ModelData::Builder getModel(); + inline void setModel( ::cereal::ModelData::Reader value); + inline ::cereal::ModelData::Builder initModel(); + inline void adoptModel(::capnp::Orphan< ::cereal::ModelData>&& value); + inline ::capnp::Orphan< ::cereal::ModelData> disownModel(); + + inline bool isFeatures(); + inline bool hasFeatures(); + inline ::cereal::CalibrationFeatures::Builder getFeatures(); + inline void setFeatures( ::cereal::CalibrationFeatures::Reader value); + inline ::cereal::CalibrationFeatures::Builder initFeatures(); + inline void adoptFeatures(::capnp::Orphan< ::cereal::CalibrationFeatures>&& value); + inline ::capnp::Orphan< ::cereal::CalibrationFeatures> disownFeatures(); + + inline bool isSensorEvents(); + inline bool hasSensorEvents(); + inline ::capnp::List< ::cereal::SensorEventData>::Builder getSensorEvents(); + inline void setSensorEvents( ::capnp::List< ::cereal::SensorEventData>::Reader value); + inline ::capnp::List< ::cereal::SensorEventData>::Builder initSensorEvents(unsigned int size); + inline void adoptSensorEvents(::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>> disownSensorEvents(); + + inline bool isHealth(); + inline bool hasHealth(); + inline ::cereal::HealthData::Builder getHealth(); + inline void setHealth( ::cereal::HealthData::Reader value); + inline ::cereal::HealthData::Builder initHealth(); + inline void adoptHealth(::capnp::Orphan< ::cereal::HealthData>&& value); + inline ::capnp::Orphan< ::cereal::HealthData> disownHealth(); + + inline bool isLive20(); + inline bool hasLive20(); + inline ::cereal::Live20Data::Builder getLive20(); + inline void setLive20( ::cereal::Live20Data::Reader value); + inline ::cereal::Live20Data::Builder initLive20(); + inline void adoptLive20(::capnp::Orphan< ::cereal::Live20Data>&& value); + inline ::capnp::Orphan< ::cereal::Live20Data> disownLive20(); + + inline bool isLiveUIDEPRECATED(); + inline bool hasLiveUIDEPRECATED(); + inline ::cereal::LiveUI::Builder getLiveUIDEPRECATED(); + inline void setLiveUIDEPRECATED( ::cereal::LiveUI::Reader value); + inline ::cereal::LiveUI::Builder initLiveUIDEPRECATED(); + inline void adoptLiveUIDEPRECATED(::capnp::Orphan< ::cereal::LiveUI>&& value); + inline ::capnp::Orphan< ::cereal::LiveUI> disownLiveUIDEPRECATED(); + + inline bool isEncodeIdx(); + inline bool hasEncodeIdx(); + inline ::cereal::EncodeIndex::Builder getEncodeIdx(); + inline void setEncodeIdx( ::cereal::EncodeIndex::Reader value); + inline ::cereal::EncodeIndex::Builder initEncodeIdx(); + inline void adoptEncodeIdx(::capnp::Orphan< ::cereal::EncodeIndex>&& value); + inline ::capnp::Orphan< ::cereal::EncodeIndex> disownEncodeIdx(); + + inline bool isLiveTracks(); + inline bool hasLiveTracks(); + inline ::capnp::List< ::cereal::LiveTracks>::Builder getLiveTracks(); + inline void setLiveTracks( ::capnp::List< ::cereal::LiveTracks>::Reader value); + inline ::capnp::List< ::cereal::LiveTracks>::Builder initLiveTracks(unsigned int size); + inline void adoptLiveTracks(::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>> disownLiveTracks(); + + inline bool isSendcan(); + inline bool hasSendcan(); + inline ::capnp::List< ::cereal::CanData>::Builder getSendcan(); + inline void setSendcan( ::capnp::List< ::cereal::CanData>::Reader value); + inline ::capnp::List< ::cereal::CanData>::Builder initSendcan(unsigned int size); + inline void adoptSendcan(::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> disownSendcan(); + + inline bool isLogMessage(); + inline bool hasLogMessage(); + inline ::capnp::Text::Builder getLogMessage(); + inline void setLogMessage( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initLogMessage(unsigned int size); + inline void adoptLogMessage(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownLogMessage(); + + inline bool isLiveCalibration(); + inline bool hasLiveCalibration(); + inline ::cereal::LiveCalibrationData::Builder getLiveCalibration(); + inline void setLiveCalibration( ::cereal::LiveCalibrationData::Reader value); + inline ::cereal::LiveCalibrationData::Builder initLiveCalibration(); + inline void adoptLiveCalibration(::capnp::Orphan< ::cereal::LiveCalibrationData>&& value); + inline ::capnp::Orphan< ::cereal::LiveCalibrationData> disownLiveCalibration(); + + inline bool isAndroidLogEntry(); + inline bool hasAndroidLogEntry(); + inline ::cereal::AndroidLogEntry::Builder getAndroidLogEntry(); + inline void setAndroidLogEntry( ::cereal::AndroidLogEntry::Reader value); + inline ::cereal::AndroidLogEntry::Builder initAndroidLogEntry(); + inline void adoptAndroidLogEntry(::capnp::Orphan< ::cereal::AndroidLogEntry>&& value); + inline ::capnp::Orphan< ::cereal::AndroidLogEntry> disownAndroidLogEntry(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Event::Pipeline { +public: + typedef Event Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool InitData::Reader::hasKernelArgs() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasKernelArgs() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text>::Reader InitData::Reader::getKernelArgs() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text>::Builder InitData::Builder::getKernelArgs() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setKernelArgs( ::capnp::List< ::capnp::Text>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void InitData::Builder::setKernelArgs(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text>::Builder InitData::Builder::initKernelArgs(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptKernelArgs( + ::capnp::Orphan< ::capnp::List< ::capnp::Text>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text>> InitData::Builder::disownKernelArgs() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool InitData::Reader::hasGctx() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasGctx() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InitData::Reader::getGctx() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InitData::Builder::getGctx() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setGctx( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InitData::Builder::initGctx(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptGctx( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InitData::Builder::disownGctx() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool InitData::Reader::hasDongleId() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool InitData::Builder::hasDongleId() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InitData::Reader::getDongleId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InitData::Builder::getDongleId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void InitData::Builder::setDongleId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InitData::Builder::initDongleId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void InitData::Builder::adoptDongleId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InitData::Builder::disownDongleId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline ::uint32_t FrameData::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t FrameData::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t FrameData::Reader::getEncodeId() const { + return _reader.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint32_t FrameData::Builder::getEncodeId() { + return _builder.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setEncodeId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t FrameData::Reader::getTimestampEof() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t FrameData::Builder::getTimestampEof() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setTimestampEof( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getFrameLength() const { + return _reader.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getFrameLength() { + return _builder.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setFrameLength( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getIntegLines() const { + return _reader.getDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getIntegLines() { + return _builder.getDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setIntegLines( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t FrameData::Reader::getGlobalGain() const { + return _reader.getDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS); +} + +inline ::int32_t FrameData::Builder::getGlobalGain() { + return _builder.getDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS); +} +inline void FrameData::Builder::setGlobalGain( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 6 * ::capnp::ELEMENTS, value); +} + +inline bool FrameData::Reader::hasImage() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool FrameData::Builder::hasImage() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader FrameData::Reader::getImage() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder FrameData::Builder::getImage() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void FrameData::Builder::setImage( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder FrameData::Builder::initImage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void FrameData::Builder::adoptImage( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> FrameData::Builder::disownImage() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int64_t GPSNMEAData::Reader::getTimestamp() const { + return _reader.getDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int64_t GPSNMEAData::Builder::getTimestamp() { + return _builder.getDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS); +} +inline void GPSNMEAData::Builder::setTimestamp( ::int64_t value) { + _builder.setDataField< ::int64_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t GPSNMEAData::Reader::getLocalWallTime() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t GPSNMEAData::Builder::getLocalWallTime() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void GPSNMEAData::Builder::setLocalWallTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool GPSNMEAData::Reader::hasNmea() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool GPSNMEAData::Builder::hasNmea() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader GPSNMEAData::Reader::getNmea() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder GPSNMEAData::Builder::getNmea() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void GPSNMEAData::Builder::setNmea( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder GPSNMEAData::Builder::initNmea(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void GPSNMEAData::Builder::adoptNmea( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> GPSNMEAData::Builder::disownNmea() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::cereal::SensorEventData::Which SensorEventData::Reader::which() const { + return _reader.getDataField(6 * ::capnp::ELEMENTS); +} +inline ::cereal::SensorEventData::Which SensorEventData::Builder::which() { + return _builder.getDataField(6 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Reader::getVersion() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getVersion() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setVersion( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t SensorEventData::Reader::getSensor() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getSensor() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setSensor( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t SensorEventData::Reader::getType() const { + return _reader.getDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::int32_t SensorEventData::Builder::getType() { + return _builder.getDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setType( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::int64_t SensorEventData::Reader::getTimestamp() const { + return _reader.getDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::int64_t SensorEventData::Builder::getTimestamp() { + return _builder.getDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS); +} +inline void SensorEventData::Builder::setTimestamp( ::int64_t value) { + _builder.setDataField< ::int64_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline bool SensorEventData::Reader::isAcceleration() const { + return which() == SensorEventData::ACCELERATION; +} +inline bool SensorEventData::Builder::isAcceleration() { + return which() == SensorEventData::ACCELERATION; +} +inline bool SensorEventData::Reader::hasAcceleration() const { + if (which() != SensorEventData::ACCELERATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasAcceleration() { + if (which() != SensorEventData::ACCELERATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getAcceleration() const { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getAcceleration() { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setAcceleration( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initAcceleration() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptAcceleration( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ACCELERATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownAcceleration() { + KJ_IREQUIRE(which() == SensorEventData::ACCELERATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isMagnetic() const { + return which() == SensorEventData::MAGNETIC; +} +inline bool SensorEventData::Builder::isMagnetic() { + return which() == SensorEventData::MAGNETIC; +} +inline bool SensorEventData::Reader::hasMagnetic() const { + if (which() != SensorEventData::MAGNETIC) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasMagnetic() { + if (which() != SensorEventData::MAGNETIC) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getMagnetic() const { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getMagnetic() { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setMagnetic( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initMagnetic() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptMagnetic( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::MAGNETIC); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownMagnetic() { + KJ_IREQUIRE(which() == SensorEventData::MAGNETIC, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isOrientation() const { + return which() == SensorEventData::ORIENTATION; +} +inline bool SensorEventData::Builder::isOrientation() { + return which() == SensorEventData::ORIENTATION; +} +inline bool SensorEventData::Reader::hasOrientation() const { + if (which() != SensorEventData::ORIENTATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasOrientation() { + if (which() != SensorEventData::ORIENTATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getOrientation() const { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getOrientation() { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setOrientation( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initOrientation() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptOrientation( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::ORIENTATION); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownOrientation() { + KJ_IREQUIRE(which() == SensorEventData::ORIENTATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::Reader::isGyro() const { + return which() == SensorEventData::GYRO; +} +inline bool SensorEventData::Builder::isGyro() { + return which() == SensorEventData::GYRO; +} +inline bool SensorEventData::Reader::hasGyro() const { + if (which() != SensorEventData::GYRO) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::Builder::hasGyro() { + if (which() != SensorEventData::GYRO) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::SensorVec::Reader SensorEventData::Reader::getGyro() const { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::getGyro() { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::setGyro( ::cereal::SensorEventData::SensorVec::Reader value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::SensorVec::Builder SensorEventData::Builder::initGyro() { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::Builder::adoptGyro( + ::capnp::Orphan< ::cereal::SensorEventData::SensorVec>&& value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, SensorEventData::GYRO); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData::SensorVec> SensorEventData::Builder::disownGyro() { + KJ_IREQUIRE(which() == SensorEventData::GYRO, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData::SensorVec>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool SensorEventData::SensorVec::Reader::hasV() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool SensorEventData::SensorVec::Builder::hasV() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader SensorEventData::SensorVec::Reader::getV() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder SensorEventData::SensorVec::Builder::getV() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void SensorEventData::SensorVec::Builder::setV( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void SensorEventData::SensorVec::Builder::setV(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder SensorEventData::SensorVec::Builder::initV(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void SensorEventData::SensorVec::Builder::adoptV( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> SensorEventData::SensorVec::Builder::disownV() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t SensorEventData::SensorVec::Reader::getStatus() const { + return _reader.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int8_t SensorEventData::SensorVec::Builder::getStatus() { + return _builder.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void SensorEventData::SensorVec::Builder::setStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t CanData::Reader::getAddress() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t CanData::Builder::getAddress() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setAddress( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t CanData::Reader::getBusTime() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t CanData::Builder::getBusTime() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setBusTime( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline bool CanData::Reader::hasDat() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool CanData::Builder::hasDat() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader CanData::Reader::getDat() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder CanData::Builder::getDat() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void CanData::Builder::setDat( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder CanData::Builder::initDat(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void CanData::Builder::adoptDat( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> CanData::Builder::disownDat() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t CanData::Reader::getSrc() const { + return _reader.getDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS); +} + +inline ::int8_t CanData::Builder::getSrc() { + return _builder.getDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS); +} +inline void CanData::Builder::setSrc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 6 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu0() const { + return _reader.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu0() { + return _builder.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu0( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu1() const { + return _reader.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu1() { + return _builder.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu1( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu2() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu2() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu2( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getCpu3() const { + return _reader.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getCpu3() { + return _builder.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setCpu3( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getMem() const { + return _reader.getDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getMem() { + return _builder.getDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setMem( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ThermalData::Reader::getGpu() const { + return _reader.getDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ThermalData::Builder::getGpu() { + return _builder.getDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setGpu( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ThermalData::Reader::getBat() const { + return _reader.getDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint32_t ThermalData::Builder::getBat() { + return _builder.getDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ThermalData::Builder::setBat( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t HealthData::Reader::getVoltage() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t HealthData::Builder::getVoltage() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setVoltage( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t HealthData::Reader::getCurrent() const { + return _reader.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint32_t HealthData::Builder::getCurrent() { + return _builder.getDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setCurrent( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getStarted() const { + return _reader.getDataField( + 64 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getStarted() { + return _builder.getDataField( + 64 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setStarted(bool value) { + _builder.setDataField( + 64 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getControlsAllowed() const { + return _reader.getDataField( + 65 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getControlsAllowed() { + return _builder.getDataField( + 65 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setControlsAllowed(bool value) { + _builder.setDataField( + 65 * ::capnp::ELEMENTS, value); +} + +inline bool HealthData::Reader::getGasInterceptorDetected() const { + return _reader.getDataField( + 66 * ::capnp::ELEMENTS); +} + +inline bool HealthData::Builder::getGasInterceptorDetected() { + return _builder.getDataField( + 66 * ::capnp::ELEMENTS); +} +inline void HealthData::Builder::setGasInterceptorDetected(bool value) { + _builder.setDataField( + 66 * ::capnp::ELEMENTS, value); +} + +inline bool LiveUI::Reader::getRearViewCam() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline bool LiveUI::Builder::getRearViewCam() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void LiveUI::Builder::setRearViewCam(bool value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool LiveUI::Reader::hasAlertText1() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveUI::Builder::hasAlertText1() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveUI::Reader::getAlertText1() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveUI::Builder::getAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveUI::Builder::setAlertText1( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveUI::Builder::initAlertText1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveUI::Builder::adoptAlertText1( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveUI::Builder::disownAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool LiveUI::Reader::hasAlertText2() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool LiveUI::Builder::hasAlertText2() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveUI::Reader::getAlertText2() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveUI::Builder::getAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void LiveUI::Builder::setAlertText2( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveUI::Builder::initAlertText2(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void LiveUI::Builder::adoptAlertText2( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveUI::Builder::disownAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline float LiveUI::Reader::getAwarenessStatus() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float LiveUI::Builder::getAwarenessStatus() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void LiveUI::Builder::setAwarenessStatus(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasWarpMatrix() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasWarpMatrix() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Live20Data::Reader::getWarpMatrix() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Live20Data::Builder::getWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::setWarpMatrix( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void Live20Data::Builder::setWarpMatrix(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Live20Data::Builder::initWarpMatrix(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Live20Data::Builder::adoptWarpMatrix( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Live20Data::Builder::disownWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float Live20Data::Reader::getAngleOffset() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live20Data::Builder::getAngleOffset() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setAngleOffset(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t Live20Data::Reader::getCalStatus() const { + return _reader.getDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int8_t Live20Data::Builder::getCalStatus() { + return _builder.getDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasLeadOne() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasLeadOne() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::LeadData::Reader Live20Data::Reader::getLeadOne() const { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::getLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::Live20Data::LeadData::Pipeline Live20Data::Pipeline::getLeadOne() { + return ::cereal::Live20Data::LeadData::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Live20Data::Builder::setLeadOne( ::cereal::Live20Data::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::initLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::init( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::adoptLeadOne( + ::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> Live20Data::Builder::disownLeadOne() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool Live20Data::Reader::hasLeadTwo() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasLeadTwo() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::LeadData::Reader Live20Data::Reader::getLeadTwo() const { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::getLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::Live20Data::LeadData::Pipeline Live20Data::Pipeline::getLeadTwo() { + return ::cereal::Live20Data::LeadData::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Live20Data::Builder::setLeadTwo( ::cereal::Live20Data::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::LeadData::Builder Live20Data::Builder::initLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::init( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::adoptLeadTwo( + ::capnp::Orphan< ::cereal::Live20Data::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data::LeadData> Live20Data::Builder::disownLeadTwo() { + return ::capnp::_::PointerHelpers< ::cereal::Live20Data::LeadData>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline float Live20Data::Reader::getCumLagMs() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live20Data::Builder::getCumLagMs() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCumLagMs(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live20Data::Reader::getMdMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live20Data::Builder::getMdMonoTime() { + return _builder.getDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setMdMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live20Data::Reader::getFtMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live20Data::Builder::getFtMonoTime() { + return _builder.getDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setFtMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Live20Data::Reader::getCalCycle() const { + return _reader.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::int32_t Live20Data::Builder::getCalCycle() { + return _builder.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalCycle( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t Live20Data::Reader::getCalPerc() const { + return _reader.getDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS); +} + +inline ::int8_t Live20Data::Builder::getCalPerc() { + return _builder.getDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS); +} +inline void Live20Data::Builder::setCalPerc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 5 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::Reader::hasCanMonoTimes() const { + return !_reader.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline bool Live20Data::Builder::hasCanMonoTimes() { + return !_builder.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint64_t>::Reader Live20Data::Reader::getCanMonoTimes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _reader.getPointerField(3 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint64_t>::Builder Live20Data::Builder::getCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +inline void Live20Data::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline void Live20Data::Builder::setCanMonoTimes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint64_t>::Builder Live20Data::Builder::initCanMonoTimes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( + _builder.getPointerField(3 * ::capnp::POINTERS), size); +} +inline void Live20Data::Builder::adoptCanMonoTimes( + ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( + _builder.getPointerField(3 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> Live20Data::Builder::disownCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} + +inline float Live20Data::LeadData::Reader::getDRel() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getDRel() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setDRel(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getYRel() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getYRel() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setYRel(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVRel() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVRel() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVRel(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getARel() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getARel() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setARel(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLead() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLead() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLead(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getALead() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getALead() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setALead(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getDPath() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getDPath() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setDPath(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLat() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLat() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLat(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getVLeadK() const { + return _reader.getDataField( + 8 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getVLeadK() { + return _builder.getDataField( + 8 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setVLeadK(float value) { + _builder.setDataField( + 8 * ::capnp::ELEMENTS, value); +} + +inline float Live20Data::LeadData::Reader::getALeadK() const { + return _reader.getDataField( + 9 * ::capnp::ELEMENTS); +} + +inline float Live20Data::LeadData::Builder::getALeadK() { + return _builder.getDataField( + 9 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setALeadK(float value) { + _builder.setDataField( + 9 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::LeadData::Reader::getFcw() const { + return _reader.getDataField( + 320 * ::capnp::ELEMENTS); +} + +inline bool Live20Data::LeadData::Builder::getFcw() { + return _builder.getDataField( + 320 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setFcw(bool value) { + _builder.setDataField( + 320 * ::capnp::ELEMENTS, value); +} + +inline bool Live20Data::LeadData::Reader::getStatus() const { + return _reader.getDataField( + 321 * ::capnp::ELEMENTS); +} + +inline bool Live20Data::LeadData::Builder::getStatus() { + return _builder.getDataField( + 321 * ::capnp::ELEMENTS); +} +inline void Live20Data::LeadData::Builder::setStatus(bool value) { + _builder.setDataField( + 321 * ::capnp::ELEMENTS, value); +} + +inline bool LiveCalibrationData::Reader::hasWarpMatrix() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveCalibrationData::Builder::hasWarpMatrix() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LiveCalibrationData::Reader::getWarpMatrix() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LiveCalibrationData::Builder::getWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveCalibrationData::Builder::setWarpMatrix( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void LiveCalibrationData::Builder::setWarpMatrix(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LiveCalibrationData::Builder::initWarpMatrix(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveCalibrationData::Builder::adoptWarpMatrix( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LiveCalibrationData::Builder::disownWarpMatrix() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int8_t LiveCalibrationData::Reader::getCalStatus() const { + return _reader.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int8_t LiveCalibrationData::Builder::getCalStatus() { + return _builder.getDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t LiveCalibrationData::Reader::getCalCycle() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveCalibrationData::Builder::getCalCycle() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalCycle( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int8_t LiveCalibrationData::Reader::getCalPerc() const { + return _reader.getDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int8_t LiveCalibrationData::Builder::getCalPerc() { + return _builder.getDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS); +} +inline void LiveCalibrationData::Builder::setCalPerc( ::int8_t value) { + _builder.setDataField< ::int8_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t LiveTracks::Reader::getTrackId() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveTracks::Builder::getTrackId() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setTrackId( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getDRel() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getDRel() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setDRel(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getYRel() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getYRel() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setYRel(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getVRel() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getVRel() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setVRel(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getARel() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getARel() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setARel(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getTimeStamp() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getTimeStamp() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setTimeStamp(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getStatus() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getStatus() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setStatus(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float LiveTracks::Reader::getCurrentTime() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float LiveTracks::Builder::getCurrentTime() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setCurrentTime(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline bool LiveTracks::Reader::getStationary() const { + return _reader.getDataField( + 256 * ::capnp::ELEMENTS); +} + +inline bool LiveTracks::Builder::getStationary() { + return _builder.getDataField( + 256 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setStationary(bool value) { + _builder.setDataField( + 256 * ::capnp::ELEMENTS, value); +} + +inline bool LiveTracks::Reader::getOncoming() const { + return _reader.getDataField( + 257 * ::capnp::ELEMENTS); +} + +inline bool LiveTracks::Builder::getOncoming() { + return _builder.getDataField( + 257 * ::capnp::ELEMENTS); +} +inline void LiveTracks::Builder::setOncoming(bool value) { + _builder.setDataField( + 257 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVEgo() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVEgo() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVEgo(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getAEgo() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAEgo() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAEgo(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVPid() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVPid() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVPid(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getVTargetLead() const { + return _reader.getDataField( + 3 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVTargetLead() { + return _builder.getDataField( + 3 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVTargetLead(float value) { + _builder.setDataField( + 3 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUpAccelCmd() const { + return _reader.getDataField( + 4 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUpAccelCmd() { + return _builder.getDataField( + 4 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUpAccelCmd(float value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUiAccelCmd() const { + return _reader.getDataField( + 5 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUiAccelCmd() { + return _builder.getDataField( + 5 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUiAccelCmd(float value) { + _builder.setDataField( + 5 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getYActual() const { + return _reader.getDataField( + 6 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getYActual() { + return _builder.getDataField( + 6 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setYActual(float value) { + _builder.setDataField( + 6 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getYDes() const { + return _reader.getDataField( + 7 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getYDes() { + return _builder.getDataField( + 7 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setYDes(float value) { + _builder.setDataField( + 7 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUpSteer() const { + return _reader.getDataField( + 8 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUpSteer() { + return _builder.getDataField( + 8 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUpSteer(float value) { + _builder.setDataField( + 8 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getUiSteer() const { + return _reader.getDataField( + 9 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getUiSteer() { + return _builder.getDataField( + 9 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setUiSteer(float value) { + _builder.setDataField( + 9 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getATargetMin() const { + return _reader.getDataField( + 10 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getATargetMin() { + return _builder.getDataField( + 10 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setATargetMin(float value) { + _builder.setDataField( + 10 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getATargetMax() const { + return _reader.getDataField( + 11 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getATargetMax() { + return _builder.getDataField( + 11 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setATargetMax(float value) { + _builder.setDataField( + 11 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getJerkFactor() const { + return _reader.getDataField( + 12 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getJerkFactor() { + return _builder.getDataField( + 12 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setJerkFactor(float value) { + _builder.setDataField( + 12 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getAngleSteers() const { + return _reader.getDataField( + 13 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAngleSteers() { + return _builder.getDataField( + 13 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAngleSteers(float value) { + _builder.setDataField( + 13 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Live100Data::Reader::getHudLead() const { + return _reader.getDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS); +} + +inline ::int32_t Live100Data::Builder::getHudLead() { + return _builder.getDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setHudLead( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 14 * ::capnp::ELEMENTS, value); +} + +inline float Live100Data::Reader::getCumLagMs() const { + return _reader.getDataField( + 15 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getCumLagMs() { + return _builder.getDataField( + 15 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setCumLagMs(float value) { + _builder.setDataField( + 15 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getCanMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getCanMonoTime() { + return _builder.getDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setCanMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 8 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getL20MonoTime() const { + return _reader.getDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getL20MonoTime() { + return _builder.getDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setL20MonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 9 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Live100Data::Reader::getMdMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Live100Data::Builder::getMdMonoTime() { + return _builder.getDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setMdMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 10 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getEnabled() const { + return _reader.getDataField( + 704 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getEnabled() { + return _builder.getDataField( + 704 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setEnabled(bool value) { + _builder.setDataField( + 704 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getSteerOverride() const { + return _reader.getDataField( + 705 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getSteerOverride() { + return _builder.getDataField( + 705 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setSteerOverride(bool value) { + _builder.setDataField( + 705 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::hasCanMonoTimes() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasCanMonoTimes() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint64_t>::Reader Live100Data::Reader::getCanMonoTimes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint64_t>::Builder Live100Data::Builder::getCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setCanMonoTimes( ::capnp::List< ::uint64_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void Live100Data::Builder::setCanMonoTimes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint64_t>::Builder Live100Data::Builder::initCanMonoTimes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptCanMonoTimes( + ::capnp::Orphan< ::capnp::List< ::uint64_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint64_t>> Live100Data::Builder::disownCanMonoTimes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float Live100Data::Reader::getVCruise() const { + return _reader.getDataField( + 23 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getVCruise() { + return _builder.getDataField( + 23 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setVCruise(float value) { + _builder.setDataField( + 23 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::getRearViewCam() const { + return _reader.getDataField( + 706 * ::capnp::ELEMENTS); +} + +inline bool Live100Data::Builder::getRearViewCam() { + return _builder.getDataField( + 706 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setRearViewCam(bool value) { + _builder.setDataField( + 706 * ::capnp::ELEMENTS, value); +} + +inline bool Live100Data::Reader::hasAlertText1() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasAlertText1() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Live100Data::Reader::getAlertText1() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Live100Data::Builder::getAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setAlertText1( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Live100Data::Builder::initAlertText1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptAlertText1( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Live100Data::Builder::disownAlertText1() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool Live100Data::Reader::hasAlertText2() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool Live100Data::Builder::hasAlertText2() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Live100Data::Reader::getAlertText2() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Live100Data::Builder::getAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void Live100Data::Builder::setAlertText2( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Live100Data::Builder::initAlertText2(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void Live100Data::Builder::adoptAlertText2( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Live100Data::Builder::disownAlertText2() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline float Live100Data::Reader::getAwarenessStatus() const { + return _reader.getDataField( + 24 * ::capnp::ELEMENTS); +} + +inline float Live100Data::Builder::getAwarenessStatus() { + return _builder.getDataField( + 24 * ::capnp::ELEMENTS); +} +inline void Live100Data::Builder::setAwarenessStatus(float value) { + _builder.setDataField( + 24 * ::capnp::ELEMENTS, value); +} + +inline bool LiveEventData::Reader::hasName() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LiveEventData::Builder::hasName() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveEventData::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveEventData::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LiveEventData::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveEventData::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LiveEventData::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveEventData::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::int32_t LiveEventData::Reader::getValue() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LiveEventData::Builder::getValue() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LiveEventData::Builder::setValue( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ModelData::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t ModelData::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool ModelData::Reader::hasPath() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasPath() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getPath() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getPath() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setPath( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptPath( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownPath() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasLeftLane() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasLeftLane() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getLeftLane() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getLeftLane() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setLeftLane( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptLeftLane( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownLeftLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasRightLane() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasRightLane() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::PathData::Reader ModelData::Reader::getRightLane() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::getRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::PathData::Pipeline ModelData::Pipeline::getRightLane() { + return ::cereal::ModelData::PathData::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setRightLane( ::cereal::ModelData::PathData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::PathData::Builder ModelData::Builder::initRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::init( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptRightLane( + ::capnp::Orphan< ::cereal::ModelData::PathData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::PathData> ModelData::Builder::disownRightLane() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::PathData>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasLead() const { + return !_reader.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasLead() { + return !_builder.getPointerField(3 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::LeadData::Reader ModelData::Reader::getLead() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::get( + _reader.getPointerField(3 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::LeadData::Builder ModelData::Builder::getLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::get( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::LeadData::Pipeline ModelData::Pipeline::getLead() { + return ::cereal::ModelData::LeadData::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setLead( ::cereal::ModelData::LeadData::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::set( + _builder.getPointerField(3 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::LeadData::Builder ModelData::Builder::initLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::init( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptLead( + ::capnp::Orphan< ::cereal::ModelData::LeadData>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::adopt( + _builder.getPointerField(3 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::LeadData> ModelData::Builder::disownLead() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::LeadData>::disown( + _builder.getPointerField(3 * ::capnp::POINTERS)); +} + +inline bool ModelData::Reader::hasSettings() const { + return !_reader.getPointerField(4 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::Builder::hasSettings() { + return !_builder.getPointerField(4 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::ModelSettings::Reader ModelData::Reader::getSettings() const { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::get( + _reader.getPointerField(4 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::ModelSettings::Builder ModelData::Builder::getSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::get( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::cereal::ModelData::ModelSettings::Pipeline ModelData::Pipeline::getSettings() { + return ::cereal::ModelData::ModelSettings::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void ModelData::Builder::setSettings( ::cereal::ModelData::ModelSettings::Reader value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::set( + _builder.getPointerField(4 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::ModelSettings::Builder ModelData::Builder::initSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::init( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} +inline void ModelData::Builder::adoptSettings( + ::capnp::Orphan< ::cereal::ModelData::ModelSettings>&& value) { + ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::adopt( + _builder.getPointerField(4 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData::ModelSettings> ModelData::Builder::disownSettings() { + return ::capnp::_::PointerHelpers< ::cereal::ModelData::ModelSettings>::disown( + _builder.getPointerField(4 * ::capnp::POINTERS)); +} + +inline bool ModelData::PathData::Reader::hasPoints() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::PathData::Builder::hasPoints() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::PathData::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::PathData::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::PathData::Builder::setPoints( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void ModelData::PathData::Builder::setPoints(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::PathData::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void ModelData::PathData::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::PathData::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline float ModelData::PathData::Reader::getProb() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float ModelData::PathData::Builder::getProb() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::PathData::Builder::setProb(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::PathData::Reader::getStd() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float ModelData::PathData::Builder::getStd() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::PathData::Builder::setStd(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getDist() const { + return _reader.getDataField( + 0 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getDist() { + return _builder.getDataField( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setDist(float value) { + _builder.setDataField( + 0 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getProb() const { + return _reader.getDataField( + 1 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getProb() { + return _builder.getDataField( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setProb(float value) { + _builder.setDataField( + 1 * ::capnp::ELEMENTS, value); +} + +inline float ModelData::LeadData::Reader::getStd() const { + return _reader.getDataField( + 2 * ::capnp::ELEMENTS); +} + +inline float ModelData::LeadData::Builder::getStd() { + return _builder.getDataField( + 2 * ::capnp::ELEMENTS); +} +inline void ModelData::LeadData::Builder::setStd(float value) { + _builder.setDataField( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxX() const { + return _reader.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxX() { + return _builder.getDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxX( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxY() const { + return _reader.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxY() { + return _builder.getDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxY( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxWidth() const { + return _reader.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxWidth() { + return _builder.getDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxWidth( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t ModelData::ModelSettings::Reader::getBigBoxHeight() const { + return _reader.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::uint16_t ModelData::ModelSettings::Builder::getBigBoxHeight() { + return _builder.getDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS); +} +inline void ModelData::ModelSettings::Builder::setBigBoxHeight( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline bool ModelData::ModelSettings::Reader::hasBoxProjection() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::ModelSettings::Builder::hasBoxProjection() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::ModelSettings::Reader::getBoxProjection() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::getBoxProjection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ModelData::ModelSettings::Builder::setBoxProjection( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void ModelData::ModelSettings::Builder::setBoxProjection(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::initBoxProjection(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void ModelData::ModelSettings::Builder::adoptBoxProjection( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::ModelSettings::Builder::disownBoxProjection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool ModelData::ModelSettings::Reader::hasYuvCorrection() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool ModelData::ModelSettings::Builder::hasYuvCorrection() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ModelData::ModelSettings::Reader::getYuvCorrection() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::getYuvCorrection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void ModelData::ModelSettings::Builder::setYuvCorrection( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline void ModelData::ModelSettings::Builder::setYuvCorrection(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ModelData::ModelSettings::Builder::initYuvCorrection(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void ModelData::ModelSettings::Builder::adoptYuvCorrection( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ModelData::ModelSettings::Builder::disownYuvCorrection() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline ::uint32_t CalibrationFeatures::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t CalibrationFeatures::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void CalibrationFeatures::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool CalibrationFeatures::Reader::hasP0() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasP0() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CalibrationFeatures::Reader::getP0() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::getP0() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setP0( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setP0(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::initP0(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptP0( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CalibrationFeatures::Builder::disownP0() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool CalibrationFeatures::Reader::hasP1() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasP1() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CalibrationFeatures::Reader::getP1() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::getP1() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setP1( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setP1(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CalibrationFeatures::Builder::initP1(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptP1( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CalibrationFeatures::Builder::disownP1() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline bool CalibrationFeatures::Reader::hasStatus() const { + return !_reader.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline bool CalibrationFeatures::Builder::hasStatus() { + return !_builder.getPointerField(2 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int8_t>::Reader CalibrationFeatures::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::get( + _reader.getPointerField(2 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int8_t>::Builder CalibrationFeatures::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::get( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} +inline void CalibrationFeatures::Builder::setStatus( ::capnp::List< ::int8_t>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline void CalibrationFeatures::Builder::setStatus(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::set( + _builder.getPointerField(2 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int8_t>::Builder CalibrationFeatures::Builder::initStatus(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::init( + _builder.getPointerField(2 * ::capnp::POINTERS), size); +} +inline void CalibrationFeatures::Builder::adoptStatus( + ::capnp::Orphan< ::capnp::List< ::int8_t>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::adopt( + _builder.getPointerField(2 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int8_t>> CalibrationFeatures::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int8_t>>::disown( + _builder.getPointerField(2 * ::capnp::POINTERS)); +} + +inline ::uint32_t EncodeIndex::Reader::getFrameId() const { + return _reader.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getFrameId() { + return _builder.getDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setFrameId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::cereal::EncodeIndex::Type EncodeIndex::Reader::getType() const { + return _reader.getDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS); +} + +inline ::cereal::EncodeIndex::Type EncodeIndex::Builder::getType() { + return _builder.getDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setType( ::cereal::EncodeIndex::Type value) { + _builder.setDataField< ::cereal::EncodeIndex::Type>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t EncodeIndex::Reader::getEncodeId() const { + return _reader.getDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getEncodeId() { + return _builder.getDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setEncodeId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 2 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t EncodeIndex::Reader::getSegmentNum() const { + return _reader.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} + +inline ::int32_t EncodeIndex::Builder::getSegmentNum() { + return _builder.getDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setSegmentNum( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 3 * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t EncodeIndex::Reader::getSegmentId() const { + return _reader.getDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::uint32_t EncodeIndex::Builder::getSegmentId() { + return _builder.getDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void EncodeIndex::Builder::setSegmentId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t AndroidLogEntry::Reader::getId() const { + return _reader.getDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint8_t AndroidLogEntry::Builder::getId() { + return _builder.getDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setId( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t AndroidLogEntry::Reader::getTs() const { + return _reader.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint64_t AndroidLogEntry::Builder::getTs() { + return _builder.getDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setTs( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t AndroidLogEntry::Reader::getPriority() const { + return _reader.getDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::uint8_t AndroidLogEntry::Builder::getPriority() { + return _builder.getDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setPriority( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t AndroidLogEntry::Reader::getPid() const { + return _reader.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} + +inline ::int32_t AndroidLogEntry::Builder::getPid() { + return _builder.getDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setPid( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 1 * ::capnp::ELEMENTS, value); +} + +inline ::int32_t AndroidLogEntry::Reader::getTid() const { + return _reader.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} + +inline ::int32_t AndroidLogEntry::Builder::getTid() { + return _builder.getDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS); +} +inline void AndroidLogEntry::Builder::setTid( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 4 * ::capnp::ELEMENTS, value); +} + +inline bool AndroidLogEntry::Reader::hasTag() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool AndroidLogEntry::Builder::hasTag() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader AndroidLogEntry::Reader::getTag() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::getTag() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void AndroidLogEntry::Builder::setTag( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::initTag(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void AndroidLogEntry::Builder::adoptTag( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> AndroidLogEntry::Builder::disownTag() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool AndroidLogEntry::Reader::hasMessage() const { + return !_reader.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline bool AndroidLogEntry::Builder::hasMessage() { + return !_builder.getPointerField(1 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader AndroidLogEntry::Reader::getMessage() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(1 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::getMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} +inline void AndroidLogEntry::Builder::setMessage( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(1 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder AndroidLogEntry::Builder::initMessage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(1 * ::capnp::POINTERS), size); +} +inline void AndroidLogEntry::Builder::adoptMessage( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(1 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> AndroidLogEntry::Builder::disownMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(1 * ::capnp::POINTERS)); +} + +inline ::int32_t LogRotate::Reader::getSegmentNum() const { + return _reader.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::int32_t LogRotate::Builder::getSegmentNum() { + return _builder.getDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS); +} +inline void LogRotate::Builder::setSegmentNum( ::int32_t value) { + _builder.setDataField< ::int32_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool LogRotate::Reader::hasPath() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool LogRotate::Builder::hasPath() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LogRotate::Reader::getPath() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LogRotate::Builder::getPath() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void LogRotate::Builder::setPath( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LogRotate::Builder::initPath(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void LogRotate::Builder::adoptPath( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LogRotate::Builder::disownPath() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline ::cereal::Event::Which Event::Reader::which() const { + return _reader.getDataField(4 * ::capnp::ELEMENTS); +} +inline ::cereal::Event::Which Event::Builder::which() { + return _builder.getDataField(4 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Event::Reader::getLogMonoTime() const { + return _reader.getDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS); +} + +inline ::uint64_t Event::Builder::getLogMonoTime() { + return _builder.getDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS); +} +inline void Event::Builder::setLogMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + 0 * ::capnp::ELEMENTS, value); +} + +inline bool Event::Reader::isInitData() const { + return which() == Event::INIT_DATA; +} +inline bool Event::Builder::isInitData() { + return which() == Event::INIT_DATA; +} +inline bool Event::Reader::hasInitData() const { + if (which() != Event::INIT_DATA) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasInitData() { + if (which() != Event::INIT_DATA) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::InitData::Reader Event::Reader::getInitData() const { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::InitData::Builder Event::Builder::getInitData() { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setInitData( ::cereal::InitData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + ::capnp::_::PointerHelpers< ::cereal::InitData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::InitData::Builder Event::Builder::initInitData() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptInitData( + ::capnp::Orphan< ::cereal::InitData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::INIT_DATA); + ::capnp::_::PointerHelpers< ::cereal::InitData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::InitData> Event::Builder::disownInitData() { + KJ_IREQUIRE(which() == Event::INIT_DATA, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::InitData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isFrame() const { + return which() == Event::FRAME; +} +inline bool Event::Builder::isFrame() { + return which() == Event::FRAME; +} +inline bool Event::Reader::hasFrame() const { + if (which() != Event::FRAME) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasFrame() { + if (which() != Event::FRAME) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::FrameData::Reader Event::Reader::getFrame() const { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::FrameData::Builder Event::Builder::getFrame() { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setFrame( ::cereal::FrameData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + ::capnp::_::PointerHelpers< ::cereal::FrameData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::FrameData::Builder Event::Builder::initFrame() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptFrame( + ::capnp::Orphan< ::cereal::FrameData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FRAME); + ::capnp::_::PointerHelpers< ::cereal::FrameData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::FrameData> Event::Builder::disownFrame() { + KJ_IREQUIRE(which() == Event::FRAME, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::FrameData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isGpsNMEA() const { + return which() == Event::GPS_N_M_E_A; +} +inline bool Event::Builder::isGpsNMEA() { + return which() == Event::GPS_N_M_E_A; +} +inline bool Event::Reader::hasGpsNMEA() const { + if (which() != Event::GPS_N_M_E_A) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasGpsNMEA() { + if (which() != Event::GPS_N_M_E_A) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::GPSNMEAData::Reader Event::Reader::getGpsNMEA() const { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::GPSNMEAData::Builder Event::Builder::getGpsNMEA() { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setGpsNMEA( ::cereal::GPSNMEAData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::GPSNMEAData::Builder Event::Builder::initGpsNMEA() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptGpsNMEA( + ::capnp::Orphan< ::cereal::GPSNMEAData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::GPS_N_M_E_A); + ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::GPSNMEAData> Event::Builder::disownGpsNMEA() { + KJ_IREQUIRE(which() == Event::GPS_N_M_E_A, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::GPSNMEAData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSensorEventDEPRECATED() const { + return which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isSensorEventDEPRECATED() { + return which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasSensorEventDEPRECATED() const { + if (which() != Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSensorEventDEPRECATED() { + if (which() != Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::SensorEventData::Reader Event::Reader::getSensorEventDEPRECATED() const { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::SensorEventData::Builder Event::Builder::getSensorEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSensorEventDEPRECATED( ::cereal::SensorEventData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::SensorEventData::Builder Event::Builder::initSensorEventDEPRECATED() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptSensorEventDEPRECATED( + ::capnp::Orphan< ::cereal::SensorEventData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::SensorEventData> Event::Builder::disownSensorEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::SensorEventData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isCan() const { + return which() == Event::CAN; +} +inline bool Event::Builder::isCan() { + return which() == Event::CAN; +} +inline bool Event::Reader::hasCan() const { + if (which() != Event::CAN) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasCan() { + if (which() != Event::CAN) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::CanData>::Reader Event::Reader::getCan() const { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::getCan() { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setCan( ::capnp::List< ::cereal::CanData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::initCan(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptCan( + ::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> Event::Builder::disownCan() { + KJ_IREQUIRE(which() == Event::CAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isThermal() const { + return which() == Event::THERMAL; +} +inline bool Event::Builder::isThermal() { + return which() == Event::THERMAL; +} +inline bool Event::Reader::hasThermal() const { + if (which() != Event::THERMAL) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasThermal() { + if (which() != Event::THERMAL) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ThermalData::Reader Event::Reader::getThermal() const { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ThermalData::Builder Event::Builder::getThermal() { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setThermal( ::cereal::ThermalData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + ::capnp::_::PointerHelpers< ::cereal::ThermalData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ThermalData::Builder Event::Builder::initThermal() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptThermal( + ::capnp::Orphan< ::cereal::ThermalData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::THERMAL); + ::capnp::_::PointerHelpers< ::cereal::ThermalData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ThermalData> Event::Builder::disownThermal() { + KJ_IREQUIRE(which() == Event::THERMAL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ThermalData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLive100() const { + return which() == Event::LIVE100; +} +inline bool Event::Builder::isLive100() { + return which() == Event::LIVE100; +} +inline bool Event::Reader::hasLive100() const { + if (which() != Event::LIVE100) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLive100() { + if (which() != Event::LIVE100) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live100Data::Reader Event::Reader::getLive100() const { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::Live100Data::Builder Event::Builder::getLive100() { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLive100( ::cereal::Live100Data::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + ::capnp::_::PointerHelpers< ::cereal::Live100Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::Live100Data::Builder Event::Builder::initLive100() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLive100( + ::capnp::Orphan< ::cereal::Live100Data>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE100); + ::capnp::_::PointerHelpers< ::cereal::Live100Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live100Data> Event::Builder::disownLive100() { + KJ_IREQUIRE(which() == Event::LIVE100, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live100Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveEventDEPRECATED() const { + return which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isLiveEventDEPRECATED() { + return which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasLiveEventDEPRECATED() const { + if (which() != Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveEventDEPRECATED() { + if (which() != Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::LiveEventData>::Reader Event::Reader::getLiveEventDEPRECATED() const { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::LiveEventData>::Builder Event::Builder::getLiveEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveEventDEPRECATED( ::capnp::List< ::cereal::LiveEventData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::LiveEventData>::Builder Event::Builder::initLiveEventDEPRECATED(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLiveEventDEPRECATED( + ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveEventData>> Event::Builder::disownLiveEventDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_EVENT_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveEventData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isModel() const { + return which() == Event::MODEL; +} +inline bool Event::Builder::isModel() { + return which() == Event::MODEL; +} +inline bool Event::Reader::hasModel() const { + if (which() != Event::MODEL) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasModel() { + if (which() != Event::MODEL) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::ModelData::Reader Event::Reader::getModel() const { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::ModelData::Builder Event::Builder::getModel() { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setModel( ::cereal::ModelData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + ::capnp::_::PointerHelpers< ::cereal::ModelData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::ModelData::Builder Event::Builder::initModel() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptModel( + ::capnp::Orphan< ::cereal::ModelData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::MODEL); + ::capnp::_::PointerHelpers< ::cereal::ModelData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::ModelData> Event::Builder::disownModel() { + KJ_IREQUIRE(which() == Event::MODEL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::ModelData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isFeatures() const { + return which() == Event::FEATURES; +} +inline bool Event::Builder::isFeatures() { + return which() == Event::FEATURES; +} +inline bool Event::Reader::hasFeatures() const { + if (which() != Event::FEATURES) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasFeatures() { + if (which() != Event::FEATURES) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::CalibrationFeatures::Reader Event::Reader::getFeatures() const { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::CalibrationFeatures::Builder Event::Builder::getFeatures() { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setFeatures( ::cereal::CalibrationFeatures::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::CalibrationFeatures::Builder Event::Builder::initFeatures() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptFeatures( + ::capnp::Orphan< ::cereal::CalibrationFeatures>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::FEATURES); + ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::CalibrationFeatures> Event::Builder::disownFeatures() { + KJ_IREQUIRE(which() == Event::FEATURES, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CalibrationFeatures>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSensorEvents() const { + return which() == Event::SENSOR_EVENTS; +} +inline bool Event::Builder::isSensorEvents() { + return which() == Event::SENSOR_EVENTS; +} +inline bool Event::Reader::hasSensorEvents() const { + if (which() != Event::SENSOR_EVENTS) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSensorEvents() { + if (which() != Event::SENSOR_EVENTS) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::SensorEventData>::Reader Event::Reader::getSensorEvents() const { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::SensorEventData>::Builder Event::Builder::getSensorEvents() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSensorEvents( ::capnp::List< ::cereal::SensorEventData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::SensorEventData>::Builder Event::Builder::initSensorEvents(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptSensorEvents( + ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENSOR_EVENTS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::SensorEventData>> Event::Builder::disownSensorEvents() { + KJ_IREQUIRE(which() == Event::SENSOR_EVENTS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::SensorEventData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isHealth() const { + return which() == Event::HEALTH; +} +inline bool Event::Builder::isHealth() { + return which() == Event::HEALTH; +} +inline bool Event::Reader::hasHealth() const { + if (which() != Event::HEALTH) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasHealth() { + if (which() != Event::HEALTH) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::HealthData::Reader Event::Reader::getHealth() const { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::HealthData::Builder Event::Builder::getHealth() { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setHealth( ::cereal::HealthData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + ::capnp::_::PointerHelpers< ::cereal::HealthData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::HealthData::Builder Event::Builder::initHealth() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptHealth( + ::capnp::Orphan< ::cereal::HealthData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::HEALTH); + ::capnp::_::PointerHelpers< ::cereal::HealthData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::HealthData> Event::Builder::disownHealth() { + KJ_IREQUIRE(which() == Event::HEALTH, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::HealthData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLive20() const { + return which() == Event::LIVE20; +} +inline bool Event::Builder::isLive20() { + return which() == Event::LIVE20; +} +inline bool Event::Reader::hasLive20() const { + if (which() != Event::LIVE20) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLive20() { + if (which() != Event::LIVE20) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::Live20Data::Reader Event::Reader::getLive20() const { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::Live20Data::Builder Event::Builder::getLive20() { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLive20( ::cereal::Live20Data::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + ::capnp::_::PointerHelpers< ::cereal::Live20Data>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::Live20Data::Builder Event::Builder::initLive20() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLive20( + ::capnp::Orphan< ::cereal::Live20Data>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE20); + ::capnp::_::PointerHelpers< ::cereal::Live20Data>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::Live20Data> Event::Builder::disownLive20() { + KJ_IREQUIRE(which() == Event::LIVE20, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::Live20Data>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveUIDEPRECATED() const { + return which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Builder::isLiveUIDEPRECATED() { + return which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D; +} +inline bool Event::Reader::hasLiveUIDEPRECATED() const { + if (which() != Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveUIDEPRECATED() { + if (which() != Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::LiveUI::Reader Event::Reader::getLiveUIDEPRECATED() const { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::LiveUI::Builder Event::Builder::getLiveUIDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveUIDEPRECATED( ::cereal::LiveUI::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::LiveUI>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::LiveUI::Builder Event::Builder::initLiveUIDEPRECATED() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLiveUIDEPRECATED( + ::capnp::Orphan< ::cereal::LiveUI>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D); + ::capnp::_::PointerHelpers< ::cereal::LiveUI>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::LiveUI> Event::Builder::disownLiveUIDEPRECATED() { + KJ_IREQUIRE(which() == Event::LIVE_U_I_D_E_P_R_E_C_A_T_E_D, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveUI>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isEncodeIdx() const { + return which() == Event::ENCODE_IDX; +} +inline bool Event::Builder::isEncodeIdx() { + return which() == Event::ENCODE_IDX; +} +inline bool Event::Reader::hasEncodeIdx() const { + if (which() != Event::ENCODE_IDX) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasEncodeIdx() { + if (which() != Event::ENCODE_IDX) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::EncodeIndex::Reader Event::Reader::getEncodeIdx() const { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::EncodeIndex::Builder Event::Builder::getEncodeIdx() { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setEncodeIdx( ::cereal::EncodeIndex::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::EncodeIndex::Builder Event::Builder::initEncodeIdx() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptEncodeIdx( + ::capnp::Orphan< ::cereal::EncodeIndex>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ENCODE_IDX); + ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::EncodeIndex> Event::Builder::disownEncodeIdx() { + KJ_IREQUIRE(which() == Event::ENCODE_IDX, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::EncodeIndex>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveTracks() const { + return which() == Event::LIVE_TRACKS; +} +inline bool Event::Builder::isLiveTracks() { + return which() == Event::LIVE_TRACKS; +} +inline bool Event::Reader::hasLiveTracks() const { + if (which() != Event::LIVE_TRACKS) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveTracks() { + if (which() != Event::LIVE_TRACKS) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::LiveTracks>::Reader Event::Reader::getLiveTracks() const { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::LiveTracks>::Builder Event::Builder::getLiveTracks() { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveTracks( ::capnp::List< ::cereal::LiveTracks>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::LiveTracks>::Builder Event::Builder::initLiveTracks(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLiveTracks( + ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_TRACKS); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::LiveTracks>> Event::Builder::disownLiveTracks() { + KJ_IREQUIRE(which() == Event::LIVE_TRACKS, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::LiveTracks>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isSendcan() const { + return which() == Event::SENDCAN; +} +inline bool Event::Builder::isSendcan() { + return which() == Event::SENDCAN; +} +inline bool Event::Reader::hasSendcan() const { + if (which() != Event::SENDCAN) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasSendcan() { + if (which() != Event::SENDCAN) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::cereal::CanData>::Reader Event::Reader::getSendcan() const { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::getSendcan() { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setSendcan( ::capnp::List< ::cereal::CanData>::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::cereal::CanData>::Builder Event::Builder::initSendcan(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptSendcan( + ::capnp::Orphan< ::capnp::List< ::cereal::CanData>>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::SENDCAN); + ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::cereal::CanData>> Event::Builder::disownSendcan() { + KJ_IREQUIRE(which() == Event::SENDCAN, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::cereal::CanData>>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLogMessage() const { + return which() == Event::LOG_MESSAGE; +} +inline bool Event::Builder::isLogMessage() { + return which() == Event::LOG_MESSAGE; +} +inline bool Event::Reader::hasLogMessage() const { + if (which() != Event::LOG_MESSAGE) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLogMessage() { + if (which() != Event::LOG_MESSAGE) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Event::Reader::getLogMessage() const { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Event::Builder::getLogMessage() { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLogMessage( ::capnp::Text::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Event::Builder::initLogMessage(unsigned int size) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void Event::Builder::adoptLogMessage( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LOG_MESSAGE); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Event::Builder::disownLogMessage() { + KJ_IREQUIRE(which() == Event::LOG_MESSAGE, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isLiveCalibration() const { + return which() == Event::LIVE_CALIBRATION; +} +inline bool Event::Builder::isLiveCalibration() { + return which() == Event::LIVE_CALIBRATION; +} +inline bool Event::Reader::hasLiveCalibration() const { + if (which() != Event::LIVE_CALIBRATION) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasLiveCalibration() { + if (which() != Event::LIVE_CALIBRATION) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::LiveCalibrationData::Reader Event::Reader::getLiveCalibration() const { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::LiveCalibrationData::Builder Event::Builder::getLiveCalibration() { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setLiveCalibration( ::cereal::LiveCalibrationData::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::LiveCalibrationData::Builder Event::Builder::initLiveCalibration() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptLiveCalibration( + ::capnp::Orphan< ::cereal::LiveCalibrationData>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::LIVE_CALIBRATION); + ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::LiveCalibrationData> Event::Builder::disownLiveCalibration() { + KJ_IREQUIRE(which() == Event::LIVE_CALIBRATION, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::LiveCalibrationData>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +inline bool Event::Reader::isAndroidLogEntry() const { + return which() == Event::ANDROID_LOG_ENTRY; +} +inline bool Event::Builder::isAndroidLogEntry() { + return which() == Event::ANDROID_LOG_ENTRY; +} +inline bool Event::Reader::hasAndroidLogEntry() const { + if (which() != Event::ANDROID_LOG_ENTRY) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasAndroidLogEntry() { + if (which() != Event::ANDROID_LOG_ENTRY) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::AndroidLogEntry::Reader Event::Reader::getAndroidLogEntry() const { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::AndroidLogEntry::Builder Event::Builder::getAndroidLogEntry() { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setAndroidLogEntry( ::cereal::AndroidLogEntry::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::AndroidLogEntry::Builder Event::Builder::initAndroidLogEntry() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptAndroidLogEntry( + ::capnp::Orphan< ::cereal::AndroidLogEntry>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::ANDROID_LOG_ENTRY); + ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::AndroidLogEntry> Event::Builder::disownAndroidLogEntry() { + KJ_IREQUIRE(which() == Event::ANDROID_LOG_ENTRY, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::AndroidLogEntry>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + +} // namespace + +#endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ diff --git a/cereal/log.capnp b/cereal/log.capnp new file mode 100644 index 0000000000..166b2b558d --- /dev/null +++ b/cereal/log.capnp @@ -0,0 +1,272 @@ +using Cxx = import "c++.capnp"; +$Cxx.namespace("cereal"); + +@0xf3b1f17e25a4285b; + +const logVersion :Int32 = 1; + +struct InitData { + kernelArgs @0 :List(Text); + gctx @1 :Text; + dongleId @2 :Text; +} + +struct FrameData { + frameId @0 :UInt32; + encodeId @1 :UInt32; # DEPRECATED + timestampEof @2 :UInt64; + frameLength @3 :Int32; + integLines @4 :Int32; + globalGain @5 :Int32; + image @6 :Data; +} + +struct GPSNMEAData { + timestamp @0 :Int64; + localWallTime @1 :UInt64; + nmea @2 :Text; +} + +# android sensor_event_t +struct SensorEventData { + version @0 :Int32; + sensor @1 :Int32; + type @2 :Int32; + timestamp @3 :Int64; + union { + acceleration @4 :SensorVec; + magnetic @5 :SensorVec; + orientation @6 :SensorVec; + gyro @7 :SensorVec; + } + + struct SensorVec { + v @0 :List(Float32); + status @1 :Int8; + } +} + +struct CanData { + address @0 :UInt32; + busTime @1 :UInt16; + dat @2 :Data; + src @3 :Int8; +} + +struct ThermalData { + cpu0 @0 :UInt16; + cpu1 @1 :UInt16; + cpu2 @2 :UInt16; + cpu3 @3 :UInt16; + mem @4 :UInt16; + gpu @5 :UInt16; + bat @6 :UInt32; +} + +struct HealthData { + # from can health + voltage @0 :UInt32; + current @1 :UInt32; + started @2 :Bool; + controlsAllowed @3 :Bool; + gasInterceptorDetected @4 :Bool; +} + +struct LiveUI { + rearViewCam @0 :Bool; + alertText1 @1 :Text; + alertText2 @2 :Text; + awarenessStatus @3 :Float32; +} + +struct Live20Data { + canMonoTimes @10 :List(UInt64); + mdMonoTime @6 :UInt64; + ftMonoTime @7 :UInt64; + + # all deprecated + warpMatrix @0 :List(Float32); + angleOffset @1 :Float32; + calStatus @2 :Int8; + calCycle @8 :Int32; + calPerc @9 :Int8; + + leadOne @3 :LeadData; + leadTwo @4 :LeadData; + cumLagMs @5 :Float32; + + struct LeadData { + dRel @0 :Float32; + yRel @1 :Float32; + vRel @2 :Float32; + aRel @3 :Float32; + vLead @4 :Float32; + aLead @5 :Float32; + dPath @6 :Float32; + vLat @7 :Float32; + vLeadK @8 :Float32; + aLeadK @9 :Float32; + fcw @10 :Bool; + status @11 :Bool; + } +} + +struct LiveCalibrationData { + warpMatrix @0 :List(Float32); + calStatus @1 :Int8; + calCycle @2 :Int32; + calPerc @3 :Int8; +} + +struct LiveTracks { + trackId @0 :Int32; + dRel @1 :Float32; + yRel @2 :Float32; + vRel @3 :Float32; + aRel @4 :Float32; + timeStamp @5 :Float32; + status @6 :Float32; + currentTime @7 :Float32; + stationary @8 :Bool; + oncoming @9 :Bool; +} + +struct Live100Data { + canMonoTime @16 :UInt64; + canMonoTimes @21 :List(UInt64); + l20MonoTime @17 :UInt64; + mdMonoTime @18 :UInt64; + + vEgo @0 :Float32; + aEgo @1 :Float32; + vPid @2 :Float32; + vTargetLead @3 :Float32; + upAccelCmd @4 :Float32; + uiAccelCmd @5 :Float32; + yActual @6 :Float32; + yDes @7 :Float32; + upSteer @8 :Float32; + uiSteer @9 :Float32; + aTargetMin @10 :Float32; + aTargetMax @11 :Float32; + jerkFactor @12 :Float32; + angleSteers @13 :Float32; + hudLead @14 :Int32; + cumLagMs @15 :Float32; + + enabled @19: Bool; + steerOverride @20: Bool; + + vCruise @22: Float32; + + rearViewCam @23 :Bool; + alertText1 @24 :Text; + alertText2 @25 :Text; + awarenessStatus @26 :Float32; +} + +struct LiveEventData { + name @0 :Text; + value @1 :Int32; +} + +struct ModelData { + frameId @0 :UInt32; + + path @1 :PathData; + leftLane @2 :PathData; + rightLane @3 :PathData; + lead @4 :LeadData; + + settings @5 :ModelSettings; + + struct PathData { + points @0 :List(Float32); + prob @1 :Float32; + std @2 :Float32; + } + + struct LeadData { + dist @0 :Float32; + prob @1 :Float32; + std @2 :Float32; + } + + struct ModelSettings { + bigBoxX @0 :UInt16; + bigBoxY @1 :UInt16; + bigBoxWidth @2 :UInt16; + bigBoxHeight @3 :UInt16; + boxProjection @4 :List(Float32); + yuvCorrection @5 :List(Float32); + } +} + +struct CalibrationFeatures { + frameId @0 :UInt32; + + p0 @1 :List(Float32); + p1 @2 :List(Float32); + status @3 :List(Int8); +} + +struct EncodeIndex { + # picture from camera + frameId @0 :UInt32; + type @1 :Type; + # index of encoder from start of route + encodeId @2 :UInt32; + # minute long segment this frame is in + segmentNum @3 :Int32; + # index into camera file in segment from 0 + segmentId @4 :UInt32; + + enum Type { + bigBoxLossless @0; # rcamera.mkv + fullHEVC @1; # fcamera.hevc + bigBoxHEVC @2; # bcamera.hevc + } +} + +struct AndroidLogEntry { + id @0 :UInt8; + ts @1 :UInt64; + priority @2 :UInt8; + pid @3 :Int32; + tid @4 :Int32; + tag @5 :Text; + message @6 :Text; +} + +struct LogRotate { + segmentNum @0 :Int32; + path @1 :Text; +} + + +struct Event { + logMonoTime @0 :UInt64; + + union { + initData @1 :InitData; + frame @2 :FrameData; + gpsNMEA @3 :GPSNMEAData; + sensorEventDEPRECATED @4 :SensorEventData; + can @5 :List(CanData); + thermal @6 :ThermalData; + live100 @7 :Live100Data; + liveEventDEPRECATED @8 :List(LiveEventData); + model @9 :ModelData; + features @10 :CalibrationFeatures; + sensorEvents @11 :List(SensorEventData); + health @12 : HealthData; + live20 @13 :Live20Data; + liveUIDEPRECATED @14 :LiveUI; + encodeIdx @15 :EncodeIndex; + liveTracks @16 :List(LiveTracks); + sendcan @17 :List(CanData); + logMessage @18 :Text; + liveCalibration @19 :LiveCalibrationData; + androidLogEntry @20 :AndroidLogEntry; + } +} diff --git a/common/__init__.py b/common/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/common/api/__init__.py b/common/api/__init__.py new file mode 100644 index 0000000000..daf21cd4a3 --- /dev/null +++ b/common/api/__init__.py @@ -0,0 +1,8 @@ +import requests + +def api_get(endpoint, method='GET', timeout=None, **params): + backend = "https://api.commadotai.com/" + + params['_version'] = "OPENPILOTv0.0" + + return requests.request(method, backend+endpoint, timeout=timeout, params=params) diff --git a/common/crash.py b/common/crash.py new file mode 100644 index 0000000000..e886758184 --- /dev/null +++ b/common/crash.py @@ -0,0 +1,26 @@ +"""Install exception handler for process crash.""" +import os +import sys + +if os.getenv("NOLOG"): + def capture_exception(*exc_info): + pass + def install(): + pass +else: + from raven import Client + from raven.transport.http import HTTPTransport + + client = Client('https://1994756b5e6f41cf939a4c65de45f4f2:cefebaf3a8aa40d182609785f7189bd7@app.getsentry.com/77924', + install_sys_hook=False, transport=HTTPTransport) + + capture_exception = client.captureException + + def install(): + # installs a sys.excepthook + __excepthook__ = sys.excepthook + def handle_exception(*exc_info): + if exc_info[0] not in (KeyboardInterrupt, SystemExit): + client.captureException(exc_info=exc_info) + __excepthook__(*exc_info) + sys.excepthook = handle_exception diff --git a/common/dbc.py b/common/dbc.py new file mode 100755 index 0000000000..bc9dab3bac --- /dev/null +++ b/common/dbc.py @@ -0,0 +1,182 @@ +import re +from collections import namedtuple +import bitstring + +def int_or_float(s): + # return number, trying to maintain int format + try: + return int(s) + except ValueError: + return float(s) + +DBCSignal = namedtuple( + "DBCSignal", ["name", "start_bit", "size", "is_little_endian", "is_signed", + "factor", "offset", "tmin", "tmax", "units"]) + +class dbc(object): + def __init__(self, fn): + self.txt = open(fn).read().split("\n") + self._warned_addresses = set() + + # regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py + bo_regexp = re.compile("^BO\_ (\w+) (\w+) *: (\w+) (\w+)") + sg_regexp = re.compile("^SG\_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + sgm_regexp = re.compile("^SG\_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + + # A dictionary which maps message ids to tuples ((name, size), signals). + # name is the ASCII name of the message. + # size is the size of the message in bytes. + # signals is a list signals contained in the message. + # signals is a list of DBCSignal in order of increasing start_bit. + self.msgs = {} + + self.bits = [] + for i in range(0, 64, 8): + for j in range(7, -1, -1): + self.bits.append(i+j) + + for l in self.txt: + l = l.strip() + + if l.startswith("BO_ "): + # new group + dat = bo_regexp.match(l) + + if dat is None: + print "bad BO", l + name = dat.group(2) + size = int(dat.group(3)) + ids = int(dat.group(1), 0) # could be hex + + self.msgs[ids] = ((name, size), []) + + if l.startswith("SG_ "): + # new signal + dat = sg_regexp.match(l) + go = 0 + if dat is None: + dat = sgm_regexp.match(l) + go = 1 + if dat is None: + print "bad SG", l + + sgname = dat.group(1) + start_bit = int(dat.group(go+2)) + signal_size = int(dat.group(go+3)) + is_little_endian = int(dat.group(go+4))==1 + is_signed = dat.group(go+5)=='-' + factor = int_or_float(dat.group(go+6)) + offset = int_or_float(dat.group(go+7)) + tmin = int_or_float(dat.group(go+8)) + tmax = int_or_float(dat.group(go+9)) + units = dat.group(go+10) + + self.msgs[ids][1].append( + DBCSignal(sgname, start_bit, signal_size, is_little_endian, + is_signed, factor, offset, tmin, tmax, units)) + + for msg in self.msgs.viewvalues(): + msg[1].sort(key=lambda x: x.start_bit) + + def encode(self, msg_id, dd): + """Encode a CAN message using the dbc. + + Inputs: + msg_id: The message ID. + dd: A dictionary mapping signal name to signal data. + """ + # TODO: Stop using bitstring, which is super slow. + msg_def = self.msgs[msg_id] + size = msg_def[0][1] + + bsf = bitstring.Bits(hex="00"*size) + for s in msg_def[1]: + ival = dd.get(s.name) + if ival is not None: + ival = (ival / s.factor) - s.offset + ival = int(round(ival)) + + # should pack this + if s.is_little_endian: + ss = s.start_bit + else: + ss = self.bits.index(s.start_bit) + + + if s.is_signed: + tbs = bitstring.Bits(int=ival, length=s.size) + else: + tbs = bitstring.Bits(uint=ival, length=s.size) + + lpad = bitstring.Bits(bin="0b"+"0"*ss) + rpad = bitstring.Bits(bin="0b"+"0"*(8*size-(ss+s.size))) + tbs = lpad+tbs+rpad + + bsf |= tbs + return bsf.tobytes() + + def decode(self, x, arr=None, debug=False): + """Decode a CAN message using the dbc. + + Inputs: + x: A collection with elements (address, time, data), where address is + the CAN address, time is the bus time, and data is the CAN data as a + hex string. + arr: Optional list of signals which should be decoded and returned. + debug: True to print debugging statements. + + Returns: + A tuple (name, data), where name is the name of the CAN message and data + is the decoded result. If arr is None, data is a dict of properties. + Otherwise data is a list of the same length as arr. + + Returns (None, None) if the message could not be decoded. + """ + if arr is None: + out = {} + else: + out = [None]*len(arr) + + msg = self.msgs.get(x[0]) + if msg is None: + if x[0] not in self._warned_addresses: + print("WARNING: Unknown message address {}".format(x[0])) + self._warned_addresses.add(x[0]) + return None, None + + name = msg[0][0] + if debug: + print name + + blen = (len(x[2])/2)*8 + x2_int = int(x[2], 16) + + for s in msg[1]: + if arr is not None and s[0] not in arr: + continue + + # big or little endian? + # see http://vi-firmware.openxcplatform.com/en/master/config/bit-numbering.html + if s[3] is False: + ss = self.bits.index(s[1]) + else: + ss = s[1] + + data_bit_pos = (blen - (ss + s[2])) + if data_bit_pos < 0: + continue + ival = (x2_int >> data_bit_pos) & ((1 << (s[2])) - 1) + + if s[4] and (ival & (1<<(s[2]-1))): # signed + ival -= (1< +CLOCK_BOOTTIME = 7 + +class timespec(ctypes.Structure): + _fields_ = [ + ('tv_sec', ctypes.c_long), + ('tv_nsec', ctypes.c_long), + ] + + +try: + libc = ctypes.CDLL('libc.so', use_errno=True) +except OSError: + try: + libc = ctypes.CDLL('libc.so.6', use_errno=True) + except OSError: + libc = None + +if libc is not None: + libc.clock_gettime.argtypes = [ctypes.c_int, ctypes.POINTER(timespec)] + +def clock_gettime(clk_id): + if platform.system() == "darwin": + # TODO: fix this + return time.time() + else: + t = timespec() + if libc.clock_gettime(clk_id, ctypes.pointer(t)) != 0: + errno_ = ctypes.get_errno() + raise OSError(errno_, os.strerror(errno_)) + return t.tv_sec + t.tv_nsec * 1e-9 + +def monotonic_time(): + return clock_gettime(CLOCK_MONOTONIC_RAW) + +def sec_since_boot(): + return clock_gettime(CLOCK_BOOTTIME) + + +def set_realtime_priority(level): + if os.getuid() != 0: + print "not setting priority, not root" + return + if platform.machine() == "x86_64": + NR_gettid = 186 + elif platform.machine() == "aarch64": + NR_gettid = 178 + else: + raise NotImplementedError + + tid = libc.syscall(NR_gettid) + subprocess.check_call(['chrt', '-f', '-p', str(level), str(tid)]) + + +class Ratekeeper(object): + def __init__(self, rate, print_delay_threshold=0.): + """Rate in Hz for ratekeeping. print_delay_threshold must be nonnegative.""" + self._interval = 1. / rate + self._next_frame_time = sec_since_boot() + self._interval + self._print_delay_threshold = print_delay_threshold + self._frame = 0 + self._remaining = 0 + self._process_name = multiprocessing.current_process().name + + @property + def frame(self): + return self._frame + + @property + def remaining(self): + return self._remaining + + # Maintain loop rate by calling this at the end of each loop + def keep_time(self): + self.monitor_time() + if self._remaining > 0: + time.sleep(self._remaining) + + # this only monitor the cumulative lag, but does not enforce a rate + def monitor_time(self): + remaining = self._next_frame_time - sec_since_boot() + self._next_frame_time += self._interval + if remaining < -self._print_delay_threshold: + print self._process_name, "lagging by", round(-remaining * 1000, 2), "ms" + self._frame += 1 + self._remaining = remaining diff --git a/common/services.py b/common/services.py new file mode 100644 index 0000000000..6a2cd948c7 --- /dev/null +++ b/common/services.py @@ -0,0 +1,82 @@ +# TODO: these port numbers are hardcoded in c, fix this + +# LogRotate: 8001 is a PUSH PULL socket between loggerd and visiond + +class Service(object): + def __init__(self, port, should_log): + self.port = port + self.should_log = should_log + +# all ZMQ pub sub +service_list = { + # frame syncing packet + "frame": Service(8002, True), + # accel, gyro, and compass + "sensorEvents": Service(8003, True), + # GPS data, also global timestamp + "gpsNMEA": Service(8004, True), + # CPU+MEM+GPU+BAT temps + "thermal": Service(8005, True), + # List(CanData), list of can messages + "can": Service(8006, True), + "live100": Service(8007, True), + # random events we want to log + #"liveEvent": Service(8008, True), + "model": Service(8009, True), + "features": Service(8010, True), + "health": Service(8011, True), + "live20": Service(8012, True), + #"liveUI": Service(8014, True), + "encodeIdx": Service(8015, True), + "liveTracks": Service(8016, True), + "sendcan": Service(8017, True), + "logMessage": Service(8018, True), + "liveCalibration": Service(8019, True), + "androidLog": Service(8020, True), +} + +# manager -- base process to manage starting and stopping of all others +# subscribes: health +# publishes: thermal + +# boardd -- communicates with the car +# subscribes: sendcan +# publishes: can, health + +# visiond -- talks to the cameras, runs the model, saves the videos +# subscribes: liveCalibration, sensorEvents +# publishes: frame, encodeIdx, model, features + +# controlsd -- actually drives the car +# subscribes: can, thermal, model, live20 +# publishes: sendcan, live100 + +# radard -- processes the radar data +# subscribes: can, live100, model +# publishes: live20, liveTracks + +# sensord -- publishes the IMU and GPS +# publishes: sensorEvents, gpsNMEA + +# calibrationd -- places the camera box +# subscribes: features, live100 +# publishes: liveCalibration + +# **** LOGGING SERVICE **** + +# loggerd +# subscribes: EVERYTHING + +# **** NON VITAL SERVICES **** + +# ui +# subscribes: live100, live20, liveCalibration, model, (raw frames) + +# uploader +# communicates through file system with loggerd + +# logmessaged -- central logging service, can log to cloud +# publishes: logMessage + +# logcatd -- fetches logcat info from android +# publishes: androidLog diff --git a/dbcs/__init__.py b/dbcs/__init__.py new file mode 100644 index 0000000000..a74a06029f --- /dev/null +++ b/dbcs/__init__.py @@ -0,0 +1,2 @@ +import os +DBC_PATH = os.path.dirname(os.path.abspath(__file__)) diff --git a/dbcs/acura_ilx_2016_can.dbc b/dbcs/acura_ilx_2016_can.dbc new file mode 100644 index 0000000000..87c201d117 --- /dev/null +++ b/dbcs/acura_ilx_2016_can.dbc @@ -0,0 +1,295 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BO_ 0x039 XXX: 3 XXX + +BO_ 0x091 XXX: 8 XXX + SG_ LAT_ACCEL : 0|10@1+ (0.02,-512) [-20|20] "m/s2" Vector__XXX + +BO_ 0x0E4 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 0|16@1- (1,0) [-3840|3840] "" Vector__XXX + SG_ STEER_TORQUE_REQUEST : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X00 : 17|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ SET_ME_X00 : 24|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x130 GAS_PEDAL2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 0|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ ENGINE_TORQUE_REQUEST : 16|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x13C GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x156 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 0|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ STEER_ANGLE_RATE : 16|16@1- (1,0) [-3000|3000] "deg/s" Vector__XXX + SG_ COUNTER : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 44|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x158 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 0|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ XMISSION_SPEED2 : 32|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x17C POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ GAS_PRESSED : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_STATUS : 33|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH_17C : 34|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_LIGHTS_ON : 39|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH2_17C : 40|10@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_PRESSED : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH3_17C : 51|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x18E XXX: 3 XXX + +BO_ 0x18F STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 0|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_TORQUE_MOTOR : 16|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_STATUS : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ STEER_CONTROL_ACTIVE : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A3 GEARBOX: 8 PCM + SG_ GEAR : 0|8@1+ (1,0) [0|256] "" Vector__XXX + SG_ GEAR_SHIFTER : 36|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A4 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 0|16@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ ESP_DISABLED : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A6 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 0|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ LIGHTS_SETTING : 6|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ MAIN_ON : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_SETTING : 44|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1AC XXX: 8 XXX + +BO_ 0x1B0 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_1 : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_2 : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D0 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 0|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_FR : 15|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RL : 30|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RR : 45|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1DC XXX: 4 XXX + +BO_ 0x1EA VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 16|16@1- (0.0015384,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x1FA BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 0|10@1+ (0.003906248,0) [0|1] "" Vector__XXX + SG_ ZEROS_BOH : 10|5@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH2 : 16|3@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_OVERRIDE : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH3 : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_FAULT_CMD : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_CANCEL_CMD : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST_2 : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH4 : 24|8@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_LIGHTS : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH5 : 33|7@1+ (1,0) [0|1] "" Vector__XXX + SG_ CHIME : 40|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ CRUISE_BOH6 : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCW : 44|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_BOH7 : 46|10@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x200 GAS_COMMAND: 3 ADAS + SG_ GAS_COMMAND : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ COUNTER : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 20|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x201 GAS_SENSOR: 5 ADAS + SG_ INTERCEPTOR_GAS : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ INTERCEPTOR_GAS2 : 16|16@1+ (0.126992032,-656) [0|1] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x21E XXX: 7 XXX +BO_ 0x221 XXX: 4 XXX + +BO_ 0x255 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 0|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_FR : 8|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RL : 16|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RR : 24|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ SET_TO_X55 : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SET_TO_X55 : 40|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x294 SCM_COMMANDS: 8 SCM + SG_ RIGHT_BLINKER : 1|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LEFT_BLINKER : 2|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ WIPERS_SPEED : 3|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x305 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SEATBELT_DRIVER_LATCHED : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x309 XXX: 8 XXX + +BO_ 0x30C ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 0|16@1+ (0.002763889,0) [0|100] "m/s" Vector__XXX + SG_ PCM_GAS : 16|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ ZEROS_BOH : 23|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ DTC_MODE : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_PROBLEM : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_OFF : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH_2 : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_PROBLEM : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RADAR_OBSTRUCTED : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ENABLE_MINI_CAR : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X03 : 40|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_LEAD : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_3 : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_4 : 45|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_5 : 46|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_CONTROL_LABEL : 47|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_DISTANCE_3 : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x320 XXX: 8 XXX + +BO_ 0x324 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 8|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ TRIP_FUEL_CONSUMED : 16|16@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED_PCM : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH2 : 40|8@1- (1,0) [0|255] "" Vector__XXX + SG_ BOH3 : 48|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x328 XXX: 8 XXX +BO_ 0x333 XXX: 7 XXX +BO_ 0x335 XXX: 5 XXX + +BO_ 0x33D LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 0|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 1|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ DASHED_LANES : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DTC : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_PROBLEM : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_OFF : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SOLID_LANES : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_RIGHT : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STEERING_REQUIRED : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 16|2@1+ (1,0) [0|4] "" Vector__XXX + SG_ LDW_PROBLEM : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BEEP : 22|2@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_OFF : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CLEAN_WINDSHIELD : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X48 : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + + +BO_ 0x372 XXX: 2 XXX + +BO_ 0x374 XXX: 7 XXX +BO_ 0x377 XXX: 8 XXX +BO_ 0x378 XXX: 8 XXX +BO_ 0x37C XXX: 8 XXX +BO_ 0x39B XXX: 2 XXX +BO_ 0x3A1 XXX: 4 XXX +BO_ 0x3D7 XXX: 8 XXX +BO_ 0x3D9 XXX: 3 XXX +BO_ 0x400 XXX: 5 XXX +BO_ 0x403 XXX: 5 XXX + +BO_ 0x405 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RL : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RR : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x406 XXX: 5 VSA +BO_ 0x40A XXX: 5 XXX +BO_ 0x40C XXX: 8 XXX +BO_ 0x40F XXX: 8 XXX +BO_ 0x421 XXX: 5 EPS +BO_ 0x428 XXX: 7 XXX +BO_ 0x454 XXX: 8 XXX +BO_ 0x555 XXX: 5 XXX +BO_ 0x640 XXX: 5 XXX +BO_ 0x641 XXX: 8 XXX + +VAL_ 0x1A6 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 0x1A6 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 0x30C HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 0x1A6 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights"; +VAL_ 0x18F STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal"; +VAL_ 0x1A3 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P"; +VAL_ 0x33D BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 0x1FA CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 0x1FA FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; + +CM_ SG_ 0x1A3 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 0x324 CRUISE_SPEED_ECHO "255 = no speed"; +CM_ SG_ 0x33D CRUISE_SPEED "255 = no speed"; +CM_ SG_ 0x1EA LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 0x33D BEEP "beeps are pleasant, chimes are for warnngs etc..."; diff --git a/dbcs/acura_ilx_2016_nidec.dbc b/dbcs/acura_ilx_2016_nidec.dbc new file mode 100644 index 0000000000..70105e38e2 --- /dev/null +++ b/dbcs/acura_ilx_2016_nidec.dbc @@ -0,0 +1,175 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + + +BO_ 0x300 VEHICLE_STATE: 8 ADAS + SG_ SET_ME_XF9 : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ VEHICLE_SPEED : 8|8@1+ (1,0) [0|255] "kph" Vector__XXX + +BO_ 0x301 VEHICLE_STATE2: 8 ADAS + SG_ SET_ME_0F18510 : 0|28@1+ (1,0) [0|268435455] "" Vector__XXX + SG_ SET_ME_25A0000 : 28|28@1+ (1,0) [0|268435455] "" Vector__XXX + +BO_ 0x400 XXX: 8 RADAR + +BO_ 0x410 XXX: 8 RADAR + +BO_ 0x411 XXX: 8 RADAR + +BO_ 0x412 XXX: 8 RADAR + +BO_ 0x413 XXX: 8 RADAR + +BO_ 0x414 XXX: 8 RADAR + +BO_ 0x415 XXX: 8 RADAR + +BO_ 0x416 XXX: 8 RADAR + +BO_ 0x417 XXX: 8 RADAR + +BO_ 0x420 XXX: 8 RADAR + +BO_ 0x421 XXX: 8 RADAR + +BO_ 0x422 XXX: 8 RADAR + +BO_ 0x423 XXX: 8 RADAR + +BO_ 0x424 XXX: 8 RADAR + +BO_ 0x430 TRACK_0: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x431 TRACK_1: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x432 TRACK_2: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x433 TRACK_3: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x434 TRACK_4: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x435 TRACK_5: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x436 TRACK_6: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x437 TRACK_7: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x438 TRACK_8: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x439 TRACK_9: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x440 TRACK_10: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x441 TRACK_11: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x442 TRACK_12: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x443 TRACK_13: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x444 TRACK_14: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x445 TRACK_15: 8 RADAR + SG_ LONG_DIST : 0|12@1+ (0.0625,0) [0|255.5] "m" Vector__XXX + SG_ NEW_TRACK : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LAT_DIST : 14|10@1- (0.0625,0) [0|63.5] "m" Vector__XXX + SG_ REL_SPEED : 24|12@1- (0.03125,0) [0|127.5] "m/s" Vector__XXX + +BO_ 0x4FF XXX: 8 RADAR + +BO_ 0x500 XXX: 8 RADAR + +BO_ 0x510 XXX: 8 RADAR + +BO_ 0x511 XXX: 8 RADAR diff --git a/dbcs/honda_civic_touring_2016_can.dbc b/dbcs/honda_civic_touring_2016_can.dbc new file mode 100644 index 0000000000..3ba510c44b --- /dev/null +++ b/dbcs/honda_civic_touring_2016_can.dbc @@ -0,0 +1,319 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BO_ 0x039 XXX: 3 XXX + +BO_ 0x94 XXX: 8 XXX + SG_ LAT_ACCEL : 0|10@1+ (0.02,-512) [-20|20] "m/s2" Vector__XXX + SG_ LONG_ACCEL : 31|9@1- (-0.02,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x0E4 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 0|16@1- (1,0) [-3840|3840] "" Vector__XXX + SG_ STEER_TORQUE_REQUEST : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X00 : 17|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ SET_ME_X00_2 : 24|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ CHECKSUM : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 38|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x130 GAS_PEDAL2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 0|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ ENGINE_TORQUE_REQUEST : 16|16@1- (1,0) [-1000|1000] "Nm" Vector__XXX + SG_ CAR_GAS : 32|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x14A STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 0|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ STEER_ANGLE_RATE : 16|16@1- (-1,0) [-3000|3000] "deg/s" Vector__XXX + SG_ STEER_ANGLE_OFFSET : 32|8@1- (-0.1,0) [-128|127] "deg" Vector__XXX + SG_ STEER_WHEEL_ANGLE : 40|16@1- (-0.1,0) [-500|500] "deg" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x158 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 0|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ XMISSION_SPEED2 : 32|16@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x17C POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ENGINE_RPM : 16|16@1+ (1,0) [0|15000] "rpm" Vector__XXX + SG_ GAS_PRESSED : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_STATUS : 33|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH_17C : 34|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_LIGHTS_ON : 39|1@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BOH2_17C : 40|10@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ BRAKE_PRESSED : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH3_17C : 51|5@1+ (1,0) [0|1] "rpm" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x18F STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 0|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_TORQUE_MOTOR : 16|16@1- (1,0) [-31000|31000] "tbd" Vector__XXX + SG_ STEER_STATUS : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ STEER_CONTROL_ACTIVE : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x191 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 2|6@1+ (1,0) [0|63] "" Vector__XXX + SG_ GEAR : 36|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1A4 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 0|16@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ ESP_DISABLED : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1AB XXX: 3 VSA + +BO_ 0x1AC XXX: 8 XXX + +BO_ 0x1B0 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_1 : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_ERROR_2 : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1C2 XXX: 8 EPB + SG_ EPB_ACTIVE : 4|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_STATE : 26|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D0 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 0|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_FR : 15|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RL : 30|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ WHEEL_SPEED_RR : 45|15@1+ (0.002759506,0) [0|70] "m/s" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x1D6 XXX: 2 VSA + +BO_ 0x1DC XXX: 7 XXX + +BO_ 0x1E7 XXX: 4 VSA + SG_ BRAKE_PRESSURE1 : 0|10@1+ (0.015625,-103) [0|1000] "" Vector__XXX + SG_ BRAKE_PRESSURE2 : 14|10@1+ (0.015625,-103) [0|1000] "" Vector__XXX + +BO_ 0x1EA VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 16|16@1- (0.0015384,0) [-20|20] "m/s2" Vector__XXX + +BO_ 0x1ED XXX: 5 VSA + +BO_ 0x1FA BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 0|10@1+ (0.003906248,0) [0|1.0] "" Vector__XXX + SG_ ZEROS_BOH : 10|5@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH2 : 16|3@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_OVERRIDE : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_BOH3 : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_FAULT_CMD : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_CANCEL_CMD : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COMPUTER_BRAKE_REQUEST_2 : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_0X80 : 24|8@1+ (1,0) [0|1] "" Vector__XXX + SG_ BRAKE_LIGHTS : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CRUISE_STATES : 33|7@1+ (1,0) [0|1] "" Vector__XXX + SG_ CHIME : 40|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ ZEROS_BOH6 : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCW : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ ZEROS_BOH3 : 45|2@1+ (1,0) [0|0] "" Vector__XXX + SG_ FCW2 : 47|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ ZEROS_BOH4 : 48|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x200 GAS_COMMAND: 3 ADAS + SG_ GAS_COMMAND : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ COUNTER : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 20|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x201 GAS_SENSOR: 5 ADAS + SG_ INTERCEPTOR_GAS : 0|16@1+ (0.253984064,-328) [0|1] "" Vector__XXX + SG_ INTERCEPTOR_GAS2 : 16|16@1+ (0.126992032,-656) [0|1] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x221 XXX: 6 XXX + +BO_ 0x255 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 0|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_FR : 8|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RL : 16|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ WHEEL_SPEED_RR : 24|8@1+ (1,0) [0|255] "mph" Vector__XXX + SG_ SET_TO_X55 : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SET_TO_X55 : 40|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 0x296 CRUISE_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 0|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ CRUISE_SETTING : 4|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x305 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SEATBELT_DRIVER_LATCHED : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 52|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x309 XXX: 8 XXX + +BO_ 0x30C ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 0|16@1+ (0.002763889,0) [0|100] "m/s" Vector__XXX + SG_ PCM_GAS : 16|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ ZEROS_BOH : 23|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ DTC_MODE : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ACC_PROBLEM : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_OFF : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH_2 : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ FCM_PROBLEM : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RADAR_OBSTRUCTED : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ENABLE_MINI_CAR : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HUD_DISTANCE : 40|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ HUD_LEAD : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_3 : 44|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_4 : 45|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ BOH_5 : 46|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ CRUISE_CONTROL_LABEL : 47|1@1+ (1,0) [0|3] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x31B XXX: 8 XXX + +BO_ 0x320 XXX: 8 XXX + +BO_ 0x324 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 8|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ TRIP_FUEL_CONSUMED : 16|16@1+ (1,0) [0|255] "" Vector__XXX + SG_ CRUISE_SPEED_PCM : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH2 : 40|8@1- (1,0) [0|255] "" Vector__XXX + SG_ BOH3 : 48|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x326 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 17|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ MAIN_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RIGHT_BLINKER : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LEFT_BLINKER : 29|1@1+ (1,0) [0|1] "" Vector__XXX + + +BO_ 0x328 XXX: 8 XXX + +BO_ 0x33D LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 0|1@1+ (1,0) [0|255] "" Vector__XXX + SG_ BOH : 1|7@1+ (1,0) [0|127] "" Vector__XXX + SG_ DASHED_LANES : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DTC : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_PROBLEM : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LKAS_OFF : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SOLID_LANES : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_RIGHT : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STEERING_REQUIRED : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BOH : 16|2@1+ (1,0) [0|4] "" Vector__XXX + SG_ LDW_PROBLEM : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BEEP : 22|2@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_ON : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LDW_OFF : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CLEAN_WINDSHIELD : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SET_ME_X48 : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 34|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 36|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x35E XXX: 8 ADAS + SG_ UI_ALERTS : 0|56@1+ (1,0) [0|127] "" Vector__XXX + +BO_ 0x374 XXX: 8 XXX +BO_ 0x37B XXX: 8 XXX +BO_ 0x37C XXX: 8 XXX + +BO_ 0x39F XXX: 8 ADAS + SG_ ZEROS_BOH : 0|17@1+ (1,0) [0|127] "" Vector__XXX + SG_ APPLY_BRAKES_FOR_CANC : 16|1@1+ (1,0) [0|15] "" Vector__XXX + SG_ ZEROS_BOH2 : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ RESUME_INSTRUCTION : 18|1@1+ (1,0) [0|15] "" Vector__XXX + SG_ ACC_ALERTS : 19|5@1+ (1,0) [0|15] "" Vector__XXX + SG_ ZEROS_BOH2 : 24|8@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_SPEED : 32|9@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_STATE : 41|3@1+ (1,0) [0|127] "" Vector__XXX + SG_ LEAD_DISTANCE : 44|5@1+ (1,0) [0|31] "" Vector__XXX + SG_ ZEROS_BOH3 : 49|7@1+ (1,0) [0|127] "" Vector__XXX + +BO_ 0x3A1 XXX: 8 XXX +BO_ 0x3D9 XXX: 3 XXX +BO_ 0x400 XXX: 5 XXX +BO_ 0x403 XXX: 5 XXX + +BO_ 0x405 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RL : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DOOR_OPEN_RR : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ COUNTER : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ CHECKSUM : 60|4@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 0x40C XXX: 8 XXX +BO_ 0x40F XXX: 8 XXX +BO_ 0x454 XXX: 8 XXX +BO_ 0x516 XXX: 8 XXX +BO_ 0x52A XXX: 5 XXX +BO_ 0x551 XXX: 5 XXX +BO_ 0x555 XXX: 5 XXX +BO_ 0x590 XXX: 5 XXX +BO_ 0x640 XXX: 5 XXX +BO_ 0x641 XXX: 8 XXX +BO_ 0x661 XXX: 8 XXX + +VAL_ 0x296 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 0x296 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 0x33D HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 0x1A6 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights"; +VAL_ 0x18F STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal"; +VAL_ 0x191 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P"; +VAL_ 0x33D BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 0x1FA CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 0x1C2 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged"; +VAL_ 0x326 CMBS_BUTTON 3 "pressed" 0 "released"; +VAL_ 0x39F ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead"; +VAL_ 0x30C CRUISE_SPEED 255 "no_speed" 252 "stopped"; + +CM_ SG_ 0x1A3 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 0x324 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 0x30C CRUISE_SPEED "255 = no speed"; +CM_ SG_ 0x1EA LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 0x33D BEEP "beeps are pleasant, chimes are for warnngs etc..."; diff --git a/installation/files/continue.sh b/installation/files/continue.sh new file mode 100755 index 0000000000..2030d907a9 --- /dev/null +++ b/installation/files/continue.sh @@ -0,0 +1,28 @@ +#!/usr/bin/bash + +# enable wifi access point for debugging only! +#service call wifi 37 i32 0 i32 1 # WifiService.setWifiApEnabled(null, true) + +# use the openpilot ro key +export GIT_SSH_COMMAND="ssh -i /data/data/com.termux/files/id_rsa_openpilot_ro" + +# check out the openpilot repo +# TODO: release branch only +if [ ! -d /data/openpilot ]; then + cd /tmp + git clone git@github.com:commaai/openpilot.git + mv /tmp/openpilot /data/openpilot +fi + +# update the openpilot repo +cd /data/openpilot +git pull + +# start manager +cd selfdrive +mkdir -p /sdcard/realdata +PYTHONPATH=/data/openpilot ./manager.py + +# if broken, keep on screen error +while true; do sleep 1; done + diff --git a/installation/files/id_rsa_openpilot_ro b/installation/files/id_rsa_openpilot_ro new file mode 100644 index 0000000000..de98cabe17 --- /dev/null +++ b/installation/files/id_rsa_openpilot_ro @@ -0,0 +1,27 @@ +-----BEGIN RSA PRIVATE KEY----- +MIIEpAIBAAKCAQEAy/ZlYE/iHHjhbSvCnBm5Zsq5GPpVugLXFHai/doqyfRxErop +/g1TIRhzK3mkHRYRN7H0L9whogwoIVr5CldoxU49FDnNbVHNimScNrL4LprRWjq6 +dRmCVoxMpLHZTyX1jIkcHsMr7klcUnssyeQO2pWvZv0ZC67wM7G20r7+ZLdEa0Ck +MBh8JYhDaZx2xvYtTnt6vKMmFVE5+zW/+wDVma3a4r9pG9s0+r0wCl8CUuJ+yDhR +mzNkPJ5mJCMx99AI6k4Gq9Vsng8/35b6Azh3TucPaXOLK7yPnL3YBKUa0PpR7IRH ++OKkVCH+LL7tcPFSqPPVy/pUTBdEUROjJdSHxwIDAQABAoIBAQCxBgUM56h3T89Q +AoghFg6dkdu/Ox8GmAp231UuAJncuMUfHObvcj8xXVgwZp4zBIEjFte6ZlPmoqh9 +8sht2lm7zeEjWdvbQwGjWRlgPEs9n++OYaSNl/tRBOpMk3Ppxydst1/prznE0nVH +vVKtU7w0qXAYchm30zj1lQv5s/12CTGmnpQatbo5X488RfCfv2zFX1h+lEWF8ycL +eZRi8z6l8h2Y+JLyEwPCmR+gR6XtosZ/ECQcTknavqLqdr7NbYYfOo3JfHCUtpJa +8s7m0VFhMuxFFCl1sV0eMzAynJYNVz45DyaKpr2b/2YAGY8fn96FxaWv1xw1xTkK +c5+wStwJAoGBAOjQpLZ1qGa4GwXzeHoDsGFpGgY9ug6af0M23c8O42fJHAwYkk7r +Qeo4SSBddoSfo3jdchFLo59+m3qyTKpjkph7NBBCEwaCvX3heStDIMZEWX0IOV5y +iJD/D6EXSqFmXCUUaudX2OxlaHguA0yOEx9s/5uUJrvaIHbBAOpYyar1AoGBAOBG +MJp+EA3e1Zx/VszD2Tdxn8V0DAwvy9WIEqZuG689S/Sk5GnA4m2L8Txv0xAHFvLv +JpF7Zn9AoFXGpjf9P0FF53cpjEYn9f+uK84j1HOL/6R7Nj9rcS5yL2PCP1ZHymw6 +xOXl3oZa1YtYE6jfvXUaOb8Z7y8gaStP763sXmpLAoGBAM1WSBANUcvXES58gIPN +ASHJGwTqKFF8/kV//L4EuZjuDWi1u0UTxX0Yy5ZaGI/8ZKfTWCnc9qFTfzoGTAvz +6nXGJDM6s6EIaqy90qrPd/amje7y8/ZTOhP4ggZojpAvwZGKoocMOey1vCBTJOG+ +ZStQbVkAn/EK/5r9uxr12FiJAoGAH9UWlPcLpExamWnhkhLCRAJWoRoFk708+0Pj +EchTGZ5jp4e3++KqwM26Ic/lb0LyWOzk1oVjWPB9UW9urEe/sK4RWnKFPHfzjKTW +Bt5DC1t1n4z1eC7x05vVah1qC/8IljAJPnBQE1XVNX/82l1XcMWWKK+vqUq6YrFn +3ZHNHN0CgYA3uUVWqW37vfJuk0MJBkQSqMo5Y5TPlCt4b1ebkdhlM4v/N+iuiPiC +PBhjP1MLeudkJvzllt4YvNWLerCKpMWuw7Zvy5uzFEsqOrVlzfnyWqqqYbYjHe9f +Ef0/yXKuGJajs54Ts6Xrm0+elVUu//pEuf6NI96Ehctqz8/BqGqAtw== +-----END RSA PRIVATE KEY----- diff --git a/installation/install.sh b/installation/install.sh new file mode 100755 index 0000000000..011e2c187f --- /dev/null +++ b/installation/install.sh @@ -0,0 +1,11 @@ +#!/bin/bash +set -e + +# move files into place +adb push files/id_rsa_openpilot_ro /tmp/id_rsa_openpilot_ro +adb shell mv /tmp/id_rsa_openpilot_ro /data/data/com.termux/files/ + +# moving continue into place runs the continue script +adb push files/continue.sh /tmp/continue.sh +adb shell mv /tmp/continue.sh /data/data/com.termux/files/ + diff --git a/phonelibs/hierarchy/lib/_hierarchy.so b/phonelibs/hierarchy/lib/_hierarchy.so new file mode 100755 index 0000000000..367b717758 Binary files /dev/null and b/phonelibs/hierarchy/lib/_hierarchy.so differ diff --git a/phonelibs/nanovg/fontstash.h b/phonelibs/nanovg/fontstash.h new file mode 100644 index 0000000000..35dfb0f652 --- /dev/null +++ b/phonelibs/nanovg/fontstash.h @@ -0,0 +1,1718 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef FONS_H +#define FONS_H + +#define FONS_INVALID -1 + +enum FONSflags { + FONS_ZERO_TOPLEFT = 1, + FONS_ZERO_BOTTOMLEFT = 2, +}; + +enum FONSalign { + // Horizontal align + FONS_ALIGN_LEFT = 1<<0, // Default + FONS_ALIGN_CENTER = 1<<1, + FONS_ALIGN_RIGHT = 1<<2, + // Vertical align + FONS_ALIGN_TOP = 1<<3, + FONS_ALIGN_MIDDLE = 1<<4, + FONS_ALIGN_BOTTOM = 1<<5, + FONS_ALIGN_BASELINE = 1<<6, // Default +}; + +enum FONSerrorCode { + // Font atlas is full. + FONS_ATLAS_FULL = 1, + // Scratch memory used to render glyphs is full, requested size reported in 'val', you may need to bump up FONS_SCRATCH_BUF_SIZE. + FONS_SCRATCH_FULL = 2, + // Calls to fonsPushState has created too large stack, if you need deep state stack bump up FONS_MAX_STATES. + FONS_STATES_OVERFLOW = 3, + // Trying to pop too many states fonsPopState(). + FONS_STATES_UNDERFLOW = 4, +}; + +struct FONSparams { + int width, height; + unsigned char flags; + void* userPtr; + int (*renderCreate)(void* uptr, int width, int height); + int (*renderResize)(void* uptr, int width, int height); + void (*renderUpdate)(void* uptr, int* rect, const unsigned char* data); + void (*renderDraw)(void* uptr, const float* verts, const float* tcoords, const unsigned int* colors, int nverts); + void (*renderDelete)(void* uptr); +}; +typedef struct FONSparams FONSparams; + +struct FONSquad +{ + float x0,y0,s0,t0; + float x1,y1,s1,t1; +}; +typedef struct FONSquad FONSquad; + +struct FONStextIter { + float x, y, nextx, nexty, scale, spacing; + unsigned int codepoint; + short isize, iblur; + struct FONSfont* font; + int prevGlyphIndex; + const char* str; + const char* next; + const char* end; + unsigned int utf8state; +}; +typedef struct FONStextIter FONStextIter; + +typedef struct FONScontext FONScontext; + +// Constructor and destructor. +FONScontext* fonsCreateInternal(FONSparams* params); +void fonsDeleteInternal(FONScontext* s); + +void fonsSetErrorCallback(FONScontext* s, void (*callback)(void* uptr, int error, int val), void* uptr); +// Returns current atlas size. +void fonsGetAtlasSize(FONScontext* s, int* width, int* height); +// Expands the atlas size. +int fonsExpandAtlas(FONScontext* s, int width, int height); +// Resets the whole stash. +int fonsResetAtlas(FONScontext* stash, int width, int height); + +// Add fonts +int fonsAddFont(FONScontext* s, const char* name, const char* path); +int fonsAddFontMem(FONScontext* s, const char* name, unsigned char* data, int ndata, int freeData); +int fonsGetFontByName(FONScontext* s, const char* name); + +// State handling +void fonsPushState(FONScontext* s); +void fonsPopState(FONScontext* s); +void fonsClearState(FONScontext* s); + +// State setting +void fonsSetSize(FONScontext* s, float size); +void fonsSetColor(FONScontext* s, unsigned int color); +void fonsSetSpacing(FONScontext* s, float spacing); +void fonsSetBlur(FONScontext* s, float blur); +void fonsSetAlign(FONScontext* s, int align); +void fonsSetFont(FONScontext* s, int font); + +// Draw text +float fonsDrawText(FONScontext* s, float x, float y, const char* string, const char* end); + +// Measure text +float fonsTextBounds(FONScontext* s, float x, float y, const char* string, const char* end, float* bounds); +void fonsLineBounds(FONScontext* s, float y, float* miny, float* maxy); +void fonsVertMetrics(FONScontext* s, float* ascender, float* descender, float* lineh); + +// Text iterator +int fonsTextIterInit(FONScontext* stash, FONStextIter* iter, float x, float y, const char* str, const char* end); +int fonsTextIterNext(FONScontext* stash, FONStextIter* iter, struct FONSquad* quad); + +// Pull texture changes +const unsigned char* fonsGetTextureData(FONScontext* stash, int* width, int* height); +int fonsValidateTexture(FONScontext* s, int* dirty); + +// Draws the stash texture for debugging +void fonsDrawDebug(FONScontext* s, float x, float y); + +#endif // FONTSTASH_H + + +#ifdef FONTSTASH_IMPLEMENTATION + +#define FONS_NOTUSED(v) (void)sizeof(v) + +#ifdef FONS_USE_FREETYPE + +#include +#include FT_FREETYPE_H +#include FT_ADVANCES_H +#include + +struct FONSttFontImpl { + FT_Face font; +}; +typedef struct FONSttFontImpl FONSttFontImpl; + +static FT_Library ftLibrary; + +int fons__tt_init(FONScontext *context) +{ + FT_Error ftError; + FONS_NOTUSED(context); + ftError = FT_Init_FreeType(&ftLibrary); + return ftError == 0; +} + +int fons__tt_loadFont(FONScontext *context, FONSttFontImpl *font, unsigned char *data, int dataSize) +{ + FT_Error ftError; + FONS_NOTUSED(context); + + //font->font.userdata = stash; + ftError = FT_New_Memory_Face(ftLibrary, (const FT_Byte*)data, dataSize, 0, &font->font); + return ftError == 0; +} + +void fons__tt_getFontVMetrics(FONSttFontImpl *font, int *ascent, int *descent, int *lineGap) +{ + *ascent = font->font->ascender; + *descent = font->font->descender; + *lineGap = font->font->height - (*ascent - *descent); +} + +float fons__tt_getPixelHeightScale(FONSttFontImpl *font, float size) +{ + return size / (font->font->ascender - font->font->descender); +} + +int fons__tt_getGlyphIndex(FONSttFontImpl *font, int codepoint) +{ + return FT_Get_Char_Index(font->font, codepoint); +} + +int fons__tt_buildGlyphBitmap(FONSttFontImpl *font, int glyph, float size, float scale, + int *advance, int *lsb, int *x0, int *y0, int *x1, int *y1) +{ + FT_Error ftError; + FT_GlyphSlot ftGlyph; + FT_Fixed advFixed; + FONS_NOTUSED(scale); + + ftError = FT_Set_Pixel_Sizes(font->font, 0, (FT_UInt)(size * (float)font->font->units_per_EM / (float)(font->font->ascender - font->font->descender))); + if (ftError) return 0; + ftError = FT_Load_Glyph(font->font, glyph, FT_LOAD_RENDER); + if (ftError) return 0; + ftError = FT_Get_Advance(font->font, glyph, FT_LOAD_NO_SCALE, &advFixed); + if (ftError) return 0; + ftGlyph = font->font->glyph; + *advance = (int)advFixed; + *lsb = (int)ftGlyph->metrics.horiBearingX; + *x0 = ftGlyph->bitmap_left; + *x1 = *x0 + ftGlyph->bitmap.width; + *y0 = -ftGlyph->bitmap_top; + *y1 = *y0 + ftGlyph->bitmap.rows; + return 1; +} + +void fons__tt_renderGlyphBitmap(FONSttFontImpl *font, unsigned char *output, int outWidth, int outHeight, int outStride, + float scaleX, float scaleY, int glyph) +{ + FT_GlyphSlot ftGlyph = font->font->glyph; + int ftGlyphOffset = 0; + int x, y; + FONS_NOTUSED(outWidth); + FONS_NOTUSED(outHeight); + FONS_NOTUSED(scaleX); + FONS_NOTUSED(scaleY); + FONS_NOTUSED(glyph); // glyph has already been loaded by fons__tt_buildGlyphBitmap + + for ( y = 0; y < ftGlyph->bitmap.rows; y++ ) { + for ( x = 0; x < ftGlyph->bitmap.width; x++ ) { + output[(y * outStride) + x] = ftGlyph->bitmap.buffer[ftGlyphOffset++]; + } + } +} + +int fons__tt_getGlyphKernAdvance(FONSttFontImpl *font, int glyph1, int glyph2) +{ + FT_Vector ftKerning; + FT_Get_Kerning(font->font, glyph1, glyph2, FT_KERNING_DEFAULT, &ftKerning); + return (int)((ftKerning.x + 32) >> 6); // Round up and convert to integer +} + +#else + +#define STB_TRUETYPE_IMPLEMENTATION +static void* fons__tmpalloc(size_t size, void* up); +static void fons__tmpfree(void* ptr, void* up); +#define STBTT_malloc(x,u) fons__tmpalloc(x,u) +#define STBTT_free(x,u) fons__tmpfree(x,u) +#include "stb_truetype.h" + +struct FONSttFontImpl { + stbtt_fontinfo font; +}; +typedef struct FONSttFontImpl FONSttFontImpl; + +int fons__tt_init(FONScontext *context) +{ + FONS_NOTUSED(context); + return 1; +} + +int fons__tt_loadFont(FONScontext *context, FONSttFontImpl *font, unsigned char *data, int dataSize) +{ + int stbError; + FONS_NOTUSED(dataSize); + + font->font.userdata = context; + stbError = stbtt_InitFont(&font->font, data, 0); + return stbError; +} + +void fons__tt_getFontVMetrics(FONSttFontImpl *font, int *ascent, int *descent, int *lineGap) +{ + stbtt_GetFontVMetrics(&font->font, ascent, descent, lineGap); +} + +float fons__tt_getPixelHeightScale(FONSttFontImpl *font, float size) +{ + return stbtt_ScaleForPixelHeight(&font->font, size); +} + +int fons__tt_getGlyphIndex(FONSttFontImpl *font, int codepoint) +{ + return stbtt_FindGlyphIndex(&font->font, codepoint); +} + +int fons__tt_buildGlyphBitmap(FONSttFontImpl *font, int glyph, float size, float scale, + int *advance, int *lsb, int *x0, int *y0, int *x1, int *y1) +{ + FONS_NOTUSED(size); + stbtt_GetGlyphHMetrics(&font->font, glyph, advance, lsb); + stbtt_GetGlyphBitmapBox(&font->font, glyph, scale, scale, x0, y0, x1, y1); + return 1; +} + +void fons__tt_renderGlyphBitmap(FONSttFontImpl *font, unsigned char *output, int outWidth, int outHeight, int outStride, + float scaleX, float scaleY, int glyph) +{ + stbtt_MakeGlyphBitmap(&font->font, output, outWidth, outHeight, outStride, scaleX, scaleY, glyph); +} + +int fons__tt_getGlyphKernAdvance(FONSttFontImpl *font, int glyph1, int glyph2) +{ + return stbtt_GetGlyphKernAdvance(&font->font, glyph1, glyph2); +} + +#endif + +#ifndef FONS_SCRATCH_BUF_SIZE +# define FONS_SCRATCH_BUF_SIZE 64000 +#endif +#ifndef FONS_HASH_LUT_SIZE +# define FONS_HASH_LUT_SIZE 256 +#endif +#ifndef FONS_INIT_FONTS +# define FONS_INIT_FONTS 4 +#endif +#ifndef FONS_INIT_GLYPHS +# define FONS_INIT_GLYPHS 256 +#endif +#ifndef FONS_INIT_ATLAS_NODES +# define FONS_INIT_ATLAS_NODES 256 +#endif +#ifndef FONS_VERTEX_COUNT +# define FONS_VERTEX_COUNT 1024 +#endif +#ifndef FONS_MAX_STATES +# define FONS_MAX_STATES 20 +#endif +#ifndef FONS_MAX_FALLBACKS +# define FONS_MAX_FALLBACKS 20 +#endif + +static unsigned int fons__hashint(unsigned int a) +{ + a += ~(a<<15); + a ^= (a>>10); + a += (a<<3); + a ^= (a>>6); + a += ~(a<<11); + a ^= (a>>16); + return a; +} + +static int fons__mini(int a, int b) +{ + return a < b ? a : b; +} + +static int fons__maxi(int a, int b) +{ + return a > b ? a : b; +} + +struct FONSglyph +{ + unsigned int codepoint; + int index; + int next; + short size, blur; + short x0,y0,x1,y1; + short xadv,xoff,yoff; +}; +typedef struct FONSglyph FONSglyph; + +struct FONSfont +{ + FONSttFontImpl font; + char name[64]; + unsigned char* data; + int dataSize; + unsigned char freeData; + float ascender; + float descender; + float lineh; + FONSglyph* glyphs; + int cglyphs; + int nglyphs; + int lut[FONS_HASH_LUT_SIZE]; + int fallbacks[FONS_MAX_FALLBACKS]; + int nfallbacks; +}; +typedef struct FONSfont FONSfont; + +struct FONSstate +{ + int font; + int align; + float size; + unsigned int color; + float blur; + float spacing; +}; +typedef struct FONSstate FONSstate; + +struct FONSatlasNode { + short x, y, width; +}; +typedef struct FONSatlasNode FONSatlasNode; + +struct FONSatlas +{ + int width, height; + FONSatlasNode* nodes; + int nnodes; + int cnodes; +}; +typedef struct FONSatlas FONSatlas; + +struct FONScontext +{ + FONSparams params; + float itw,ith; + unsigned char* texData; + int dirtyRect[4]; + FONSfont** fonts; + FONSatlas* atlas; + int cfonts; + int nfonts; + float verts[FONS_VERTEX_COUNT*2]; + float tcoords[FONS_VERTEX_COUNT*2]; + unsigned int colors[FONS_VERTEX_COUNT]; + int nverts; + unsigned char* scratch; + int nscratch; + FONSstate states[FONS_MAX_STATES]; + int nstates; + void (*handleError)(void* uptr, int error, int val); + void* errorUptr; +}; + +#ifdef STB_TRUETYPE_IMPLEMENTATION + +static void* fons__tmpalloc(size_t size, void* up) +{ + unsigned char* ptr; + FONScontext* stash = (FONScontext*)up; + + // 16-byte align the returned pointer + size = (size + 0xf) & ~0xf; + + if (stash->nscratch+(int)size > FONS_SCRATCH_BUF_SIZE) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_SCRATCH_FULL, stash->nscratch+(int)size); + return NULL; + } + ptr = stash->scratch + stash->nscratch; + stash->nscratch += (int)size; + return ptr; +} + +static void fons__tmpfree(void* ptr, void* up) +{ + (void)ptr; + (void)up; + // empty +} + +#endif // STB_TRUETYPE_IMPLEMENTATION + +// Copyright (c) 2008-2010 Bjoern Hoehrmann +// See http://bjoern.hoehrmann.de/utf-8/decoder/dfa/ for details. + +#define FONS_UTF8_ACCEPT 0 +#define FONS_UTF8_REJECT 12 + +static unsigned int fons__decutf8(unsigned int* state, unsigned int* codep, unsigned int byte) +{ + static const unsigned char utf8d[] = { + // The first part of the table maps bytes to character classes that + // to reduce the size of the transition table and create bitmasks. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 9,9,9,9,9,9,9,9,9,9,9,9,9,9,9,9, + 7,7,7,7,7,7,7,7,7,7,7,7,7,7,7,7, 7,7,7,7,7,7,7,7,7,7,7,7,7,7,7,7, + 8,8,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, + 10,3,3,3,3,3,3,3,3,3,3,3,3,4,3,3, 11,6,6,6,5,8,8,8,8,8,8,8,8,8,8,8, + + // The second part is a transition table that maps a combination + // of a state of the automaton and a character class to a state. + 0,12,24,36,60,96,84,12,12,12,48,72, 12,12,12,12,12,12,12,12,12,12,12,12, + 12, 0,12,12,12,12,12, 0,12, 0,12,12, 12,24,12,12,12,12,12,24,12,24,12,12, + 12,12,12,12,12,12,12,24,12,12,12,12, 12,24,12,12,12,12,12,12,12,24,12,12, + 12,12,12,12,12,12,12,36,12,36,12,12, 12,36,12,12,12,12,12,36,12,36,12,12, + 12,36,12,12,12,12,12,12,12,12,12,12, + }; + + unsigned int type = utf8d[byte]; + + *codep = (*state != FONS_UTF8_ACCEPT) ? + (byte & 0x3fu) | (*codep << 6) : + (0xff >> type) & (byte); + + *state = utf8d[256 + *state + type]; + return *state; +} + +// Atlas based on Skyline Bin Packer by Jukka Jylänki + +static void fons__deleteAtlas(FONSatlas* atlas) +{ + if (atlas == NULL) return; + if (atlas->nodes != NULL) free(atlas->nodes); + free(atlas); +} + +static FONSatlas* fons__allocAtlas(int w, int h, int nnodes) +{ + FONSatlas* atlas = NULL; + + // Allocate memory for the font stash. + atlas = (FONSatlas*)malloc(sizeof(FONSatlas)); + if (atlas == NULL) goto error; + memset(atlas, 0, sizeof(FONSatlas)); + + atlas->width = w; + atlas->height = h; + + // Allocate space for skyline nodes + atlas->nodes = (FONSatlasNode*)malloc(sizeof(FONSatlasNode) * nnodes); + if (atlas->nodes == NULL) goto error; + memset(atlas->nodes, 0, sizeof(FONSatlasNode) * nnodes); + atlas->nnodes = 0; + atlas->cnodes = nnodes; + + // Init root node. + atlas->nodes[0].x = 0; + atlas->nodes[0].y = 0; + atlas->nodes[0].width = (short)w; + atlas->nnodes++; + + return atlas; + +error: + if (atlas) fons__deleteAtlas(atlas); + return NULL; +} + +static int fons__atlasInsertNode(FONSatlas* atlas, int idx, int x, int y, int w) +{ + int i; + // Insert node + if (atlas->nnodes+1 > atlas->cnodes) { + atlas->cnodes = atlas->cnodes == 0 ? 8 : atlas->cnodes * 2; + atlas->nodes = (FONSatlasNode*)realloc(atlas->nodes, sizeof(FONSatlasNode) * atlas->cnodes); + if (atlas->nodes == NULL) + return 0; + } + for (i = atlas->nnodes; i > idx; i--) + atlas->nodes[i] = atlas->nodes[i-1]; + atlas->nodes[idx].x = (short)x; + atlas->nodes[idx].y = (short)y; + atlas->nodes[idx].width = (short)w; + atlas->nnodes++; + + return 1; +} + +static void fons__atlasRemoveNode(FONSatlas* atlas, int idx) +{ + int i; + if (atlas->nnodes == 0) return; + for (i = idx; i < atlas->nnodes-1; i++) + atlas->nodes[i] = atlas->nodes[i+1]; + atlas->nnodes--; +} + +static void fons__atlasExpand(FONSatlas* atlas, int w, int h) +{ + // Insert node for empty space + if (w > atlas->width) + fons__atlasInsertNode(atlas, atlas->nnodes, atlas->width, 0, w - atlas->width); + atlas->width = w; + atlas->height = h; +} + +static void fons__atlasReset(FONSatlas* atlas, int w, int h) +{ + atlas->width = w; + atlas->height = h; + atlas->nnodes = 0; + + // Init root node. + atlas->nodes[0].x = 0; + atlas->nodes[0].y = 0; + atlas->nodes[0].width = (short)w; + atlas->nnodes++; +} + +static int fons__atlasAddSkylineLevel(FONSatlas* atlas, int idx, int x, int y, int w, int h) +{ + int i; + + // Insert new node + if (fons__atlasInsertNode(atlas, idx, x, y+h, w) == 0) + return 0; + + // Delete skyline segments that fall under the shadow of the new segment. + for (i = idx+1; i < atlas->nnodes; i++) { + if (atlas->nodes[i].x < atlas->nodes[i-1].x + atlas->nodes[i-1].width) { + int shrink = atlas->nodes[i-1].x + atlas->nodes[i-1].width - atlas->nodes[i].x; + atlas->nodes[i].x += (short)shrink; + atlas->nodes[i].width -= (short)shrink; + if (atlas->nodes[i].width <= 0) { + fons__atlasRemoveNode(atlas, i); + i--; + } else { + break; + } + } else { + break; + } + } + + // Merge same height skyline segments that are next to each other. + for (i = 0; i < atlas->nnodes-1; i++) { + if (atlas->nodes[i].y == atlas->nodes[i+1].y) { + atlas->nodes[i].width += atlas->nodes[i+1].width; + fons__atlasRemoveNode(atlas, i+1); + i--; + } + } + + return 1; +} + +static int fons__atlasRectFits(FONSatlas* atlas, int i, int w, int h) +{ + // Checks if there is enough space at the location of skyline span 'i', + // and return the max height of all skyline spans under that at that location, + // (think tetris block being dropped at that position). Or -1 if no space found. + int x = atlas->nodes[i].x; + int y = atlas->nodes[i].y; + int spaceLeft; + if (x + w > atlas->width) + return -1; + spaceLeft = w; + while (spaceLeft > 0) { + if (i == atlas->nnodes) return -1; + y = fons__maxi(y, atlas->nodes[i].y); + if (y + h > atlas->height) return -1; + spaceLeft -= atlas->nodes[i].width; + ++i; + } + return y; +} + +static int fons__atlasAddRect(FONSatlas* atlas, int rw, int rh, int* rx, int* ry) +{ + int besth = atlas->height, bestw = atlas->width, besti = -1; + int bestx = -1, besty = -1, i; + + // Bottom left fit heuristic. + for (i = 0; i < atlas->nnodes; i++) { + int y = fons__atlasRectFits(atlas, i, rw, rh); + if (y != -1) { + if (y + rh < besth || (y + rh == besth && atlas->nodes[i].width < bestw)) { + besti = i; + bestw = atlas->nodes[i].width; + besth = y + rh; + bestx = atlas->nodes[i].x; + besty = y; + } + } + } + + if (besti == -1) + return 0; + + // Perform the actual packing. + if (fons__atlasAddSkylineLevel(atlas, besti, bestx, besty, rw, rh) == 0) + return 0; + + *rx = bestx; + *ry = besty; + + return 1; +} + +static void fons__addWhiteRect(FONScontext* stash, int w, int h) +{ + int x, y, gx, gy; + unsigned char* dst; + if (fons__atlasAddRect(stash->atlas, w, h, &gx, &gy) == 0) + return; + + // Rasterize + dst = &stash->texData[gx + gy * stash->params.width]; + for (y = 0; y < h; y++) { + for (x = 0; x < w; x++) + dst[x] = 0xff; + dst += stash->params.width; + } + + stash->dirtyRect[0] = fons__mini(stash->dirtyRect[0], gx); + stash->dirtyRect[1] = fons__mini(stash->dirtyRect[1], gy); + stash->dirtyRect[2] = fons__maxi(stash->dirtyRect[2], gx+w); + stash->dirtyRect[3] = fons__maxi(stash->dirtyRect[3], gy+h); +} + +FONScontext* fonsCreateInternal(FONSparams* params) +{ + FONScontext* stash = NULL; + + // Allocate memory for the font stash. + stash = (FONScontext*)malloc(sizeof(FONScontext)); + if (stash == NULL) goto error; + memset(stash, 0, sizeof(FONScontext)); + + stash->params = *params; + + // Allocate scratch buffer. + stash->scratch = (unsigned char*)malloc(FONS_SCRATCH_BUF_SIZE); + if (stash->scratch == NULL) goto error; + + // Initialize implementation library + if (!fons__tt_init(stash)) goto error; + + if (stash->params.renderCreate != NULL) { + if (stash->params.renderCreate(stash->params.userPtr, stash->params.width, stash->params.height) == 0) + goto error; + } + + stash->atlas = fons__allocAtlas(stash->params.width, stash->params.height, FONS_INIT_ATLAS_NODES); + if (stash->atlas == NULL) goto error; + + // Allocate space for fonts. + stash->fonts = (FONSfont**)malloc(sizeof(FONSfont*) * FONS_INIT_FONTS); + if (stash->fonts == NULL) goto error; + memset(stash->fonts, 0, sizeof(FONSfont*) * FONS_INIT_FONTS); + stash->cfonts = FONS_INIT_FONTS; + stash->nfonts = 0; + + // Create texture for the cache. + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + stash->texData = (unsigned char*)malloc(stash->params.width * stash->params.height); + if (stash->texData == NULL) goto error; + memset(stash->texData, 0, stash->params.width * stash->params.height); + + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + + // Add white rect at 0,0 for debug drawing. + fons__addWhiteRect(stash, 2,2); + + fonsPushState(stash); + fonsClearState(stash); + + return stash; + +error: + fonsDeleteInternal(stash); + return NULL; +} + +static FONSstate* fons__getState(FONScontext* stash) +{ + return &stash->states[stash->nstates-1]; +} + +int fonsAddFallbackFont(FONScontext* stash, int base, int fallback) +{ + FONSfont* baseFont = stash->fonts[base]; + if (baseFont->nfallbacks < FONS_MAX_FALLBACKS) { + baseFont->fallbacks[baseFont->nfallbacks++] = fallback; + return 1; + } + return 0; +} + +void fonsSetSize(FONScontext* stash, float size) +{ + fons__getState(stash)->size = size; +} + +void fonsSetColor(FONScontext* stash, unsigned int color) +{ + fons__getState(stash)->color = color; +} + +void fonsSetSpacing(FONScontext* stash, float spacing) +{ + fons__getState(stash)->spacing = spacing; +} + +void fonsSetBlur(FONScontext* stash, float blur) +{ + fons__getState(stash)->blur = blur; +} + +void fonsSetAlign(FONScontext* stash, int align) +{ + fons__getState(stash)->align = align; +} + +void fonsSetFont(FONScontext* stash, int font) +{ + fons__getState(stash)->font = font; +} + +void fonsPushState(FONScontext* stash) +{ + if (stash->nstates >= FONS_MAX_STATES) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_STATES_OVERFLOW, 0); + return; + } + if (stash->nstates > 0) + memcpy(&stash->states[stash->nstates], &stash->states[stash->nstates-1], sizeof(FONSstate)); + stash->nstates++; +} + +void fonsPopState(FONScontext* stash) +{ + if (stash->nstates <= 1) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_STATES_UNDERFLOW, 0); + return; + } + stash->nstates--; +} + +void fonsClearState(FONScontext* stash) +{ + FONSstate* state = fons__getState(stash); + state->size = 12.0f; + state->color = 0xffffffff; + state->font = 0; + state->blur = 0; + state->spacing = 0; + state->align = FONS_ALIGN_LEFT | FONS_ALIGN_BASELINE; +} + +static void fons__freeFont(FONSfont* font) +{ + if (font == NULL) return; + if (font->glyphs) free(font->glyphs); + if (font->freeData && font->data) free(font->data); + free(font); +} + +static int fons__allocFont(FONScontext* stash) +{ + FONSfont* font = NULL; + if (stash->nfonts+1 > stash->cfonts) { + stash->cfonts = stash->cfonts == 0 ? 8 : stash->cfonts * 2; + stash->fonts = (FONSfont**)realloc(stash->fonts, sizeof(FONSfont*) * stash->cfonts); + if (stash->fonts == NULL) + return -1; + } + font = (FONSfont*)malloc(sizeof(FONSfont)); + if (font == NULL) goto error; + memset(font, 0, sizeof(FONSfont)); + + font->glyphs = (FONSglyph*)malloc(sizeof(FONSglyph) * FONS_INIT_GLYPHS); + if (font->glyphs == NULL) goto error; + font->cglyphs = FONS_INIT_GLYPHS; + font->nglyphs = 0; + + stash->fonts[stash->nfonts++] = font; + return stash->nfonts-1; + +error: + fons__freeFont(font); + + return FONS_INVALID; +} + +int fonsAddFont(FONScontext* stash, const char* name, const char* path) +{ + FILE* fp = 0; + int dataSize = 0; + unsigned char* data = NULL; + + // Read in the font data. + fp = fopen(path, "rb"); + if (fp == NULL) goto error; + fseek(fp,0,SEEK_END); + dataSize = (int)ftell(fp); + fseek(fp,0,SEEK_SET); + data = (unsigned char*)malloc(dataSize); + if (data == NULL) goto error; + fread(data, 1, dataSize, fp); + fclose(fp); + fp = 0; + + return fonsAddFontMem(stash, name, data, dataSize, 1); + +error: + if (data) free(data); + if (fp) fclose(fp); + return FONS_INVALID; +} + +int fonsAddFontMem(FONScontext* stash, const char* name, unsigned char* data, int dataSize, int freeData) +{ + int i, ascent, descent, fh, lineGap; + FONSfont* font; + + int idx = fons__allocFont(stash); + if (idx == FONS_INVALID) + return FONS_INVALID; + + font = stash->fonts[idx]; + + strncpy(font->name, name, sizeof(font->name)); + font->name[sizeof(font->name)-1] = '\0'; + + // Init hash lookup. + for (i = 0; i < FONS_HASH_LUT_SIZE; ++i) + font->lut[i] = -1; + + // Read in the font data. + font->dataSize = dataSize; + font->data = data; + font->freeData = (unsigned char)freeData; + + // Init font + stash->nscratch = 0; + if (!fons__tt_loadFont(stash, &font->font, data, dataSize)) goto error; + + // Store normalized line height. The real line height is got + // by multiplying the lineh by font size. + fons__tt_getFontVMetrics( &font->font, &ascent, &descent, &lineGap); + fh = ascent - descent; + font->ascender = (float)ascent / (float)fh; + font->descender = (float)descent / (float)fh; + font->lineh = (float)(fh + lineGap) / (float)fh; + + return idx; + +error: + fons__freeFont(font); + stash->nfonts--; + return FONS_INVALID; +} + +int fonsGetFontByName(FONScontext* s, const char* name) +{ + int i; + for (i = 0; i < s->nfonts; i++) { + if (strcmp(s->fonts[i]->name, name) == 0) + return i; + } + return FONS_INVALID; +} + + +static FONSglyph* fons__allocGlyph(FONSfont* font) +{ + if (font->nglyphs+1 > font->cglyphs) { + font->cglyphs = font->cglyphs == 0 ? 8 : font->cglyphs * 2; + font->glyphs = (FONSglyph*)realloc(font->glyphs, sizeof(FONSglyph) * font->cglyphs); + if (font->glyphs == NULL) return NULL; + } + font->nglyphs++; + return &font->glyphs[font->nglyphs-1]; +} + + +// Based on Exponential blur, Jani Huhtanen, 2006 + +#define APREC 16 +#define ZPREC 7 + +static void fons__blurCols(unsigned char* dst, int w, int h, int dstStride, int alpha) +{ + int x, y; + for (y = 0; y < h; y++) { + int z = 0; // force zero border + for (x = 1; x < w; x++) { + z += (alpha * (((int)(dst[x]) << ZPREC) - z)) >> APREC; + dst[x] = (unsigned char)(z >> ZPREC); + } + dst[w-1] = 0; // force zero border + z = 0; + for (x = w-2; x >= 0; x--) { + z += (alpha * (((int)(dst[x]) << ZPREC) - z)) >> APREC; + dst[x] = (unsigned char)(z >> ZPREC); + } + dst[0] = 0; // force zero border + dst += dstStride; + } +} + +static void fons__blurRows(unsigned char* dst, int w, int h, int dstStride, int alpha) +{ + int x, y; + for (x = 0; x < w; x++) { + int z = 0; // force zero border + for (y = dstStride; y < h*dstStride; y += dstStride) { + z += (alpha * (((int)(dst[y]) << ZPREC) - z)) >> APREC; + dst[y] = (unsigned char)(z >> ZPREC); + } + dst[(h-1)*dstStride] = 0; // force zero border + z = 0; + for (y = (h-2)*dstStride; y >= 0; y -= dstStride) { + z += (alpha * (((int)(dst[y]) << ZPREC) - z)) >> APREC; + dst[y] = (unsigned char)(z >> ZPREC); + } + dst[0] = 0; // force zero border + dst++; + } +} + + +static void fons__blur(FONScontext* stash, unsigned char* dst, int w, int h, int dstStride, int blur) +{ + int alpha; + float sigma; + (void)stash; + + if (blur < 1) + return; + // Calculate the alpha such that 90% of the kernel is within the radius. (Kernel extends to infinity) + sigma = (float)blur * 0.57735f; // 1 / sqrt(3) + alpha = (int)((1< 20) iblur = 20; + pad = iblur+2; + + // Reset allocator. + stash->nscratch = 0; + + // Find code point and size. + h = fons__hashint(codepoint) & (FONS_HASH_LUT_SIZE-1); + i = font->lut[h]; + while (i != -1) { + if (font->glyphs[i].codepoint == codepoint && font->glyphs[i].size == isize && font->glyphs[i].blur == iblur) + return &font->glyphs[i]; + i = font->glyphs[i].next; + } + + // Could not find glyph, create it. + scale = fons__tt_getPixelHeightScale(&font->font, size); + g = fons__tt_getGlyphIndex(&font->font, codepoint); + // Try to find the glyph in fallback fonts. + if (g == 0) { + for (i = 0; i < font->nfallbacks; ++i) { + FONSglyph* fallbackGlyph = fons__getGlyph(stash, stash->fonts[font->fallbacks[i]], codepoint, isize, iblur); + if (fallbackGlyph != NULL && fallbackGlyph->index != 0) { + return fallbackGlyph; + } + } + } + fons__tt_buildGlyphBitmap(&font->font, g, size, scale, &advance, &lsb, &x0, &y0, &x1, &y1); + gw = x1-x0 + pad*2; + gh = y1-y0 + pad*2; + + // Find free spot for the rect in the atlas + added = fons__atlasAddRect(stash->atlas, gw, gh, &gx, &gy); + if (added == 0 && stash->handleError != NULL) { + // Atlas is full, let the user to resize the atlas (or not), and try again. + stash->handleError(stash->errorUptr, FONS_ATLAS_FULL, 0); + added = fons__atlasAddRect(stash->atlas, gw, gh, &gx, &gy); + } + if (added == 0) return NULL; + + // Init glyph. + glyph = fons__allocGlyph(font); + glyph->codepoint = codepoint; + glyph->size = isize; + glyph->blur = iblur; + glyph->index = g; + glyph->x0 = (short)gx; + glyph->y0 = (short)gy; + glyph->x1 = (short)(glyph->x0+gw); + glyph->y1 = (short)(glyph->y0+gh); + glyph->xadv = (short)(scale * advance * 10.0f); + glyph->xoff = (short)(x0 - pad); + glyph->yoff = (short)(y0 - pad); + glyph->next = 0; + + // Insert char to hash lookup. + glyph->next = font->lut[h]; + font->lut[h] = font->nglyphs-1; + + // Rasterize + dst = &stash->texData[(glyph->x0+pad) + (glyph->y0+pad) * stash->params.width]; + fons__tt_renderGlyphBitmap(&font->font, dst, gw-pad*2,gh-pad*2, stash->params.width, scale,scale, g); + + // Make sure there is one pixel empty border. + dst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + for (y = 0; y < gh; y++) { + dst[y*stash->params.width] = 0; + dst[gw-1 + y*stash->params.width] = 0; + } + for (x = 0; x < gw; x++) { + dst[x] = 0; + dst[x + (gh-1)*stash->params.width] = 0; + } + + // Debug code to color the glyph background +/* unsigned char* fdst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + for (y = 0; y < gh; y++) { + for (x = 0; x < gw; x++) { + int a = (int)fdst[x+y*stash->params.width] + 20; + if (a > 255) a = 255; + fdst[x+y*stash->params.width] = a; + } + }*/ + + // Blur + if (iblur > 0) { + stash->nscratch = 0; + bdst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + fons__blur(stash, bdst, gw,gh, stash->params.width, iblur); + } + + stash->dirtyRect[0] = fons__mini(stash->dirtyRect[0], glyph->x0); + stash->dirtyRect[1] = fons__mini(stash->dirtyRect[1], glyph->y0); + stash->dirtyRect[2] = fons__maxi(stash->dirtyRect[2], glyph->x1); + stash->dirtyRect[3] = fons__maxi(stash->dirtyRect[3], glyph->y1); + + return glyph; +} + +static void fons__getQuad(FONScontext* stash, FONSfont* font, + int prevGlyphIndex, FONSglyph* glyph, + float scale, float spacing, float* x, float* y, FONSquad* q) +{ + float rx,ry,xoff,yoff,x0,y0,x1,y1; + + if (prevGlyphIndex != -1) { + float adv = fons__tt_getGlyphKernAdvance(&font->font, prevGlyphIndex, glyph->index) * scale; + *x += (int)(adv + spacing + 0.5f); + } + + // Each glyph has 2px border to allow good interpolation, + // one pixel to prevent leaking, and one to allow good interpolation for rendering. + // Inset the texture region by one pixel for correct interpolation. + xoff = (short)(glyph->xoff+1); + yoff = (short)(glyph->yoff+1); + x0 = (float)(glyph->x0+1); + y0 = (float)(glyph->y0+1); + x1 = (float)(glyph->x1-1); + y1 = (float)(glyph->y1-1); + + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + rx = (float)(int)(*x + xoff); + ry = (float)(int)(*y + yoff); + + q->x0 = rx; + q->y0 = ry; + q->x1 = rx + x1 - x0; + q->y1 = ry + y1 - y0; + + q->s0 = x0 * stash->itw; + q->t0 = y0 * stash->ith; + q->s1 = x1 * stash->itw; + q->t1 = y1 * stash->ith; + } else { + rx = (float)(int)(*x + xoff); + ry = (float)(int)(*y - yoff); + + q->x0 = rx; + q->y0 = ry; + q->x1 = rx + x1 - x0; + q->y1 = ry - y1 + y0; + + q->s0 = x0 * stash->itw; + q->t0 = y0 * stash->ith; + q->s1 = x1 * stash->itw; + q->t1 = y1 * stash->ith; + } + + *x += (int)(glyph->xadv / 10.0f + 0.5f); +} + +static void fons__flush(FONScontext* stash) +{ + // Flush texture + if (stash->dirtyRect[0] < stash->dirtyRect[2] && stash->dirtyRect[1] < stash->dirtyRect[3]) { + if (stash->params.renderUpdate != NULL) + stash->params.renderUpdate(stash->params.userPtr, stash->dirtyRect, stash->texData); + // Reset dirty rect + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + } + + // Flush triangles + if (stash->nverts > 0) { + if (stash->params.renderDraw != NULL) + stash->params.renderDraw(stash->params.userPtr, stash->verts, stash->tcoords, stash->colors, stash->nverts); + stash->nverts = 0; + } +} + +static __inline void fons__vertex(FONScontext* stash, float x, float y, float s, float t, unsigned int c) +{ + stash->verts[stash->nverts*2+0] = x; + stash->verts[stash->nverts*2+1] = y; + stash->tcoords[stash->nverts*2+0] = s; + stash->tcoords[stash->nverts*2+1] = t; + stash->colors[stash->nverts] = c; + stash->nverts++; +} + +static float fons__getVertAlign(FONScontext* stash, FONSfont* font, int align, short isize) +{ + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + if (align & FONS_ALIGN_TOP) { + return font->ascender * (float)isize/10.0f; + } else if (align & FONS_ALIGN_MIDDLE) { + return (font->ascender + font->descender) / 2.0f * (float)isize/10.0f; + } else if (align & FONS_ALIGN_BASELINE) { + return 0.0f; + } else if (align & FONS_ALIGN_BOTTOM) { + return font->descender * (float)isize/10.0f; + } + } else { + if (align & FONS_ALIGN_TOP) { + return -font->ascender * (float)isize/10.0f; + } else if (align & FONS_ALIGN_MIDDLE) { + return -(font->ascender + font->descender) / 2.0f * (float)isize/10.0f; + } else if (align & FONS_ALIGN_BASELINE) { + return 0.0f; + } else if (align & FONS_ALIGN_BOTTOM) { + return -font->descender * (float)isize/10.0f; + } + } + return 0.0; +} + +float fonsDrawText(FONScontext* stash, + float x, float y, + const char* str, const char* end) +{ + FONSstate* state = fons__getState(stash); + unsigned int codepoint; + unsigned int utf8state = 0; + FONSglyph* glyph = NULL; + FONSquad q; + int prevGlyphIndex = -1; + short isize = (short)(state->size*10.0f); + short iblur = (short)state->blur; + float scale; + FONSfont* font; + float width; + + if (stash == NULL) return x; + if (state->font < 0 || state->font >= stash->nfonts) return x; + font = stash->fonts[state->font]; + if (font->data == NULL) return x; + + scale = fons__tt_getPixelHeightScale(&font->font, (float)isize/10.0f); + + if (end == NULL) + end = str + strlen(str); + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width; + } else if (state->align & FONS_ALIGN_CENTER) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width * 0.5f; + } + // Align vertically. + y += fons__getVertAlign(stash, font, state->align, isize); + + for (; str != end; ++str) { + if (fons__decutf8(&utf8state, &codepoint, *(const unsigned char*)str)) + continue; + glyph = fons__getGlyph(stash, font, codepoint, isize, iblur); + if (glyph != NULL) { + fons__getQuad(stash, font, prevGlyphIndex, glyph, scale, state->spacing, &x, &y, &q); + + if (stash->nverts+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + fons__vertex(stash, q.x0, q.y0, q.s0, q.t0, state->color); + fons__vertex(stash, q.x1, q.y1, q.s1, q.t1, state->color); + fons__vertex(stash, q.x1, q.y0, q.s1, q.t0, state->color); + + fons__vertex(stash, q.x0, q.y0, q.s0, q.t0, state->color); + fons__vertex(stash, q.x0, q.y1, q.s0, q.t1, state->color); + fons__vertex(stash, q.x1, q.y1, q.s1, q.t1, state->color); + } + prevGlyphIndex = glyph != NULL ? glyph->index : -1; + } + fons__flush(stash); + + return x; +} + +int fonsTextIterInit(FONScontext* stash, FONStextIter* iter, + float x, float y, const char* str, const char* end) +{ + FONSstate* state = fons__getState(stash); + float width; + + memset(iter, 0, sizeof(*iter)); + + if (stash == NULL) return 0; + if (state->font < 0 || state->font >= stash->nfonts) return 0; + iter->font = stash->fonts[state->font]; + if (iter->font->data == NULL) return 0; + + iter->isize = (short)(state->size*10.0f); + iter->iblur = (short)state->blur; + iter->scale = fons__tt_getPixelHeightScale(&iter->font->font, (float)iter->isize/10.0f); + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width; + } else if (state->align & FONS_ALIGN_CENTER) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width * 0.5f; + } + // Align vertically. + y += fons__getVertAlign(stash, iter->font, state->align, iter->isize); + + if (end == NULL) + end = str + strlen(str); + + iter->x = iter->nextx = x; + iter->y = iter->nexty = y; + iter->spacing = state->spacing; + iter->str = str; + iter->next = str; + iter->end = end; + iter->codepoint = 0; + iter->prevGlyphIndex = -1; + + return 1; +} + +int fonsTextIterNext(FONScontext* stash, FONStextIter* iter, FONSquad* quad) +{ + FONSglyph* glyph = NULL; + const char* str = iter->next; + iter->str = iter->next; + + if (str == iter->end) + return 0; + + for (; str != iter->end; str++) { + if (fons__decutf8(&iter->utf8state, &iter->codepoint, *(const unsigned char*)str)) + continue; + str++; + // Get glyph and quad + iter->x = iter->nextx; + iter->y = iter->nexty; + glyph = fons__getGlyph(stash, iter->font, iter->codepoint, iter->isize, iter->iblur); + if (glyph != NULL) + fons__getQuad(stash, iter->font, iter->prevGlyphIndex, glyph, iter->scale, iter->spacing, &iter->nextx, &iter->nexty, quad); + iter->prevGlyphIndex = glyph != NULL ? glyph->index : -1; + break; + } + iter->next = str; + + return 1; +} + +void fonsDrawDebug(FONScontext* stash, float x, float y) +{ + int i; + int w = stash->params.width; + int h = stash->params.height; + float u = w == 0 ? 0 : (1.0f / w); + float v = h == 0 ? 0 : (1.0f / h); + + if (stash->nverts+6+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + // Draw background + fons__vertex(stash, x+0, y+0, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+h, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+0, u, v, 0x0fffffff); + + fons__vertex(stash, x+0, y+0, u, v, 0x0fffffff); + fons__vertex(stash, x+0, y+h, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+h, u, v, 0x0fffffff); + + // Draw texture + fons__vertex(stash, x+0, y+0, 0, 0, 0xffffffff); + fons__vertex(stash, x+w, y+h, 1, 1, 0xffffffff); + fons__vertex(stash, x+w, y+0, 1, 0, 0xffffffff); + + fons__vertex(stash, x+0, y+0, 0, 0, 0xffffffff); + fons__vertex(stash, x+0, y+h, 0, 1, 0xffffffff); + fons__vertex(stash, x+w, y+h, 1, 1, 0xffffffff); + + // Drawbug draw atlas + for (i = 0; i < stash->atlas->nnodes; i++) { + FONSatlasNode* n = &stash->atlas->nodes[i]; + + if (stash->nverts+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + fons__vertex(stash, x+n->x+0, y+n->y+0, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+1, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+0, u, v, 0xc00000ff); + + fons__vertex(stash, x+n->x+0, y+n->y+0, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+0, y+n->y+1, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+1, u, v, 0xc00000ff); + } + + fons__flush(stash); +} + +float fonsTextBounds(FONScontext* stash, + float x, float y, + const char* str, const char* end, + float* bounds) +{ + FONSstate* state = fons__getState(stash); + unsigned int codepoint; + unsigned int utf8state = 0; + FONSquad q; + FONSglyph* glyph = NULL; + int prevGlyphIndex = -1; + short isize = (short)(state->size*10.0f); + short iblur = (short)state->blur; + float scale; + FONSfont* font; + float startx, advance; + float minx, miny, maxx, maxy; + + if (stash == NULL) return 0; + if (state->font < 0 || state->font >= stash->nfonts) return 0; + font = stash->fonts[state->font]; + if (font->data == NULL) return 0; + + scale = fons__tt_getPixelHeightScale(&font->font, (float)isize/10.0f); + + // Align vertically. + y += fons__getVertAlign(stash, font, state->align, isize); + + minx = maxx = x; + miny = maxy = y; + startx = x; + + if (end == NULL) + end = str + strlen(str); + + for (; str != end; ++str) { + if (fons__decutf8(&utf8state, &codepoint, *(const unsigned char*)str)) + continue; + glyph = fons__getGlyph(stash, font, codepoint, isize, iblur); + if (glyph != NULL) { + fons__getQuad(stash, font, prevGlyphIndex, glyph, scale, state->spacing, &x, &y, &q); + if (q.x0 < minx) minx = q.x0; + if (q.x1 > maxx) maxx = q.x1; + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + if (q.y0 < miny) miny = q.y0; + if (q.y1 > maxy) maxy = q.y1; + } else { + if (q.y1 < miny) miny = q.y1; + if (q.y0 > maxy) maxy = q.y0; + } + } + prevGlyphIndex = glyph != NULL ? glyph->index : -1; + } + + advance = x - startx; + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + minx -= advance; + maxx -= advance; + } else if (state->align & FONS_ALIGN_CENTER) { + minx -= advance * 0.5f; + maxx -= advance * 0.5f; + } + + if (bounds) { + bounds[0] = minx; + bounds[1] = miny; + bounds[2] = maxx; + bounds[3] = maxy; + } + + return advance; +} + +void fonsVertMetrics(FONScontext* stash, + float* ascender, float* descender, float* lineh) +{ + FONSfont* font; + FONSstate* state = fons__getState(stash); + short isize; + + if (stash == NULL) return; + if (state->font < 0 || state->font >= stash->nfonts) return; + font = stash->fonts[state->font]; + isize = (short)(state->size*10.0f); + if (font->data == NULL) return; + + if (ascender) + *ascender = font->ascender*isize/10.0f; + if (descender) + *descender = font->descender*isize/10.0f; + if (lineh) + *lineh = font->lineh*isize/10.0f; +} + +void fonsLineBounds(FONScontext* stash, float y, float* miny, float* maxy) +{ + FONSfont* font; + FONSstate* state = fons__getState(stash); + short isize; + + if (stash == NULL) return; + if (state->font < 0 || state->font >= stash->nfonts) return; + font = stash->fonts[state->font]; + isize = (short)(state->size*10.0f); + if (font->data == NULL) return; + + y += fons__getVertAlign(stash, font, state->align, isize); + + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + *miny = y - font->ascender * (float)isize/10.0f; + *maxy = *miny + font->lineh*isize/10.0f; + } else { + *maxy = y + font->descender * (float)isize/10.0f; + *miny = *maxy - font->lineh*isize/10.0f; + } +} + +const unsigned char* fonsGetTextureData(FONScontext* stash, int* width, int* height) +{ + if (width != NULL) + *width = stash->params.width; + if (height != NULL) + *height = stash->params.height; + return stash->texData; +} + +int fonsValidateTexture(FONScontext* stash, int* dirty) +{ + if (stash->dirtyRect[0] < stash->dirtyRect[2] && stash->dirtyRect[1] < stash->dirtyRect[3]) { + dirty[0] = stash->dirtyRect[0]; + dirty[1] = stash->dirtyRect[1]; + dirty[2] = stash->dirtyRect[2]; + dirty[3] = stash->dirtyRect[3]; + // Reset dirty rect + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + return 1; + } + return 0; +} + +void fonsDeleteInternal(FONScontext* stash) +{ + int i; + if (stash == NULL) return; + + if (stash->params.renderDelete) + stash->params.renderDelete(stash->params.userPtr); + + for (i = 0; i < stash->nfonts; ++i) + fons__freeFont(stash->fonts[i]); + + if (stash->atlas) fons__deleteAtlas(stash->atlas); + if (stash->fonts) free(stash->fonts); + if (stash->texData) free(stash->texData); + if (stash->scratch) free(stash->scratch); + free(stash); +} + +void fonsSetErrorCallback(FONScontext* stash, void (*callback)(void* uptr, int error, int val), void* uptr) +{ + if (stash == NULL) return; + stash->handleError = callback; + stash->errorUptr = uptr; +} + +void fonsGetAtlasSize(FONScontext* stash, int* width, int* height) +{ + if (stash == NULL) return; + *width = stash->params.width; + *height = stash->params.height; +} + +int fonsExpandAtlas(FONScontext* stash, int width, int height) +{ + int i, maxy = 0; + unsigned char* data = NULL; + if (stash == NULL) return 0; + + width = fons__maxi(width, stash->params.width); + height = fons__maxi(height, stash->params.height); + + if (width == stash->params.width && height == stash->params.height) + return 1; + + // Flush pending glyphs. + fons__flush(stash); + + // Create new texture + if (stash->params.renderResize != NULL) { + if (stash->params.renderResize(stash->params.userPtr, width, height) == 0) + return 0; + } + // Copy old texture data over. + data = (unsigned char*)malloc(width * height); + if (data == NULL) + return 0; + for (i = 0; i < stash->params.height; i++) { + unsigned char* dst = &data[i*width]; + unsigned char* src = &stash->texData[i*stash->params.width]; + memcpy(dst, src, stash->params.width); + if (width > stash->params.width) + memset(dst+stash->params.width, 0, width - stash->params.width); + } + if (height > stash->params.height) + memset(&data[stash->params.height * width], 0, (height - stash->params.height) * width); + + free(stash->texData); + stash->texData = data; + + // Increase atlas size + fons__atlasExpand(stash->atlas, width, height); + + // Add existing data as dirty. + for (i = 0; i < stash->atlas->nnodes; i++) + maxy = fons__maxi(maxy, stash->atlas->nodes[i].y); + stash->dirtyRect[0] = 0; + stash->dirtyRect[1] = 0; + stash->dirtyRect[2] = stash->params.width; + stash->dirtyRect[3] = maxy; + + stash->params.width = width; + stash->params.height = height; + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + + return 1; +} + +int fonsResetAtlas(FONScontext* stash, int width, int height) +{ + int i, j; + if (stash == NULL) return 0; + + // Flush pending glyphs. + fons__flush(stash); + + // Create new texture + if (stash->params.renderResize != NULL) { + if (stash->params.renderResize(stash->params.userPtr, width, height) == 0) + return 0; + } + + // Reset atlas + fons__atlasReset(stash->atlas, width, height); + + // Clear texture data. + stash->texData = (unsigned char*)realloc(stash->texData, width * height); + if (stash->texData == NULL) return 0; + memset(stash->texData, 0, width * height); + + // Reset dirty rect + stash->dirtyRect[0] = width; + stash->dirtyRect[1] = height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + + // Reset cached glyphs + for (i = 0; i < stash->nfonts; i++) { + FONSfont* font = stash->fonts[i]; + font->nglyphs = 0; + for (j = 0; j < FONS_HASH_LUT_SIZE; j++) + font->lut[j] = -1; + } + + stash->params.width = width; + stash->params.height = height; + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + + // Add white rect at 0,0 for debug drawing. + fons__addWhiteRect(stash, 2,2); + + return 1; +} + + +#endif diff --git a/phonelibs/nanovg/nanovg.c b/phonelibs/nanovg/nanovg.c new file mode 100644 index 0000000000..51f972ca5b --- /dev/null +++ b/phonelibs/nanovg/nanovg.c @@ -0,0 +1,2870 @@ +// +// Copyright (c) 2013 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#include +#include +#include +#include + +#include "nanovg.h" +#define FONTSTASH_IMPLEMENTATION +#include "fontstash.h" +#define STB_IMAGE_IMPLEMENTATION +#include "stb_image.h" + +#ifdef _MSC_VER +#pragma warning(disable: 4100) // unreferenced formal parameter +#pragma warning(disable: 4127) // conditional expression is constant +#pragma warning(disable: 4204) // nonstandard extension used : non-constant aggregate initializer +#pragma warning(disable: 4706) // assignment within conditional expression +#endif + +#define NVG_INIT_FONTIMAGE_SIZE 512 +#define NVG_MAX_FONTIMAGE_SIZE 2048 +#define NVG_MAX_FONTIMAGES 4 + +#define NVG_INIT_COMMANDS_SIZE 256 +#define NVG_INIT_POINTS_SIZE 128 +#define NVG_INIT_PATHS_SIZE 16 +#define NVG_INIT_VERTS_SIZE 256 +#define NVG_MAX_STATES 32 + +#define NVG_KAPPA90 0.5522847493f // Length proportional to radius of a cubic bezier handle for 90deg arcs. + +#define NVG_COUNTOF(arr) (sizeof(arr) / sizeof(0[arr])) + + +enum NVGcommands { + NVG_MOVETO = 0, + NVG_LINETO = 1, + NVG_BEZIERTO = 2, + NVG_CLOSE = 3, + NVG_WINDING = 4, +}; + +enum NVGpointFlags +{ + NVG_PT_CORNER = 0x01, + NVG_PT_LEFT = 0x02, + NVG_PT_BEVEL = 0x04, + NVG_PR_INNERBEVEL = 0x08, +}; + +struct NVGstate { + NVGcompositeOperationState compositeOperation; + NVGpaint fill; + NVGpaint stroke; + float strokeWidth; + float miterLimit; + int lineJoin; + int lineCap; + float alpha; + float xform[6]; + NVGscissor scissor; + float fontSize; + float letterSpacing; + float lineHeight; + float fontBlur; + int textAlign; + int fontId; +}; +typedef struct NVGstate NVGstate; + +struct NVGpoint { + float x,y; + float dx, dy; + float len; + float dmx, dmy; + unsigned char flags; +}; +typedef struct NVGpoint NVGpoint; + +struct NVGpathCache { + NVGpoint* points; + int npoints; + int cpoints; + NVGpath* paths; + int npaths; + int cpaths; + NVGvertex* verts; + int nverts; + int cverts; + float bounds[4]; +}; +typedef struct NVGpathCache NVGpathCache; + +struct NVGcontext { + NVGparams params; + float* commands; + int ccommands; + int ncommands; + float commandx, commandy; + NVGstate states[NVG_MAX_STATES]; + int nstates; + NVGpathCache* cache; + float tessTol; + float distTol; + float fringeWidth; + float devicePxRatio; + struct FONScontext* fs; + int fontImages[NVG_MAX_FONTIMAGES]; + int fontImageIdx; + int drawCallCount; + int fillTriCount; + int strokeTriCount; + int textTriCount; +}; + +static float nvg__sqrtf(float a) { return sqrtf(a); } +static float nvg__modf(float a, float b) { return fmodf(a, b); } +static float nvg__sinf(float a) { return sinf(a); } +static float nvg__cosf(float a) { return cosf(a); } +static float nvg__tanf(float a) { return tanf(a); } +static float nvg__atan2f(float a,float b) { return atan2f(a, b); } +static float nvg__acosf(float a) { return acosf(a); } + +static int nvg__mini(int a, int b) { return a < b ? a : b; } +static int nvg__maxi(int a, int b) { return a > b ? a : b; } +static int nvg__clampi(int a, int mn, int mx) { return a < mn ? mn : (a > mx ? mx : a); } +static float nvg__minf(float a, float b) { return a < b ? a : b; } +static float nvg__maxf(float a, float b) { return a > b ? a : b; } +static float nvg__absf(float a) { return a >= 0.0f ? a : -a; } +static float nvg__signf(float a) { return a >= 0.0f ? 1.0f : -1.0f; } +static float nvg__clampf(float a, float mn, float mx) { return a < mn ? mn : (a > mx ? mx : a); } +static float nvg__cross(float dx0, float dy0, float dx1, float dy1) { return dx1*dy0 - dx0*dy1; } + +static float nvg__normalize(float *x, float* y) +{ + float d = nvg__sqrtf((*x)*(*x) + (*y)*(*y)); + if (d > 1e-6f) { + float id = 1.0f / d; + *x *= id; + *y *= id; + } + return d; +} + + +static void nvg__deletePathCache(NVGpathCache* c) +{ + if (c == NULL) return; + if (c->points != NULL) free(c->points); + if (c->paths != NULL) free(c->paths); + if (c->verts != NULL) free(c->verts); + free(c); +} + +static NVGpathCache* nvg__allocPathCache(void) +{ + NVGpathCache* c = (NVGpathCache*)malloc(sizeof(NVGpathCache)); + if (c == NULL) goto error; + memset(c, 0, sizeof(NVGpathCache)); + + c->points = (NVGpoint*)malloc(sizeof(NVGpoint)*NVG_INIT_POINTS_SIZE); + if (!c->points) goto error; + c->npoints = 0; + c->cpoints = NVG_INIT_POINTS_SIZE; + + c->paths = (NVGpath*)malloc(sizeof(NVGpath)*NVG_INIT_PATHS_SIZE); + if (!c->paths) goto error; + c->npaths = 0; + c->cpaths = NVG_INIT_PATHS_SIZE; + + c->verts = (NVGvertex*)malloc(sizeof(NVGvertex)*NVG_INIT_VERTS_SIZE); + if (!c->verts) goto error; + c->nverts = 0; + c->cverts = NVG_INIT_VERTS_SIZE; + + return c; +error: + nvg__deletePathCache(c); + return NULL; +} + +static void nvg__setDevicePixelRatio(NVGcontext* ctx, float ratio) +{ + ctx->tessTol = 0.25f / ratio; + ctx->distTol = 0.01f / ratio; + ctx->fringeWidth = 1.0f / ratio; + ctx->devicePxRatio = ratio; +} + +static NVGcompositeOperationState nvg__compositeOperationState(int op) +{ + int sfactor, dfactor; + + if (op == NVG_SOURCE_OVER) + { + sfactor = NVG_ONE; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_SOURCE_IN) + { + sfactor = NVG_DST_ALPHA; + dfactor = NVG_ZERO; + } + else if (op == NVG_SOURCE_OUT) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ZERO; + } + else if (op == NVG_ATOP) + { + sfactor = NVG_DST_ALPHA; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_OVER) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ONE; + } + else if (op == NVG_DESTINATION_IN) + { + sfactor = NVG_ZERO; + dfactor = NVG_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_OUT) + { + sfactor = NVG_ZERO; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_ATOP) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_SRC_ALPHA; + } + else if (op == NVG_LIGHTER) + { + sfactor = NVG_ONE; + dfactor = NVG_ONE; + } + else if (op == NVG_COPY) + { + sfactor = NVG_ONE; + dfactor = NVG_ZERO; + } + else if (op == NVG_XOR) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + + NVGcompositeOperationState state; + state.srcRGB = sfactor; + state.dstRGB = dfactor; + state.srcAlpha = sfactor; + state.dstAlpha = dfactor; + return state; +} + +static NVGstate* nvg__getState(NVGcontext* ctx) +{ + return &ctx->states[ctx->nstates-1]; +} + +NVGcontext* nvgCreateInternal(NVGparams* params) +{ + FONSparams fontParams; + NVGcontext* ctx = (NVGcontext*)malloc(sizeof(NVGcontext)); + int i; + if (ctx == NULL) goto error; + memset(ctx, 0, sizeof(NVGcontext)); + + ctx->params = *params; + for (i = 0; i < NVG_MAX_FONTIMAGES; i++) + ctx->fontImages[i] = 0; + + ctx->commands = (float*)malloc(sizeof(float)*NVG_INIT_COMMANDS_SIZE); + if (!ctx->commands) goto error; + ctx->ncommands = 0; + ctx->ccommands = NVG_INIT_COMMANDS_SIZE; + + ctx->cache = nvg__allocPathCache(); + if (ctx->cache == NULL) goto error; + + nvgSave(ctx); + nvgReset(ctx); + + nvg__setDevicePixelRatio(ctx, 1.0f); + + if (ctx->params.renderCreate(ctx->params.userPtr) == 0) goto error; + + // Init font rendering + memset(&fontParams, 0, sizeof(fontParams)); + fontParams.width = NVG_INIT_FONTIMAGE_SIZE; + fontParams.height = NVG_INIT_FONTIMAGE_SIZE; + fontParams.flags = FONS_ZERO_TOPLEFT; + fontParams.renderCreate = NULL; + fontParams.renderUpdate = NULL; + fontParams.renderDraw = NULL; + fontParams.renderDelete = NULL; + fontParams.userPtr = NULL; + ctx->fs = fonsCreateInternal(&fontParams); + if (ctx->fs == NULL) goto error; + + // Create font texture + ctx->fontImages[0] = ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_ALPHA, fontParams.width, fontParams.height, 0, NULL); + if (ctx->fontImages[0] == 0) goto error; + ctx->fontImageIdx = 0; + + return ctx; + +error: + nvgDeleteInternal(ctx); + return 0; +} + +NVGparams* nvgInternalParams(NVGcontext* ctx) +{ + return &ctx->params; +} + +void nvgDeleteInternal(NVGcontext* ctx) +{ + int i; + if (ctx == NULL) return; + if (ctx->commands != NULL) free(ctx->commands); + if (ctx->cache != NULL) nvg__deletePathCache(ctx->cache); + + if (ctx->fs) + fonsDeleteInternal(ctx->fs); + + for (i = 0; i < NVG_MAX_FONTIMAGES; i++) { + if (ctx->fontImages[i] != 0) { + nvgDeleteImage(ctx, ctx->fontImages[i]); + ctx->fontImages[i] = 0; + } + } + + if (ctx->params.renderDelete != NULL) + ctx->params.renderDelete(ctx->params.userPtr); + + free(ctx); +} + +void nvgBeginFrame(NVGcontext* ctx, int windowWidth, int windowHeight, float devicePixelRatio) +{ +/* printf("Tris: draws:%d fill:%d stroke:%d text:%d TOT:%d\n", + ctx->drawCallCount, ctx->fillTriCount, ctx->strokeTriCount, ctx->textTriCount, + ctx->fillTriCount+ctx->strokeTriCount+ctx->textTriCount);*/ + + ctx->nstates = 0; + nvgSave(ctx); + nvgReset(ctx); + + nvg__setDevicePixelRatio(ctx, devicePixelRatio); + + ctx->params.renderViewport(ctx->params.userPtr, windowWidth, windowHeight, devicePixelRatio); + + ctx->drawCallCount = 0; + ctx->fillTriCount = 0; + ctx->strokeTriCount = 0; + ctx->textTriCount = 0; +} + +void nvgCancelFrame(NVGcontext* ctx) +{ + ctx->params.renderCancel(ctx->params.userPtr); +} + +void nvgEndFrame(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + ctx->params.renderFlush(ctx->params.userPtr, state->compositeOperation); + if (ctx->fontImageIdx != 0) { + int fontImage = ctx->fontImages[ctx->fontImageIdx]; + int i, j, iw, ih; + // delete images that smaller than current one + if (fontImage == 0) + return; + nvgImageSize(ctx, fontImage, &iw, &ih); + for (i = j = 0; i < ctx->fontImageIdx; i++) { + if (ctx->fontImages[i] != 0) { + int nw, nh; + nvgImageSize(ctx, ctx->fontImages[i], &nw, &nh); + if (nw < iw || nh < ih) + nvgDeleteImage(ctx, ctx->fontImages[i]); + else + ctx->fontImages[j++] = ctx->fontImages[i]; + } + } + // make current font image to first + ctx->fontImages[j++] = ctx->fontImages[0]; + ctx->fontImages[0] = fontImage; + ctx->fontImageIdx = 0; + // clear all images after j + for (i = j; i < NVG_MAX_FONTIMAGES; i++) + ctx->fontImages[i] = 0; + } +} + +NVGcolor nvgRGB(unsigned char r, unsigned char g, unsigned char b) +{ + return nvgRGBA(r,g,b,255); +} + +NVGcolor nvgRGBf(float r, float g, float b) +{ + return nvgRGBAf(r,g,b,1.0f); +} + +NVGcolor nvgRGBA(unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + NVGcolor color; + // Use longer initialization to suppress warning. + color.r = r / 255.0f; + color.g = g / 255.0f; + color.b = b / 255.0f; + color.a = a / 255.0f; + return color; +} + +NVGcolor nvgRGBAf(float r, float g, float b, float a) +{ + NVGcolor color; + // Use longer initialization to suppress warning. + color.r = r; + color.g = g; + color.b = b; + color.a = a; + return color; +} + +NVGcolor nvgTransRGBA(NVGcolor c, unsigned char a) +{ + c.a = a / 255.0f; + return c; +} + +NVGcolor nvgTransRGBAf(NVGcolor c, float a) +{ + c.a = a; + return c; +} + +NVGcolor nvgLerpRGBA(NVGcolor c0, NVGcolor c1, float u) +{ + int i; + float oneminu; + NVGcolor cint = {0}; + + u = nvg__clampf(u, 0.0f, 1.0f); + oneminu = 1.0f - u; + for( i = 0; i <4; i++ ) + { + cint.rgba[i] = c0.rgba[i] * oneminu + c1.rgba[i] * u; + } + + return cint; +} + +NVGcolor nvgHSL(float h, float s, float l) +{ + return nvgHSLA(h,s,l,255); +} + +static float nvg__hue(float h, float m1, float m2) +{ + if (h < 0) h += 1; + if (h > 1) h -= 1; + if (h < 1.0f/6.0f) + return m1 + (m2 - m1) * h * 6.0f; + else if (h < 3.0f/6.0f) + return m2; + else if (h < 4.0f/6.0f) + return m1 + (m2 - m1) * (2.0f/3.0f - h) * 6.0f; + return m1; +} + +NVGcolor nvgHSLA(float h, float s, float l, unsigned char a) +{ + float m1, m2; + NVGcolor col; + h = nvg__modf(h, 1.0f); + if (h < 0.0f) h += 1.0f; + s = nvg__clampf(s, 0.0f, 1.0f); + l = nvg__clampf(l, 0.0f, 1.0f); + m2 = l <= 0.5f ? (l * (1 + s)) : (l + s - l * s); + m1 = 2 * l - m2; + col.r = nvg__clampf(nvg__hue(h + 1.0f/3.0f, m1, m2), 0.0f, 1.0f); + col.g = nvg__clampf(nvg__hue(h, m1, m2), 0.0f, 1.0f); + col.b = nvg__clampf(nvg__hue(h - 1.0f/3.0f, m1, m2), 0.0f, 1.0f); + col.a = a/255.0f; + return col; +} + +void nvgTransformIdentity(float* t) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = 0.0f; t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformTranslate(float* t, float tx, float ty) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = 0.0f; t[3] = 1.0f; + t[4] = tx; t[5] = ty; +} + +void nvgTransformScale(float* t, float sx, float sy) +{ + t[0] = sx; t[1] = 0.0f; + t[2] = 0.0f; t[3] = sy; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformRotate(float* t, float a) +{ + float cs = nvg__cosf(a), sn = nvg__sinf(a); + t[0] = cs; t[1] = sn; + t[2] = -sn; t[3] = cs; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformSkewX(float* t, float a) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = nvg__tanf(a); t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformSkewY(float* t, float a) +{ + t[0] = 1.0f; t[1] = nvg__tanf(a); + t[2] = 0.0f; t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformMultiply(float* t, const float* s) +{ + float t0 = t[0] * s[0] + t[1] * s[2]; + float t2 = t[2] * s[0] + t[3] * s[2]; + float t4 = t[4] * s[0] + t[5] * s[2] + s[4]; + t[1] = t[0] * s[1] + t[1] * s[3]; + t[3] = t[2] * s[1] + t[3] * s[3]; + t[5] = t[4] * s[1] + t[5] * s[3] + s[5]; + t[0] = t0; + t[2] = t2; + t[4] = t4; +} + +void nvgTransformPremultiply(float* t, const float* s) +{ + float s2[6]; + memcpy(s2, s, sizeof(float)*6); + nvgTransformMultiply(s2, t); + memcpy(t, s2, sizeof(float)*6); +} + +int nvgTransformInverse(float* inv, const float* t) +{ + double invdet, det = (double)t[0] * t[3] - (double)t[2] * t[1]; + if (det > -1e-6 && det < 1e-6) { + nvgTransformIdentity(inv); + return 0; + } + invdet = 1.0 / det; + inv[0] = (float)(t[3] * invdet); + inv[2] = (float)(-t[2] * invdet); + inv[4] = (float)(((double)t[2] * t[5] - (double)t[3] * t[4]) * invdet); + inv[1] = (float)(-t[1] * invdet); + inv[3] = (float)(t[0] * invdet); + inv[5] = (float)(((double)t[1] * t[4] - (double)t[0] * t[5]) * invdet); + return 1; +} + +void nvgTransformPoint(float* dx, float* dy, const float* t, float sx, float sy) +{ + *dx = sx*t[0] + sy*t[2] + t[4]; + *dy = sx*t[1] + sy*t[3] + t[5]; +} + +float nvgDegToRad(float deg) +{ + return deg / 180.0f * NVG_PI; +} + +float nvgRadToDeg(float rad) +{ + return rad / NVG_PI * 180.0f; +} + +static void nvg__setPaintColor(NVGpaint* p, NVGcolor color) +{ + memset(p, 0, sizeof(*p)); + nvgTransformIdentity(p->xform); + p->radius = 0.0f; + p->feather = 1.0f; + p->innerColor = color; + p->outerColor = color; +} + + +// State handling +void nvgSave(NVGcontext* ctx) +{ + if (ctx->nstates >= NVG_MAX_STATES) + return; + if (ctx->nstates > 0) + memcpy(&ctx->states[ctx->nstates], &ctx->states[ctx->nstates-1], sizeof(NVGstate)); + ctx->nstates++; +} + +void nvgRestore(NVGcontext* ctx) +{ + if (ctx->nstates <= 1) + return; + ctx->nstates--; +} + +void nvgReset(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + memset(state, 0, sizeof(*state)); + + nvg__setPaintColor(&state->fill, nvgRGBA(255,255,255,255)); + nvg__setPaintColor(&state->stroke, nvgRGBA(0,0,0,255)); + state->compositeOperation = nvg__compositeOperationState(NVG_SOURCE_OVER); + state->strokeWidth = 1.0f; + state->miterLimit = 10.0f; + state->lineCap = NVG_BUTT; + state->lineJoin = NVG_MITER; + state->alpha = 1.0f; + nvgTransformIdentity(state->xform); + + state->scissor.extent[0] = -1.0f; + state->scissor.extent[1] = -1.0f; + + state->fontSize = 16.0f; + state->letterSpacing = 0.0f; + state->lineHeight = 1.0f; + state->fontBlur = 0.0f; + state->textAlign = NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE; + state->fontId = 0; +} + +// State setting +void nvgStrokeWidth(NVGcontext* ctx, float width) +{ + NVGstate* state = nvg__getState(ctx); + state->strokeWidth = width; +} + +void nvgMiterLimit(NVGcontext* ctx, float limit) +{ + NVGstate* state = nvg__getState(ctx); + state->miterLimit = limit; +} + +void nvgLineCap(NVGcontext* ctx, int cap) +{ + NVGstate* state = nvg__getState(ctx); + state->lineCap = cap; +} + +void nvgLineJoin(NVGcontext* ctx, int join) +{ + NVGstate* state = nvg__getState(ctx); + state->lineJoin = join; +} + +void nvgGlobalAlpha(NVGcontext* ctx, float alpha) +{ + NVGstate* state = nvg__getState(ctx); + state->alpha = alpha; +} + +void nvgTransform(NVGcontext* ctx, float a, float b, float c, float d, float e, float f) +{ + NVGstate* state = nvg__getState(ctx); + float t[6] = { a, b, c, d, e, f }; + nvgTransformPremultiply(state->xform, t); +} + +void nvgResetTransform(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + nvgTransformIdentity(state->xform); +} + +void nvgTranslate(NVGcontext* ctx, float x, float y) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformTranslate(t, x,y); + nvgTransformPremultiply(state->xform, t); +} + +void nvgRotate(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformRotate(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgSkewX(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformSkewX(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgSkewY(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformSkewY(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgScale(NVGcontext* ctx, float x, float y) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformScale(t, x,y); + nvgTransformPremultiply(state->xform, t); +} + +void nvgCurrentTransform(NVGcontext* ctx, float* xform) +{ + NVGstate* state = nvg__getState(ctx); + if (xform == NULL) return; + memcpy(xform, state->xform, sizeof(float)*6); +} + +void nvgStrokeColor(NVGcontext* ctx, NVGcolor color) +{ + NVGstate* state = nvg__getState(ctx); + nvg__setPaintColor(&state->stroke, color); +} + +void nvgStrokePaint(NVGcontext* ctx, NVGpaint paint) +{ + NVGstate* state = nvg__getState(ctx); + state->stroke = paint; + nvgTransformMultiply(state->stroke.xform, state->xform); +} + +void nvgFillColor(NVGcontext* ctx, NVGcolor color) +{ + NVGstate* state = nvg__getState(ctx); + nvg__setPaintColor(&state->fill, color); +} + +void nvgFillPaint(NVGcontext* ctx, NVGpaint paint) +{ + NVGstate* state = nvg__getState(ctx); + state->fill = paint; + nvgTransformMultiply(state->fill.xform, state->xform); +} + +int nvgCreateImage(NVGcontext* ctx, const char* filename, int imageFlags) +{ + int w, h, n, image; + unsigned char* img; + stbi_set_unpremultiply_on_load(1); + stbi_convert_iphone_png_to_rgb(1); + img = stbi_load(filename, &w, &h, &n, 4); + if (img == NULL) { +// printf("Failed to load %s - %s\n", filename, stbi_failure_reason()); + return 0; + } + image = nvgCreateImageRGBA(ctx, w, h, imageFlags, img); + stbi_image_free(img); + return image; +} + +int nvgCreateImageMem(NVGcontext* ctx, int imageFlags, unsigned char* data, int ndata) +{ + int w, h, n, image; + unsigned char* img = stbi_load_from_memory(data, ndata, &w, &h, &n, 4); + if (img == NULL) { +// printf("Failed to load %s - %s\n", filename, stbi_failure_reason()); + return 0; + } + image = nvgCreateImageRGBA(ctx, w, h, imageFlags, img); + stbi_image_free(img); + return image; +} + +int nvgCreateImageRGBA(NVGcontext* ctx, int w, int h, int imageFlags, const unsigned char* data) +{ + return ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_RGBA, w, h, imageFlags, data); +} + +void nvgUpdateImage(NVGcontext* ctx, int image, const unsigned char* data) +{ + int w, h; + ctx->params.renderGetTextureSize(ctx->params.userPtr, image, &w, &h); + ctx->params.renderUpdateTexture(ctx->params.userPtr, image, 0,0, w,h, data); +} + +void nvgImageSize(NVGcontext* ctx, int image, int* w, int* h) +{ + ctx->params.renderGetTextureSize(ctx->params.userPtr, image, w, h); +} + +void nvgDeleteImage(NVGcontext* ctx, int image) +{ + ctx->params.renderDeleteTexture(ctx->params.userPtr, image); +} + +NVGpaint nvgLinearGradient(NVGcontext* ctx, + float sx, float sy, float ex, float ey, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + float dx, dy, d; + const float large = 1e5; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + // Calculate transform aligned to the line + dx = ex - sx; + dy = ey - sy; + d = sqrtf(dx*dx + dy*dy); + if (d > 0.0001f) { + dx /= d; + dy /= d; + } else { + dx = 0; + dy = 1; + } + + p.xform[0] = dy; p.xform[1] = -dx; + p.xform[2] = dx; p.xform[3] = dy; + p.xform[4] = sx - dx*large; p.xform[5] = sy - dy*large; + + p.extent[0] = large; + p.extent[1] = large + d*0.5f; + + p.radius = 0.0f; + + p.feather = nvg__maxf(1.0f, d); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + +NVGpaint nvgRadialGradient(NVGcontext* ctx, + float cx, float cy, float inr, float outr, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + float r = (inr+outr)*0.5f; + float f = (outr-inr); + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformIdentity(p.xform); + p.xform[4] = cx; + p.xform[5] = cy; + + p.extent[0] = r; + p.extent[1] = r; + + p.radius = r; + + p.feather = nvg__maxf(1.0f, f); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + +NVGpaint nvgBoxGradient(NVGcontext* ctx, + float x, float y, float w, float h, float r, float f, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformIdentity(p.xform); + p.xform[4] = x+w*0.5f; + p.xform[5] = y+h*0.5f; + + p.extent[0] = w*0.5f; + p.extent[1] = h*0.5f; + + p.radius = r; + + p.feather = nvg__maxf(1.0f, f); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + + +NVGpaint nvgImagePattern(NVGcontext* ctx, + float cx, float cy, float w, float h, float angle, + int image, float alpha) +{ + NVGpaint p; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformRotate(p.xform, angle); + p.xform[4] = cx; + p.xform[5] = cy; + + p.extent[0] = w; + p.extent[1] = h; + + p.image = image; + + p.innerColor = p.outerColor = nvgRGBAf(1,1,1,alpha); + + return p; +} + +// Scissoring +void nvgScissor(NVGcontext* ctx, float x, float y, float w, float h) +{ + NVGstate* state = nvg__getState(ctx); + + w = nvg__maxf(0.0f, w); + h = nvg__maxf(0.0f, h); + + nvgTransformIdentity(state->scissor.xform); + state->scissor.xform[4] = x+w*0.5f; + state->scissor.xform[5] = y+h*0.5f; + nvgTransformMultiply(state->scissor.xform, state->xform); + + state->scissor.extent[0] = w*0.5f; + state->scissor.extent[1] = h*0.5f; +} + +static void nvg__isectRects(float* dst, + float ax, float ay, float aw, float ah, + float bx, float by, float bw, float bh) +{ + float minx = nvg__maxf(ax, bx); + float miny = nvg__maxf(ay, by); + float maxx = nvg__minf(ax+aw, bx+bw); + float maxy = nvg__minf(ay+ah, by+bh); + dst[0] = minx; + dst[1] = miny; + dst[2] = nvg__maxf(0.0f, maxx - minx); + dst[3] = nvg__maxf(0.0f, maxy - miny); +} + +void nvgIntersectScissor(NVGcontext* ctx, float x, float y, float w, float h) +{ + NVGstate* state = nvg__getState(ctx); + float pxform[6], invxorm[6]; + float rect[4]; + float ex, ey, tex, tey; + + // If no previous scissor has been set, set the scissor as current scissor. + if (state->scissor.extent[0] < 0) { + nvgScissor(ctx, x, y, w, h); + return; + } + + // Transform the current scissor rect into current transform space. + // If there is difference in rotation, this will be approximation. + memcpy(pxform, state->scissor.xform, sizeof(float)*6); + ex = state->scissor.extent[0]; + ey = state->scissor.extent[1]; + nvgTransformInverse(invxorm, state->xform); + nvgTransformMultiply(pxform, invxorm); + tex = ex*nvg__absf(pxform[0]) + ey*nvg__absf(pxform[2]); + tey = ex*nvg__absf(pxform[1]) + ey*nvg__absf(pxform[3]); + + // Intersect rects. + nvg__isectRects(rect, pxform[4]-tex,pxform[5]-tey,tex*2,tey*2, x,y,w,h); + + nvgScissor(ctx, rect[0], rect[1], rect[2], rect[3]); +} + +void nvgResetScissor(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + memset(state->scissor.xform, 0, sizeof(state->scissor.xform)); + state->scissor.extent[0] = -1.0f; + state->scissor.extent[1] = -1.0f; +} + +// Global composite operation. +void nvgGlobalCompositeOperation(NVGcontext* ctx, int op) +{ + NVGstate* state = nvg__getState(ctx); + state->compositeOperation = nvg__compositeOperationState(op); +} + +void nvgGlobalCompositeBlendFunc(NVGcontext* ctx, int sfactor, int dfactor) +{ + nvgGlobalCompositeBlendFuncSeparate(ctx, sfactor, dfactor, sfactor, dfactor); +} + +void nvgGlobalCompositeBlendFuncSeparate(NVGcontext* ctx, int srcRGB, int dstRGB, int srcAlpha, int dstAlpha) +{ + NVGcompositeOperationState op; + op.srcRGB = srcRGB; + op.dstRGB = dstRGB; + op.srcAlpha = srcAlpha; + op.dstAlpha = dstAlpha; + + NVGstate* state = nvg__getState(ctx); + state->compositeOperation = op; +} + +static int nvg__ptEquals(float x1, float y1, float x2, float y2, float tol) +{ + float dx = x2 - x1; + float dy = y2 - y1; + return dx*dx + dy*dy < tol*tol; +} + +static float nvg__distPtSeg(float x, float y, float px, float py, float qx, float qy) +{ + float pqx, pqy, dx, dy, d, t; + pqx = qx-px; + pqy = qy-py; + dx = x-px; + dy = y-py; + d = pqx*pqx + pqy*pqy; + t = pqx*dx + pqy*dy; + if (d > 0) t /= d; + if (t < 0) t = 0; + else if (t > 1) t = 1; + dx = px + t*pqx - x; + dy = py + t*pqy - y; + return dx*dx + dy*dy; +} + +static void nvg__appendCommands(NVGcontext* ctx, float* vals, int nvals) +{ + NVGstate* state = nvg__getState(ctx); + int i; + + if (ctx->ncommands+nvals > ctx->ccommands) { + float* commands; + int ccommands = ctx->ncommands+nvals + ctx->ccommands/2; + commands = (float*)realloc(ctx->commands, sizeof(float)*ccommands); + if (commands == NULL) return; + ctx->commands = commands; + ctx->ccommands = ccommands; + } + + if ((int)vals[0] != NVG_CLOSE && (int)vals[0] != NVG_WINDING) { + ctx->commandx = vals[nvals-2]; + ctx->commandy = vals[nvals-1]; + } + + // transform commands + i = 0; + while (i < nvals) { + int cmd = (int)vals[i]; + switch (cmd) { + case NVG_MOVETO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + i += 3; + break; + case NVG_LINETO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + i += 3; + break; + case NVG_BEZIERTO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + nvgTransformPoint(&vals[i+3],&vals[i+4], state->xform, vals[i+3],vals[i+4]); + nvgTransformPoint(&vals[i+5],&vals[i+6], state->xform, vals[i+5],vals[i+6]); + i += 7; + break; + case NVG_CLOSE: + i++; + break; + case NVG_WINDING: + i += 2; + break; + default: + i++; + } + } + + memcpy(&ctx->commands[ctx->ncommands], vals, nvals*sizeof(float)); + + ctx->ncommands += nvals; +} + + +static void nvg__clearPathCache(NVGcontext* ctx) +{ + ctx->cache->npoints = 0; + ctx->cache->npaths = 0; +} + +static NVGpath* nvg__lastPath(NVGcontext* ctx) +{ + if (ctx->cache->npaths > 0) + return &ctx->cache->paths[ctx->cache->npaths-1]; + return NULL; +} + +static void nvg__addPath(NVGcontext* ctx) +{ + NVGpath* path; + if (ctx->cache->npaths+1 > ctx->cache->cpaths) { + NVGpath* paths; + int cpaths = ctx->cache->npaths+1 + ctx->cache->cpaths/2; + paths = (NVGpath*)realloc(ctx->cache->paths, sizeof(NVGpath)*cpaths); + if (paths == NULL) return; + ctx->cache->paths = paths; + ctx->cache->cpaths = cpaths; + } + path = &ctx->cache->paths[ctx->cache->npaths]; + memset(path, 0, sizeof(*path)); + path->first = ctx->cache->npoints; + path->winding = NVG_CCW; + + ctx->cache->npaths++; +} + +static NVGpoint* nvg__lastPoint(NVGcontext* ctx) +{ + if (ctx->cache->npoints > 0) + return &ctx->cache->points[ctx->cache->npoints-1]; + return NULL; +} + +static void nvg__addPoint(NVGcontext* ctx, float x, float y, int flags) +{ + NVGpath* path = nvg__lastPath(ctx); + NVGpoint* pt; + if (path == NULL) return; + + if (path->count > 0 && ctx->cache->npoints > 0) { + pt = nvg__lastPoint(ctx); + if (nvg__ptEquals(pt->x,pt->y, x,y, ctx->distTol)) { + pt->flags |= flags; + return; + } + } + + if (ctx->cache->npoints+1 > ctx->cache->cpoints) { + NVGpoint* points; + int cpoints = ctx->cache->npoints+1 + ctx->cache->cpoints/2; + points = (NVGpoint*)realloc(ctx->cache->points, sizeof(NVGpoint)*cpoints); + if (points == NULL) return; + ctx->cache->points = points; + ctx->cache->cpoints = cpoints; + } + + pt = &ctx->cache->points[ctx->cache->npoints]; + memset(pt, 0, sizeof(*pt)); + pt->x = x; + pt->y = y; + pt->flags = (unsigned char)flags; + + ctx->cache->npoints++; + path->count++; +} + +static void nvg__closePath(NVGcontext* ctx) +{ + NVGpath* path = nvg__lastPath(ctx); + if (path == NULL) return; + path->closed = 1; +} + +static void nvg__pathWinding(NVGcontext* ctx, int winding) +{ + NVGpath* path = nvg__lastPath(ctx); + if (path == NULL) return; + path->winding = winding; +} + +static float nvg__getAverageScale(float *t) +{ + float sx = sqrtf(t[0]*t[0] + t[2]*t[2]); + float sy = sqrtf(t[1]*t[1] + t[3]*t[3]); + return (sx + sy) * 0.5f; +} + +static NVGvertex* nvg__allocTempVerts(NVGcontext* ctx, int nverts) +{ + if (nverts > ctx->cache->cverts) { + NVGvertex* verts; + int cverts = (nverts + 0xff) & ~0xff; // Round up to prevent allocations when things change just slightly. + verts = (NVGvertex*)realloc(ctx->cache->verts, sizeof(NVGvertex)*cverts); + if (verts == NULL) return NULL; + ctx->cache->verts = verts; + ctx->cache->cverts = cverts; + } + + return ctx->cache->verts; +} + +static float nvg__triarea2(float ax, float ay, float bx, float by, float cx, float cy) +{ + float abx = bx - ax; + float aby = by - ay; + float acx = cx - ax; + float acy = cy - ay; + return acx*aby - abx*acy; +} + +static float nvg__polyArea(NVGpoint* pts, int npts) +{ + int i; + float area = 0; + for (i = 2; i < npts; i++) { + NVGpoint* a = &pts[0]; + NVGpoint* b = &pts[i-1]; + NVGpoint* c = &pts[i]; + area += nvg__triarea2(a->x,a->y, b->x,b->y, c->x,c->y); + } + return area * 0.5f; +} + +static void nvg__polyReverse(NVGpoint* pts, int npts) +{ + NVGpoint tmp; + int i = 0, j = npts-1; + while (i < j) { + tmp = pts[i]; + pts[i] = pts[j]; + pts[j] = tmp; + i++; + j--; + } +} + + +static void nvg__vset(NVGvertex* vtx, float x, float y, float u, float v) +{ + vtx->x = x; + vtx->y = y; + vtx->u = u; + vtx->v = v; +} + +static void nvg__tesselateBezier(NVGcontext* ctx, + float x1, float y1, float x2, float y2, + float x3, float y3, float x4, float y4, + int level, int type) +{ + float x12,y12,x23,y23,x34,y34,x123,y123,x234,y234,x1234,y1234; + float dx,dy,d2,d3; + + if (level > 10) return; + + x12 = (x1+x2)*0.5f; + y12 = (y1+y2)*0.5f; + x23 = (x2+x3)*0.5f; + y23 = (y2+y3)*0.5f; + x34 = (x3+x4)*0.5f; + y34 = (y3+y4)*0.5f; + x123 = (x12+x23)*0.5f; + y123 = (y12+y23)*0.5f; + + dx = x4 - x1; + dy = y4 - y1; + d2 = nvg__absf(((x2 - x4) * dy - (y2 - y4) * dx)); + d3 = nvg__absf(((x3 - x4) * dy - (y3 - y4) * dx)); + + if ((d2 + d3)*(d2 + d3) < ctx->tessTol * (dx*dx + dy*dy)) { + nvg__addPoint(ctx, x4, y4, type); + return; + } + +/* if (nvg__absf(x1+x3-x2-x2) + nvg__absf(y1+y3-y2-y2) + nvg__absf(x2+x4-x3-x3) + nvg__absf(y2+y4-y3-y3) < ctx->tessTol) { + nvg__addPoint(ctx, x4, y4, type); + return; + }*/ + + x234 = (x23+x34)*0.5f; + y234 = (y23+y34)*0.5f; + x1234 = (x123+x234)*0.5f; + y1234 = (y123+y234)*0.5f; + + nvg__tesselateBezier(ctx, x1,y1, x12,y12, x123,y123, x1234,y1234, level+1, 0); + nvg__tesselateBezier(ctx, x1234,y1234, x234,y234, x34,y34, x4,y4, level+1, type); +} + +static void nvg__flattenPaths(NVGcontext* ctx) +{ + NVGpathCache* cache = ctx->cache; +// NVGstate* state = nvg__getState(ctx); + NVGpoint* last; + NVGpoint* p0; + NVGpoint* p1; + NVGpoint* pts; + NVGpath* path; + int i, j; + float* cp1; + float* cp2; + float* p; + float area; + + if (cache->npaths > 0) + return; + + // Flatten + i = 0; + while (i < ctx->ncommands) { + int cmd = (int)ctx->commands[i]; + switch (cmd) { + case NVG_MOVETO: + nvg__addPath(ctx); + p = &ctx->commands[i+1]; + nvg__addPoint(ctx, p[0], p[1], NVG_PT_CORNER); + i += 3; + break; + case NVG_LINETO: + p = &ctx->commands[i+1]; + nvg__addPoint(ctx, p[0], p[1], NVG_PT_CORNER); + i += 3; + break; + case NVG_BEZIERTO: + last = nvg__lastPoint(ctx); + if (last != NULL) { + cp1 = &ctx->commands[i+1]; + cp2 = &ctx->commands[i+3]; + p = &ctx->commands[i+5]; + nvg__tesselateBezier(ctx, last->x,last->y, cp1[0],cp1[1], cp2[0],cp2[1], p[0],p[1], 0, NVG_PT_CORNER); + } + i += 7; + break; + case NVG_CLOSE: + nvg__closePath(ctx); + i++; + break; + case NVG_WINDING: + nvg__pathWinding(ctx, (int)ctx->commands[i+1]); + i += 2; + break; + default: + i++; + } + } + + cache->bounds[0] = cache->bounds[1] = 1e6f; + cache->bounds[2] = cache->bounds[3] = -1e6f; + + // Calculate the direction and length of line segments. + for (j = 0; j < cache->npaths; j++) { + path = &cache->paths[j]; + pts = &cache->points[path->first]; + + // If the first and last points are the same, remove the last, mark as closed path. + p0 = &pts[path->count-1]; + p1 = &pts[0]; + if (nvg__ptEquals(p0->x,p0->y, p1->x,p1->y, ctx->distTol)) { + path->count--; + p0 = &pts[path->count-1]; + path->closed = 1; + } + + // Enforce winding. + if (path->count > 2) { + area = nvg__polyArea(pts, path->count); + if (path->winding == NVG_CCW && area < 0.0f) + nvg__polyReverse(pts, path->count); + if (path->winding == NVG_CW && area > 0.0f) + nvg__polyReverse(pts, path->count); + } + + for(i = 0; i < path->count; i++) { + // Calculate segment direction and length + p0->dx = p1->x - p0->x; + p0->dy = p1->y - p0->y; + p0->len = nvg__normalize(&p0->dx, &p0->dy); + // Update bounds + cache->bounds[0] = nvg__minf(cache->bounds[0], p0->x); + cache->bounds[1] = nvg__minf(cache->bounds[1], p0->y); + cache->bounds[2] = nvg__maxf(cache->bounds[2], p0->x); + cache->bounds[3] = nvg__maxf(cache->bounds[3], p0->y); + // Advance + p0 = p1++; + } + } +} + +static int nvg__curveDivs(float r, float arc, float tol) +{ + float da = acosf(r / (r + tol)) * 2.0f; + return nvg__maxi(2, (int)ceilf(arc / da)); +} + +static void nvg__chooseBevel(int bevel, NVGpoint* p0, NVGpoint* p1, float w, + float* x0, float* y0, float* x1, float* y1) +{ + if (bevel) { + *x0 = p1->x + p0->dy * w; + *y0 = p1->y - p0->dx * w; + *x1 = p1->x + p1->dy * w; + *y1 = p1->y - p1->dx * w; + } else { + *x0 = p1->x + p1->dmx * w; + *y0 = p1->y + p1->dmy * w; + *x1 = p1->x + p1->dmx * w; + *y1 = p1->y + p1->dmy * w; + } +} + +static NVGvertex* nvg__roundJoin(NVGvertex* dst, NVGpoint* p0, NVGpoint* p1, + float lw, float rw, float lu, float ru, int ncap, float fringe) +{ + int i, n; + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + NVG_NOTUSED(fringe); + + if (p1->flags & NVG_PT_LEFT) { + float lx0,ly0,lx1,ly1,a0,a1; + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, lw, &lx0,&ly0, &lx1,&ly1); + a0 = atan2f(-dly0, -dlx0); + a1 = atan2f(-dly1, -dlx1); + if (a1 > a0) a1 -= NVG_PI*2; + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + n = nvg__clampi((int)ceilf(((a0 - a1) / NVG_PI) * ncap), 2, ncap); + for (i = 0; i < n; i++) { + float u = i/(float)(n-1); + float a = a0 + u*(a1-a0); + float rx = p1->x + cosf(a) * rw; + float ry = p1->y + sinf(a) * rw; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, rx, ry, ru,1); dst++; + } + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + + } else { + float rx0,ry0,rx1,ry1,a0,a1; + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, -rw, &rx0,&ry0, &rx1,&ry1); + a0 = atan2f(dly0, dlx0); + a1 = atan2f(dly1, dlx1); + if (a1 < a0) a1 += NVG_PI*2; + + nvg__vset(dst, p1->x + dlx0*rw, p1->y + dly0*rw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + n = nvg__clampi((int)ceilf(((a1 - a0) / NVG_PI) * ncap), 2, ncap); + for (i = 0; i < n; i++) { + float u = i/(float)(n-1); + float a = a0 + u*(a1-a0); + float lx = p1->x + cosf(a) * lw; + float ly = p1->y + sinf(a) * lw; + nvg__vset(dst, lx, ly, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + } + + nvg__vset(dst, p1->x + dlx1*rw, p1->y + dly1*rw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + + } + return dst; +} + +static NVGvertex* nvg__bevelJoin(NVGvertex* dst, NVGpoint* p0, NVGpoint* p1, + float lw, float rw, float lu, float ru, float fringe) +{ + float rx0,ry0,rx1,ry1; + float lx0,ly0,lx1,ly1; + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + NVG_NOTUSED(fringe); + + if (p1->flags & NVG_PT_LEFT) { + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, lw, &lx0,&ly0, &lx1,&ly1); + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + if (p1->flags & NVG_PT_BEVEL) { + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + } else { + rx0 = p1->x - p1->dmx * rw; + ry0 = p1->y - p1->dmy * rw; + + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + nvg__vset(dst, rx0, ry0, ru,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + } + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + + } else { + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, -rw, &rx0,&ry0, &rx1,&ry1); + + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + if (p1->flags & NVG_PT_BEVEL) { + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + } else { + lx0 = p1->x + p1->dmx * lw; + ly0 = p1->y + p1->dmy * lw; + + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, lx0, ly0, lu,1); dst++; + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + } + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + } + + return dst; +} + +static NVGvertex* nvg__buttCapStart(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, float d, float aa) +{ + float px = p->x - dx*d; + float py = p->y - dy*d; + float dlx = dy; + float dly = -dx; + nvg__vset(dst, px + dlx*w - dx*aa, py + dly*w - dy*aa, 0,0); dst++; + nvg__vset(dst, px - dlx*w - dx*aa, py - dly*w - dy*aa, 1,0); dst++; + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + return dst; +} + +static NVGvertex* nvg__buttCapEnd(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, float d, float aa) +{ + float px = p->x + dx*d; + float py = p->y + dy*d; + float dlx = dy; + float dly = -dx; + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + nvg__vset(dst, px + dlx*w + dx*aa, py + dly*w + dy*aa, 0,0); dst++; + nvg__vset(dst, px - dlx*w + dx*aa, py - dly*w + dy*aa, 1,0); dst++; + return dst; +} + + +static NVGvertex* nvg__roundCapStart(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, int ncap, float aa) +{ + int i; + float px = p->x; + float py = p->y; + float dlx = dy; + float dly = -dx; + NVG_NOTUSED(aa); + for (i = 0; i < ncap; i++) { + float a = i/(float)(ncap-1)*NVG_PI; + float ax = cosf(a) * w, ay = sinf(a) * w; + nvg__vset(dst, px - dlx*ax - dx*ay, py - dly*ax - dy*ay, 0,1); dst++; + nvg__vset(dst, px, py, 0.5f,1); dst++; + } + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + return dst; +} + +static NVGvertex* nvg__roundCapEnd(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, int ncap, float aa) +{ + int i; + float px = p->x; + float py = p->y; + float dlx = dy; + float dly = -dx; + NVG_NOTUSED(aa); + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + for (i = 0; i < ncap; i++) { + float a = i/(float)(ncap-1)*NVG_PI; + float ax = cosf(a) * w, ay = sinf(a) * w; + nvg__vset(dst, px, py, 0.5f,1); dst++; + nvg__vset(dst, px - dlx*ax + dx*ay, py - dly*ax + dy*ay, 0,1); dst++; + } + return dst; +} + + +static void nvg__calculateJoins(NVGcontext* ctx, float w, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + int i, j; + float iw = 0.0f; + + if (w > 0.0f) iw = 1.0f / w; + + // Calculate which joins needs extra vertices to append, and gather vertex count. + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0 = &pts[path->count-1]; + NVGpoint* p1 = &pts[0]; + int nleft = 0; + + path->nbevel = 0; + + for (j = 0; j < path->count; j++) { + float dlx0, dly0, dlx1, dly1, dmr2, cross, limit; + dlx0 = p0->dy; + dly0 = -p0->dx; + dlx1 = p1->dy; + dly1 = -p1->dx; + // Calculate extrusions + p1->dmx = (dlx0 + dlx1) * 0.5f; + p1->dmy = (dly0 + dly1) * 0.5f; + dmr2 = p1->dmx*p1->dmx + p1->dmy*p1->dmy; + if (dmr2 > 0.000001f) { + float scale = 1.0f / dmr2; + if (scale > 600.0f) { + scale = 600.0f; + } + p1->dmx *= scale; + p1->dmy *= scale; + } + + // Clear flags, but keep the corner. + p1->flags = (p1->flags & NVG_PT_CORNER) ? NVG_PT_CORNER : 0; + + // Keep track of left turns. + cross = p1->dx * p0->dy - p0->dx * p1->dy; + if (cross > 0.0f) { + nleft++; + p1->flags |= NVG_PT_LEFT; + } + + // Calculate if we should use bevel or miter for inner join. + limit = nvg__maxf(1.01f, nvg__minf(p0->len, p1->len) * iw); + if ((dmr2 * limit*limit) < 1.0f) + p1->flags |= NVG_PR_INNERBEVEL; + + // Check to see if the corner needs to be beveled. + if (p1->flags & NVG_PT_CORNER) { + if ((dmr2 * miterLimit*miterLimit) < 1.0f || lineJoin == NVG_BEVEL || lineJoin == NVG_ROUND) { + p1->flags |= NVG_PT_BEVEL; + } + } + + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) + path->nbevel++; + + p0 = p1++; + } + + path->convex = (nleft == path->count) ? 1 : 0; + } +} + + +static int nvg__expandStroke(NVGcontext* ctx, float w, int lineCap, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + NVGvertex* verts; + NVGvertex* dst; + int cverts, i, j; + float aa = ctx->fringeWidth; + int ncap = nvg__curveDivs(w, NVG_PI, ctx->tessTol); // Calculate divisions per half circle. + + nvg__calculateJoins(ctx, w, lineJoin, miterLimit); + + // Calculate max vertex usage. + cverts = 0; + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + int loop = (path->closed == 0) ? 0 : 1; + if (lineJoin == NVG_ROUND) + cverts += (path->count + path->nbevel*(ncap+2) + 1) * 2; // plus one for loop + else + cverts += (path->count + path->nbevel*5 + 1) * 2; // plus one for loop + if (loop == 0) { + // space for caps + if (lineCap == NVG_ROUND) { + cverts += (ncap*2 + 2)*2; + } else { + cverts += (3+3)*2; + } + } + } + + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return 0; + + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0; + NVGpoint* p1; + int s, e, loop; + float dx, dy; + + path->fill = 0; + path->nfill = 0; + + // Calculate fringe or stroke + loop = (path->closed == 0) ? 0 : 1; + dst = verts; + path->stroke = dst; + + if (loop) { + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + s = 0; + e = path->count; + } else { + // Add cap + p0 = &pts[0]; + p1 = &pts[1]; + s = 1; + e = path->count-1; + } + + if (loop == 0) { + // Add cap + dx = p1->x - p0->x; + dy = p1->y - p0->y; + nvg__normalize(&dx, &dy); + if (lineCap == NVG_BUTT) + dst = nvg__buttCapStart(dst, p0, dx, dy, w, -aa*0.5f, aa); + else if (lineCap == NVG_BUTT || lineCap == NVG_SQUARE) + dst = nvg__buttCapStart(dst, p0, dx, dy, w, w-aa, aa); + else if (lineCap == NVG_ROUND) + dst = nvg__roundCapStart(dst, p0, dx, dy, w, ncap, aa); + } + + for (j = s; j < e; ++j) { + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) { + if (lineJoin == NVG_ROUND) { + dst = nvg__roundJoin(dst, p0, p1, w, w, 0, 1, ncap, aa); + } else { + dst = nvg__bevelJoin(dst, p0, p1, w, w, 0, 1, aa); + } + } else { + nvg__vset(dst, p1->x + (p1->dmx * w), p1->y + (p1->dmy * w), 0,1); dst++; + nvg__vset(dst, p1->x - (p1->dmx * w), p1->y - (p1->dmy * w), 1,1); dst++; + } + p0 = p1++; + } + + if (loop) { + // Loop it + nvg__vset(dst, verts[0].x, verts[0].y, 0,1); dst++; + nvg__vset(dst, verts[1].x, verts[1].y, 1,1); dst++; + } else { + // Add cap + dx = p1->x - p0->x; + dy = p1->y - p0->y; + nvg__normalize(&dx, &dy); + if (lineCap == NVG_BUTT) + dst = nvg__buttCapEnd(dst, p1, dx, dy, w, -aa*0.5f, aa); + else if (lineCap == NVG_BUTT || lineCap == NVG_SQUARE) + dst = nvg__buttCapEnd(dst, p1, dx, dy, w, w-aa, aa); + else if (lineCap == NVG_ROUND) + dst = nvg__roundCapEnd(dst, p1, dx, dy, w, ncap, aa); + } + + path->nstroke = (int)(dst - verts); + + verts = dst; + } + + return 1; +} + +static int nvg__expandFill(NVGcontext* ctx, float w, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + NVGvertex* verts; + NVGvertex* dst; + int cverts, convex, i, j; + float aa = ctx->fringeWidth; + int fringe = w > 0.0f; + + nvg__calculateJoins(ctx, w, lineJoin, miterLimit); + + // Calculate max vertex usage. + cverts = 0; + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + cverts += path->count + path->nbevel + 1; + if (fringe) + cverts += (path->count + path->nbevel*5 + 1) * 2; // plus one for loop + } + + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return 0; + + convex = cache->npaths == 1 && cache->paths[0].convex; + + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0; + NVGpoint* p1; + float rw, lw, woff; + float ru, lu; + + // Calculate shape vertices. + woff = 0.5f*aa; + dst = verts; + path->fill = dst; + + if (fringe) { + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + for (j = 0; j < path->count; ++j) { + if (p1->flags & NVG_PT_BEVEL) { + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + if (p1->flags & NVG_PT_LEFT) { + float lx = p1->x + p1->dmx * woff; + float ly = p1->y + p1->dmy * woff; + nvg__vset(dst, lx, ly, 0.5f,1); dst++; + } else { + float lx0 = p1->x + dlx0 * woff; + float ly0 = p1->y + dly0 * woff; + float lx1 = p1->x + dlx1 * woff; + float ly1 = p1->y + dly1 * woff; + nvg__vset(dst, lx0, ly0, 0.5f,1); dst++; + nvg__vset(dst, lx1, ly1, 0.5f,1); dst++; + } + } else { + nvg__vset(dst, p1->x + (p1->dmx * woff), p1->y + (p1->dmy * woff), 0.5f,1); dst++; + } + p0 = p1++; + } + } else { + for (j = 0; j < path->count; ++j) { + nvg__vset(dst, pts[j].x, pts[j].y, 0.5f,1); + dst++; + } + } + + path->nfill = (int)(dst - verts); + verts = dst; + + // Calculate fringe + if (fringe) { + lw = w + woff; + rw = w - woff; + lu = 0; + ru = 1; + dst = verts; + path->stroke = dst; + + // Create only half a fringe for convex shapes so that + // the shape can be rendered without stenciling. + if (convex) { + lw = woff; // This should generate the same vertex as fill inset above. + lu = 0.5f; // Set outline fade at middle. + } + + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + + for (j = 0; j < path->count; ++j) { + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) { + dst = nvg__bevelJoin(dst, p0, p1, lw, rw, lu, ru, ctx->fringeWidth); + } else { + nvg__vset(dst, p1->x + (p1->dmx * lw), p1->y + (p1->dmy * lw), lu,1); dst++; + nvg__vset(dst, p1->x - (p1->dmx * rw), p1->y - (p1->dmy * rw), ru,1); dst++; + } + p0 = p1++; + } + + // Loop it + nvg__vset(dst, verts[0].x, verts[0].y, lu,1); dst++; + nvg__vset(dst, verts[1].x, verts[1].y, ru,1); dst++; + + path->nstroke = (int)(dst - verts); + verts = dst; + } else { + path->stroke = NULL; + path->nstroke = 0; + } + } + + return 1; +} + + +// Draw +void nvgBeginPath(NVGcontext* ctx) +{ + ctx->ncommands = 0; + nvg__clearPathCache(ctx); +} + +void nvgMoveTo(NVGcontext* ctx, float x, float y) +{ + float vals[] = { NVG_MOVETO, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgLineTo(NVGcontext* ctx, float x, float y) +{ + float vals[] = { NVG_LINETO, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgBezierTo(NVGcontext* ctx, float c1x, float c1y, float c2x, float c2y, float x, float y) +{ + float vals[] = { NVG_BEZIERTO, c1x, c1y, c2x, c2y, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgQuadTo(NVGcontext* ctx, float cx, float cy, float x, float y) +{ + float x0 = ctx->commandx; + float y0 = ctx->commandy; + float vals[] = { NVG_BEZIERTO, + x0 + 2.0f/3.0f*(cx - x0), y0 + 2.0f/3.0f*(cy - y0), + x + 2.0f/3.0f*(cx - x), y + 2.0f/3.0f*(cy - y), + x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgArcTo(NVGcontext* ctx, float x1, float y1, float x2, float y2, float radius) +{ + float x0 = ctx->commandx; + float y0 = ctx->commandy; + float dx0,dy0, dx1,dy1, a, d, cx,cy, a0,a1; + int dir; + + if (ctx->ncommands == 0) { + return; + } + + // Handle degenerate cases. + if (nvg__ptEquals(x0,y0, x1,y1, ctx->distTol) || + nvg__ptEquals(x1,y1, x2,y2, ctx->distTol) || + nvg__distPtSeg(x1,y1, x0,y0, x2,y2) < ctx->distTol*ctx->distTol || + radius < ctx->distTol) { + nvgLineTo(ctx, x1,y1); + return; + } + + // Calculate tangential circle to lines (x0,y0)-(x1,y1) and (x1,y1)-(x2,y2). + dx0 = x0-x1; + dy0 = y0-y1; + dx1 = x2-x1; + dy1 = y2-y1; + nvg__normalize(&dx0,&dy0); + nvg__normalize(&dx1,&dy1); + a = nvg__acosf(dx0*dx1 + dy0*dy1); + d = radius / nvg__tanf(a/2.0f); + +// printf("a=%f° d=%f\n", a/NVG_PI*180.0f, d); + + if (d > 10000.0f) { + nvgLineTo(ctx, x1,y1); + return; + } + + if (nvg__cross(dx0,dy0, dx1,dy1) > 0.0f) { + cx = x1 + dx0*d + dy0*radius; + cy = y1 + dy0*d + -dx0*radius; + a0 = nvg__atan2f(dx0, -dy0); + a1 = nvg__atan2f(-dx1, dy1); + dir = NVG_CW; +// printf("CW c=(%f, %f) a0=%f° a1=%f°\n", cx, cy, a0/NVG_PI*180.0f, a1/NVG_PI*180.0f); + } else { + cx = x1 + dx0*d + -dy0*radius; + cy = y1 + dy0*d + dx0*radius; + a0 = nvg__atan2f(-dx0, dy0); + a1 = nvg__atan2f(dx1, -dy1); + dir = NVG_CCW; +// printf("CCW c=(%f, %f) a0=%f° a1=%f°\n", cx, cy, a0/NVG_PI*180.0f, a1/NVG_PI*180.0f); + } + + nvgArc(ctx, cx, cy, radius, a0, a1, dir); +} + +void nvgClosePath(NVGcontext* ctx) +{ + float vals[] = { NVG_CLOSE }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgPathWinding(NVGcontext* ctx, int dir) +{ + float vals[] = { NVG_WINDING, (float)dir }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgArc(NVGcontext* ctx, float cx, float cy, float r, float a0, float a1, int dir) +{ + float a = 0, da = 0, hda = 0, kappa = 0; + float dx = 0, dy = 0, x = 0, y = 0, tanx = 0, tany = 0; + float px = 0, py = 0, ptanx = 0, ptany = 0; + float vals[3 + 5*7 + 100]; + int i, ndivs, nvals; + int move = ctx->ncommands > 0 ? NVG_LINETO : NVG_MOVETO; + + // Clamp angles + da = a1 - a0; + if (dir == NVG_CW) { + if (nvg__absf(da) >= NVG_PI*2) { + da = NVG_PI*2; + } else { + while (da < 0.0f) da += NVG_PI*2; + } + } else { + if (nvg__absf(da) >= NVG_PI*2) { + da = -NVG_PI*2; + } else { + while (da > 0.0f) da -= NVG_PI*2; + } + } + + // Split arc into max 90 degree segments. + ndivs = nvg__maxi(1, nvg__mini((int)(nvg__absf(da) / (NVG_PI*0.5f) + 0.5f), 5)); + hda = (da / (float)ndivs) / 2.0f; + kappa = nvg__absf(4.0f / 3.0f * (1.0f - nvg__cosf(hda)) / nvg__sinf(hda)); + + if (dir == NVG_CCW) + kappa = -kappa; + + nvals = 0; + for (i = 0; i <= ndivs; i++) { + a = a0 + da * (i/(float)ndivs); + dx = nvg__cosf(a); + dy = nvg__sinf(a); + x = cx + dx*r; + y = cy + dy*r; + tanx = -dy*r*kappa; + tany = dx*r*kappa; + + if (i == 0) { + vals[nvals++] = (float)move; + vals[nvals++] = x; + vals[nvals++] = y; + } else { + vals[nvals++] = NVG_BEZIERTO; + vals[nvals++] = px+ptanx; + vals[nvals++] = py+ptany; + vals[nvals++] = x-tanx; + vals[nvals++] = y-tany; + vals[nvals++] = x; + vals[nvals++] = y; + } + px = x; + py = y; + ptanx = tanx; + ptany = tany; + } + + nvg__appendCommands(ctx, vals, nvals); +} + +void nvgRect(NVGcontext* ctx, float x, float y, float w, float h) +{ + float vals[] = { + NVG_MOVETO, x,y, + NVG_LINETO, x,y+h, + NVG_LINETO, x+w,y+h, + NVG_LINETO, x+w,y, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgRoundedRect(NVGcontext* ctx, float x, float y, float w, float h, float r) +{ + nvgRoundedRectVarying(ctx, x, y, w, h, r, r, r, r); +} + +void nvgRoundedRectVarying(NVGcontext* ctx, float x, float y, float w, float h, float radTopLeft, float radTopRight, float radBottomRight, float radBottomLeft) +{ + if(radTopLeft < 0.1f && radTopRight < 0.1f && radBottomRight < 0.1f && radBottomLeft < 0.1f) { + nvgRect(ctx, x, y, w, h); + return; + } else { + float halfw = nvg__absf(w)*0.5f; + float halfh = nvg__absf(h)*0.5f; + float rxBL = nvg__minf(radBottomLeft, halfw) * nvg__signf(w), ryBL = nvg__minf(radBottomLeft, halfh) * nvg__signf(h); + float rxBR = nvg__minf(radBottomRight, halfw) * nvg__signf(w), ryBR = nvg__minf(radBottomRight, halfh) * nvg__signf(h); + float rxTR = nvg__minf(radTopRight, halfw) * nvg__signf(w), ryTR = nvg__minf(radTopRight, halfh) * nvg__signf(h); + float rxTL = nvg__minf(radTopLeft, halfw) * nvg__signf(w), ryTL = nvg__minf(radTopLeft, halfh) * nvg__signf(h); + float vals[] = { + NVG_MOVETO, x, y + ryTL, + NVG_LINETO, x, y + h - ryBL, + NVG_BEZIERTO, x, y + h - ryBL*(1 - NVG_KAPPA90), x + rxBL*(1 - NVG_KAPPA90), y + h, x + rxBL, y + h, + NVG_LINETO, x + w - rxBR, y + h, + NVG_BEZIERTO, x + w - rxBR*(1 - NVG_KAPPA90), y + h, x + w, y + h - ryBR*(1 - NVG_KAPPA90), x + w, y + h - ryBR, + NVG_LINETO, x + w, y + ryTR, + NVG_BEZIERTO, x + w, y + ryTR*(1 - NVG_KAPPA90), x + w - rxTR*(1 - NVG_KAPPA90), y, x + w - rxTR, y, + NVG_LINETO, x + rxTL, y, + NVG_BEZIERTO, x + rxTL*(1 - NVG_KAPPA90), y, x, y + ryTL*(1 - NVG_KAPPA90), x, y + ryTL, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); + } +} + +void nvgEllipse(NVGcontext* ctx, float cx, float cy, float rx, float ry) +{ + float vals[] = { + NVG_MOVETO, cx-rx, cy, + NVG_BEZIERTO, cx-rx, cy+ry*NVG_KAPPA90, cx-rx*NVG_KAPPA90, cy+ry, cx, cy+ry, + NVG_BEZIERTO, cx+rx*NVG_KAPPA90, cy+ry, cx+rx, cy+ry*NVG_KAPPA90, cx+rx, cy, + NVG_BEZIERTO, cx+rx, cy-ry*NVG_KAPPA90, cx+rx*NVG_KAPPA90, cy-ry, cx, cy-ry, + NVG_BEZIERTO, cx-rx*NVG_KAPPA90, cy-ry, cx-rx, cy-ry*NVG_KAPPA90, cx-rx, cy, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgCircle(NVGcontext* ctx, float cx, float cy, float r) +{ + nvgEllipse(ctx, cx,cy, r,r); +} + +void nvgDebugDumpPathCache(NVGcontext* ctx) +{ + const NVGpath* path; + int i, j; + + printf("Dumping %d cached paths\n", ctx->cache->npaths); + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + printf(" - Path %d\n", i); + if (path->nfill) { + printf(" - fill: %d\n", path->nfill); + for (j = 0; j < path->nfill; j++) + printf("%f\t%f\n", path->fill[j].x, path->fill[j].y); + } + if (path->nstroke) { + printf(" - stroke: %d\n", path->nstroke); + for (j = 0; j < path->nstroke; j++) + printf("%f\t%f\n", path->stroke[j].x, path->stroke[j].y); + } + } +} + +void nvgFill(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + const NVGpath* path; + NVGpaint fillPaint = state->fill; + int i; + + nvg__flattenPaths(ctx); + if (ctx->params.edgeAntiAlias) + nvg__expandFill(ctx, ctx->fringeWidth, NVG_MITER, 2.4f); + else + nvg__expandFill(ctx, 0.0f, NVG_MITER, 2.4f); + + // Apply global alpha + fillPaint.innerColor.a *= state->alpha; + fillPaint.outerColor.a *= state->alpha; + + ctx->params.renderFill(ctx->params.userPtr, &fillPaint, &state->scissor, ctx->fringeWidth, + ctx->cache->bounds, ctx->cache->paths, ctx->cache->npaths); + + // Count triangles + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + ctx->fillTriCount += path->nfill-2; + ctx->fillTriCount += path->nstroke-2; + ctx->drawCallCount += 2; + } +} + +void nvgStroke(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getAverageScale(state->xform); + float strokeWidth = nvg__clampf(state->strokeWidth * scale, 0.0f, 200.0f); + NVGpaint strokePaint = state->stroke; + const NVGpath* path; + int i; + + if (strokeWidth < ctx->fringeWidth) { + // If the stroke width is less than pixel size, use alpha to emulate coverage. + // Since coverage is area, scale by alpha*alpha. + float alpha = nvg__clampf(strokeWidth / ctx->fringeWidth, 0.0f, 1.0f); + strokePaint.innerColor.a *= alpha*alpha; + strokePaint.outerColor.a *= alpha*alpha; + strokeWidth = ctx->fringeWidth; + } + + // Apply global alpha + strokePaint.innerColor.a *= state->alpha; + strokePaint.outerColor.a *= state->alpha; + + nvg__flattenPaths(ctx); + + if (ctx->params.edgeAntiAlias) + nvg__expandStroke(ctx, strokeWidth*0.5f + ctx->fringeWidth*0.5f, state->lineCap, state->lineJoin, state->miterLimit); + else + nvg__expandStroke(ctx, strokeWidth*0.5f, state->lineCap, state->lineJoin, state->miterLimit); + + ctx->params.renderStroke(ctx->params.userPtr, &strokePaint, &state->scissor, ctx->fringeWidth, + strokeWidth, ctx->cache->paths, ctx->cache->npaths); + + // Count triangles + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + ctx->strokeTriCount += path->nstroke-2; + ctx->drawCallCount++; + } +} + +// Add fonts +int nvgCreateFont(NVGcontext* ctx, const char* name, const char* path) +{ + return fonsAddFont(ctx->fs, name, path); +} + +int nvgCreateFontMem(NVGcontext* ctx, const char* name, unsigned char* data, int ndata, int freeData) +{ + return fonsAddFontMem(ctx->fs, name, data, ndata, freeData); +} + +int nvgFindFont(NVGcontext* ctx, const char* name) +{ + if (name == NULL) return -1; + return fonsGetFontByName(ctx->fs, name); +} + + +int nvgAddFallbackFontId(NVGcontext* ctx, int baseFont, int fallbackFont) +{ + if(baseFont == -1 || fallbackFont == -1) return 0; + return fonsAddFallbackFont(ctx->fs, baseFont, fallbackFont); +} + +int nvgAddFallbackFont(NVGcontext* ctx, const char* baseFont, const char* fallbackFont) +{ + return nvgAddFallbackFontId(ctx, nvgFindFont(ctx, baseFont), nvgFindFont(ctx, fallbackFont)); +} + +// State setting +void nvgFontSize(NVGcontext* ctx, float size) +{ + NVGstate* state = nvg__getState(ctx); + state->fontSize = size; +} + +void nvgFontBlur(NVGcontext* ctx, float blur) +{ + NVGstate* state = nvg__getState(ctx); + state->fontBlur = blur; +} + +void nvgTextLetterSpacing(NVGcontext* ctx, float spacing) +{ + NVGstate* state = nvg__getState(ctx); + state->letterSpacing = spacing; +} + +void nvgTextLineHeight(NVGcontext* ctx, float lineHeight) +{ + NVGstate* state = nvg__getState(ctx); + state->lineHeight = lineHeight; +} + +void nvgTextAlign(NVGcontext* ctx, int align) +{ + NVGstate* state = nvg__getState(ctx); + state->textAlign = align; +} + +void nvgFontFaceId(NVGcontext* ctx, int font) +{ + NVGstate* state = nvg__getState(ctx); + state->fontId = font; +} + +void nvgFontFace(NVGcontext* ctx, const char* font) +{ + NVGstate* state = nvg__getState(ctx); + state->fontId = fonsGetFontByName(ctx->fs, font); +} + +static float nvg__quantize(float a, float d) +{ + return ((int)(a / d + 0.5f)) * d; +} + +static float nvg__getFontScale(NVGstate* state) +{ + return nvg__minf(nvg__quantize(nvg__getAverageScale(state->xform), 0.01f), 4.0f); +} + +static void nvg__flushTextTexture(NVGcontext* ctx) +{ + int dirty[4]; + + if (fonsValidateTexture(ctx->fs, dirty)) { + int fontImage = ctx->fontImages[ctx->fontImageIdx]; + // Update texture + if (fontImage != 0) { + int iw, ih; + const unsigned char* data = fonsGetTextureData(ctx->fs, &iw, &ih); + int x = dirty[0]; + int y = dirty[1]; + int w = dirty[2] - dirty[0]; + int h = dirty[3] - dirty[1]; + ctx->params.renderUpdateTexture(ctx->params.userPtr, fontImage, x,y, w,h, data); + } + } +} + +static int nvg__allocTextAtlas(NVGcontext* ctx) +{ + int iw, ih; + nvg__flushTextTexture(ctx); + if (ctx->fontImageIdx >= NVG_MAX_FONTIMAGES-1) + return 0; + // if next fontImage already have a texture + if (ctx->fontImages[ctx->fontImageIdx+1] != 0) + nvgImageSize(ctx, ctx->fontImages[ctx->fontImageIdx+1], &iw, &ih); + else { // calculate the new font image size and create it. + nvgImageSize(ctx, ctx->fontImages[ctx->fontImageIdx], &iw, &ih); + if (iw > ih) + ih *= 2; + else + iw *= 2; + if (iw > NVG_MAX_FONTIMAGE_SIZE || ih > NVG_MAX_FONTIMAGE_SIZE) + iw = ih = NVG_MAX_FONTIMAGE_SIZE; + ctx->fontImages[ctx->fontImageIdx+1] = ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_ALPHA, iw, ih, 0, NULL); + } + ++ctx->fontImageIdx; + fonsResetAtlas(ctx->fs, iw, ih); + return 1; +} + +static void nvg__renderText(NVGcontext* ctx, NVGvertex* verts, int nverts) +{ + NVGstate* state = nvg__getState(ctx); + NVGpaint paint = state->fill; + + // Render triangles. + paint.image = ctx->fontImages[ctx->fontImageIdx]; + + // Apply global alpha + paint.innerColor.a *= state->alpha; + paint.outerColor.a *= state->alpha; + + ctx->params.renderTriangles(ctx->params.userPtr, &paint, &state->scissor, verts, nverts); + + ctx->drawCallCount++; + ctx->textTriCount += nverts/3; +} + +float nvgText(NVGcontext* ctx, float x, float y, const char* string, const char* end) +{ + NVGstate* state = nvg__getState(ctx); + FONStextIter iter, prevIter; + FONSquad q; + NVGvertex* verts; + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + int cverts = 0; + int nverts = 0; + + if (end == NULL) + end = string + strlen(string); + + if (state->fontId == FONS_INVALID) return x; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + cverts = nvg__maxi(2, (int)(end - string)) * 6; // conservative estimate. + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return x; + + fonsTextIterInit(ctx->fs, &iter, x*scale, y*scale, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + float c[4*2]; + if (iter.prevGlyphIndex == -1) { // can not retrieve glyph? + if (!nvg__allocTextAtlas(ctx)) + break; // no memory :( + if (nverts != 0) { + nvg__renderText(ctx, verts, nverts); + nverts = 0; + } + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + if (iter.prevGlyphIndex == -1) // still can not find glyph? + break; + } + prevIter = iter; + // Transform corners. + nvgTransformPoint(&c[0],&c[1], state->xform, q.x0*invscale, q.y0*invscale); + nvgTransformPoint(&c[2],&c[3], state->xform, q.x1*invscale, q.y0*invscale); + nvgTransformPoint(&c[4],&c[5], state->xform, q.x1*invscale, q.y1*invscale); + nvgTransformPoint(&c[6],&c[7], state->xform, q.x0*invscale, q.y1*invscale); + // Create triangles + if (nverts+6 <= cverts) { + nvg__vset(&verts[nverts], c[0], c[1], q.s0, q.t0); nverts++; + nvg__vset(&verts[nverts], c[4], c[5], q.s1, q.t1); nverts++; + nvg__vset(&verts[nverts], c[2], c[3], q.s1, q.t0); nverts++; + nvg__vset(&verts[nverts], c[0], c[1], q.s0, q.t0); nverts++; + nvg__vset(&verts[nverts], c[6], c[7], q.s0, q.t1); nverts++; + nvg__vset(&verts[nverts], c[4], c[5], q.s1, q.t1); nverts++; + } + } + + // TODO: add back-end bit to do this just once per frame. + nvg__flushTextTexture(ctx); + + nvg__renderText(ctx, verts, nverts); + + return iter.x; +} + +void nvgTextBox(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end) +{ + NVGstate* state = nvg__getState(ctx); + NVGtextRow rows[2]; + int nrows = 0, i; + int oldAlign = state->textAlign; + int haling = state->textAlign & (NVG_ALIGN_LEFT | NVG_ALIGN_CENTER | NVG_ALIGN_RIGHT); + int valign = state->textAlign & (NVG_ALIGN_TOP | NVG_ALIGN_MIDDLE | NVG_ALIGN_BOTTOM | NVG_ALIGN_BASELINE); + float lineh = 0; + + if (state->fontId == FONS_INVALID) return; + + nvgTextMetrics(ctx, NULL, NULL, &lineh); + + state->textAlign = NVG_ALIGN_LEFT | valign; + + while ((nrows = nvgTextBreakLines(ctx, string, end, breakRowWidth, rows, 2))) { + for (i = 0; i < nrows; i++) { + NVGtextRow* row = &rows[i]; + if (haling & NVG_ALIGN_LEFT) + nvgText(ctx, x, y, row->start, row->end); + else if (haling & NVG_ALIGN_CENTER) + nvgText(ctx, x + breakRowWidth*0.5f - row->width*0.5f, y, row->start, row->end); + else if (haling & NVG_ALIGN_RIGHT) + nvgText(ctx, x + breakRowWidth - row->width, y, row->start, row->end); + y += lineh * state->lineHeight; + } + string = rows[nrows-1].next; + } + + state->textAlign = oldAlign; +} + +int nvgTextGlyphPositions(NVGcontext* ctx, float x, float y, const char* string, const char* end, NVGglyphPosition* positions, int maxPositions) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + FONStextIter iter, prevIter; + FONSquad q; + int npos = 0; + + if (state->fontId == FONS_INVALID) return 0; + + if (end == NULL) + end = string + strlen(string); + + if (string == end) + return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + fonsTextIterInit(ctx->fs, &iter, x*scale, y*scale, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + if (iter.prevGlyphIndex < 0 && nvg__allocTextAtlas(ctx)) { // can not retrieve glyph? + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + } + prevIter = iter; + positions[npos].str = iter.str; + positions[npos].x = iter.x * invscale; + positions[npos].minx = nvg__minf(iter.x, q.x0) * invscale; + positions[npos].maxx = nvg__maxf(iter.nextx, q.x1) * invscale; + npos++; + if (npos >= maxPositions) + break; + } + + return npos; +} + +enum NVGcodepointType { + NVG_SPACE, + NVG_NEWLINE, + NVG_CHAR, +}; + +int nvgTextBreakLines(NVGcontext* ctx, const char* string, const char* end, float breakRowWidth, NVGtextRow* rows, int maxRows) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + FONStextIter iter, prevIter; + FONSquad q; + int nrows = 0; + float rowStartX = 0; + float rowWidth = 0; + float rowMinX = 0; + float rowMaxX = 0; + const char* rowStart = NULL; + const char* rowEnd = NULL; + const char* wordStart = NULL; + float wordStartX = 0; + float wordMinX = 0; + const char* breakEnd = NULL; + float breakWidth = 0; + float breakMaxX = 0; + int type = NVG_SPACE, ptype = NVG_SPACE; + unsigned int pcodepoint = 0; + + if (maxRows == 0) return 0; + if (state->fontId == FONS_INVALID) return 0; + + if (end == NULL) + end = string + strlen(string); + + if (string == end) return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + breakRowWidth *= scale; + + fonsTextIterInit(ctx->fs, &iter, 0, 0, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + if (iter.prevGlyphIndex < 0 && nvg__allocTextAtlas(ctx)) { // can not retrieve glyph? + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + } + prevIter = iter; + switch (iter.codepoint) { + case 9: // \t + case 11: // \v + case 12: // \f + case 32: // space + case 0x00a0: // NBSP + type = NVG_SPACE; + break; + case 10: // \n + type = pcodepoint == 13 ? NVG_SPACE : NVG_NEWLINE; + break; + case 13: // \r + type = pcodepoint == 10 ? NVG_SPACE : NVG_NEWLINE; + break; + case 0x0085: // NEL + type = NVG_NEWLINE; + break; + default: + type = NVG_CHAR; + break; + } + + if (type == NVG_NEWLINE) { + // Always handle new lines. + rows[nrows].start = rowStart != NULL ? rowStart : iter.str; + rows[nrows].end = rowEnd != NULL ? rowEnd : iter.str; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = iter.next; + nrows++; + if (nrows >= maxRows) + return nrows; + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + // Indicate to skip the white space at the beginning of the row. + rowStart = NULL; + rowEnd = NULL; + rowWidth = 0; + rowMinX = rowMaxX = 0; + } else { + if (rowStart == NULL) { + // Skip white space until the beginning of the line + if (type == NVG_CHAR) { + // The current char is the row so far + rowStartX = iter.x; + rowStart = iter.str; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; // q.x1 - rowStartX; + rowMinX = q.x0 - rowStartX; + rowMaxX = q.x1 - rowStartX; + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + } + } else { + float nextWidth = iter.nextx - rowStartX; + + // track last non-white space character + if (type == NVG_CHAR) { + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMaxX = q.x1 - rowStartX; + } + // track last end of a word + if (ptype == NVG_CHAR && type == NVG_SPACE) { + breakEnd = iter.str; + breakWidth = rowWidth; + breakMaxX = rowMaxX; + } + // track last beginning of a word + if (ptype == NVG_SPACE && type == NVG_CHAR) { + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + } + + // Break to new line when a character is beyond break width. + if (type == NVG_CHAR && nextWidth > breakRowWidth) { + // The run length is too long, need to break to new line. + if (breakEnd == rowStart) { + // The current word is longer than the row length, just break it from here. + rows[nrows].start = rowStart; + rows[nrows].end = iter.str; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = iter.str; + nrows++; + if (nrows >= maxRows) + return nrows; + rowStartX = iter.x; + rowStart = iter.str; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMinX = q.x0 - rowStartX; + rowMaxX = q.x1 - rowStartX; + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + } else { + // Break the line from the end of the last word, and start new line from the beginning of the new. + rows[nrows].start = rowStart; + rows[nrows].end = breakEnd; + rows[nrows].width = breakWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = breakMaxX * invscale; + rows[nrows].next = wordStart; + nrows++; + if (nrows >= maxRows) + return nrows; + rowStartX = wordStartX; + rowStart = wordStart; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMinX = wordMinX; + rowMaxX = q.x1 - rowStartX; + // No change to the word start + } + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + } + } + } + + pcodepoint = iter.codepoint; + ptype = type; + } + + // Break the line from the end of the last word, and start new line from the beginning of the new. + if (rowStart != NULL) { + rows[nrows].start = rowStart; + rows[nrows].end = rowEnd; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = end; + nrows++; + } + + return nrows; +} + +float nvgTextBounds(NVGcontext* ctx, float x, float y, const char* string, const char* end, float* bounds) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + float width; + + if (state->fontId == FONS_INVALID) return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + width = fonsTextBounds(ctx->fs, x*scale, y*scale, string, end, bounds); + if (bounds != NULL) { + // Use line bounds for height. + fonsLineBounds(ctx->fs, y*scale, &bounds[1], &bounds[3]); + bounds[0] *= invscale; + bounds[1] *= invscale; + bounds[2] *= invscale; + bounds[3] *= invscale; + } + return width * invscale; +} + +void nvgTextBoxBounds(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end, float* bounds) +{ + NVGstate* state = nvg__getState(ctx); + NVGtextRow rows[2]; + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + int nrows = 0, i; + int oldAlign = state->textAlign; + int haling = state->textAlign & (NVG_ALIGN_LEFT | NVG_ALIGN_CENTER | NVG_ALIGN_RIGHT); + int valign = state->textAlign & (NVG_ALIGN_TOP | NVG_ALIGN_MIDDLE | NVG_ALIGN_BOTTOM | NVG_ALIGN_BASELINE); + float lineh = 0, rminy = 0, rmaxy = 0; + float minx, miny, maxx, maxy; + + if (state->fontId == FONS_INVALID) { + if (bounds != NULL) + bounds[0] = bounds[1] = bounds[2] = bounds[3] = 0.0f; + return; + } + + nvgTextMetrics(ctx, NULL, NULL, &lineh); + + state->textAlign = NVG_ALIGN_LEFT | valign; + + minx = maxx = x; + miny = maxy = y; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + fonsLineBounds(ctx->fs, 0, &rminy, &rmaxy); + rminy *= invscale; + rmaxy *= invscale; + + while ((nrows = nvgTextBreakLines(ctx, string, end, breakRowWidth, rows, 2))) { + for (i = 0; i < nrows; i++) { + NVGtextRow* row = &rows[i]; + float rminx, rmaxx, dx = 0; + // Horizontal bounds + if (haling & NVG_ALIGN_LEFT) + dx = 0; + else if (haling & NVG_ALIGN_CENTER) + dx = breakRowWidth*0.5f - row->width*0.5f; + else if (haling & NVG_ALIGN_RIGHT) + dx = breakRowWidth - row->width; + rminx = x + row->minx + dx; + rmaxx = x + row->maxx + dx; + minx = nvg__minf(minx, rminx); + maxx = nvg__maxf(maxx, rmaxx); + // Vertical bounds. + miny = nvg__minf(miny, y + rminy); + maxy = nvg__maxf(maxy, y + rmaxy); + + y += lineh * state->lineHeight; + } + string = rows[nrows-1].next; + } + + state->textAlign = oldAlign; + + if (bounds != NULL) { + bounds[0] = minx; + bounds[1] = miny; + bounds[2] = maxx; + bounds[3] = maxy; + } +} + +void nvgTextMetrics(NVGcontext* ctx, float* ascender, float* descender, float* lineh) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + + if (state->fontId == FONS_INVALID) return; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + fonsVertMetrics(ctx->fs, ascender, descender, lineh); + if (ascender != NULL) + *ascender *= invscale; + if (descender != NULL) + *descender *= invscale; + if (lineh != NULL) + *lineh *= invscale; +} +// vim: ft=c nu noet ts=4 diff --git a/phonelibs/nanovg/nanovg.h b/phonelibs/nanovg/nanovg.h new file mode 100644 index 0000000000..bb0d3417a2 --- /dev/null +++ b/phonelibs/nanovg/nanovg.h @@ -0,0 +1,681 @@ +// +// Copyright (c) 2013 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef NANOVG_H +#define NANOVG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define NVG_PI 3.14159265358979323846264338327f + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4201) // nonstandard extension used : nameless struct/union +#endif + +typedef struct NVGcontext NVGcontext; + +struct NVGcolor { + union { + float rgba[4]; + struct { + float r,g,b,a; + }; + }; +}; +typedef struct NVGcolor NVGcolor; + +struct NVGpaint { + float xform[6]; + float extent[2]; + float radius; + float feather; + NVGcolor innerColor; + NVGcolor outerColor; + int image; +}; +typedef struct NVGpaint NVGpaint; + +enum NVGwinding { + NVG_CCW = 1, // Winding for solid shapes + NVG_CW = 2, // Winding for holes +}; + +enum NVGsolidity { + NVG_SOLID = 1, // CCW + NVG_HOLE = 2, // CW +}; + +enum NVGlineCap { + NVG_BUTT, + NVG_ROUND, + NVG_SQUARE, + NVG_BEVEL, + NVG_MITER, +}; + +enum NVGalign { + // Horizontal align + NVG_ALIGN_LEFT = 1<<0, // Default, align text horizontally to left. + NVG_ALIGN_CENTER = 1<<1, // Align text horizontally to center. + NVG_ALIGN_RIGHT = 1<<2, // Align text horizontally to right. + // Vertical align + NVG_ALIGN_TOP = 1<<3, // Align text vertically to top. + NVG_ALIGN_MIDDLE = 1<<4, // Align text vertically to middle. + NVG_ALIGN_BOTTOM = 1<<5, // Align text vertically to bottom. + NVG_ALIGN_BASELINE = 1<<6, // Default, align text vertically to baseline. +}; + +enum NVGblendFactor { + NVG_ZERO = 1<<0, + NVG_ONE = 1<<1, + NVG_SRC_COLOR = 1<<2, + NVG_ONE_MINUS_SRC_COLOR = 1<<3, + NVG_DST_COLOR = 1<<4, + NVG_ONE_MINUS_DST_COLOR = 1<<5, + NVG_SRC_ALPHA = 1<<6, + NVG_ONE_MINUS_SRC_ALPHA = 1<<7, + NVG_DST_ALPHA = 1<<8, + NVG_ONE_MINUS_DST_ALPHA = 1<<9, + NVG_SRC_ALPHA_SATURATE = 1<<10, +}; + +enum NVGcompositeOperation { + NVG_SOURCE_OVER, + NVG_SOURCE_IN, + NVG_SOURCE_OUT, + NVG_ATOP, + NVG_DESTINATION_OVER, + NVG_DESTINATION_IN, + NVG_DESTINATION_OUT, + NVG_DESTINATION_ATOP, + NVG_LIGHTER, + NVG_COPY, + NVG_XOR, +}; + +struct NVGcompositeOperationState { + int srcRGB; + int dstRGB; + int srcAlpha; + int dstAlpha; +}; +typedef struct NVGcompositeOperationState NVGcompositeOperationState; + +struct NVGglyphPosition { + const char* str; // Position of the glyph in the input string. + float x; // The x-coordinate of the logical glyph position. + float minx, maxx; // The bounds of the glyph shape. +}; +typedef struct NVGglyphPosition NVGglyphPosition; + +struct NVGtextRow { + const char* start; // Pointer to the input text where the row starts. + const char* end; // Pointer to the input text where the row ends (one past the last character). + const char* next; // Pointer to the beginning of the next row. + float width; // Logical width of the row. + float minx, maxx; // Actual bounds of the row. Logical with and bounds can differ because of kerning and some parts over extending. +}; +typedef struct NVGtextRow NVGtextRow; + +enum NVGimageFlags { + NVG_IMAGE_GENERATE_MIPMAPS = 1<<0, // Generate mipmaps during creation of the image. + NVG_IMAGE_REPEATX = 1<<1, // Repeat image in X direction. + NVG_IMAGE_REPEATY = 1<<2, // Repeat image in Y direction. + NVG_IMAGE_FLIPY = 1<<3, // Flips (inverses) image in Y direction when rendered. + NVG_IMAGE_PREMULTIPLIED = 1<<4, // Image data has premultiplied alpha. +}; + +// Begin drawing a new frame +// Calls to nanovg drawing API should be wrapped in nvgBeginFrame() & nvgEndFrame() +// nvgBeginFrame() defines the size of the window to render to in relation currently +// set viewport (i.e. glViewport on GL backends). Device pixel ration allows to +// control the rendering on Hi-DPI devices. +// For example, GLFW returns two dimension for an opened window: window size and +// frame buffer size. In that case you would set windowWidth/Height to the window size +// devicePixelRatio to: frameBufferWidth / windowWidth. +void nvgBeginFrame(NVGcontext* ctx, int windowWidth, int windowHeight, float devicePixelRatio); + +// Cancels drawing the current frame. +void nvgCancelFrame(NVGcontext* ctx); + +// Ends drawing flushing remaining render state. +void nvgEndFrame(NVGcontext* ctx); + +// +// Composite operation +// +// The composite operations in NanoVG are modeled after HTML Canvas API, and +// the blend func is based on OpenGL (see corresponding manuals for more info). +// The colors in the blending state have premultiplied alpha. + +// Sets the composite operation. The op parameter should be one of NVGcompositeOperation. +void nvgGlobalCompositeOperation(NVGcontext* ctx, int op); + +// Sets the composite operation with custom pixel arithmetic. The parameters should be one of NVGblendFactor. +void nvgGlobalCompositeBlendFunc(NVGcontext* ctx, int sfactor, int dfactor); + +// Sets the composite operation with custom pixel arithmetic for RGB and alpha components separately. The parameters should be one of NVGblendFactor. +void nvgGlobalCompositeBlendFuncSeparate(NVGcontext* ctx, int srcRGB, int dstRGB, int srcAlpha, int dstAlpha); + +// +// Color utils +// +// Colors in NanoVG are stored as unsigned ints in ABGR format. + +// Returns a color value from red, green, blue values. Alpha will be set to 255 (1.0f). +NVGcolor nvgRGB(unsigned char r, unsigned char g, unsigned char b); + +// Returns a color value from red, green, blue values. Alpha will be set to 1.0f. +NVGcolor nvgRGBf(float r, float g, float b); + + +// Returns a color value from red, green, blue and alpha values. +NVGcolor nvgRGBA(unsigned char r, unsigned char g, unsigned char b, unsigned char a); + +// Returns a color value from red, green, blue and alpha values. +NVGcolor nvgRGBAf(float r, float g, float b, float a); + + +// Linearly interpolates from color c0 to c1, and returns resulting color value. +NVGcolor nvgLerpRGBA(NVGcolor c0, NVGcolor c1, float u); + +// Sets transparency of a color value. +NVGcolor nvgTransRGBA(NVGcolor c0, unsigned char a); + +// Sets transparency of a color value. +NVGcolor nvgTransRGBAf(NVGcolor c0, float a); + +// Returns color value specified by hue, saturation and lightness. +// HSL values are all in range [0..1], alpha will be set to 255. +NVGcolor nvgHSL(float h, float s, float l); + +// Returns color value specified by hue, saturation and lightness and alpha. +// HSL values are all in range [0..1], alpha in range [0..255] +NVGcolor nvgHSLA(float h, float s, float l, unsigned char a); + +// +// State Handling +// +// NanoVG contains state which represents how paths will be rendered. +// The state contains transform, fill and stroke styles, text and font styles, +// and scissor clipping. + +// Pushes and saves the current render state into a state stack. +// A matching nvgRestore() must be used to restore the state. +void nvgSave(NVGcontext* ctx); + +// Pops and restores current render state. +void nvgRestore(NVGcontext* ctx); + +// Resets current render state to default values. Does not affect the render state stack. +void nvgReset(NVGcontext* ctx); + +// +// Render styles +// +// Fill and stroke render style can be either a solid color or a paint which is a gradient or a pattern. +// Solid color is simply defined as a color value, different kinds of paints can be created +// using nvgLinearGradient(), nvgBoxGradient(), nvgRadialGradient() and nvgImagePattern(). +// +// Current render style can be saved and restored using nvgSave() and nvgRestore(). + +// Sets current stroke style to a solid color. +void nvgStrokeColor(NVGcontext* ctx, NVGcolor color); + +// Sets current stroke style to a paint, which can be a one of the gradients or a pattern. +void nvgStrokePaint(NVGcontext* ctx, NVGpaint paint); + +// Sets current fill style to a solid color. +void nvgFillColor(NVGcontext* ctx, NVGcolor color); + +// Sets current fill style to a paint, which can be a one of the gradients or a pattern. +void nvgFillPaint(NVGcontext* ctx, NVGpaint paint); + +// Sets the miter limit of the stroke style. +// Miter limit controls when a sharp corner is beveled. +void nvgMiterLimit(NVGcontext* ctx, float limit); + +// Sets the stroke width of the stroke style. +void nvgStrokeWidth(NVGcontext* ctx, float size); + +// Sets how the end of the line (cap) is drawn, +// Can be one of: NVG_BUTT (default), NVG_ROUND, NVG_SQUARE. +void nvgLineCap(NVGcontext* ctx, int cap); + +// Sets how sharp path corners are drawn. +// Can be one of NVG_MITER (default), NVG_ROUND, NVG_BEVEL. +void nvgLineJoin(NVGcontext* ctx, int join); + +// Sets the transparency applied to all rendered shapes. +// Already transparent paths will get proportionally more transparent as well. +void nvgGlobalAlpha(NVGcontext* ctx, float alpha); + +// +// Transforms +// +// The paths, gradients, patterns and scissor region are transformed by an transformation +// matrix at the time when they are passed to the API. +// The current transformation matrix is a affine matrix: +// [sx kx tx] +// [ky sy ty] +// [ 0 0 1] +// Where: sx,sy define scaling, kx,ky skewing, and tx,ty translation. +// The last row is assumed to be 0,0,1 and is not stored. +// +// Apart from nvgResetTransform(), each transformation function first creates +// specific transformation matrix and pre-multiplies the current transformation by it. +// +// Current coordinate system (transformation) can be saved and restored using nvgSave() and nvgRestore(). + +// Resets current transform to a identity matrix. +void nvgResetTransform(NVGcontext* ctx); + +// Premultiplies current coordinate system by specified matrix. +// The parameters are interpreted as matrix as follows: +// [a c e] +// [b d f] +// [0 0 1] +void nvgTransform(NVGcontext* ctx, float a, float b, float c, float d, float e, float f); + +// Translates current coordinate system. +void nvgTranslate(NVGcontext* ctx, float x, float y); + +// Rotates current coordinate system. Angle is specified in radians. +void nvgRotate(NVGcontext* ctx, float angle); + +// Skews the current coordinate system along X axis. Angle is specified in radians. +void nvgSkewX(NVGcontext* ctx, float angle); + +// Skews the current coordinate system along Y axis. Angle is specified in radians. +void nvgSkewY(NVGcontext* ctx, float angle); + +// Scales the current coordinate system. +void nvgScale(NVGcontext* ctx, float x, float y); + +// Stores the top part (a-f) of the current transformation matrix in to the specified buffer. +// [a c e] +// [b d f] +// [0 0 1] +// There should be space for 6 floats in the return buffer for the values a-f. +void nvgCurrentTransform(NVGcontext* ctx, float* xform); + + +// The following functions can be used to make calculations on 2x3 transformation matrices. +// A 2x3 matrix is represented as float[6]. + +// Sets the transform to identity matrix. +void nvgTransformIdentity(float* dst); + +// Sets the transform to translation matrix matrix. +void nvgTransformTranslate(float* dst, float tx, float ty); + +// Sets the transform to scale matrix. +void nvgTransformScale(float* dst, float sx, float sy); + +// Sets the transform to rotate matrix. Angle is specified in radians. +void nvgTransformRotate(float* dst, float a); + +// Sets the transform to skew-x matrix. Angle is specified in radians. +void nvgTransformSkewX(float* dst, float a); + +// Sets the transform to skew-y matrix. Angle is specified in radians. +void nvgTransformSkewY(float* dst, float a); + +// Sets the transform to the result of multiplication of two transforms, of A = A*B. +void nvgTransformMultiply(float* dst, const float* src); + +// Sets the transform to the result of multiplication of two transforms, of A = B*A. +void nvgTransformPremultiply(float* dst, const float* src); + +// Sets the destination to inverse of specified transform. +// Returns 1 if the inverse could be calculated, else 0. +int nvgTransformInverse(float* dst, const float* src); + +// Transform a point by given transform. +void nvgTransformPoint(float* dstx, float* dsty, const float* xform, float srcx, float srcy); + +// Converts degrees to radians and vice versa. +float nvgDegToRad(float deg); +float nvgRadToDeg(float rad); + +// +// Images +// +// NanoVG allows you to load jpg, png, psd, tga, pic and gif files to be used for rendering. +// In addition you can upload your own image. The image loading is provided by stb_image. +// The parameter imageFlags is combination of flags defined in NVGimageFlags. + +// Creates image by loading it from the disk from specified file name. +// Returns handle to the image. +int nvgCreateImage(NVGcontext* ctx, const char* filename, int imageFlags); + +// Creates image by loading it from the specified chunk of memory. +// Returns handle to the image. +int nvgCreateImageMem(NVGcontext* ctx, int imageFlags, unsigned char* data, int ndata); + +// Creates image from specified image data. +// Returns handle to the image. +int nvgCreateImageRGBA(NVGcontext* ctx, int w, int h, int imageFlags, const unsigned char* data); + +// Updates image data specified by image handle. +void nvgUpdateImage(NVGcontext* ctx, int image, const unsigned char* data); + +// Returns the dimensions of a created image. +void nvgImageSize(NVGcontext* ctx, int image, int* w, int* h); + +// Deletes created image. +void nvgDeleteImage(NVGcontext* ctx, int image); + +// +// Paints +// +// NanoVG supports four types of paints: linear gradient, box gradient, radial gradient and image pattern. +// These can be used as paints for strokes and fills. + +// Creates and returns a linear gradient. Parameters (sx,sy)-(ex,ey) specify the start and end coordinates +// of the linear gradient, icol specifies the start color and ocol the end color. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgLinearGradient(NVGcontext* ctx, float sx, float sy, float ex, float ey, + NVGcolor icol, NVGcolor ocol); + +// Creates and returns a box gradient. Box gradient is a feathered rounded rectangle, it is useful for rendering +// drop shadows or highlights for boxes. Parameters (x,y) define the top-left corner of the rectangle, +// (w,h) define the size of the rectangle, r defines the corner radius, and f feather. Feather defines how blurry +// the border of the rectangle is. Parameter icol specifies the inner color and ocol the outer color of the gradient. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgBoxGradient(NVGcontext* ctx, float x, float y, float w, float h, + float r, float f, NVGcolor icol, NVGcolor ocol); + +// Creates and returns a radial gradient. Parameters (cx,cy) specify the center, inr and outr specify +// the inner and outer radius of the gradient, icol specifies the start color and ocol the end color. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgRadialGradient(NVGcontext* ctx, float cx, float cy, float inr, float outr, + NVGcolor icol, NVGcolor ocol); + +// Creates and returns an image patter. Parameters (ox,oy) specify the left-top location of the image pattern, +// (ex,ey) the size of one image, angle rotation around the top-left corner, image is handle to the image to render. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgImagePattern(NVGcontext* ctx, float ox, float oy, float ex, float ey, + float angle, int image, float alpha); + +// +// Scissoring +// +// Scissoring allows you to clip the rendering into a rectangle. This is useful for various +// user interface cases like rendering a text edit or a timeline. + +// Sets the current scissor rectangle. +// The scissor rectangle is transformed by the current transform. +void nvgScissor(NVGcontext* ctx, float x, float y, float w, float h); + +// Intersects current scissor rectangle with the specified rectangle. +// The scissor rectangle is transformed by the current transform. +// Note: in case the rotation of previous scissor rect differs from +// the current one, the intersection will be done between the specified +// rectangle and the previous scissor rectangle transformed in the current +// transform space. The resulting shape is always rectangle. +void nvgIntersectScissor(NVGcontext* ctx, float x, float y, float w, float h); + +// Reset and disables scissoring. +void nvgResetScissor(NVGcontext* ctx); + +// +// Paths +// +// Drawing a new shape starts with nvgBeginPath(), it clears all the currently defined paths. +// Then you define one or more paths and sub-paths which describe the shape. The are functions +// to draw common shapes like rectangles and circles, and lower level step-by-step functions, +// which allow to define a path curve by curve. +// +// NanoVG uses even-odd fill rule to draw the shapes. Solid shapes should have counter clockwise +// winding and holes should have counter clockwise order. To specify winding of a path you can +// call nvgPathWinding(). This is useful especially for the common shapes, which are drawn CCW. +// +// Finally you can fill the path using current fill style by calling nvgFill(), and stroke it +// with current stroke style by calling nvgStroke(). +// +// The curve segments and sub-paths are transformed by the current transform. + +// Clears the current path and sub-paths. +void nvgBeginPath(NVGcontext* ctx); + +// Starts new sub-path with specified point as first point. +void nvgMoveTo(NVGcontext* ctx, float x, float y); + +// Adds line segment from the last point in the path to the specified point. +void nvgLineTo(NVGcontext* ctx, float x, float y); + +// Adds cubic bezier segment from last point in the path via two control points to the specified point. +void nvgBezierTo(NVGcontext* ctx, float c1x, float c1y, float c2x, float c2y, float x, float y); + +// Adds quadratic bezier segment from last point in the path via a control point to the specified point. +void nvgQuadTo(NVGcontext* ctx, float cx, float cy, float x, float y); + +// Adds an arc segment at the corner defined by the last path point, and two specified points. +void nvgArcTo(NVGcontext* ctx, float x1, float y1, float x2, float y2, float radius); + +// Closes current sub-path with a line segment. +void nvgClosePath(NVGcontext* ctx); + +// Sets the current sub-path winding, see NVGwinding and NVGsolidity. +void nvgPathWinding(NVGcontext* ctx, int dir); + +// Creates new circle arc shaped sub-path. The arc center is at cx,cy, the arc radius is r, +// and the arc is drawn from angle a0 to a1, and swept in direction dir (NVG_CCW, or NVG_CW). +// Angles are specified in radians. +void nvgArc(NVGcontext* ctx, float cx, float cy, float r, float a0, float a1, int dir); + +// Creates new rectangle shaped sub-path. +void nvgRect(NVGcontext* ctx, float x, float y, float w, float h); + +// Creates new rounded rectangle shaped sub-path. +void nvgRoundedRect(NVGcontext* ctx, float x, float y, float w, float h, float r); + +// Creates new rounded rectangle shaped sub-path with varying radii for each corner. +void nvgRoundedRectVarying(NVGcontext* ctx, float x, float y, float w, float h, float radTopLeft, float radTopRight, float radBottomRight, float radBottomLeft); + +// Creates new ellipse shaped sub-path. +void nvgEllipse(NVGcontext* ctx, float cx, float cy, float rx, float ry); + +// Creates new circle shaped sub-path. +void nvgCircle(NVGcontext* ctx, float cx, float cy, float r); + +// Fills the current path with current fill style. +void nvgFill(NVGcontext* ctx); + +// Fills the current path with current stroke style. +void nvgStroke(NVGcontext* ctx); + + +// +// Text +// +// NanoVG allows you to load .ttf files and use the font to render text. +// +// The appearance of the text can be defined by setting the current text style +// and by specifying the fill color. Common text and font settings such as +// font size, letter spacing and text align are supported. Font blur allows you +// to create simple text effects such as drop shadows. +// +// At render time the font face can be set based on the font handles or name. +// +// Font measure functions return values in local space, the calculations are +// carried in the same resolution as the final rendering. This is done because +// the text glyph positions are snapped to the nearest pixels sharp rendering. +// +// The local space means that values are not rotated or scale as per the current +// transformation. For example if you set font size to 12, which would mean that +// line height is 16, then regardless of the current scaling and rotation, the +// returned line height is always 16. Some measures may vary because of the scaling +// since aforementioned pixel snapping. +// +// While this may sound a little odd, the setup allows you to always render the +// same way regardless of scaling. I.e. following works regardless of scaling: +// +// const char* txt = "Text me up."; +// nvgTextBounds(vg, x,y, txt, NULL, bounds); +// nvgBeginPath(vg); +// nvgRoundedRect(vg, bounds[0],bounds[1], bounds[2]-bounds[0], bounds[3]-bounds[1]); +// nvgFill(vg); +// +// Note: currently only solid color fill is supported for text. + +// Creates font by loading it from the disk from specified file name. +// Returns handle to the font. +int nvgCreateFont(NVGcontext* ctx, const char* name, const char* filename); + +// Creates font by loading it from the specified memory chunk. +// Returns handle to the font. +int nvgCreateFontMem(NVGcontext* ctx, const char* name, unsigned char* data, int ndata, int freeData); + +// Finds a loaded font of specified name, and returns handle to it, or -1 if the font is not found. +int nvgFindFont(NVGcontext* ctx, const char* name); + +// Adds a fallback font by handle. +int nvgAddFallbackFontId(NVGcontext* ctx, int baseFont, int fallbackFont); + +// Adds a fallback font by name. +int nvgAddFallbackFont(NVGcontext* ctx, const char* baseFont, const char* fallbackFont); + +// Sets the font size of current text style. +void nvgFontSize(NVGcontext* ctx, float size); + +// Sets the blur of current text style. +void nvgFontBlur(NVGcontext* ctx, float blur); + +// Sets the letter spacing of current text style. +void nvgTextLetterSpacing(NVGcontext* ctx, float spacing); + +// Sets the proportional line height of current text style. The line height is specified as multiple of font size. +void nvgTextLineHeight(NVGcontext* ctx, float lineHeight); + +// Sets the text align of current text style, see NVGalign for options. +void nvgTextAlign(NVGcontext* ctx, int align); + +// Sets the font face based on specified id of current text style. +void nvgFontFaceId(NVGcontext* ctx, int font); + +// Sets the font face based on specified name of current text style. +void nvgFontFace(NVGcontext* ctx, const char* font); + +// Draws text string at specified location. If end is specified only the sub-string up to the end is drawn. +float nvgText(NVGcontext* ctx, float x, float y, const char* string, const char* end); + +// Draws multi-line text string at specified location wrapped at the specified width. If end is specified only the sub-string up to the end is drawn. +// White space is stripped at the beginning of the rows, the text is split at word boundaries or when new-line characters are encountered. +// Words longer than the max width are slit at nearest character (i.e. no hyphenation). +void nvgTextBox(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end); + +// Measures the specified text string. Parameter bounds should be a pointer to float[4], +// if the bounding box of the text should be returned. The bounds value are [xmin,ymin, xmax,ymax] +// Returns the horizontal advance of the measured text (i.e. where the next character should drawn). +// Measured values are returned in local coordinate space. +float nvgTextBounds(NVGcontext* ctx, float x, float y, const char* string, const char* end, float* bounds); + +// Measures the specified multi-text string. Parameter bounds should be a pointer to float[4], +// if the bounding box of the text should be returned. The bounds value are [xmin,ymin, xmax,ymax] +// Measured values are returned in local coordinate space. +void nvgTextBoxBounds(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end, float* bounds); + +// Calculates the glyph x positions of the specified text. If end is specified only the sub-string will be used. +// Measured values are returned in local coordinate space. +int nvgTextGlyphPositions(NVGcontext* ctx, float x, float y, const char* string, const char* end, NVGglyphPosition* positions, int maxPositions); + +// Returns the vertical metrics based on the current text style. +// Measured values are returned in local coordinate space. +void nvgTextMetrics(NVGcontext* ctx, float* ascender, float* descender, float* lineh); + +// Breaks the specified text into lines. If end is specified only the sub-string will be used. +// White space is stripped at the beginning of the rows, the text is split at word boundaries or when new-line characters are encountered. +// Words longer than the max width are slit at nearest character (i.e. no hyphenation). +int nvgTextBreakLines(NVGcontext* ctx, const char* string, const char* end, float breakRowWidth, NVGtextRow* rows, int maxRows); + +// +// Internal Render API +// +enum NVGtexture { + NVG_TEXTURE_ALPHA = 0x01, + NVG_TEXTURE_RGBA = 0x02, +}; + +struct NVGscissor { + float xform[6]; + float extent[2]; +}; +typedef struct NVGscissor NVGscissor; + +struct NVGvertex { + float x,y,u,v; +}; +typedef struct NVGvertex NVGvertex; + +struct NVGpath { + int first; + int count; + unsigned char closed; + int nbevel; + NVGvertex* fill; + int nfill; + NVGvertex* stroke; + int nstroke; + int winding; + int convex; +}; +typedef struct NVGpath NVGpath; + +struct NVGparams { + void* userPtr; + int edgeAntiAlias; + int (*renderCreate)(void* uptr); + int (*renderCreateTexture)(void* uptr, int type, int w, int h, int imageFlags, const unsigned char* data); + int (*renderDeleteTexture)(void* uptr, int image); + int (*renderUpdateTexture)(void* uptr, int image, int x, int y, int w, int h, const unsigned char* data); + int (*renderGetTextureSize)(void* uptr, int image, int* w, int* h); + void (*renderViewport)(void* uptr, int width, int height, float devicePixelRatio); + void (*renderCancel)(void* uptr); + void (*renderFlush)(void* uptr, NVGcompositeOperationState compositeOperation); + void (*renderFill)(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, const float* bounds, const NVGpath* paths, int npaths); + void (*renderStroke)(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, float strokeWidth, const NVGpath* paths, int npaths); + void (*renderTriangles)(void* uptr, NVGpaint* paint, NVGscissor* scissor, const NVGvertex* verts, int nverts); + void (*renderDelete)(void* uptr); +}; +typedef struct NVGparams NVGparams; + +// Constructor and destructor, called by the render back-end. +NVGcontext* nvgCreateInternal(NVGparams* params); +void nvgDeleteInternal(NVGcontext* ctx); + +NVGparams* nvgInternalParams(NVGcontext* ctx); + +// Debug function to dump cached path data. +void nvgDebugDumpPathCache(NVGcontext* ctx); + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#define NVG_NOTUSED(v) for (;;) { (void)(1 ? (void)0 : ( (void)(v) ) ); break; } + +#ifdef __cplusplus +} +#endif + +#endif // NANOVG_H diff --git a/phonelibs/nanovg/nanovg_gl.h b/phonelibs/nanovg/nanovg_gl.h new file mode 100644 index 0000000000..c050067321 --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl.h @@ -0,0 +1,1592 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// +#ifndef NANOVG_GL_H +#define NANOVG_GL_H + +#ifdef __cplusplus +extern "C" { +#endif + +// Create flags + +enum NVGcreateFlags { + // Flag indicating if geometry based anti-aliasing is used (may not be needed when using MSAA). + NVG_ANTIALIAS = 1<<0, + // Flag indicating if strokes should be drawn using stencil buffer. The rendering will be a little + // slower, but path overlaps (i.e. self-intersecting or sharp turns) will be drawn just once. + NVG_STENCIL_STROKES = 1<<1, + // Flag indicating that additional debug checks are done. + NVG_DEBUG = 1<<2, +}; + +#if defined NANOVG_GL2_IMPLEMENTATION +# define NANOVG_GL2 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#elif defined NANOVG_GL3_IMPLEMENTATION +# define NANOVG_GL3 1 +# define NANOVG_GL_IMPLEMENTATION 1 +# define NANOVG_GL_USE_UNIFORMBUFFER 1 +#elif defined NANOVG_GLES2_IMPLEMENTATION +# define NANOVG_GLES2 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#elif defined NANOVG_GLES3_IMPLEMENTATION +# define NANOVG_GLES3 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#endif + +#define NANOVG_GL_USE_STATE_FILTER (1) + +// Creates NanoVG contexts for different OpenGL (ES) versions. +// Flags should be combination of the create flags above. + +#if defined NANOVG_GL2 + +NVGcontext* nvgCreateGL2(int flags); +void nvgDeleteGL2(NVGcontext* ctx); + +int nvglCreateImageFromHandleGL2(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGL2(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GL3 + +NVGcontext* nvgCreateGL3(int flags); +void nvgDeleteGL3(NVGcontext* ctx); + +int nvglCreateImageFromHandleGL3(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGL3(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GLES2 + +NVGcontext* nvgCreateGLES2(int flags); +void nvgDeleteGLES2(NVGcontext* ctx); + +int nvglCreateImageFromHandleGLES2(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGLES2(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GLES3 + +NVGcontext* nvgCreateGLES3(int flags); +void nvgDeleteGLES3(NVGcontext* ctx); + +int nvglCreateImageFromHandleGLES3(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGLES3(NVGcontext* ctx, int image); + +#endif + +// These are additional flags on top of NVGimageFlags. +enum NVGimageFlagsGL { + NVG_IMAGE_NODELETE = 1<<16, // Do not delete GL texture handle. +}; + +#ifdef __cplusplus +} +#endif + +#endif /* NANOVG_GL_H */ + +#ifdef NANOVG_GL_IMPLEMENTATION + +#include +#include +#include +#include +#include "nanovg.h" + +enum GLNVGuniformLoc { + GLNVG_LOC_VIEWSIZE, + GLNVG_LOC_TEX, + GLNVG_LOC_FRAG, + GLNVG_MAX_LOCS +}; + +enum GLNVGshaderType { + NSVG_SHADER_FILLGRAD, + NSVG_SHADER_FILLIMG, + NSVG_SHADER_SIMPLE, + NSVG_SHADER_IMG +}; + +#if NANOVG_GL_USE_UNIFORMBUFFER +enum GLNVGuniformBindings { + GLNVG_FRAG_BINDING = 0, +}; +#endif + +struct GLNVGshader { + GLuint prog; + GLuint frag; + GLuint vert; + GLint loc[GLNVG_MAX_LOCS]; +}; +typedef struct GLNVGshader GLNVGshader; + +struct GLNVGtexture { + int id; + GLuint tex; + int width, height; + int type; + int flags; +}; +typedef struct GLNVGtexture GLNVGtexture; + +enum GLNVGcallType { + GLNVG_NONE = 0, + GLNVG_FILL, + GLNVG_CONVEXFILL, + GLNVG_STROKE, + GLNVG_TRIANGLES, +}; + +struct GLNVGcall { + int type; + int image; + int pathOffset; + int pathCount; + int triangleOffset; + int triangleCount; + int uniformOffset; +}; +typedef struct GLNVGcall GLNVGcall; + +struct GLNVGpath { + int fillOffset; + int fillCount; + int strokeOffset; + int strokeCount; +}; +typedef struct GLNVGpath GLNVGpath; + +struct GLNVGfragUniforms { + #if NANOVG_GL_USE_UNIFORMBUFFER + float scissorMat[12]; // matrices are actually 3 vec4s + float paintMat[12]; + struct NVGcolor innerCol; + struct NVGcolor outerCol; + float scissorExt[2]; + float scissorScale[2]; + float extent[2]; + float radius; + float feather; + float strokeMult; + float strokeThr; + int texType; + int type; + #else + // note: after modifying layout or size of uniform array, + // don't forget to also update the fragment shader source! + #define NANOVG_GL_UNIFORMARRAY_SIZE 11 + union { + struct { + float scissorMat[12]; // matrices are actually 3 vec4s + float paintMat[12]; + struct NVGcolor innerCol; + struct NVGcolor outerCol; + float scissorExt[2]; + float scissorScale[2]; + float extent[2]; + float radius; + float feather; + float strokeMult; + float strokeThr; + float texType; + float type; + }; + float uniformArray[NANOVG_GL_UNIFORMARRAY_SIZE][4]; + }; + #endif +}; +typedef struct GLNVGfragUniforms GLNVGfragUniforms; + +struct GLNVGcontext { + GLNVGshader shader; + GLNVGtexture* textures; + float view[2]; + int ntextures; + int ctextures; + int textureId; + GLuint vertBuf; +#if defined NANOVG_GL3 + GLuint vertArr; +#endif +#if NANOVG_GL_USE_UNIFORMBUFFER + GLuint fragBuf; +#endif + int fragSize; + int flags; + + // Per frame buffers + GLNVGcall* calls; + int ccalls; + int ncalls; + GLNVGpath* paths; + int cpaths; + int npaths; + struct NVGvertex* verts; + int cverts; + int nverts; + unsigned char* uniforms; + int cuniforms; + int nuniforms; + + // cached state + #if NANOVG_GL_USE_STATE_FILTER + GLuint boundTexture; + GLuint stencilMask; + GLenum stencilFunc; + GLint stencilFuncRef; + GLuint stencilFuncMask; + #endif +}; +typedef struct GLNVGcontext GLNVGcontext; + +static int glnvg__maxi(int a, int b) { return a > b ? a : b; } + +#ifdef NANOVG_GLES2 +static unsigned int glnvg__nearestPow2(unsigned int num) +{ + unsigned n = num > 0 ? num - 1 : 0; + n |= n >> 1; + n |= n >> 2; + n |= n >> 4; + n |= n >> 8; + n |= n >> 16; + n++; + return n; +} +#endif + +static void glnvg__bindTexture(GLNVGcontext* gl, GLuint tex) +{ +#if NANOVG_GL_USE_STATE_FILTER + if (gl->boundTexture != tex) { + gl->boundTexture = tex; + glBindTexture(GL_TEXTURE_2D, tex); + } +#else + glBindTexture(GL_TEXTURE_2D, tex); +#endif +} + +static void glnvg__stencilMask(GLNVGcontext* gl, GLuint mask) +{ +#if NANOVG_GL_USE_STATE_FILTER + if (gl->stencilMask != mask) { + gl->stencilMask = mask; + glStencilMask(mask); + } +#else + glStencilMask(mask); +#endif +} + +static void glnvg__stencilFunc(GLNVGcontext* gl, GLenum func, GLint ref, GLuint mask) +{ +#if NANOVG_GL_USE_STATE_FILTER + if ((gl->stencilFunc != func) || + (gl->stencilFuncRef != ref) || + (gl->stencilFuncMask != mask)) { + + gl->stencilFunc = func; + gl->stencilFuncRef = ref; + gl->stencilFuncMask = mask; + glStencilFunc(func, ref, mask); + } +#else + glStencilFunc(func, ref, mask); +#endif +} + +static GLNVGtexture* glnvg__allocTexture(GLNVGcontext* gl) +{ + GLNVGtexture* tex = NULL; + int i; + + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].id == 0) { + tex = &gl->textures[i]; + break; + } + } + if (tex == NULL) { + if (gl->ntextures+1 > gl->ctextures) { + GLNVGtexture* textures; + int ctextures = glnvg__maxi(gl->ntextures+1, 4) + gl->ctextures/2; // 1.5x Overallocate + textures = (GLNVGtexture*)realloc(gl->textures, sizeof(GLNVGtexture)*ctextures); + if (textures == NULL) return NULL; + gl->textures = textures; + gl->ctextures = ctextures; + } + tex = &gl->textures[gl->ntextures++]; + } + + memset(tex, 0, sizeof(*tex)); + tex->id = ++gl->textureId; + + return tex; +} + +static GLNVGtexture* glnvg__findTexture(GLNVGcontext* gl, int id) +{ + int i; + for (i = 0; i < gl->ntextures; i++) + if (gl->textures[i].id == id) + return &gl->textures[i]; + return NULL; +} + +static int glnvg__deleteTexture(GLNVGcontext* gl, int id) +{ + int i; + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].id == id) { + if (gl->textures[i].tex != 0 && (gl->textures[i].flags & NVG_IMAGE_NODELETE) == 0) + glDeleteTextures(1, &gl->textures[i].tex); + memset(&gl->textures[i], 0, sizeof(gl->textures[i])); + return 1; + } + } + return 0; +} + +static void glnvg__dumpShaderError(GLuint shader, const char* name, const char* type) +{ + GLchar str[512+1]; + GLsizei len = 0; + glGetShaderInfoLog(shader, 512, &len, str); + if (len > 512) len = 512; + str[len] = '\0'; + printf("Shader %s/%s error:\n%s\n", name, type, str); +} + +static void glnvg__dumpProgramError(GLuint prog, const char* name) +{ + GLchar str[512+1]; + GLsizei len = 0; + glGetProgramInfoLog(prog, 512, &len, str); + if (len > 512) len = 512; + str[len] = '\0'; + printf("Program %s error:\n%s\n", name, str); +} + +static void glnvg__checkError(GLNVGcontext* gl, const char* str) +{ + GLenum err; + if ((gl->flags & NVG_DEBUG) == 0) return; + err = glGetError(); + if (err != GL_NO_ERROR) { + printf("Error %08x after %s\n", err, str); + return; + } +} + +static int glnvg__createShader(GLNVGshader* shader, const char* name, const char* header, const char* opts, const char* vshader, const char* fshader) +{ + GLint status; + GLuint prog, vert, frag; + const char* str[3]; + str[0] = header; + str[1] = opts != NULL ? opts : ""; + + memset(shader, 0, sizeof(*shader)); + + prog = glCreateProgram(); + vert = glCreateShader(GL_VERTEX_SHADER); + frag = glCreateShader(GL_FRAGMENT_SHADER); + str[2] = vshader; + glShaderSource(vert, 3, str, 0); + str[2] = fshader; + glShaderSource(frag, 3, str, 0); + + glCompileShader(vert); + glGetShaderiv(vert, GL_COMPILE_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpShaderError(vert, name, "vert"); + return 0; + } + + glCompileShader(frag); + glGetShaderiv(frag, GL_COMPILE_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpShaderError(frag, name, "frag"); + return 0; + } + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + + glBindAttribLocation(prog, 0, "vertex"); + glBindAttribLocation(prog, 1, "tcoord"); + + glLinkProgram(prog); + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpProgramError(prog, name); + return 0; + } + + shader->prog = prog; + shader->vert = vert; + shader->frag = frag; + + return 1; +} + +static void glnvg__deleteShader(GLNVGshader* shader) +{ + if (shader->prog != 0) + glDeleteProgram(shader->prog); + if (shader->vert != 0) + glDeleteShader(shader->vert); + if (shader->frag != 0) + glDeleteShader(shader->frag); +} + +static void glnvg__getUniforms(GLNVGshader* shader) +{ + shader->loc[GLNVG_LOC_VIEWSIZE] = glGetUniformLocation(shader->prog, "viewSize"); + shader->loc[GLNVG_LOC_TEX] = glGetUniformLocation(shader->prog, "tex"); + +#if NANOVG_GL_USE_UNIFORMBUFFER + shader->loc[GLNVG_LOC_FRAG] = glGetUniformBlockIndex(shader->prog, "frag"); +#else + shader->loc[GLNVG_LOC_FRAG] = glGetUniformLocation(shader->prog, "frag"); +#endif +} + +static int glnvg__renderCreate(void* uptr) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int align = 4; + + // TODO: mediump float may not be enough for GLES2 in iOS. + // see the following discussion: https://github.com/memononen/nanovg/issues/46 + static const char* shaderHeader = +#if defined NANOVG_GL2 + "#define NANOVG_GL2 1\n" +#elif defined NANOVG_GL3 + "#version 150 core\n" + "#define NANOVG_GL3 1\n" +#elif defined NANOVG_GLES2 + "#version 100\n" + "#define NANOVG_GL2 1\n" +#elif defined NANOVG_GLES3 + "#version 300 es\n" + "#define NANOVG_GL3 1\n" +#endif + +#if NANOVG_GL_USE_UNIFORMBUFFER + "#define USE_UNIFORMBUFFER 1\n" +#else + "#define UNIFORMARRAY_SIZE 11\n" +#endif + "\n"; + + static const char* fillVertShader = + "#ifdef NANOVG_GL3\n" + " uniform vec2 viewSize;\n" + " in vec2 vertex;\n" + " in vec2 tcoord;\n" + " out vec2 ftcoord;\n" + " out vec2 fpos;\n" + "#else\n" + " uniform vec2 viewSize;\n" + " attribute vec2 vertex;\n" + " attribute vec2 tcoord;\n" + " varying vec2 ftcoord;\n" + " varying vec2 fpos;\n" + "#endif\n" + "void main(void) {\n" + " ftcoord = tcoord;\n" + " fpos = vertex;\n" + " gl_Position = vec4(2.0*vertex.x/viewSize.x - 1.0, 1.0 - 2.0*vertex.y/viewSize.y, 0, 1);\n" + "}\n"; + + static const char* fillFragShader = + "#ifdef GL_ES\n" + "#if defined(GL_FRAGMENT_PRECISION_HIGH) || defined(NANOVG_GL3)\n" + " precision highp float;\n" + "#else\n" + " precision mediump float;\n" + "#endif\n" + "#endif\n" + "#ifdef NANOVG_GL3\n" + "#ifdef USE_UNIFORMBUFFER\n" + " layout(std140) uniform frag {\n" + " mat3 scissorMat;\n" + " mat3 paintMat;\n" + " vec4 innerCol;\n" + " vec4 outerCol;\n" + " vec2 scissorExt;\n" + " vec2 scissorScale;\n" + " vec2 extent;\n" + " float radius;\n" + " float feather;\n" + " float strokeMult;\n" + " float strokeThr;\n" + " int texType;\n" + " int type;\n" + " };\n" + "#else\n" // NANOVG_GL3 && !USE_UNIFORMBUFFER + " uniform vec4 frag[UNIFORMARRAY_SIZE];\n" + "#endif\n" + " uniform sampler2D tex;\n" + " in vec2 ftcoord;\n" + " in vec2 fpos;\n" + " out vec4 outColor;\n" + "#else\n" // !NANOVG_GL3 + " uniform vec4 frag[UNIFORMARRAY_SIZE];\n" + " uniform sampler2D tex;\n" + " varying vec2 ftcoord;\n" + " varying vec2 fpos;\n" + "#endif\n" + "#ifndef USE_UNIFORMBUFFER\n" + " #define scissorMat mat3(frag[0].xyz, frag[1].xyz, frag[2].xyz)\n" + " #define paintMat mat3(frag[3].xyz, frag[4].xyz, frag[5].xyz)\n" + " #define innerCol frag[6]\n" + " #define outerCol frag[7]\n" + " #define scissorExt frag[8].xy\n" + " #define scissorScale frag[8].zw\n" + " #define extent frag[9].xy\n" + " #define radius frag[9].z\n" + " #define feather frag[9].w\n" + " #define strokeMult frag[10].x\n" + " #define strokeThr frag[10].y\n" + " #define texType int(frag[10].z)\n" + " #define type int(frag[10].w)\n" + "#endif\n" + "\n" + "float sdroundrect(vec2 pt, vec2 ext, float rad) {\n" + " vec2 ext2 = ext - vec2(rad,rad);\n" + " vec2 d = abs(pt) - ext2;\n" + " return min(max(d.x,d.y),0.0) + length(max(d,0.0)) - rad;\n" + "}\n" + "\n" + "// Scissoring\n" + "float scissorMask(vec2 p) {\n" + " vec2 sc = (abs((scissorMat * vec3(p,1.0)).xy) - scissorExt);\n" + " sc = vec2(0.5,0.5) - sc * scissorScale;\n" + " return clamp(sc.x,0.0,1.0) * clamp(sc.y,0.0,1.0);\n" + "}\n" + "#ifdef EDGE_AA\n" + "// Stroke - from [0..1] to clipped pyramid, where the slope is 1px.\n" + "float strokeMask() {\n" + " return min(1.0, (1.0-abs(ftcoord.x*2.0-1.0))*strokeMult) * min(1.0, ftcoord.y);\n" + "}\n" + "#endif\n" + "\n" + "void main(void) {\n" + " vec4 result;\n" + " float scissor = scissorMask(fpos);\n" + "#ifdef EDGE_AA\n" + " float strokeAlpha = strokeMask();\n" + "#else\n" + " float strokeAlpha = 1.0;\n" + "#endif\n" + " if (type == 0) { // Gradient\n" + " // Calculate gradient color using box gradient\n" + " vec2 pt = (paintMat * vec3(fpos,1.0)).xy;\n" + " float d = clamp((sdroundrect(pt, extent, radius) + feather*0.5) / feather, 0.0, 1.0);\n" + " vec4 color = mix(innerCol,outerCol,d);\n" + " // Combine alpha\n" + " color *= strokeAlpha * scissor;\n" + " result = color;\n" + " } else if (type == 1) { // Image\n" + " // Calculate color fron texture\n" + " vec2 pt = (paintMat * vec3(fpos,1.0)).xy / extent;\n" + "#ifdef NANOVG_GL3\n" + " vec4 color = texture(tex, pt);\n" + "#else\n" + " vec4 color = texture2D(tex, pt);\n" + "#endif\n" + " if (texType == 1) color = vec4(color.xyz*color.w,color.w);" + " if (texType == 2) color = vec4(color.x);" + " // Apply color tint and alpha.\n" + " color *= innerCol;\n" + " // Combine alpha\n" + " color *= strokeAlpha * scissor;\n" + " result = color;\n" + " } else if (type == 2) { // Stencil fill\n" + " result = vec4(1,1,1,1);\n" + " } else if (type == 3) { // Textured tris\n" + "#ifdef NANOVG_GL3\n" + " vec4 color = texture(tex, ftcoord);\n" + "#else\n" + " vec4 color = texture2D(tex, ftcoord);\n" + "#endif\n" + " if (texType == 1) color = vec4(color.xyz*color.w,color.w);" + " if (texType == 2) color = vec4(color.x);" + " color *= scissor;\n" + " result = color * innerCol;\n" + " }\n" + "#ifdef EDGE_AA\n" + " if (strokeAlpha < strokeThr) discard;\n" + "#endif\n" + "#ifdef NANOVG_GL3\n" + " outColor = result;\n" + "#else\n" + " gl_FragColor = result;\n" + "#endif\n" + "}\n"; + + glnvg__checkError(gl, "init"); + + if (gl->flags & NVG_ANTIALIAS) { + if (glnvg__createShader(&gl->shader, "shader", shaderHeader, "#define EDGE_AA 1\n", fillVertShader, fillFragShader) == 0) + return 0; + } else { + if (glnvg__createShader(&gl->shader, "shader", shaderHeader, NULL, fillVertShader, fillFragShader) == 0) + return 0; + } + + glnvg__checkError(gl, "uniform locations"); + glnvg__getUniforms(&gl->shader); + + // Create dynamic vertex array +#if defined NANOVG_GL3 + glGenVertexArrays(1, &gl->vertArr); +#endif + glGenBuffers(1, &gl->vertBuf); + +#if NANOVG_GL_USE_UNIFORMBUFFER + // Create UBOs + glUniformBlockBinding(gl->shader.prog, gl->shader.loc[GLNVG_LOC_FRAG], GLNVG_FRAG_BINDING); + glGenBuffers(1, &gl->fragBuf); + glGetIntegerv(GL_UNIFORM_BUFFER_OFFSET_ALIGNMENT, &align); +#endif + gl->fragSize = sizeof(GLNVGfragUniforms) + align - sizeof(GLNVGfragUniforms) % align; + + glnvg__checkError(gl, "create done"); + + glFinish(); + + return 1; +} + +static int glnvg__renderCreateTexture(void* uptr, int type, int w, int h, int imageFlags, const unsigned char* data) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__allocTexture(gl); + + if (tex == NULL) return 0; + +#ifdef NANOVG_GLES2 + // Check for non-power of 2. + if (glnvg__nearestPow2(w) != (unsigned int)w || glnvg__nearestPow2(h) != (unsigned int)h) { + // No repeat + if ((imageFlags & NVG_IMAGE_REPEATX) != 0 || (imageFlags & NVG_IMAGE_REPEATY) != 0) { + printf("Repeat X/Y is not supported for non power-of-two textures (%d x %d)\n", w, h); + imageFlags &= ~(NVG_IMAGE_REPEATX | NVG_IMAGE_REPEATY); + } + // No mips. + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + printf("Mip-maps is not support for non power-of-two textures (%d x %d)\n", w, h); + imageFlags &= ~NVG_IMAGE_GENERATE_MIPMAPS; + } + } +#endif + + glGenTextures(1, &tex->tex); + tex->width = w; + tex->height = h; + tex->type = type; + tex->flags = imageFlags; + glnvg__bindTexture(gl, tex->tex); + + glPixelStorei(GL_UNPACK_ALIGNMENT,1); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, tex->width); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + +#if defined (NANOVG_GL2) + // GL 1.4 and later has support for generating mipmaps using a tex parameter. + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glTexParameteri(GL_TEXTURE_2D, GL_GENERATE_MIPMAP, GL_TRUE); + } +#endif + + if (type == NVG_TEXTURE_RGBA) + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, w, h, 0, GL_RGBA, GL_UNSIGNED_BYTE, data); + else +#if defined(NANOVG_GLES2) + glTexImage2D(GL_TEXTURE_2D, 0, GL_LUMINANCE, w, h, 0, GL_LUMINANCE, GL_UNSIGNED_BYTE, data); +#elif defined(NANOVG_GLES3) + glTexImage2D(GL_TEXTURE_2D, 0, GL_R8, w, h, 0, GL_RED, GL_UNSIGNED_BYTE, data); +#else + glTexImage2D(GL_TEXTURE_2D, 0, GL_RED, w, h, 0, GL_RED, GL_UNSIGNED_BYTE, data); +#endif + + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR); + } else { + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + } + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + + if (imageFlags & NVG_IMAGE_REPEATX) + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT); + else + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + + if (imageFlags & NVG_IMAGE_REPEATY) + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT); + else + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + + // The new way to build mipmaps on GLES and GL3 +#if !defined(NANOVG_GL2) + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glGenerateMipmap(GL_TEXTURE_2D); + } +#endif + + glnvg__checkError(gl, "create tex"); + glnvg__bindTexture(gl, 0); + + return tex->id; +} + + +static int glnvg__renderDeleteTexture(void* uptr, int image) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + return glnvg__deleteTexture(gl, image); +} + +static int glnvg__renderUpdateTexture(void* uptr, int image, int x, int y, int w, int h, const unsigned char* data) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + + if (tex == NULL) return 0; + glnvg__bindTexture(gl, tex->tex); + + glPixelStorei(GL_UNPACK_ALIGNMENT,1); + +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, tex->width); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, x); + glPixelStorei(GL_UNPACK_SKIP_ROWS, y); +#else + // No support for all of skip, need to update a whole row at a time. + if (tex->type == NVG_TEXTURE_RGBA) + data += y*tex->width*4; + else + data += y*tex->width; + x = 0; + w = tex->width; +#endif + + if (tex->type == NVG_TEXTURE_RGBA) + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_RGBA, GL_UNSIGNED_BYTE, data); + else +#ifdef NANOVG_GLES2 + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_LUMINANCE, GL_UNSIGNED_BYTE, data); +#else + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_RED, GL_UNSIGNED_BYTE, data); +#endif + + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + + glnvg__bindTexture(gl, 0); + + return 1; +} + +static int glnvg__renderGetTextureSize(void* uptr, int image, int* w, int* h) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + if (tex == NULL) return 0; + *w = tex->width; + *h = tex->height; + return 1; +} + +static void glnvg__xformToMat3x4(float* m3, float* t) +{ + m3[0] = t[0]; + m3[1] = t[1]; + m3[2] = 0.0f; + m3[3] = 0.0f; + m3[4] = t[2]; + m3[5] = t[3]; + m3[6] = 0.0f; + m3[7] = 0.0f; + m3[8] = t[4]; + m3[9] = t[5]; + m3[10] = 1.0f; + m3[11] = 0.0f; +} + +static NVGcolor glnvg__premulColor(NVGcolor c) +{ + c.r *= c.a; + c.g *= c.a; + c.b *= c.a; + return c; +} + +static int glnvg__convertPaint(GLNVGcontext* gl, GLNVGfragUniforms* frag, NVGpaint* paint, + NVGscissor* scissor, float width, float fringe, float strokeThr) +{ + GLNVGtexture* tex = NULL; + float invxform[6]; + + memset(frag, 0, sizeof(*frag)); + + frag->innerCol = glnvg__premulColor(paint->innerColor); + frag->outerCol = glnvg__premulColor(paint->outerColor); + + if (scissor->extent[0] < -0.5f || scissor->extent[1] < -0.5f) { + memset(frag->scissorMat, 0, sizeof(frag->scissorMat)); + frag->scissorExt[0] = 1.0f; + frag->scissorExt[1] = 1.0f; + frag->scissorScale[0] = 1.0f; + frag->scissorScale[1] = 1.0f; + } else { + nvgTransformInverse(invxform, scissor->xform); + glnvg__xformToMat3x4(frag->scissorMat, invxform); + frag->scissorExt[0] = scissor->extent[0]; + frag->scissorExt[1] = scissor->extent[1]; + frag->scissorScale[0] = sqrtf(scissor->xform[0]*scissor->xform[0] + scissor->xform[2]*scissor->xform[2]) / fringe; + frag->scissorScale[1] = sqrtf(scissor->xform[1]*scissor->xform[1] + scissor->xform[3]*scissor->xform[3]) / fringe; + } + + memcpy(frag->extent, paint->extent, sizeof(frag->extent)); + frag->strokeMult = (width*0.5f + fringe*0.5f) / fringe; + frag->strokeThr = strokeThr; + + if (paint->image != 0) { + tex = glnvg__findTexture(gl, paint->image); + if (tex == NULL) return 0; + if ((tex->flags & NVG_IMAGE_FLIPY) != 0) { + float m1[6], m2[6]; + nvgTransformTranslate(m1, 0.0f, frag->extent[1] * 0.5f); + nvgTransformMultiply(m1, paint->xform); + nvgTransformScale(m2, 1.0f, -1.0f); + nvgTransformMultiply(m2, m1); + nvgTransformTranslate(m1, 0.0f, -frag->extent[1] * 0.5f); + nvgTransformMultiply(m1, m2); + nvgTransformInverse(invxform, m1); + } else { + nvgTransformInverse(invxform, paint->xform); + } + frag->type = NSVG_SHADER_FILLIMG; + + if (tex->type == NVG_TEXTURE_RGBA) + frag->texType = (tex->flags & NVG_IMAGE_PREMULTIPLIED) ? 0 : 1; + else + frag->texType = 2; +// printf("frag->texType = %d\n", frag->texType); + } else { + frag->type = NSVG_SHADER_FILLGRAD; + frag->radius = paint->radius; + frag->feather = paint->feather; + nvgTransformInverse(invxform, paint->xform); + } + + glnvg__xformToMat3x4(frag->paintMat, invxform); + + return 1; +} + +static GLNVGfragUniforms* nvg__fragUniformPtr(GLNVGcontext* gl, int i); + +static void glnvg__setUniforms(GLNVGcontext* gl, int uniformOffset, int image) +{ +#if NANOVG_GL_USE_UNIFORMBUFFER + glBindBufferRange(GL_UNIFORM_BUFFER, GLNVG_FRAG_BINDING, gl->fragBuf, uniformOffset, sizeof(GLNVGfragUniforms)); +#else + GLNVGfragUniforms* frag = nvg__fragUniformPtr(gl, uniformOffset); + glUniform4fv(gl->shader.loc[GLNVG_LOC_FRAG], NANOVG_GL_UNIFORMARRAY_SIZE, &(frag->uniformArray[0][0])); +#endif + + if (image != 0) { + GLNVGtexture* tex = glnvg__findTexture(gl, image); + glnvg__bindTexture(gl, tex != NULL ? tex->tex : 0); + glnvg__checkError(gl, "tex paint tex"); + } else { + glnvg__bindTexture(gl, 0); + } +} + +static void glnvg__renderViewport(void* uptr, int width, int height, float devicePixelRatio) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + gl->view[0] = (float)width; + gl->view[1] = (float)height; +} + +static void glnvg__fill(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int i, npaths = call->pathCount; + + // Draw shapes + glEnable(GL_STENCIL_TEST); + glnvg__stencilMask(gl, 0xff); + glnvg__stencilFunc(gl, GL_ALWAYS, 0, 0xff); + glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE); + + // set bindpoint for solid loc + glnvg__setUniforms(gl, call->uniformOffset, 0); + glnvg__checkError(gl, "fill simple"); + + glStencilOpSeparate(GL_FRONT, GL_KEEP, GL_KEEP, GL_INCR_WRAP); + glStencilOpSeparate(GL_BACK, GL_KEEP, GL_KEEP, GL_DECR_WRAP); + glDisable(GL_CULL_FACE); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_FAN, paths[i].fillOffset, paths[i].fillCount); + glEnable(GL_CULL_FACE); + + // Draw anti-aliased pixels + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + + glnvg__setUniforms(gl, call->uniformOffset + gl->fragSize, call->image); + glnvg__checkError(gl, "fill fill"); + + if (gl->flags & NVG_ANTIALIAS) { + glnvg__stencilFunc(gl, GL_EQUAL, 0x00, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + // Draw fringes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } + + // Draw fill + glnvg__stencilFunc(gl, GL_NOTEQUAL, 0x0, 0xff); + glStencilOp(GL_ZERO, GL_ZERO, GL_ZERO); + glDrawArrays(GL_TRIANGLES, call->triangleOffset, call->triangleCount); + + glDisable(GL_STENCIL_TEST); +} + +static void glnvg__convexFill(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int i, npaths = call->pathCount; + + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "convex fill"); + + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_FAN, paths[i].fillOffset, paths[i].fillCount); + if (gl->flags & NVG_ANTIALIAS) { + // Draw fringes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } +} + +static void glnvg__stroke(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int npaths = call->pathCount, i; + + if (gl->flags & NVG_STENCIL_STROKES) { + + glEnable(GL_STENCIL_TEST); + glnvg__stencilMask(gl, 0xff); + + // Fill the stroke base without overlap + glnvg__stencilFunc(gl, GL_EQUAL, 0x0, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_INCR); + glnvg__setUniforms(gl, call->uniformOffset + gl->fragSize, call->image); + glnvg__checkError(gl, "stroke fill 0"); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + + // Draw anti-aliased pixels. + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__stencilFunc(gl, GL_EQUAL, 0x00, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + + // Clear stencil buffer. + glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE); + glnvg__stencilFunc(gl, GL_ALWAYS, 0x0, 0xff); + glStencilOp(GL_ZERO, GL_ZERO, GL_ZERO); + glnvg__checkError(gl, "stroke fill 1"); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + + glDisable(GL_STENCIL_TEST); + +// glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, strokeWidth, fringe, 1.0f - 0.5f/255.0f); + + } else { + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "stroke fill"); + // Draw Strokes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } +} + +static void glnvg__triangles(GLNVGcontext* gl, GLNVGcall* call) +{ + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "triangles fill"); + + glDrawArrays(GL_TRIANGLES, call->triangleOffset, call->triangleCount); +} + +static void glnvg__renderCancel(void* uptr) { + GLNVGcontext* gl = (GLNVGcontext*)uptr; + gl->nverts = 0; + gl->npaths = 0; + gl->ncalls = 0; + gl->nuniforms = 0; +} + +static GLenum glnvg_convertBlendFuncFactor(int factor) +{ + if (factor == NVG_ZERO) + return GL_ZERO; + if (factor == NVG_ONE) + return GL_ONE; + if (factor == NVG_SRC_COLOR) + return GL_SRC_COLOR; + if (factor == NVG_ONE_MINUS_SRC_COLOR) + return GL_ONE_MINUS_SRC_COLOR; + if (factor == NVG_DST_COLOR) + return GL_DST_COLOR; + if (factor == NVG_ONE_MINUS_DST_COLOR) + return GL_ONE_MINUS_DST_COLOR; + if (factor == NVG_SRC_ALPHA) + return GL_SRC_ALPHA; + if (factor == NVG_ONE_MINUS_SRC_ALPHA) + return GL_ONE_MINUS_SRC_ALPHA; + if (factor == NVG_DST_ALPHA) + return GL_DST_ALPHA; + if (factor == NVG_ONE_MINUS_DST_ALPHA) + return GL_ONE_MINUS_DST_ALPHA; + if (factor == NVG_SRC_ALPHA_SATURATE) + return GL_SRC_ALPHA_SATURATE; + return GL_INVALID_ENUM; +} + +static void glnvg__blendCompositeOperation(NVGcompositeOperationState op) +{ + GLenum srcRGB = glnvg_convertBlendFuncFactor(op.srcRGB); + GLenum dstRGB = glnvg_convertBlendFuncFactor(op.dstRGB); + GLenum srcAlpha = glnvg_convertBlendFuncFactor(op.srcAlpha); + GLenum dstAlpha = glnvg_convertBlendFuncFactor(op.dstAlpha); + if (srcRGB == GL_INVALID_ENUM || dstRGB == GL_INVALID_ENUM || srcAlpha == GL_INVALID_ENUM || dstAlpha == GL_INVALID_ENUM) + glBlendFunc(GL_ONE, GL_ONE_MINUS_SRC_ALPHA); + else + glBlendFuncSeparate(srcRGB, dstRGB, srcAlpha, dstAlpha); +} + +static void glnvg__renderFlush(void* uptr, NVGcompositeOperationState compositeOperation) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int i; + + if (gl->ncalls > 0) { + + // Setup require GL state. + glUseProgram(gl->shader.prog); + + glnvg__blendCompositeOperation(compositeOperation); + glEnable(GL_CULL_FACE); + glCullFace(GL_BACK); + glFrontFace(GL_CCW); + glEnable(GL_BLEND); + glDisable(GL_DEPTH_TEST); + glDisable(GL_SCISSOR_TEST); + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + glStencilMask(0xffffffff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + glStencilFunc(GL_ALWAYS, 0, 0xffffffff); + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, 0); + #if NANOVG_GL_USE_STATE_FILTER + gl->boundTexture = 0; + gl->stencilMask = 0xffffffff; + gl->stencilFunc = GL_ALWAYS; + gl->stencilFuncRef = 0; + gl->stencilFuncMask = 0xffffffff; + #endif + +#if NANOVG_GL_USE_UNIFORMBUFFER + // Upload ubo for frag shaders + glBindBuffer(GL_UNIFORM_BUFFER, gl->fragBuf); + glBufferData(GL_UNIFORM_BUFFER, gl->nuniforms * gl->fragSize, gl->uniforms, GL_STREAM_DRAW); +#endif + + // Upload vertex data +#if defined NANOVG_GL3 + glBindVertexArray(gl->vertArr); +#endif + glBindBuffer(GL_ARRAY_BUFFER, gl->vertBuf); + glBufferData(GL_ARRAY_BUFFER, gl->nverts * sizeof(NVGvertex), gl->verts, GL_STREAM_DRAW); + glEnableVertexAttribArray(0); + glEnableVertexAttribArray(1); + glVertexAttribPointer(0, 2, GL_FLOAT, GL_FALSE, sizeof(NVGvertex), (const GLvoid*)(size_t)0); + glVertexAttribPointer(1, 2, GL_FLOAT, GL_FALSE, sizeof(NVGvertex), (const GLvoid*)(0 + 2*sizeof(float))); + + // Set view and texture just once per frame. + glUniform1i(gl->shader.loc[GLNVG_LOC_TEX], 0); + glUniform2fv(gl->shader.loc[GLNVG_LOC_VIEWSIZE], 1, gl->view); + +#if NANOVG_GL_USE_UNIFORMBUFFER + glBindBuffer(GL_UNIFORM_BUFFER, gl->fragBuf); +#endif + + for (i = 0; i < gl->ncalls; i++) { + GLNVGcall* call = &gl->calls[i]; + if (call->type == GLNVG_FILL) + glnvg__fill(gl, call); + else if (call->type == GLNVG_CONVEXFILL) + glnvg__convexFill(gl, call); + else if (call->type == GLNVG_STROKE) + glnvg__stroke(gl, call); + else if (call->type == GLNVG_TRIANGLES) + glnvg__triangles(gl, call); + } + + glDisableVertexAttribArray(0); + glDisableVertexAttribArray(1); +#if defined NANOVG_GL3 + glBindVertexArray(0); +#endif + glDisable(GL_CULL_FACE); + glBindBuffer(GL_ARRAY_BUFFER, 0); + glUseProgram(0); + glnvg__bindTexture(gl, 0); + } + + // Reset calls + gl->nverts = 0; + gl->npaths = 0; + gl->ncalls = 0; + gl->nuniforms = 0; +} + +static int glnvg__maxVertCount(const NVGpath* paths, int npaths) +{ + int i, count = 0; + for (i = 0; i < npaths; i++) { + count += paths[i].nfill; + count += paths[i].nstroke; + } + return count; +} + +static GLNVGcall* glnvg__allocCall(GLNVGcontext* gl) +{ + GLNVGcall* ret = NULL; + if (gl->ncalls+1 > gl->ccalls) { + GLNVGcall* calls; + int ccalls = glnvg__maxi(gl->ncalls+1, 128) + gl->ccalls/2; // 1.5x Overallocate + calls = (GLNVGcall*)realloc(gl->calls, sizeof(GLNVGcall) * ccalls); + if (calls == NULL) return NULL; + gl->calls = calls; + gl->ccalls = ccalls; + } + ret = &gl->calls[gl->ncalls++]; + memset(ret, 0, sizeof(GLNVGcall)); + return ret; +} + +static int glnvg__allocPaths(GLNVGcontext* gl, int n) +{ + int ret = 0; + if (gl->npaths+n > gl->cpaths) { + GLNVGpath* paths; + int cpaths = glnvg__maxi(gl->npaths + n, 128) + gl->cpaths/2; // 1.5x Overallocate + paths = (GLNVGpath*)realloc(gl->paths, sizeof(GLNVGpath) * cpaths); + if (paths == NULL) return -1; + gl->paths = paths; + gl->cpaths = cpaths; + } + ret = gl->npaths; + gl->npaths += n; + return ret; +} + +static int glnvg__allocVerts(GLNVGcontext* gl, int n) +{ + int ret = 0; + if (gl->nverts+n > gl->cverts) { + NVGvertex* verts; + int cverts = glnvg__maxi(gl->nverts + n, 4096) + gl->cverts/2; // 1.5x Overallocate + verts = (NVGvertex*)realloc(gl->verts, sizeof(NVGvertex) * cverts); + if (verts == NULL) return -1; + gl->verts = verts; + gl->cverts = cverts; + } + ret = gl->nverts; + gl->nverts += n; + return ret; +} + +static int glnvg__allocFragUniforms(GLNVGcontext* gl, int n) +{ + int ret = 0, structSize = gl->fragSize; + if (gl->nuniforms+n > gl->cuniforms) { + unsigned char* uniforms; + int cuniforms = glnvg__maxi(gl->nuniforms+n, 128) + gl->cuniforms/2; // 1.5x Overallocate + uniforms = (unsigned char*)realloc(gl->uniforms, structSize * cuniforms); + if (uniforms == NULL) return -1; + gl->uniforms = uniforms; + gl->cuniforms = cuniforms; + } + ret = gl->nuniforms * structSize; + gl->nuniforms += n; + return ret; +} + +static GLNVGfragUniforms* nvg__fragUniformPtr(GLNVGcontext* gl, int i) +{ + return (GLNVGfragUniforms*)&gl->uniforms[i]; +} + +static void glnvg__vset(NVGvertex* vtx, float x, float y, float u, float v) +{ + vtx->x = x; + vtx->y = y; + vtx->u = u; + vtx->v = v; +} + +static void glnvg__renderFill(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, + const float* bounds, const NVGpath* paths, int npaths) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + NVGvertex* quad; + GLNVGfragUniforms* frag; + int i, maxverts, offset; + + if (call == NULL) return; + + call->type = GLNVG_FILL; + call->pathOffset = glnvg__allocPaths(gl, npaths); + if (call->pathOffset == -1) goto error; + call->pathCount = npaths; + call->image = paint->image; + + if (npaths == 1 && paths[0].convex) + call->type = GLNVG_CONVEXFILL; + + // Allocate vertices for all the paths. + maxverts = glnvg__maxVertCount(paths, npaths) + 6; + offset = glnvg__allocVerts(gl, maxverts); + if (offset == -1) goto error; + + for (i = 0; i < npaths; i++) { + GLNVGpath* copy = &gl->paths[call->pathOffset + i]; + const NVGpath* path = &paths[i]; + memset(copy, 0, sizeof(GLNVGpath)); + if (path->nfill > 0) { + copy->fillOffset = offset; + copy->fillCount = path->nfill; + memcpy(&gl->verts[offset], path->fill, sizeof(NVGvertex) * path->nfill); + offset += path->nfill; + } + if (path->nstroke > 0) { + copy->strokeOffset = offset; + copy->strokeCount = path->nstroke; + memcpy(&gl->verts[offset], path->stroke, sizeof(NVGvertex) * path->nstroke); + offset += path->nstroke; + } + } + + // Quad + call->triangleOffset = offset; + call->triangleCount = 6; + quad = &gl->verts[call->triangleOffset]; + glnvg__vset(&quad[0], bounds[0], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[1], bounds[2], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[2], bounds[2], bounds[1], 0.5f, 1.0f); + + glnvg__vset(&quad[3], bounds[0], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[4], bounds[2], bounds[1], 0.5f, 1.0f); + glnvg__vset(&quad[5], bounds[0], bounds[1], 0.5f, 1.0f); + + // Setup uniforms for draw calls + if (call->type == GLNVG_FILL) { + call->uniformOffset = glnvg__allocFragUniforms(gl, 2); + if (call->uniformOffset == -1) goto error; + // Simple shader for stencil + frag = nvg__fragUniformPtr(gl, call->uniformOffset); + memset(frag, 0, sizeof(*frag)); + frag->strokeThr = -1.0f; + frag->type = NSVG_SHADER_SIMPLE; + // Fill shader + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, fringe, fringe, -1.0f); + } else { + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + // Fill shader + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, fringe, fringe, -1.0f); + } + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderStroke(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, + float strokeWidth, const NVGpath* paths, int npaths) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + int i, maxverts, offset; + + if (call == NULL) return; + + call->type = GLNVG_STROKE; + call->pathOffset = glnvg__allocPaths(gl, npaths); + if (call->pathOffset == -1) goto error; + call->pathCount = npaths; + call->image = paint->image; + + // Allocate vertices for all the paths. + maxverts = glnvg__maxVertCount(paths, npaths); + offset = glnvg__allocVerts(gl, maxverts); + if (offset == -1) goto error; + + for (i = 0; i < npaths; i++) { + GLNVGpath* copy = &gl->paths[call->pathOffset + i]; + const NVGpath* path = &paths[i]; + memset(copy, 0, sizeof(GLNVGpath)); + if (path->nstroke) { + copy->strokeOffset = offset; + copy->strokeCount = path->nstroke; + memcpy(&gl->verts[offset], path->stroke, sizeof(NVGvertex) * path->nstroke); + offset += path->nstroke; + } + } + + if (gl->flags & NVG_STENCIL_STROKES) { + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 2); + if (call->uniformOffset == -1) goto error; + + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, strokeWidth, fringe, -1.0f); + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, strokeWidth, fringe, 1.0f - 0.5f/255.0f); + + } else { + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, strokeWidth, fringe, -1.0f); + } + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderTriangles(void* uptr, NVGpaint* paint, NVGscissor* scissor, + const NVGvertex* verts, int nverts) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + GLNVGfragUniforms* frag; + + if (call == NULL) return; + + call->type = GLNVG_TRIANGLES; + call->image = paint->image; + + // Allocate vertices for all the paths. + call->triangleOffset = glnvg__allocVerts(gl, nverts); + if (call->triangleOffset == -1) goto error; + call->triangleCount = nverts; + + memcpy(&gl->verts[call->triangleOffset], verts, sizeof(NVGvertex) * nverts); + + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + frag = nvg__fragUniformPtr(gl, call->uniformOffset); + glnvg__convertPaint(gl, frag, paint, scissor, 1.0f, 1.0f, -1.0f); + frag->type = NSVG_SHADER_IMG; + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderDelete(void* uptr) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int i; + if (gl == NULL) return; + + glnvg__deleteShader(&gl->shader); + +#if NANOVG_GL3 +#if NANOVG_GL_USE_UNIFORMBUFFER + if (gl->fragBuf != 0) + glDeleteBuffers(1, &gl->fragBuf); +#endif + if (gl->vertArr != 0) + glDeleteVertexArrays(1, &gl->vertArr); +#endif + if (gl->vertBuf != 0) + glDeleteBuffers(1, &gl->vertBuf); + + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].tex != 0 && (gl->textures[i].flags & NVG_IMAGE_NODELETE) == 0) + glDeleteTextures(1, &gl->textures[i].tex); + } + free(gl->textures); + + free(gl->paths); + free(gl->verts); + free(gl->uniforms); + free(gl->calls); + + free(gl); +} + + +#if defined NANOVG_GL2 +NVGcontext* nvgCreateGL2(int flags) +#elif defined NANOVG_GL3 +NVGcontext* nvgCreateGL3(int flags) +#elif defined NANOVG_GLES2 +NVGcontext* nvgCreateGLES2(int flags) +#elif defined NANOVG_GLES3 +NVGcontext* nvgCreateGLES3(int flags) +#endif +{ + NVGparams params; + NVGcontext* ctx = NULL; + GLNVGcontext* gl = (GLNVGcontext*)malloc(sizeof(GLNVGcontext)); + if (gl == NULL) goto error; + memset(gl, 0, sizeof(GLNVGcontext)); + + memset(¶ms, 0, sizeof(params)); + params.renderCreate = glnvg__renderCreate; + params.renderCreateTexture = glnvg__renderCreateTexture; + params.renderDeleteTexture = glnvg__renderDeleteTexture; + params.renderUpdateTexture = glnvg__renderUpdateTexture; + params.renderGetTextureSize = glnvg__renderGetTextureSize; + params.renderViewport = glnvg__renderViewport; + params.renderCancel = glnvg__renderCancel; + params.renderFlush = glnvg__renderFlush; + params.renderFill = glnvg__renderFill; + params.renderStroke = glnvg__renderStroke; + params.renderTriangles = glnvg__renderTriangles; + params.renderDelete = glnvg__renderDelete; + params.userPtr = gl; + params.edgeAntiAlias = flags & NVG_ANTIALIAS ? 1 : 0; + + gl->flags = flags; + + ctx = nvgCreateInternal(¶ms); + if (ctx == NULL) goto error; + + return ctx; + +error: + // 'gl' is freed by nvgDeleteInternal. + if (ctx != NULL) nvgDeleteInternal(ctx); + return NULL; +} + +#if defined NANOVG_GL2 +void nvgDeleteGL2(NVGcontext* ctx) +#elif defined NANOVG_GL3 +void nvgDeleteGL3(NVGcontext* ctx) +#elif defined NANOVG_GLES2 +void nvgDeleteGLES2(NVGcontext* ctx) +#elif defined NANOVG_GLES3 +void nvgDeleteGLES3(NVGcontext* ctx) +#endif +{ + nvgDeleteInternal(ctx); +} + +#if defined NANOVG_GL2 +int nvglCreateImageFromHandleGL2(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GL3 +int nvglCreateImageFromHandleGL3(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GLES2 +int nvglCreateImageFromHandleGLES2(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GLES3 +int nvglCreateImageFromHandleGLES3(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#endif +{ + GLNVGcontext* gl = (GLNVGcontext*)nvgInternalParams(ctx)->userPtr; + GLNVGtexture* tex = glnvg__allocTexture(gl); + + if (tex == NULL) return 0; + + tex->type = NVG_TEXTURE_RGBA; + tex->tex = textureId; + tex->flags = imageFlags; + tex->width = w; + tex->height = h; + + return tex->id; +} + +#if defined NANOVG_GL2 +GLuint nvglImageHandleGL2(NVGcontext* ctx, int image) +#elif defined NANOVG_GL3 +GLuint nvglImageHandleGL3(NVGcontext* ctx, int image) +#elif defined NANOVG_GLES2 +GLuint nvglImageHandleGLES2(NVGcontext* ctx, int image) +#elif defined NANOVG_GLES3 +GLuint nvglImageHandleGLES3(NVGcontext* ctx, int image) +#endif +{ + GLNVGcontext* gl = (GLNVGcontext*)nvgInternalParams(ctx)->userPtr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + return tex->tex; +} + +#endif /* NANOVG_GL_IMPLEMENTATION */ diff --git a/phonelibs/nanovg/nanovg_gl_utils.h b/phonelibs/nanovg/nanovg_gl_utils.h new file mode 100644 index 0000000000..1323e90c64 --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl_utils.h @@ -0,0 +1,143 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// +#ifndef NANOVG_GL_UTILS_H +#define NANOVG_GL_UTILS_H + +struct NVGLUframebuffer { + NVGcontext* ctx; + GLuint fbo; + GLuint rbo; + GLuint texture; + int image; +}; +typedef struct NVGLUframebuffer NVGLUframebuffer; + +// Helper function to create GL frame buffer to render to. +void nvgluBindFramebuffer(NVGLUframebuffer* fb); +NVGLUframebuffer* nvgluCreateFramebuffer(NVGcontext* ctx, int w, int h, int imageFlags); +void nvgluDeleteFramebuffer(NVGLUframebuffer* fb); + +#endif // NANOVG_GL_UTILS_H + +#ifdef NANOVG_GL_IMPLEMENTATION + +#if defined(NANOVG_GL3) || defined(NANOVG_GLES2) || defined(NANOVG_GLES3) +// FBO is core in OpenGL 3>. +# define NANOVG_FBO_VALID 1 +#elif defined(NANOVG_GL2) +// On OS X including glext defines FBO on GL2 too. +# ifdef __APPLE__ +# include +# define NANOVG_FBO_VALID 1 +# endif +#endif + +static GLint defaultFBO = -1; + +NVGLUframebuffer* nvgluCreateFramebuffer(NVGcontext* ctx, int w, int h, int imageFlags) +{ +#ifdef NANOVG_FBO_VALID + GLint defaultFBO; + GLint defaultRBO; + NVGLUframebuffer* fb = NULL; + + glGetIntegerv(GL_FRAMEBUFFER_BINDING, &defaultFBO); + glGetIntegerv(GL_RENDERBUFFER_BINDING, &defaultRBO); + + fb = (NVGLUframebuffer*)malloc(sizeof(NVGLUframebuffer)); + if (fb == NULL) goto error; + memset(fb, 0, sizeof(NVGLUframebuffer)); + + fb->image = nvgCreateImageRGBA(ctx, w, h, imageFlags | NVG_IMAGE_FLIPY | NVG_IMAGE_PREMULTIPLIED, NULL); + +#if defined NANOVG_GL2 + fb->texture = nvglImageHandleGL2(ctx, fb->image); +#elif defined NANOVG_GL3 + fb->texture = nvglImageHandleGL3(ctx, fb->image); +#elif defined NANOVG_GLES2 + fb->texture = nvglImageHandleGLES2(ctx, fb->image); +#elif defined NANOVG_GLES3 + fb->texture = nvglImageHandleGLES3(ctx, fb->image); +#endif + + fb->ctx = ctx; + + // frame buffer object + glGenFramebuffers(1, &fb->fbo); + glBindFramebuffer(GL_FRAMEBUFFER, fb->fbo); + + // render buffer object + glGenRenderbuffers(1, &fb->rbo); + glBindRenderbuffer(GL_RENDERBUFFER, fb->rbo); + glRenderbufferStorage(GL_RENDERBUFFER, GL_STENCIL_INDEX8, w, h); + + // combine all + glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, fb->texture, 0); + glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_STENCIL_ATTACHMENT, GL_RENDERBUFFER, fb->rbo); + + if (glCheckFramebufferStatus(GL_FRAMEBUFFER) != GL_FRAMEBUFFER_COMPLETE) goto error; + + glBindFramebuffer(GL_FRAMEBUFFER, defaultFBO); + glBindRenderbuffer(GL_RENDERBUFFER, defaultRBO); + return fb; +error: + glBindFramebuffer(GL_FRAMEBUFFER, defaultFBO); + glBindRenderbuffer(GL_RENDERBUFFER, defaultRBO); + nvgluDeleteFramebuffer(fb); + return NULL; +#else + NVG_NOTUSED(ctx); + NVG_NOTUSED(w); + NVG_NOTUSED(h); + NVG_NOTUSED(imageFlags); + return NULL; +#endif +} + +void nvgluBindFramebuffer(NVGLUframebuffer* fb) +{ +#ifdef NANOVG_FBO_VALID + if (defaultFBO == -1) glGetIntegerv(GL_FRAMEBUFFER_BINDING, &defaultFBO); + glBindFramebuffer(GL_FRAMEBUFFER, fb != NULL ? fb->fbo : defaultFBO); +#else + NVG_NOTUSED(fb); +#endif +} + +void nvgluDeleteFramebuffer(NVGLUframebuffer* fb) +{ +#ifdef NANOVG_FBO_VALID + if (fb == NULL) return; + if (fb->fbo != 0) + glDeleteFramebuffers(1, &fb->fbo); + if (fb->rbo != 0) + glDeleteRenderbuffers(1, &fb->rbo); + if (fb->image >= 0) + nvgDeleteImage(fb->ctx, fb->image); + fb->ctx = NULL; + fb->fbo = 0; + fb->rbo = 0; + fb->texture = 0; + fb->image = -1; + free(fb); +#else + NVG_NOTUSED(fb); +#endif +} + +#endif // NANOVG_GL_IMPLEMENTATION diff --git a/phonelibs/nanovg/stb_image.h b/phonelibs/nanovg/stb_image.h new file mode 100644 index 0000000000..e06f7a1d73 --- /dev/null +++ b/phonelibs/nanovg/stb_image.h @@ -0,0 +1,6614 @@ +/* stb_image - v2.10 - public domain image loader - http://nothings.org/stb_image.h + no warranty implied; use at your own risk + + Do this: + #define STB_IMAGE_IMPLEMENTATION + before you include this file in *one* C or C++ file to create the implementation. + + // i.e. it should look like this: + #include ... + #include ... + #include ... + #define STB_IMAGE_IMPLEMENTATION + #include "stb_image.h" + + You can #define STBI_ASSERT(x) before the #include to avoid using assert.h. + And #define STBI_MALLOC, STBI_REALLOC, and STBI_FREE to avoid using malloc,realloc,free + + + QUICK NOTES: + Primarily of interest to game developers and other people who can + avoid problematic images and only need the trivial interface + + JPEG baseline & progressive (12 bpc/arithmetic not supported, same as stock IJG lib) + PNG 1/2/4/8-bit-per-channel (16 bpc not supported) + + TGA (not sure what subset, if a subset) + BMP non-1bpp, non-RLE + PSD (composited view only, no extra channels, 8/16 bit-per-channel) + + GIF (*comp always reports as 4-channel) + HDR (radiance rgbE format) + PIC (Softimage PIC) + PNM (PPM and PGM binary only) + + Animated GIF still needs a proper API, but here's one way to do it: + http://gist.github.com/urraka/685d9a6340b26b830d49 + + - decode from memory or through FILE (define STBI_NO_STDIO to remove code) + - decode from arbitrary I/O callbacks + - SIMD acceleration on x86/x64 (SSE2) and ARM (NEON) + + Full documentation under "DOCUMENTATION" below. + + + Revision 2.00 release notes: + + - Progressive JPEG is now supported. + + - PPM and PGM binary formats are now supported, thanks to Ken Miller. + + - x86 platforms now make use of SSE2 SIMD instructions for + JPEG decoding, and ARM platforms can use NEON SIMD if requested. + This work was done by Fabian "ryg" Giesen. SSE2 is used by + default, but NEON must be enabled explicitly; see docs. + + With other JPEG optimizations included in this version, we see + 2x speedup on a JPEG on an x86 machine, and a 1.5x speedup + on a JPEG on an ARM machine, relative to previous versions of this + library. The same results will not obtain for all JPGs and for all + x86/ARM machines. (Note that progressive JPEGs are significantly + slower to decode than regular JPEGs.) This doesn't mean that this + is the fastest JPEG decoder in the land; rather, it brings it + closer to parity with standard libraries. If you want the fastest + decode, look elsewhere. (See "Philosophy" section of docs below.) + + See final bullet items below for more info on SIMD. + + - Added STBI_MALLOC, STBI_REALLOC, and STBI_FREE macros for replacing + the memory allocator. Unlike other STBI libraries, these macros don't + support a context parameter, so if you need to pass a context in to + the allocator, you'll have to store it in a global or a thread-local + variable. + + - Split existing STBI_NO_HDR flag into two flags, STBI_NO_HDR and + STBI_NO_LINEAR. + STBI_NO_HDR: suppress implementation of .hdr reader format + STBI_NO_LINEAR: suppress high-dynamic-range light-linear float API + + - You can suppress implementation of any of the decoders to reduce + your code footprint by #defining one or more of the following + symbols before creating the implementation. + + STBI_NO_JPEG + STBI_NO_PNG + STBI_NO_BMP + STBI_NO_PSD + STBI_NO_TGA + STBI_NO_GIF + STBI_NO_HDR + STBI_NO_PIC + STBI_NO_PNM (.ppm and .pgm) + + - You can request *only* certain decoders and suppress all other ones + (this will be more forward-compatible, as addition of new decoders + doesn't require you to disable them explicitly): + + STBI_ONLY_JPEG + STBI_ONLY_PNG + STBI_ONLY_BMP + STBI_ONLY_PSD + STBI_ONLY_TGA + STBI_ONLY_GIF + STBI_ONLY_HDR + STBI_ONLY_PIC + STBI_ONLY_PNM (.ppm and .pgm) + + Note that you can define multiples of these, and you will get all + of them ("only x" and "only y" is interpreted to mean "only x&y"). + + - If you use STBI_NO_PNG (or _ONLY_ without PNG), and you still + want the zlib decoder to be available, #define STBI_SUPPORT_ZLIB + + - Compilation of all SIMD code can be suppressed with + #define STBI_NO_SIMD + It should not be necessary to disable SIMD unless you have issues + compiling (e.g. using an x86 compiler which doesn't support SSE + intrinsics or that doesn't support the method used to detect + SSE2 support at run-time), and even those can be reported as + bugs so I can refine the built-in compile-time checking to be + smarter. + + - The old STBI_SIMD system which allowed installing a user-defined + IDCT etc. has been removed. If you need this, don't upgrade. My + assumption is that almost nobody was doing this, and those who + were will find the built-in SIMD more satisfactory anyway. + + - RGB values computed for JPEG images are slightly different from + previous versions of stb_image. (This is due to using less + integer precision in SIMD.) The C code has been adjusted so + that the same RGB values will be computed regardless of whether + SIMD support is available, so your app should always produce + consistent results. But these results are slightly different from + previous versions. (Specifically, about 3% of available YCbCr values + will compute different RGB results from pre-1.49 versions by +-1; + most of the deviating values are one smaller in the G channel.) + + - If you must produce consistent results with previous versions of + stb_image, #define STBI_JPEG_OLD and you will get the same results + you used to; however, you will not get the SIMD speedups for + the YCbCr-to-RGB conversion step (although you should still see + significant JPEG speedup from the other changes). + + Please note that STBI_JPEG_OLD is a temporary feature; it will be + removed in future versions of the library. It is only intended for + near-term back-compatibility use. + + + Latest revision history: + 2.10 (2016-01-22) avoid warning introduced in 2.09 + 2.09 (2016-01-16) 16-bit TGA; comments in PNM files; STBI_REALLOC_SIZED + 2.08 (2015-09-13) fix to 2.07 cleanup, reading RGB PSD as RGBA + 2.07 (2015-09-13) partial animated GIF support + limited 16-bit PSD support + minor bugs, code cleanup, and compiler warnings + 2.06 (2015-04-19) fix bug where PSD returns wrong '*comp' value + 2.05 (2015-04-19) fix bug in progressive JPEG handling, fix warning + 2.04 (2015-04-15) try to re-enable SIMD on MinGW 64-bit + 2.03 (2015-04-12) additional corruption checking + stbi_set_flip_vertically_on_load + fix NEON support; fix mingw support + 2.02 (2015-01-19) fix incorrect assert, fix warning + 2.01 (2015-01-17) fix various warnings + 2.00b (2014-12-25) fix STBI_MALLOC in progressive JPEG + 2.00 (2014-12-25) optimize JPEG, including x86 SSE2 & ARM NEON SIMD + progressive JPEG + PGM/PPM support + STBI_MALLOC,STBI_REALLOC,STBI_FREE + STBI_NO_*, STBI_ONLY_* + GIF bugfix + 1.48 (2014-12-14) fix incorrectly-named assert() + 1.47 (2014-12-14) 1/2/4-bit PNG support (both grayscale and paletted) + optimize PNG + fix bug in interlaced PNG with user-specified channel count + + See end of file for full revision history. + + + ============================ Contributors ========================= + + Image formats Extensions, features + Sean Barrett (jpeg, png, bmp) Jetro Lauha (stbi_info) + Nicolas Schulz (hdr, psd) Martin "SpartanJ" Golini (stbi_info) + Jonathan Dummer (tga) James "moose2000" Brown (iPhone PNG) + Jean-Marc Lienher (gif) Ben "Disch" Wenger (io callbacks) + Tom Seddon (pic) Omar Cornut (1/2/4-bit PNG) + Thatcher Ulrich (psd) Nicolas Guillemot (vertical flip) + Ken Miller (pgm, ppm) Richard Mitton (16-bit PSD) + urraka@github (animated gif) Junggon Kim (PNM comments) + Daniel Gibson (16-bit TGA) + + Optimizations & bugfixes + Fabian "ryg" Giesen + Arseny Kapoulkine + + Bug & warning fixes + Marc LeBlanc David Woo Guillaume George Martins Mozeiko + Christpher Lloyd Martin Golini Jerry Jansson Joseph Thomson + Dave Moore Roy Eltham Hayaki Saito Phil Jordan + Won Chun Luke Graham Johan Duparc Nathan Reed + the Horde3D community Thomas Ruf Ronny Chevalier Nick Verigakis + Janez Zemva John Bartholomew Michal Cichon svdijk@github + Jonathan Blow Ken Hamada Tero Hanninen Baldur Karlsson + Laurent Gomila Cort Stratton Sergio Gonzalez romigrou@github + Aruelien Pocheville Thibault Reuille Cass Everitt + Ryamond Barbiero Paul Du Bois Engin Manap + Blazej Dariusz Roszkowski + Michaelangel007@github + + +LICENSE + +This software is in the public domain. Where that dedication is not +recognized, you are granted a perpetual, irrevocable license to copy, +distribute, and modify this file as you see fit. + +*/ + +#ifndef STBI_INCLUDE_STB_IMAGE_H +#define STBI_INCLUDE_STB_IMAGE_H + +// DOCUMENTATION +// +// Limitations: +// - no 16-bit-per-channel PNG +// - no 12-bit-per-channel JPEG +// - no JPEGs with arithmetic coding +// - no 1-bit BMP +// - GIF always returns *comp=4 +// +// Basic usage (see HDR discussion below for HDR usage): +// int x,y,n; +// unsigned char *data = stbi_load(filename, &x, &y, &n, 0); +// // ... process data if not NULL ... +// // ... x = width, y = height, n = # 8-bit components per pixel ... +// // ... replace '0' with '1'..'4' to force that many components per pixel +// // ... but 'n' will always be the number that it would have been if you said 0 +// stbi_image_free(data) +// +// Standard parameters: +// int *x -- outputs image width in pixels +// int *y -- outputs image height in pixels +// int *comp -- outputs # of image components in image file +// int req_comp -- if non-zero, # of image components requested in result +// +// The return value from an image loader is an 'unsigned char *' which points +// to the pixel data, or NULL on an allocation failure or if the image is +// corrupt or invalid. The pixel data consists of *y scanlines of *x pixels, +// with each pixel consisting of N interleaved 8-bit components; the first +// pixel pointed to is top-left-most in the image. There is no padding between +// image scanlines or between pixels, regardless of format. The number of +// components N is 'req_comp' if req_comp is non-zero, or *comp otherwise. +// If req_comp is non-zero, *comp has the number of components that _would_ +// have been output otherwise. E.g. if you set req_comp to 4, you will always +// get RGBA output, but you can check *comp to see if it's trivially opaque +// because e.g. there were only 3 channels in the source image. +// +// An output image with N components has the following components interleaved +// in this order in each pixel: +// +// N=#comp components +// 1 grey +// 2 grey, alpha +// 3 red, green, blue +// 4 red, green, blue, alpha +// +// If image loading fails for any reason, the return value will be NULL, +// and *x, *y, *comp will be unchanged. The function stbi_failure_reason() +// can be queried for an extremely brief, end-user unfriendly explanation +// of why the load failed. Define STBI_NO_FAILURE_STRINGS to avoid +// compiling these strings at all, and STBI_FAILURE_USERMSG to get slightly +// more user-friendly ones. +// +// Paletted PNG, BMP, GIF, and PIC images are automatically depalettized. +// +// =========================================================================== +// +// Philosophy +// +// stb libraries are designed with the following priorities: +// +// 1. easy to use +// 2. easy to maintain +// 3. good performance +// +// Sometimes I let "good performance" creep up in priority over "easy to maintain", +// and for best performance I may provide less-easy-to-use APIs that give higher +// performance, in addition to the easy to use ones. Nevertheless, it's important +// to keep in mind that from the standpoint of you, a client of this library, +// all you care about is #1 and #3, and stb libraries do not emphasize #3 above all. +// +// Some secondary priorities arise directly from the first two, some of which +// make more explicit reasons why performance can't be emphasized. +// +// - Portable ("ease of use") +// - Small footprint ("easy to maintain") +// - No dependencies ("ease of use") +// +// =========================================================================== +// +// I/O callbacks +// +// I/O callbacks allow you to read from arbitrary sources, like packaged +// files or some other source. Data read from callbacks are processed +// through a small internal buffer (currently 128 bytes) to try to reduce +// overhead. +// +// The three functions you must define are "read" (reads some bytes of data), +// "skip" (skips some bytes of data), "eof" (reports if the stream is at the end). +// +// =========================================================================== +// +// SIMD support +// +// The JPEG decoder will try to automatically use SIMD kernels on x86 when +// supported by the compiler. For ARM Neon support, you must explicitly +// request it. +// +// (The old do-it-yourself SIMD API is no longer supported in the current +// code.) +// +// On x86, SSE2 will automatically be used when available based on a run-time +// test; if not, the generic C versions are used as a fall-back. On ARM targets, +// the typical path is to have separate builds for NEON and non-NEON devices +// (at least this is true for iOS and Android). Therefore, the NEON support is +// toggled by a build flag: define STBI_NEON to get NEON loops. +// +// The output of the JPEG decoder is slightly different from versions where +// SIMD support was introduced (that is, for versions before 1.49). The +// difference is only +-1 in the 8-bit RGB channels, and only on a small +// fraction of pixels. You can force the pre-1.49 behavior by defining +// STBI_JPEG_OLD, but this will disable some of the SIMD decoding path +// and hence cost some performance. +// +// If for some reason you do not want to use any of SIMD code, or if +// you have issues compiling it, you can disable it entirely by +// defining STBI_NO_SIMD. +// +// =========================================================================== +// +// HDR image support (disable by defining STBI_NO_HDR) +// +// stb_image now supports loading HDR images in general, and currently +// the Radiance .HDR file format, although the support is provided +// generically. You can still load any file through the existing interface; +// if you attempt to load an HDR file, it will be automatically remapped to +// LDR, assuming gamma 2.2 and an arbitrary scale factor defaulting to 1; +// both of these constants can be reconfigured through this interface: +// +// stbi_hdr_to_ldr_gamma(2.2f); +// stbi_hdr_to_ldr_scale(1.0f); +// +// (note, do not use _inverse_ constants; stbi_image will invert them +// appropriately). +// +// Additionally, there is a new, parallel interface for loading files as +// (linear) floats to preserve the full dynamic range: +// +// float *data = stbi_loadf(filename, &x, &y, &n, 0); +// +// If you load LDR images through this interface, those images will +// be promoted to floating point values, run through the inverse of +// constants corresponding to the above: +// +// stbi_ldr_to_hdr_scale(1.0f); +// stbi_ldr_to_hdr_gamma(2.2f); +// +// Finally, given a filename (or an open file or memory block--see header +// file for details) containing image data, you can query for the "most +// appropriate" interface to use (that is, whether the image is HDR or +// not), using: +// +// stbi_is_hdr(char *filename); +// +// =========================================================================== +// +// iPhone PNG support: +// +// By default we convert iphone-formatted PNGs back to RGB, even though +// they are internally encoded differently. You can disable this conversion +// by by calling stbi_convert_iphone_png_to_rgb(0), in which case +// you will always just get the native iphone "format" through (which +// is BGR stored in RGB). +// +// Call stbi_set_unpremultiply_on_load(1) as well to force a divide per +// pixel to remove any premultiplied alpha *only* if the image file explicitly +// says there's premultiplied data (currently only happens in iPhone images, +// and only if iPhone convert-to-rgb processing is on). +// + + +#ifndef STBI_NO_STDIO +#include +#endif // STBI_NO_STDIO + +#define STBI_VERSION 1 + +enum +{ + STBI_default = 0, // only used for req_comp + + STBI_grey = 1, + STBI_grey_alpha = 2, + STBI_rgb = 3, + STBI_rgb_alpha = 4 +}; + +typedef unsigned char stbi_uc; + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef STB_IMAGE_STATIC +#define STBIDEF static +#else +#define STBIDEF extern +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// PRIMARY API - works on images of any type +// + +// +// load image by filename, open file, or memory buffer +// + +typedef struct +{ + int (*read) (void *user,char *data,int size); // fill 'data' with 'size' bytes. return number of bytes actually read + void (*skip) (void *user,int n); // skip the next 'n' bytes, or 'unget' the last -n bytes if negative + int (*eof) (void *user); // returns nonzero if we are at end of file/data +} stbi_io_callbacks; + +STBIDEF stbi_uc *stbi_load (char const *filename, int *x, int *y, int *comp, int req_comp); +STBIDEF stbi_uc *stbi_load_from_memory (stbi_uc const *buffer, int len , int *x, int *y, int *comp, int req_comp); +STBIDEF stbi_uc *stbi_load_from_callbacks(stbi_io_callbacks const *clbk , void *user, int *x, int *y, int *comp, int req_comp); + +#ifndef STBI_NO_STDIO +STBIDEF stbi_uc *stbi_load_from_file (FILE *f, int *x, int *y, int *comp, int req_comp); +// for stbi_load_from_file, file pointer is left pointing immediately after image +#endif + +#ifndef STBI_NO_LINEAR + STBIDEF float *stbi_loadf (char const *filename, int *x, int *y, int *comp, int req_comp); + STBIDEF float *stbi_loadf_from_memory (stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp); + STBIDEF float *stbi_loadf_from_callbacks (stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp); + + #ifndef STBI_NO_STDIO + STBIDEF float *stbi_loadf_from_file (FILE *f, int *x, int *y, int *comp, int req_comp); + #endif +#endif + +#ifndef STBI_NO_HDR + STBIDEF void stbi_hdr_to_ldr_gamma(float gamma); + STBIDEF void stbi_hdr_to_ldr_scale(float scale); +#endif // STBI_NO_HDR + +#ifndef STBI_NO_LINEAR + STBIDEF void stbi_ldr_to_hdr_gamma(float gamma); + STBIDEF void stbi_ldr_to_hdr_scale(float scale); +#endif // STBI_NO_LINEAR + +// stbi_is_hdr is always defined, but always returns false if STBI_NO_HDR +STBIDEF int stbi_is_hdr_from_callbacks(stbi_io_callbacks const *clbk, void *user); +STBIDEF int stbi_is_hdr_from_memory(stbi_uc const *buffer, int len); +#ifndef STBI_NO_STDIO +STBIDEF int stbi_is_hdr (char const *filename); +STBIDEF int stbi_is_hdr_from_file(FILE *f); +#endif // STBI_NO_STDIO + + +// get a VERY brief reason for failure +// NOT THREADSAFE +STBIDEF const char *stbi_failure_reason (void); + +// free the loaded image -- this is just free() +STBIDEF void stbi_image_free (void *retval_from_stbi_load); + +// get image dimensions & components without fully decoding +STBIDEF int stbi_info_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp); +STBIDEF int stbi_info_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp); + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_info (char const *filename, int *x, int *y, int *comp); +STBIDEF int stbi_info_from_file (FILE *f, int *x, int *y, int *comp); + +#endif + + + +// for image formats that explicitly notate that they have premultiplied alpha, +// we just return the colors as stored in the file. set this flag to force +// unpremultiplication. results are undefined if the unpremultiply overflow. +STBIDEF void stbi_set_unpremultiply_on_load(int flag_true_if_should_unpremultiply); + +// indicate whether we should process iphone images back to canonical format, +// or just pass them through "as-is" +STBIDEF void stbi_convert_iphone_png_to_rgb(int flag_true_if_should_convert); + +// flip the image vertically, so the first pixel in the output array is the bottom left +STBIDEF void stbi_set_flip_vertically_on_load(int flag_true_if_should_flip); + +// ZLIB client - used by PNG, available for other purposes + +STBIDEF char *stbi_zlib_decode_malloc_guesssize(const char *buffer, int len, int initial_size, int *outlen); +STBIDEF char *stbi_zlib_decode_malloc_guesssize_headerflag(const char *buffer, int len, int initial_size, int *outlen, int parse_header); +STBIDEF char *stbi_zlib_decode_malloc(const char *buffer, int len, int *outlen); +STBIDEF int stbi_zlib_decode_buffer(char *obuffer, int olen, const char *ibuffer, int ilen); + +STBIDEF char *stbi_zlib_decode_noheader_malloc(const char *buffer, int len, int *outlen); +STBIDEF int stbi_zlib_decode_noheader_buffer(char *obuffer, int olen, const char *ibuffer, int ilen); + + +#ifdef __cplusplus +} +#endif + +// +// +//// end header file ///////////////////////////////////////////////////// +#endif // STBI_INCLUDE_STB_IMAGE_H + +#ifdef STB_IMAGE_IMPLEMENTATION + +#if defined(STBI_ONLY_JPEG) || defined(STBI_ONLY_PNG) || defined(STBI_ONLY_BMP) \ + || defined(STBI_ONLY_TGA) || defined(STBI_ONLY_GIF) || defined(STBI_ONLY_PSD) \ + || defined(STBI_ONLY_HDR) || defined(STBI_ONLY_PIC) || defined(STBI_ONLY_PNM) \ + || defined(STBI_ONLY_ZLIB) + #ifndef STBI_ONLY_JPEG + #define STBI_NO_JPEG + #endif + #ifndef STBI_ONLY_PNG + #define STBI_NO_PNG + #endif + #ifndef STBI_ONLY_BMP + #define STBI_NO_BMP + #endif + #ifndef STBI_ONLY_PSD + #define STBI_NO_PSD + #endif + #ifndef STBI_ONLY_TGA + #define STBI_NO_TGA + #endif + #ifndef STBI_ONLY_GIF + #define STBI_NO_GIF + #endif + #ifndef STBI_ONLY_HDR + #define STBI_NO_HDR + #endif + #ifndef STBI_ONLY_PIC + #define STBI_NO_PIC + #endif + #ifndef STBI_ONLY_PNM + #define STBI_NO_PNM + #endif +#endif + +#if defined(STBI_NO_PNG) && !defined(STBI_SUPPORT_ZLIB) && !defined(STBI_NO_ZLIB) +#define STBI_NO_ZLIB +#endif + + +#include +#include // ptrdiff_t on osx +#include +#include + +#if !defined(STBI_NO_LINEAR) || !defined(STBI_NO_HDR) +#include // ldexp +#endif + +#ifndef STBI_NO_STDIO +#include +#endif + +#ifndef STBI_ASSERT +#include +#define STBI_ASSERT(x) assert(x) +#endif + + +#ifndef _MSC_VER + #ifdef __cplusplus + #define stbi_inline inline + #else + #define stbi_inline + #endif +#else + #define stbi_inline __forceinline +#endif + + +#ifdef _MSC_VER +typedef unsigned short stbi__uint16; +typedef signed short stbi__int16; +typedef unsigned int stbi__uint32; +typedef signed int stbi__int32; +#else +#include +typedef uint16_t stbi__uint16; +typedef int16_t stbi__int16; +typedef uint32_t stbi__uint32; +typedef int32_t stbi__int32; +#endif + +// should produce compiler error if size is wrong +typedef unsigned char validate_uint32[sizeof(stbi__uint32)==4 ? 1 : -1]; + +#ifdef _MSC_VER +#define STBI_NOTUSED(v) (void)(v) +#else +#define STBI_NOTUSED(v) (void)sizeof(v) +#endif + +#ifdef _MSC_VER +#define STBI_HAS_LROTL +#endif + +#ifdef STBI_HAS_LROTL + #define stbi_lrot(x,y) _lrotl(x,y) +#else + #define stbi_lrot(x,y) (((x) << (y)) | ((x) >> (32 - (y)))) +#endif + +#if defined(STBI_MALLOC) && defined(STBI_FREE) && (defined(STBI_REALLOC) || defined(STBI_REALLOC_SIZED)) +// ok +#elif !defined(STBI_MALLOC) && !defined(STBI_FREE) && !defined(STBI_REALLOC) && !defined(STBI_REALLOC_SIZED) +// ok +#else +#error "Must define all or none of STBI_MALLOC, STBI_FREE, and STBI_REALLOC (or STBI_REALLOC_SIZED)." +#endif + +#ifndef STBI_MALLOC +#define STBI_MALLOC(sz) malloc(sz) +#define STBI_REALLOC(p,newsz) realloc(p,newsz) +#define STBI_FREE(p) free(p) +#endif + +#ifndef STBI_REALLOC_SIZED +#define STBI_REALLOC_SIZED(p,oldsz,newsz) STBI_REALLOC(p,newsz) +#endif + +// x86/x64 detection +#if defined(__x86_64__) || defined(_M_X64) +#define STBI__X64_TARGET +#elif defined(__i386) || defined(_M_IX86) +#define STBI__X86_TARGET +#endif + +#if defined(__GNUC__) && (defined(STBI__X86_TARGET) || defined(STBI__X64_TARGET)) && !defined(__SSE2__) && !defined(STBI_NO_SIMD) +// NOTE: not clear do we actually need this for the 64-bit path? +// gcc doesn't support sse2 intrinsics unless you compile with -msse2, +// (but compiling with -msse2 allows the compiler to use SSE2 everywhere; +// this is just broken and gcc are jerks for not fixing it properly +// http://www.virtualdub.org/blog/pivot/entry.php?id=363 ) +#define STBI_NO_SIMD +#endif + +#if defined(__MINGW32__) && defined(STBI__X86_TARGET) && !defined(STBI_MINGW_ENABLE_SSE2) && !defined(STBI_NO_SIMD) +// Note that __MINGW32__ doesn't actually mean 32-bit, so we have to avoid STBI__X64_TARGET +// +// 32-bit MinGW wants ESP to be 16-byte aligned, but this is not in the +// Windows ABI and VC++ as well as Windows DLLs don't maintain that invariant. +// As a result, enabling SSE2 on 32-bit MinGW is dangerous when not +// simultaneously enabling "-mstackrealign". +// +// See https://github.com/nothings/stb/issues/81 for more information. +// +// So default to no SSE2 on 32-bit MinGW. If you've read this far and added +// -mstackrealign to your build settings, feel free to #define STBI_MINGW_ENABLE_SSE2. +#define STBI_NO_SIMD +#endif + +#if !defined(STBI_NO_SIMD) && defined(STBI__X86_TARGET) +#define STBI_SSE2 +#include + +#ifdef _MSC_VER + +#if _MSC_VER >= 1400 // not VC6 +#include // __cpuid +static int stbi__cpuid3(void) +{ + int info[4]; + __cpuid(info,1); + return info[3]; +} +#else +static int stbi__cpuid3(void) +{ + int res; + __asm { + mov eax,1 + cpuid + mov res,edx + } + return res; +} +#endif + +#define STBI_SIMD_ALIGN(type, name) __declspec(align(16)) type name + +static int stbi__sse2_available() +{ + int info3 = stbi__cpuid3(); + return ((info3 >> 26) & 1) != 0; +} +#else // assume GCC-style if not VC++ +#define STBI_SIMD_ALIGN(type, name) type name __attribute__((aligned(16))) + +static int stbi__sse2_available() +{ +#if defined(__GNUC__) && (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 // GCC 4.8 or later + // GCC 4.8+ has a nice way to do this + return __builtin_cpu_supports("sse2"); +#else + // portable way to do this, preferably without using GCC inline ASM? + // just bail for now. + return 0; +#endif +} +#endif +#endif + +// ARM NEON +#if defined(STBI_NO_SIMD) && defined(STBI_NEON) +#undef STBI_NEON +#endif + +#ifdef STBI_NEON +#include +// assume GCC or Clang on ARM targets +#define STBI_SIMD_ALIGN(type, name) type name __attribute__((aligned(16))) +#endif + +#ifndef STBI_SIMD_ALIGN +#define STBI_SIMD_ALIGN(type, name) type name +#endif + +/////////////////////////////////////////////// +// +// stbi__context struct and start_xxx functions + +// stbi__context structure is our basic context used by all images, so it +// contains all the IO context, plus some basic image information +typedef struct +{ + stbi__uint32 img_x, img_y; + int img_n, img_out_n; + + stbi_io_callbacks io; + void *io_user_data; + + int read_from_callbacks; + int buflen; + stbi_uc buffer_start[128]; + + stbi_uc *img_buffer, *img_buffer_end; + stbi_uc *img_buffer_original, *img_buffer_original_end; +} stbi__context; + + +static void stbi__refill_buffer(stbi__context *s); + +// initialize a memory-decode context +static void stbi__start_mem(stbi__context *s, stbi_uc const *buffer, int len) +{ + s->io.read = NULL; + s->read_from_callbacks = 0; + s->img_buffer = s->img_buffer_original = (stbi_uc *) buffer; + s->img_buffer_end = s->img_buffer_original_end = (stbi_uc *) buffer+len; +} + +// initialize a callback-based context +static void stbi__start_callbacks(stbi__context *s, stbi_io_callbacks *c, void *user) +{ + s->io = *c; + s->io_user_data = user; + s->buflen = sizeof(s->buffer_start); + s->read_from_callbacks = 1; + s->img_buffer_original = s->buffer_start; + stbi__refill_buffer(s); + s->img_buffer_original_end = s->img_buffer_end; +} + +#ifndef STBI_NO_STDIO + +static int stbi__stdio_read(void *user, char *data, int size) +{ + return (int) fread(data,1,size,(FILE*) user); +} + +static void stbi__stdio_skip(void *user, int n) +{ + fseek((FILE*) user, n, SEEK_CUR); +} + +static int stbi__stdio_eof(void *user) +{ + return feof((FILE*) user); +} + +static stbi_io_callbacks stbi__stdio_callbacks = +{ + stbi__stdio_read, + stbi__stdio_skip, + stbi__stdio_eof, +}; + +static void stbi__start_file(stbi__context *s, FILE *f) +{ + stbi__start_callbacks(s, &stbi__stdio_callbacks, (void *) f); +} + +//static void stop_file(stbi__context *s) { } + +#endif // !STBI_NO_STDIO + +static void stbi__rewind(stbi__context *s) +{ + // conceptually rewind SHOULD rewind to the beginning of the stream, + // but we just rewind to the beginning of the initial buffer, because + // we only use it after doing 'test', which only ever looks at at most 92 bytes + s->img_buffer = s->img_buffer_original; + s->img_buffer_end = s->img_buffer_original_end; +} + +#ifndef STBI_NO_JPEG +static int stbi__jpeg_test(stbi__context *s); +static stbi_uc *stbi__jpeg_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__jpeg_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PNG +static int stbi__png_test(stbi__context *s); +static stbi_uc *stbi__png_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__png_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_BMP +static int stbi__bmp_test(stbi__context *s); +static stbi_uc *stbi__bmp_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__bmp_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_TGA +static int stbi__tga_test(stbi__context *s); +static stbi_uc *stbi__tga_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__tga_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PSD +static int stbi__psd_test(stbi__context *s); +static stbi_uc *stbi__psd_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__psd_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_HDR +static int stbi__hdr_test(stbi__context *s); +static float *stbi__hdr_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__hdr_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PIC +static int stbi__pic_test(stbi__context *s); +static stbi_uc *stbi__pic_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__pic_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_GIF +static int stbi__gif_test(stbi__context *s); +static stbi_uc *stbi__gif_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__gif_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PNM +static int stbi__pnm_test(stbi__context *s); +static stbi_uc *stbi__pnm_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__pnm_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +// this is not threadsafe +static const char *stbi__g_failure_reason; + +STBIDEF const char *stbi_failure_reason(void) +{ + return stbi__g_failure_reason; +} + +static int stbi__err(const char *str) +{ + stbi__g_failure_reason = str; + return 0; +} + +static void *stbi__malloc(size_t size) +{ + return STBI_MALLOC(size); +} + +// stbi__err - error +// stbi__errpf - error returning pointer to float +// stbi__errpuc - error returning pointer to unsigned char + +#ifdef STBI_NO_FAILURE_STRINGS + #define stbi__err(x,y) 0 +#elif defined(STBI_FAILURE_USERMSG) + #define stbi__err(x,y) stbi__err(y) +#else + #define stbi__err(x,y) stbi__err(x) +#endif + +#define stbi__errpf(x,y) ((float *)(size_t) (stbi__err(x,y)?NULL:NULL)) +#define stbi__errpuc(x,y) ((unsigned char *)(size_t) (stbi__err(x,y)?NULL:NULL)) + +STBIDEF void stbi_image_free(void *retval_from_stbi_load) +{ + STBI_FREE(retval_from_stbi_load); +} + +#ifndef STBI_NO_LINEAR +static float *stbi__ldr_to_hdr(stbi_uc *data, int x, int y, int comp); +#endif + +#ifndef STBI_NO_HDR +static stbi_uc *stbi__hdr_to_ldr(float *data, int x, int y, int comp); +#endif + +static int stbi__vertically_flip_on_load = 0; + +STBIDEF void stbi_set_flip_vertically_on_load(int flag_true_if_should_flip) +{ + stbi__vertically_flip_on_load = flag_true_if_should_flip; +} + +static unsigned char *stbi__load_main(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + #ifndef STBI_NO_JPEG + if (stbi__jpeg_test(s)) return stbi__jpeg_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PNG + if (stbi__png_test(s)) return stbi__png_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_BMP + if (stbi__bmp_test(s)) return stbi__bmp_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_GIF + if (stbi__gif_test(s)) return stbi__gif_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PSD + if (stbi__psd_test(s)) return stbi__psd_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PIC + if (stbi__pic_test(s)) return stbi__pic_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PNM + if (stbi__pnm_test(s)) return stbi__pnm_load(s,x,y,comp,req_comp); + #endif + + #ifndef STBI_NO_HDR + if (stbi__hdr_test(s)) { + float *hdr = stbi__hdr_load(s, x,y,comp,req_comp); + return stbi__hdr_to_ldr(hdr, *x, *y, req_comp ? req_comp : *comp); + } + #endif + + #ifndef STBI_NO_TGA + // test tga last because it's a crappy test! + if (stbi__tga_test(s)) + return stbi__tga_load(s,x,y,comp,req_comp); + #endif + + return stbi__errpuc("unknown image type", "Image not of any known type, or corrupt"); +} + +static unsigned char *stbi__load_flip(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *result = stbi__load_main(s, x, y, comp, req_comp); + + if (stbi__vertically_flip_on_load && result != NULL) { + int w = *x, h = *y; + int depth = req_comp ? req_comp : *comp; + int row,col,z; + stbi_uc temp; + + // @OPTIMIZE: use a bigger temp buffer and memcpy multiple pixels at once + for (row = 0; row < (h>>1); row++) { + for (col = 0; col < w; col++) { + for (z = 0; z < depth; z++) { + temp = result[(row * w + col) * depth + z]; + result[(row * w + col) * depth + z] = result[((h - row - 1) * w + col) * depth + z]; + result[((h - row - 1) * w + col) * depth + z] = temp; + } + } + } + } + + return result; +} + +#ifndef STBI_NO_HDR +static void stbi__float_postprocess(float *result, int *x, int *y, int *comp, int req_comp) +{ + if (stbi__vertically_flip_on_load && result != NULL) { + int w = *x, h = *y; + int depth = req_comp ? req_comp : *comp; + int row,col,z; + float temp; + + // @OPTIMIZE: use a bigger temp buffer and memcpy multiple pixels at once + for (row = 0; row < (h>>1); row++) { + for (col = 0; col < w; col++) { + for (z = 0; z < depth; z++) { + temp = result[(row * w + col) * depth + z]; + result[(row * w + col) * depth + z] = result[((h - row - 1) * w + col) * depth + z]; + result[((h - row - 1) * w + col) * depth + z] = temp; + } + } + } + } +} +#endif + +#ifndef STBI_NO_STDIO + +static FILE *stbi__fopen(char const *filename, char const *mode) +{ + FILE *f; +#if defined(_MSC_VER) && _MSC_VER >= 1400 + if (0 != fopen_s(&f, filename, mode)) + f=0; +#else + f = fopen(filename, mode); +#endif + return f; +} + + +STBIDEF stbi_uc *stbi_load(char const *filename, int *x, int *y, int *comp, int req_comp) +{ + FILE *f = stbi__fopen(filename, "rb"); + unsigned char *result; + if (!f) return stbi__errpuc("can't fopen", "Unable to open file"); + result = stbi_load_from_file(f,x,y,comp,req_comp); + fclose(f); + return result; +} + +STBIDEF stbi_uc *stbi_load_from_file(FILE *f, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *result; + stbi__context s; + stbi__start_file(&s,f); + result = stbi__load_flip(&s,x,y,comp,req_comp); + if (result) { + // need to 'unget' all the characters in the IO buffer + fseek(f, - (int) (s.img_buffer_end - s.img_buffer), SEEK_CUR); + } + return result; +} +#endif //!STBI_NO_STDIO + +STBIDEF stbi_uc *stbi_load_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__load_flip(&s,x,y,comp,req_comp); +} + +STBIDEF stbi_uc *stbi_load_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__load_flip(&s,x,y,comp,req_comp); +} + +#ifndef STBI_NO_LINEAR +static float *stbi__loadf_main(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *data; + #ifndef STBI_NO_HDR + if (stbi__hdr_test(s)) { + float *hdr_data = stbi__hdr_load(s,x,y,comp,req_comp); + if (hdr_data) + stbi__float_postprocess(hdr_data,x,y,comp,req_comp); + return hdr_data; + } + #endif + data = stbi__load_flip(s, x, y, comp, req_comp); + if (data) + return stbi__ldr_to_hdr(data, *x, *y, req_comp ? req_comp : *comp); + return stbi__errpf("unknown image type", "Image not of any known type, or corrupt"); +} + +STBIDEF float *stbi_loadf_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} + +STBIDEF float *stbi_loadf_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} + +#ifndef STBI_NO_STDIO +STBIDEF float *stbi_loadf(char const *filename, int *x, int *y, int *comp, int req_comp) +{ + float *result; + FILE *f = stbi__fopen(filename, "rb"); + if (!f) return stbi__errpf("can't fopen", "Unable to open file"); + result = stbi_loadf_from_file(f,x,y,comp,req_comp); + fclose(f); + return result; +} + +STBIDEF float *stbi_loadf_from_file(FILE *f, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_file(&s,f); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} +#endif // !STBI_NO_STDIO + +#endif // !STBI_NO_LINEAR + +// these is-hdr-or-not is defined independent of whether STBI_NO_LINEAR is +// defined, for API simplicity; if STBI_NO_LINEAR is defined, it always +// reports false! + +STBIDEF int stbi_is_hdr_from_memory(stbi_uc const *buffer, int len) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(buffer); + STBI_NOTUSED(len); + return 0; + #endif +} + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_is_hdr (char const *filename) +{ + FILE *f = stbi__fopen(filename, "rb"); + int result=0; + if (f) { + result = stbi_is_hdr_from_file(f); + fclose(f); + } + return result; +} + +STBIDEF int stbi_is_hdr_from_file(FILE *f) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_file(&s,f); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(f); + return 0; + #endif +} +#endif // !STBI_NO_STDIO + +STBIDEF int stbi_is_hdr_from_callbacks(stbi_io_callbacks const *clbk, void *user) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(clbk); + STBI_NOTUSED(user); + return 0; + #endif +} + +#ifndef STBI_NO_LINEAR +static float stbi__l2h_gamma=2.2f, stbi__l2h_scale=1.0f; + +STBIDEF void stbi_ldr_to_hdr_gamma(float gamma) { stbi__l2h_gamma = gamma; } +STBIDEF void stbi_ldr_to_hdr_scale(float scale) { stbi__l2h_scale = scale; } +#endif + +static float stbi__h2l_gamma_i=1.0f/2.2f, stbi__h2l_scale_i=1.0f; + +STBIDEF void stbi_hdr_to_ldr_gamma(float gamma) { stbi__h2l_gamma_i = 1/gamma; } +STBIDEF void stbi_hdr_to_ldr_scale(float scale) { stbi__h2l_scale_i = 1/scale; } + + +////////////////////////////////////////////////////////////////////////////// +// +// Common code used by all image loaders +// + +enum +{ + STBI__SCAN_load=0, + STBI__SCAN_type, + STBI__SCAN_header +}; + +static void stbi__refill_buffer(stbi__context *s) +{ + int n = (s->io.read)(s->io_user_data,(char*)s->buffer_start,s->buflen); + if (n == 0) { + // at end of file, treat same as if from memory, but need to handle case + // where s->img_buffer isn't pointing to safe memory, e.g. 0-byte file + s->read_from_callbacks = 0; + s->img_buffer = s->buffer_start; + s->img_buffer_end = s->buffer_start+1; + *s->img_buffer = 0; + } else { + s->img_buffer = s->buffer_start; + s->img_buffer_end = s->buffer_start + n; + } +} + +stbi_inline static stbi_uc stbi__get8(stbi__context *s) +{ + if (s->img_buffer < s->img_buffer_end) + return *s->img_buffer++; + if (s->read_from_callbacks) { + stbi__refill_buffer(s); + return *s->img_buffer++; + } + return 0; +} + +stbi_inline static int stbi__at_eof(stbi__context *s) +{ + if (s->io.read) { + if (!(s->io.eof)(s->io_user_data)) return 0; + // if feof() is true, check if buffer = end + // special case: we've only got the special 0 character at the end + if (s->read_from_callbacks == 0) return 1; + } + + return s->img_buffer >= s->img_buffer_end; +} + +static void stbi__skip(stbi__context *s, int n) +{ + if (n < 0) { + s->img_buffer = s->img_buffer_end; + return; + } + if (s->io.read) { + int blen = (int) (s->img_buffer_end - s->img_buffer); + if (blen < n) { + s->img_buffer = s->img_buffer_end; + (s->io.skip)(s->io_user_data, n - blen); + return; + } + } + s->img_buffer += n; +} + +static int stbi__getn(stbi__context *s, stbi_uc *buffer, int n) +{ + if (s->io.read) { + int blen = (int) (s->img_buffer_end - s->img_buffer); + if (blen < n) { + int res, count; + + memcpy(buffer, s->img_buffer, blen); + + count = (s->io.read)(s->io_user_data, (char*) buffer + blen, n - blen); + res = (count == (n-blen)); + s->img_buffer = s->img_buffer_end; + return res; + } + } + + if (s->img_buffer+n <= s->img_buffer_end) { + memcpy(buffer, s->img_buffer, n); + s->img_buffer += n; + return 1; + } else + return 0; +} + +static int stbi__get16be(stbi__context *s) +{ + int z = stbi__get8(s); + return (z << 8) + stbi__get8(s); +} + +static stbi__uint32 stbi__get32be(stbi__context *s) +{ + stbi__uint32 z = stbi__get16be(s); + return (z << 16) + stbi__get16be(s); +} + +#if defined(STBI_NO_BMP) && defined(STBI_NO_TGA) && defined(STBI_NO_GIF) +// nothing +#else +static int stbi__get16le(stbi__context *s) +{ + int z = stbi__get8(s); + return z + (stbi__get8(s) << 8); +} +#endif + +#ifndef STBI_NO_BMP +static stbi__uint32 stbi__get32le(stbi__context *s) +{ + stbi__uint32 z = stbi__get16le(s); + return z + (stbi__get16le(s) << 16); +} +#endif + +#define STBI__BYTECAST(x) ((stbi_uc) ((x) & 255)) // truncate int to byte without warnings + + +////////////////////////////////////////////////////////////////////////////// +// +// generic converter from built-in img_n to req_comp +// individual types do this automatically as much as possible (e.g. jpeg +// does all cases internally since it needs to colorspace convert anyway, +// and it never has alpha, so very few cases ). png can automatically +// interleave an alpha=255 channel, but falls back to this for other cases +// +// assume data buffer is malloced, so malloc a new one and free that one +// only failure mode is malloc failing + +static stbi_uc stbi__compute_y(int r, int g, int b) +{ + return (stbi_uc) (((r*77) + (g*150) + (29*b)) >> 8); +} + +static unsigned char *stbi__convert_format(unsigned char *data, int img_n, int req_comp, unsigned int x, unsigned int y) +{ + int i,j; + unsigned char *good; + + if (req_comp == img_n) return data; + STBI_ASSERT(req_comp >= 1 && req_comp <= 4); + + good = (unsigned char *) stbi__malloc(req_comp * x * y); + if (good == NULL) { + STBI_FREE(data); + return stbi__errpuc("outofmem", "Out of memory"); + } + + for (j=0; j < (int) y; ++j) { + unsigned char *src = data + j * x * img_n ; + unsigned char *dest = good + j * x * req_comp; + + #define COMBO(a,b) ((a)*8+(b)) + #define CASE(a,b) case COMBO(a,b): for(i=x-1; i >= 0; --i, src += a, dest += b) + // convert source image with img_n components to one with req_comp components; + // avoid switch per pixel, so use switch per scanline and massive macros + switch (COMBO(img_n, req_comp)) { + CASE(1,2) dest[0]=src[0], dest[1]=255; break; + CASE(1,3) dest[0]=dest[1]=dest[2]=src[0]; break; + CASE(1,4) dest[0]=dest[1]=dest[2]=src[0], dest[3]=255; break; + CASE(2,1) dest[0]=src[0]; break; + CASE(2,3) dest[0]=dest[1]=dest[2]=src[0]; break; + CASE(2,4) dest[0]=dest[1]=dest[2]=src[0], dest[3]=src[1]; break; + CASE(3,4) dest[0]=src[0],dest[1]=src[1],dest[2]=src[2],dest[3]=255; break; + CASE(3,1) dest[0]=stbi__compute_y(src[0],src[1],src[2]); break; + CASE(3,2) dest[0]=stbi__compute_y(src[0],src[1],src[2]), dest[1] = 255; break; + CASE(4,1) dest[0]=stbi__compute_y(src[0],src[1],src[2]); break; + CASE(4,2) dest[0]=stbi__compute_y(src[0],src[1],src[2]), dest[1] = src[3]; break; + CASE(4,3) dest[0]=src[0],dest[1]=src[1],dest[2]=src[2]; break; + default: STBI_ASSERT(0); + } + #undef CASE + } + + STBI_FREE(data); + return good; +} + +#ifndef STBI_NO_LINEAR +static float *stbi__ldr_to_hdr(stbi_uc *data, int x, int y, int comp) +{ + int i,k,n; + float *output = (float *) stbi__malloc(x * y * comp * sizeof(float)); + if (output == NULL) { STBI_FREE(data); return stbi__errpf("outofmem", "Out of memory"); } + // compute number of non-alpha components + if (comp & 1) n = comp; else n = comp-1; + for (i=0; i < x*y; ++i) { + for (k=0; k < n; ++k) { + output[i*comp + k] = (float) (pow(data[i*comp+k]/255.0f, stbi__l2h_gamma) * stbi__l2h_scale); + } + if (k < comp) output[i*comp + k] = data[i*comp+k]/255.0f; + } + STBI_FREE(data); + return output; +} +#endif + +#ifndef STBI_NO_HDR +#define stbi__float2int(x) ((int) (x)) +static stbi_uc *stbi__hdr_to_ldr(float *data, int x, int y, int comp) +{ + int i,k,n; + stbi_uc *output = (stbi_uc *) stbi__malloc(x * y * comp); + if (output == NULL) { STBI_FREE(data); return stbi__errpuc("outofmem", "Out of memory"); } + // compute number of non-alpha components + if (comp & 1) n = comp; else n = comp-1; + for (i=0; i < x*y; ++i) { + for (k=0; k < n; ++k) { + float z = (float) pow(data[i*comp+k]*stbi__h2l_scale_i, stbi__h2l_gamma_i) * 255 + 0.5f; + if (z < 0) z = 0; + if (z > 255) z = 255; + output[i*comp + k] = (stbi_uc) stbi__float2int(z); + } + if (k < comp) { + float z = data[i*comp+k] * 255 + 0.5f; + if (z < 0) z = 0; + if (z > 255) z = 255; + output[i*comp + k] = (stbi_uc) stbi__float2int(z); + } + } + STBI_FREE(data); + return output; +} +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// "baseline" JPEG/JFIF decoder +// +// simple implementation +// - doesn't support delayed output of y-dimension +// - simple interface (only one output format: 8-bit interleaved RGB) +// - doesn't try to recover corrupt jpegs +// - doesn't allow partial loading, loading multiple at once +// - still fast on x86 (copying globals into locals doesn't help x86) +// - allocates lots of intermediate memory (full size of all components) +// - non-interleaved case requires this anyway +// - allows good upsampling (see next) +// high-quality +// - upsampled channels are bilinearly interpolated, even across blocks +// - quality integer IDCT derived from IJG's 'slow' +// performance +// - fast huffman; reasonable integer IDCT +// - some SIMD kernels for common paths on targets with SSE2/NEON +// - uses a lot of intermediate memory, could cache poorly + +#ifndef STBI_NO_JPEG + +// huffman decoding acceleration +#define FAST_BITS 9 // larger handles more cases; smaller stomps less cache + +typedef struct +{ + stbi_uc fast[1 << FAST_BITS]; + // weirdly, repacking this into AoS is a 10% speed loss, instead of a win + stbi__uint16 code[256]; + stbi_uc values[256]; + stbi_uc size[257]; + unsigned int maxcode[18]; + int delta[17]; // old 'firstsymbol' - old 'firstcode' +} stbi__huffman; + +typedef struct +{ + stbi__context *s; + stbi__huffman huff_dc[4]; + stbi__huffman huff_ac[4]; + stbi_uc dequant[4][64]; + stbi__int16 fast_ac[4][1 << FAST_BITS]; + +// sizes for components, interleaved MCUs + int img_h_max, img_v_max; + int img_mcu_x, img_mcu_y; + int img_mcu_w, img_mcu_h; + +// definition of jpeg image component + struct + { + int id; + int h,v; + int tq; + int hd,ha; + int dc_pred; + + int x,y,w2,h2; + stbi_uc *data; + void *raw_data, *raw_coeff; + stbi_uc *linebuf; + short *coeff; // progressive only + int coeff_w, coeff_h; // number of 8x8 coefficient blocks + } img_comp[4]; + + stbi__uint32 code_buffer; // jpeg entropy-coded buffer + int code_bits; // number of valid bits + unsigned char marker; // marker seen while filling entropy buffer + int nomore; // flag if we saw a marker so must stop + + int progressive; + int spec_start; + int spec_end; + int succ_high; + int succ_low; + int eob_run; + + int scan_n, order[4]; + int restart_interval, todo; + +// kernels + void (*idct_block_kernel)(stbi_uc *out, int out_stride, short data[64]); + void (*YCbCr_to_RGB_kernel)(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step); + stbi_uc *(*resample_row_hv_2_kernel)(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs); +} stbi__jpeg; + +static int stbi__build_huffman(stbi__huffman *h, int *count) +{ + int i,j,k=0,code; + // build size list for each symbol (from JPEG spec) + for (i=0; i < 16; ++i) + for (j=0; j < count[i]; ++j) + h->size[k++] = (stbi_uc) (i+1); + h->size[k] = 0; + + // compute actual symbols (from jpeg spec) + code = 0; + k = 0; + for(j=1; j <= 16; ++j) { + // compute delta to add to code to compute symbol id + h->delta[j] = k - code; + if (h->size[k] == j) { + while (h->size[k] == j) + h->code[k++] = (stbi__uint16) (code++); + if (code-1 >= (1 << j)) return stbi__err("bad code lengths","Corrupt JPEG"); + } + // compute largest code + 1 for this size, preshifted as needed later + h->maxcode[j] = code << (16-j); + code <<= 1; + } + h->maxcode[j] = 0xffffffff; + + // build non-spec acceleration table; 255 is flag for not-accelerated + memset(h->fast, 255, 1 << FAST_BITS); + for (i=0; i < k; ++i) { + int s = h->size[i]; + if (s <= FAST_BITS) { + int c = h->code[i] << (FAST_BITS-s); + int m = 1 << (FAST_BITS-s); + for (j=0; j < m; ++j) { + h->fast[c+j] = (stbi_uc) i; + } + } + } + return 1; +} + +// build a table that decodes both magnitude and value of small ACs in +// one go. +static void stbi__build_fast_ac(stbi__int16 *fast_ac, stbi__huffman *h) +{ + int i; + for (i=0; i < (1 << FAST_BITS); ++i) { + stbi_uc fast = h->fast[i]; + fast_ac[i] = 0; + if (fast < 255) { + int rs = h->values[fast]; + int run = (rs >> 4) & 15; + int magbits = rs & 15; + int len = h->size[fast]; + + if (magbits && len + magbits <= FAST_BITS) { + // magnitude code followed by receive_extend code + int k = ((i << len) & ((1 << FAST_BITS) - 1)) >> (FAST_BITS - magbits); + int m = 1 << (magbits - 1); + if (k < m) k += (-1 << magbits) + 1; + // if the result is small enough, we can fit it in fast_ac table + if (k >= -128 && k <= 127) + fast_ac[i] = (stbi__int16) ((k << 8) + (run << 4) + (len + magbits)); + } + } + } +} + +static void stbi__grow_buffer_unsafe(stbi__jpeg *j) +{ + do { + int b = j->nomore ? 0 : stbi__get8(j->s); + if (b == 0xff) { + int c = stbi__get8(j->s); + if (c != 0) { + j->marker = (unsigned char) c; + j->nomore = 1; + return; + } + } + j->code_buffer |= b << (24 - j->code_bits); + j->code_bits += 8; + } while (j->code_bits <= 24); +} + +// (1 << n) - 1 +static stbi__uint32 stbi__bmask[17]={0,1,3,7,15,31,63,127,255,511,1023,2047,4095,8191,16383,32767,65535}; + +// decode a jpeg huffman value from the bitstream +stbi_inline static int stbi__jpeg_huff_decode(stbi__jpeg *j, stbi__huffman *h) +{ + unsigned int temp; + int c,k; + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + + // look at the top FAST_BITS and determine what symbol ID it is, + // if the code is <= FAST_BITS + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + k = h->fast[c]; + if (k < 255) { + int s = h->size[k]; + if (s > j->code_bits) + return -1; + j->code_buffer <<= s; + j->code_bits -= s; + return h->values[k]; + } + + // naive test is to shift the code_buffer down so k bits are + // valid, then test against maxcode. To speed this up, we've + // preshifted maxcode left so that it has (16-k) 0s at the + // end; in other words, regardless of the number of bits, it + // wants to be compared against something shifted to have 16; + // that way we don't need to shift inside the loop. + temp = j->code_buffer >> 16; + for (k=FAST_BITS+1 ; ; ++k) + if (temp < h->maxcode[k]) + break; + if (k == 17) { + // error! code not found + j->code_bits -= 16; + return -1; + } + + if (k > j->code_bits) + return -1; + + // convert the huffman code to the symbol id + c = ((j->code_buffer >> (32 - k)) & stbi__bmask[k]) + h->delta[k]; + STBI_ASSERT((((j->code_buffer) >> (32 - h->size[c])) & stbi__bmask[h->size[c]]) == h->code[c]); + + // convert the id to a symbol + j->code_bits -= k; + j->code_buffer <<= k; + return h->values[c]; +} + +// bias[n] = (-1<code_bits < n) stbi__grow_buffer_unsafe(j); + + sgn = (stbi__int32)j->code_buffer >> 31; // sign bit is always in MSB + k = stbi_lrot(j->code_buffer, n); + STBI_ASSERT(n >= 0 && n < (int) (sizeof(stbi__bmask)/sizeof(*stbi__bmask))); + j->code_buffer = k & ~stbi__bmask[n]; + k &= stbi__bmask[n]; + j->code_bits -= n; + return k + (stbi__jbias[n] & ~sgn); +} + +// get some unsigned bits +stbi_inline static int stbi__jpeg_get_bits(stbi__jpeg *j, int n) +{ + unsigned int k; + if (j->code_bits < n) stbi__grow_buffer_unsafe(j); + k = stbi_lrot(j->code_buffer, n); + j->code_buffer = k & ~stbi__bmask[n]; + k &= stbi__bmask[n]; + j->code_bits -= n; + return k; +} + +stbi_inline static int stbi__jpeg_get_bit(stbi__jpeg *j) +{ + unsigned int k; + if (j->code_bits < 1) stbi__grow_buffer_unsafe(j); + k = j->code_buffer; + j->code_buffer <<= 1; + --j->code_bits; + return k & 0x80000000; +} + +// given a value that's at position X in the zigzag stream, +// where does it appear in the 8x8 matrix coded as row-major? +static stbi_uc stbi__jpeg_dezigzag[64+15] = +{ + 0, 1, 8, 16, 9, 2, 3, 10, + 17, 24, 32, 25, 18, 11, 4, 5, + 12, 19, 26, 33, 40, 48, 41, 34, + 27, 20, 13, 6, 7, 14, 21, 28, + 35, 42, 49, 56, 57, 50, 43, 36, + 29, 22, 15, 23, 30, 37, 44, 51, + 58, 59, 52, 45, 38, 31, 39, 46, + 53, 60, 61, 54, 47, 55, 62, 63, + // let corrupt input sample past end + 63, 63, 63, 63, 63, 63, 63, 63, + 63, 63, 63, 63, 63, 63, 63 +}; + +// decode one 64-entry block-- +static int stbi__jpeg_decode_block(stbi__jpeg *j, short data[64], stbi__huffman *hdc, stbi__huffman *hac, stbi__int16 *fac, int b, stbi_uc *dequant) +{ + int diff,dc,k; + int t; + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + t = stbi__jpeg_huff_decode(j, hdc); + if (t < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + + // 0 all the ac values now so we can do it 32-bits at a time + memset(data,0,64*sizeof(data[0])); + + diff = t ? stbi__extend_receive(j, t) : 0; + dc = j->img_comp[b].dc_pred + diff; + j->img_comp[b].dc_pred = dc; + data[0] = (short) (dc * dequant[0]); + + // decode AC components, see JPEG spec + k = 1; + do { + unsigned int zig; + int c,r,s; + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + r = fac[c]; + if (r) { // fast-AC path + k += (r >> 4) & 15; // run + s = r & 15; // combined length + j->code_buffer <<= s; + j->code_bits -= s; + // decode into unzigzag'd location + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) ((r >> 8) * dequant[zig]); + } else { + int rs = stbi__jpeg_huff_decode(j, hac); + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (rs != 0xf0) break; // end block + k += 16; + } else { + k += r; + // decode into unzigzag'd location + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) (stbi__extend_receive(j,s) * dequant[zig]); + } + } + } while (k < 64); + return 1; +} + +static int stbi__jpeg_decode_block_prog_dc(stbi__jpeg *j, short data[64], stbi__huffman *hdc, int b) +{ + int diff,dc; + int t; + if (j->spec_end != 0) return stbi__err("can't merge dc and ac", "Corrupt JPEG"); + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + + if (j->succ_high == 0) { + // first scan for DC coefficient, must be first + memset(data,0,64*sizeof(data[0])); // 0 all the ac values now + t = stbi__jpeg_huff_decode(j, hdc); + diff = t ? stbi__extend_receive(j, t) : 0; + + dc = j->img_comp[b].dc_pred + diff; + j->img_comp[b].dc_pred = dc; + data[0] = (short) (dc << j->succ_low); + } else { + // refinement scan for DC coefficient + if (stbi__jpeg_get_bit(j)) + data[0] += (short) (1 << j->succ_low); + } + return 1; +} + +// @OPTIMIZE: store non-zigzagged during the decode passes, +// and only de-zigzag when dequantizing +static int stbi__jpeg_decode_block_prog_ac(stbi__jpeg *j, short data[64], stbi__huffman *hac, stbi__int16 *fac) +{ + int k; + if (j->spec_start == 0) return stbi__err("can't merge dc and ac", "Corrupt JPEG"); + + if (j->succ_high == 0) { + int shift = j->succ_low; + + if (j->eob_run) { + --j->eob_run; + return 1; + } + + k = j->spec_start; + do { + unsigned int zig; + int c,r,s; + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + r = fac[c]; + if (r) { // fast-AC path + k += (r >> 4) & 15; // run + s = r & 15; // combined length + j->code_buffer <<= s; + j->code_bits -= s; + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) ((r >> 8) << shift); + } else { + int rs = stbi__jpeg_huff_decode(j, hac); + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (r < 15) { + j->eob_run = (1 << r); + if (r) + j->eob_run += stbi__jpeg_get_bits(j, r); + --j->eob_run; + break; + } + k += 16; + } else { + k += r; + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) (stbi__extend_receive(j,s) << shift); + } + } + } while (k <= j->spec_end); + } else { + // refinement scan for these AC coefficients + + short bit = (short) (1 << j->succ_low); + + if (j->eob_run) { + --j->eob_run; + for (k = j->spec_start; k <= j->spec_end; ++k) { + short *p = &data[stbi__jpeg_dezigzag[k]]; + if (*p != 0) + if (stbi__jpeg_get_bit(j)) + if ((*p & bit)==0) { + if (*p > 0) + *p += bit; + else + *p -= bit; + } + } + } else { + k = j->spec_start; + do { + int r,s; + int rs = stbi__jpeg_huff_decode(j, hac); // @OPTIMIZE see if we can use the fast path here, advance-by-r is so slow, eh + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (r < 15) { + j->eob_run = (1 << r) - 1; + if (r) + j->eob_run += stbi__jpeg_get_bits(j, r); + r = 64; // force end of block + } else { + // r=15 s=0 should write 16 0s, so we just do + // a run of 15 0s and then write s (which is 0), + // so we don't have to do anything special here + } + } else { + if (s != 1) return stbi__err("bad huffman code", "Corrupt JPEG"); + // sign bit + if (stbi__jpeg_get_bit(j)) + s = bit; + else + s = -bit; + } + + // advance by r + while (k <= j->spec_end) { + short *p = &data[stbi__jpeg_dezigzag[k++]]; + if (*p != 0) { + if (stbi__jpeg_get_bit(j)) + if ((*p & bit)==0) { + if (*p > 0) + *p += bit; + else + *p -= bit; + } + } else { + if (r == 0) { + *p = (short) s; + break; + } + --r; + } + } + } while (k <= j->spec_end); + } + } + return 1; +} + +// take a -128..127 value and stbi__clamp it and convert to 0..255 +stbi_inline static stbi_uc stbi__clamp(int x) +{ + // trick to use a single test to catch both cases + if ((unsigned int) x > 255) { + if (x < 0) return 0; + if (x > 255) return 255; + } + return (stbi_uc) x; +} + +#define stbi__f2f(x) ((int) (((x) * 4096 + 0.5))) +#define stbi__fsh(x) ((x) << 12) + +// derived from jidctint -- DCT_ISLOW +#define STBI__IDCT_1D(s0,s1,s2,s3,s4,s5,s6,s7) \ + int t0,t1,t2,t3,p1,p2,p3,p4,p5,x0,x1,x2,x3; \ + p2 = s2; \ + p3 = s6; \ + p1 = (p2+p3) * stbi__f2f(0.5411961f); \ + t2 = p1 + p3*stbi__f2f(-1.847759065f); \ + t3 = p1 + p2*stbi__f2f( 0.765366865f); \ + p2 = s0; \ + p3 = s4; \ + t0 = stbi__fsh(p2+p3); \ + t1 = stbi__fsh(p2-p3); \ + x0 = t0+t3; \ + x3 = t0-t3; \ + x1 = t1+t2; \ + x2 = t1-t2; \ + t0 = s7; \ + t1 = s5; \ + t2 = s3; \ + t3 = s1; \ + p3 = t0+t2; \ + p4 = t1+t3; \ + p1 = t0+t3; \ + p2 = t1+t2; \ + p5 = (p3+p4)*stbi__f2f( 1.175875602f); \ + t0 = t0*stbi__f2f( 0.298631336f); \ + t1 = t1*stbi__f2f( 2.053119869f); \ + t2 = t2*stbi__f2f( 3.072711026f); \ + t3 = t3*stbi__f2f( 1.501321110f); \ + p1 = p5 + p1*stbi__f2f(-0.899976223f); \ + p2 = p5 + p2*stbi__f2f(-2.562915447f); \ + p3 = p3*stbi__f2f(-1.961570560f); \ + p4 = p4*stbi__f2f(-0.390180644f); \ + t3 += p1+p4; \ + t2 += p2+p3; \ + t1 += p2+p4; \ + t0 += p1+p3; + +static void stbi__idct_block(stbi_uc *out, int out_stride, short data[64]) +{ + int i,val[64],*v=val; + stbi_uc *o; + short *d = data; + + // columns + for (i=0; i < 8; ++i,++d, ++v) { + // if all zeroes, shortcut -- this avoids dequantizing 0s and IDCTing + if (d[ 8]==0 && d[16]==0 && d[24]==0 && d[32]==0 + && d[40]==0 && d[48]==0 && d[56]==0) { + // no shortcut 0 seconds + // (1|2|3|4|5|6|7)==0 0 seconds + // all separate -0.047 seconds + // 1 && 2|3 && 4|5 && 6|7: -0.047 seconds + int dcterm = d[0] << 2; + v[0] = v[8] = v[16] = v[24] = v[32] = v[40] = v[48] = v[56] = dcterm; + } else { + STBI__IDCT_1D(d[ 0],d[ 8],d[16],d[24],d[32],d[40],d[48],d[56]) + // constants scaled things up by 1<<12; let's bring them back + // down, but keep 2 extra bits of precision + x0 += 512; x1 += 512; x2 += 512; x3 += 512; + v[ 0] = (x0+t3) >> 10; + v[56] = (x0-t3) >> 10; + v[ 8] = (x1+t2) >> 10; + v[48] = (x1-t2) >> 10; + v[16] = (x2+t1) >> 10; + v[40] = (x2-t1) >> 10; + v[24] = (x3+t0) >> 10; + v[32] = (x3-t0) >> 10; + } + } + + for (i=0, v=val, o=out; i < 8; ++i,v+=8,o+=out_stride) { + // no fast case since the first 1D IDCT spread components out + STBI__IDCT_1D(v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7]) + // constants scaled things up by 1<<12, plus we had 1<<2 from first + // loop, plus horizontal and vertical each scale by sqrt(8) so together + // we've got an extra 1<<3, so 1<<17 total we need to remove. + // so we want to round that, which means adding 0.5 * 1<<17, + // aka 65536. Also, we'll end up with -128 to 127 that we want + // to encode as 0..255 by adding 128, so we'll add that before the shift + x0 += 65536 + (128<<17); + x1 += 65536 + (128<<17); + x2 += 65536 + (128<<17); + x3 += 65536 + (128<<17); + // tried computing the shifts into temps, or'ing the temps to see + // if any were out of range, but that was slower + o[0] = stbi__clamp((x0+t3) >> 17); + o[7] = stbi__clamp((x0-t3) >> 17); + o[1] = stbi__clamp((x1+t2) >> 17); + o[6] = stbi__clamp((x1-t2) >> 17); + o[2] = stbi__clamp((x2+t1) >> 17); + o[5] = stbi__clamp((x2-t1) >> 17); + o[3] = stbi__clamp((x3+t0) >> 17); + o[4] = stbi__clamp((x3-t0) >> 17); + } +} + +#ifdef STBI_SSE2 +// sse2 integer IDCT. not the fastest possible implementation but it +// produces bit-identical results to the generic C version so it's +// fully "transparent". +static void stbi__idct_simd(stbi_uc *out, int out_stride, short data[64]) +{ + // This is constructed to match our regular (generic) integer IDCT exactly. + __m128i row0, row1, row2, row3, row4, row5, row6, row7; + __m128i tmp; + + // dot product constant: even elems=x, odd elems=y + #define dct_const(x,y) _mm_setr_epi16((x),(y),(x),(y),(x),(y),(x),(y)) + + // out(0) = c0[even]*x + c0[odd]*y (c0, x, y 16-bit, out 32-bit) + // out(1) = c1[even]*x + c1[odd]*y + #define dct_rot(out0,out1, x,y,c0,c1) \ + __m128i c0##lo = _mm_unpacklo_epi16((x),(y)); \ + __m128i c0##hi = _mm_unpackhi_epi16((x),(y)); \ + __m128i out0##_l = _mm_madd_epi16(c0##lo, c0); \ + __m128i out0##_h = _mm_madd_epi16(c0##hi, c0); \ + __m128i out1##_l = _mm_madd_epi16(c0##lo, c1); \ + __m128i out1##_h = _mm_madd_epi16(c0##hi, c1) + + // out = in << 12 (in 16-bit, out 32-bit) + #define dct_widen(out, in) \ + __m128i out##_l = _mm_srai_epi32(_mm_unpacklo_epi16(_mm_setzero_si128(), (in)), 4); \ + __m128i out##_h = _mm_srai_epi32(_mm_unpackhi_epi16(_mm_setzero_si128(), (in)), 4) + + // wide add + #define dct_wadd(out, a, b) \ + __m128i out##_l = _mm_add_epi32(a##_l, b##_l); \ + __m128i out##_h = _mm_add_epi32(a##_h, b##_h) + + // wide sub + #define dct_wsub(out, a, b) \ + __m128i out##_l = _mm_sub_epi32(a##_l, b##_l); \ + __m128i out##_h = _mm_sub_epi32(a##_h, b##_h) + + // butterfly a/b, add bias, then shift by "s" and pack + #define dct_bfly32o(out0, out1, a,b,bias,s) \ + { \ + __m128i abiased_l = _mm_add_epi32(a##_l, bias); \ + __m128i abiased_h = _mm_add_epi32(a##_h, bias); \ + dct_wadd(sum, abiased, b); \ + dct_wsub(dif, abiased, b); \ + out0 = _mm_packs_epi32(_mm_srai_epi32(sum_l, s), _mm_srai_epi32(sum_h, s)); \ + out1 = _mm_packs_epi32(_mm_srai_epi32(dif_l, s), _mm_srai_epi32(dif_h, s)); \ + } + + // 8-bit interleave step (for transposes) + #define dct_interleave8(a, b) \ + tmp = a; \ + a = _mm_unpacklo_epi8(a, b); \ + b = _mm_unpackhi_epi8(tmp, b) + + // 16-bit interleave step (for transposes) + #define dct_interleave16(a, b) \ + tmp = a; \ + a = _mm_unpacklo_epi16(a, b); \ + b = _mm_unpackhi_epi16(tmp, b) + + #define dct_pass(bias,shift) \ + { \ + /* even part */ \ + dct_rot(t2e,t3e, row2,row6, rot0_0,rot0_1); \ + __m128i sum04 = _mm_add_epi16(row0, row4); \ + __m128i dif04 = _mm_sub_epi16(row0, row4); \ + dct_widen(t0e, sum04); \ + dct_widen(t1e, dif04); \ + dct_wadd(x0, t0e, t3e); \ + dct_wsub(x3, t0e, t3e); \ + dct_wadd(x1, t1e, t2e); \ + dct_wsub(x2, t1e, t2e); \ + /* odd part */ \ + dct_rot(y0o,y2o, row7,row3, rot2_0,rot2_1); \ + dct_rot(y1o,y3o, row5,row1, rot3_0,rot3_1); \ + __m128i sum17 = _mm_add_epi16(row1, row7); \ + __m128i sum35 = _mm_add_epi16(row3, row5); \ + dct_rot(y4o,y5o, sum17,sum35, rot1_0,rot1_1); \ + dct_wadd(x4, y0o, y4o); \ + dct_wadd(x5, y1o, y5o); \ + dct_wadd(x6, y2o, y5o); \ + dct_wadd(x7, y3o, y4o); \ + dct_bfly32o(row0,row7, x0,x7,bias,shift); \ + dct_bfly32o(row1,row6, x1,x6,bias,shift); \ + dct_bfly32o(row2,row5, x2,x5,bias,shift); \ + dct_bfly32o(row3,row4, x3,x4,bias,shift); \ + } + + __m128i rot0_0 = dct_const(stbi__f2f(0.5411961f), stbi__f2f(0.5411961f) + stbi__f2f(-1.847759065f)); + __m128i rot0_1 = dct_const(stbi__f2f(0.5411961f) + stbi__f2f( 0.765366865f), stbi__f2f(0.5411961f)); + __m128i rot1_0 = dct_const(stbi__f2f(1.175875602f) + stbi__f2f(-0.899976223f), stbi__f2f(1.175875602f)); + __m128i rot1_1 = dct_const(stbi__f2f(1.175875602f), stbi__f2f(1.175875602f) + stbi__f2f(-2.562915447f)); + __m128i rot2_0 = dct_const(stbi__f2f(-1.961570560f) + stbi__f2f( 0.298631336f), stbi__f2f(-1.961570560f)); + __m128i rot2_1 = dct_const(stbi__f2f(-1.961570560f), stbi__f2f(-1.961570560f) + stbi__f2f( 3.072711026f)); + __m128i rot3_0 = dct_const(stbi__f2f(-0.390180644f) + stbi__f2f( 2.053119869f), stbi__f2f(-0.390180644f)); + __m128i rot3_1 = dct_const(stbi__f2f(-0.390180644f), stbi__f2f(-0.390180644f) + stbi__f2f( 1.501321110f)); + + // rounding biases in column/row passes, see stbi__idct_block for explanation. + __m128i bias_0 = _mm_set1_epi32(512); + __m128i bias_1 = _mm_set1_epi32(65536 + (128<<17)); + + // load + row0 = _mm_load_si128((const __m128i *) (data + 0*8)); + row1 = _mm_load_si128((const __m128i *) (data + 1*8)); + row2 = _mm_load_si128((const __m128i *) (data + 2*8)); + row3 = _mm_load_si128((const __m128i *) (data + 3*8)); + row4 = _mm_load_si128((const __m128i *) (data + 4*8)); + row5 = _mm_load_si128((const __m128i *) (data + 5*8)); + row6 = _mm_load_si128((const __m128i *) (data + 6*8)); + row7 = _mm_load_si128((const __m128i *) (data + 7*8)); + + // column pass + dct_pass(bias_0, 10); + + { + // 16bit 8x8 transpose pass 1 + dct_interleave16(row0, row4); + dct_interleave16(row1, row5); + dct_interleave16(row2, row6); + dct_interleave16(row3, row7); + + // transpose pass 2 + dct_interleave16(row0, row2); + dct_interleave16(row1, row3); + dct_interleave16(row4, row6); + dct_interleave16(row5, row7); + + // transpose pass 3 + dct_interleave16(row0, row1); + dct_interleave16(row2, row3); + dct_interleave16(row4, row5); + dct_interleave16(row6, row7); + } + + // row pass + dct_pass(bias_1, 17); + + { + // pack + __m128i p0 = _mm_packus_epi16(row0, row1); // a0a1a2a3...a7b0b1b2b3...b7 + __m128i p1 = _mm_packus_epi16(row2, row3); + __m128i p2 = _mm_packus_epi16(row4, row5); + __m128i p3 = _mm_packus_epi16(row6, row7); + + // 8bit 8x8 transpose pass 1 + dct_interleave8(p0, p2); // a0e0a1e1... + dct_interleave8(p1, p3); // c0g0c1g1... + + // transpose pass 2 + dct_interleave8(p0, p1); // a0c0e0g0... + dct_interleave8(p2, p3); // b0d0f0h0... + + // transpose pass 3 + dct_interleave8(p0, p2); // a0b0c0d0... + dct_interleave8(p1, p3); // a4b4c4d4... + + // store + _mm_storel_epi64((__m128i *) out, p0); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p0, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p2); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p2, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p1); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p1, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p3); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p3, 0x4e)); + } + +#undef dct_const +#undef dct_rot +#undef dct_widen +#undef dct_wadd +#undef dct_wsub +#undef dct_bfly32o +#undef dct_interleave8 +#undef dct_interleave16 +#undef dct_pass +} + +#endif // STBI_SSE2 + +#ifdef STBI_NEON + +// NEON integer IDCT. should produce bit-identical +// results to the generic C version. +static void stbi__idct_simd(stbi_uc *out, int out_stride, short data[64]) +{ + int16x8_t row0, row1, row2, row3, row4, row5, row6, row7; + + int16x4_t rot0_0 = vdup_n_s16(stbi__f2f(0.5411961f)); + int16x4_t rot0_1 = vdup_n_s16(stbi__f2f(-1.847759065f)); + int16x4_t rot0_2 = vdup_n_s16(stbi__f2f( 0.765366865f)); + int16x4_t rot1_0 = vdup_n_s16(stbi__f2f( 1.175875602f)); + int16x4_t rot1_1 = vdup_n_s16(stbi__f2f(-0.899976223f)); + int16x4_t rot1_2 = vdup_n_s16(stbi__f2f(-2.562915447f)); + int16x4_t rot2_0 = vdup_n_s16(stbi__f2f(-1.961570560f)); + int16x4_t rot2_1 = vdup_n_s16(stbi__f2f(-0.390180644f)); + int16x4_t rot3_0 = vdup_n_s16(stbi__f2f( 0.298631336f)); + int16x4_t rot3_1 = vdup_n_s16(stbi__f2f( 2.053119869f)); + int16x4_t rot3_2 = vdup_n_s16(stbi__f2f( 3.072711026f)); + int16x4_t rot3_3 = vdup_n_s16(stbi__f2f( 1.501321110f)); + +#define dct_long_mul(out, inq, coeff) \ + int32x4_t out##_l = vmull_s16(vget_low_s16(inq), coeff); \ + int32x4_t out##_h = vmull_s16(vget_high_s16(inq), coeff) + +#define dct_long_mac(out, acc, inq, coeff) \ + int32x4_t out##_l = vmlal_s16(acc##_l, vget_low_s16(inq), coeff); \ + int32x4_t out##_h = vmlal_s16(acc##_h, vget_high_s16(inq), coeff) + +#define dct_widen(out, inq) \ + int32x4_t out##_l = vshll_n_s16(vget_low_s16(inq), 12); \ + int32x4_t out##_h = vshll_n_s16(vget_high_s16(inq), 12) + +// wide add +#define dct_wadd(out, a, b) \ + int32x4_t out##_l = vaddq_s32(a##_l, b##_l); \ + int32x4_t out##_h = vaddq_s32(a##_h, b##_h) + +// wide sub +#define dct_wsub(out, a, b) \ + int32x4_t out##_l = vsubq_s32(a##_l, b##_l); \ + int32x4_t out##_h = vsubq_s32(a##_h, b##_h) + +// butterfly a/b, then shift using "shiftop" by "s" and pack +#define dct_bfly32o(out0,out1, a,b,shiftop,s) \ + { \ + dct_wadd(sum, a, b); \ + dct_wsub(dif, a, b); \ + out0 = vcombine_s16(shiftop(sum_l, s), shiftop(sum_h, s)); \ + out1 = vcombine_s16(shiftop(dif_l, s), shiftop(dif_h, s)); \ + } + +#define dct_pass(shiftop, shift) \ + { \ + /* even part */ \ + int16x8_t sum26 = vaddq_s16(row2, row6); \ + dct_long_mul(p1e, sum26, rot0_0); \ + dct_long_mac(t2e, p1e, row6, rot0_1); \ + dct_long_mac(t3e, p1e, row2, rot0_2); \ + int16x8_t sum04 = vaddq_s16(row0, row4); \ + int16x8_t dif04 = vsubq_s16(row0, row4); \ + dct_widen(t0e, sum04); \ + dct_widen(t1e, dif04); \ + dct_wadd(x0, t0e, t3e); \ + dct_wsub(x3, t0e, t3e); \ + dct_wadd(x1, t1e, t2e); \ + dct_wsub(x2, t1e, t2e); \ + /* odd part */ \ + int16x8_t sum15 = vaddq_s16(row1, row5); \ + int16x8_t sum17 = vaddq_s16(row1, row7); \ + int16x8_t sum35 = vaddq_s16(row3, row5); \ + int16x8_t sum37 = vaddq_s16(row3, row7); \ + int16x8_t sumodd = vaddq_s16(sum17, sum35); \ + dct_long_mul(p5o, sumodd, rot1_0); \ + dct_long_mac(p1o, p5o, sum17, rot1_1); \ + dct_long_mac(p2o, p5o, sum35, rot1_2); \ + dct_long_mul(p3o, sum37, rot2_0); \ + dct_long_mul(p4o, sum15, rot2_1); \ + dct_wadd(sump13o, p1o, p3o); \ + dct_wadd(sump24o, p2o, p4o); \ + dct_wadd(sump23o, p2o, p3o); \ + dct_wadd(sump14o, p1o, p4o); \ + dct_long_mac(x4, sump13o, row7, rot3_0); \ + dct_long_mac(x5, sump24o, row5, rot3_1); \ + dct_long_mac(x6, sump23o, row3, rot3_2); \ + dct_long_mac(x7, sump14o, row1, rot3_3); \ + dct_bfly32o(row0,row7, x0,x7,shiftop,shift); \ + dct_bfly32o(row1,row6, x1,x6,shiftop,shift); \ + dct_bfly32o(row2,row5, x2,x5,shiftop,shift); \ + dct_bfly32o(row3,row4, x3,x4,shiftop,shift); \ + } + + // load + row0 = vld1q_s16(data + 0*8); + row1 = vld1q_s16(data + 1*8); + row2 = vld1q_s16(data + 2*8); + row3 = vld1q_s16(data + 3*8); + row4 = vld1q_s16(data + 4*8); + row5 = vld1q_s16(data + 5*8); + row6 = vld1q_s16(data + 6*8); + row7 = vld1q_s16(data + 7*8); + + // add DC bias + row0 = vaddq_s16(row0, vsetq_lane_s16(1024, vdupq_n_s16(0), 0)); + + // column pass + dct_pass(vrshrn_n_s32, 10); + + // 16bit 8x8 transpose + { +// these three map to a single VTRN.16, VTRN.32, and VSWP, respectively. +// whether compilers actually get this is another story, sadly. +#define dct_trn16(x, y) { int16x8x2_t t = vtrnq_s16(x, y); x = t.val[0]; y = t.val[1]; } +#define dct_trn32(x, y) { int32x4x2_t t = vtrnq_s32(vreinterpretq_s32_s16(x), vreinterpretq_s32_s16(y)); x = vreinterpretq_s16_s32(t.val[0]); y = vreinterpretq_s16_s32(t.val[1]); } +#define dct_trn64(x, y) { int16x8_t x0 = x; int16x8_t y0 = y; x = vcombine_s16(vget_low_s16(x0), vget_low_s16(y0)); y = vcombine_s16(vget_high_s16(x0), vget_high_s16(y0)); } + + // pass 1 + dct_trn16(row0, row1); // a0b0a2b2a4b4a6b6 + dct_trn16(row2, row3); + dct_trn16(row4, row5); + dct_trn16(row6, row7); + + // pass 2 + dct_trn32(row0, row2); // a0b0c0d0a4b4c4d4 + dct_trn32(row1, row3); + dct_trn32(row4, row6); + dct_trn32(row5, row7); + + // pass 3 + dct_trn64(row0, row4); // a0b0c0d0e0f0g0h0 + dct_trn64(row1, row5); + dct_trn64(row2, row6); + dct_trn64(row3, row7); + +#undef dct_trn16 +#undef dct_trn32 +#undef dct_trn64 + } + + // row pass + // vrshrn_n_s32 only supports shifts up to 16, we need + // 17. so do a non-rounding shift of 16 first then follow + // up with a rounding shift by 1. + dct_pass(vshrn_n_s32, 16); + + { + // pack and round + uint8x8_t p0 = vqrshrun_n_s16(row0, 1); + uint8x8_t p1 = vqrshrun_n_s16(row1, 1); + uint8x8_t p2 = vqrshrun_n_s16(row2, 1); + uint8x8_t p3 = vqrshrun_n_s16(row3, 1); + uint8x8_t p4 = vqrshrun_n_s16(row4, 1); + uint8x8_t p5 = vqrshrun_n_s16(row5, 1); + uint8x8_t p6 = vqrshrun_n_s16(row6, 1); + uint8x8_t p7 = vqrshrun_n_s16(row7, 1); + + // again, these can translate into one instruction, but often don't. +#define dct_trn8_8(x, y) { uint8x8x2_t t = vtrn_u8(x, y); x = t.val[0]; y = t.val[1]; } +#define dct_trn8_16(x, y) { uint16x4x2_t t = vtrn_u16(vreinterpret_u16_u8(x), vreinterpret_u16_u8(y)); x = vreinterpret_u8_u16(t.val[0]); y = vreinterpret_u8_u16(t.val[1]); } +#define dct_trn8_32(x, y) { uint32x2x2_t t = vtrn_u32(vreinterpret_u32_u8(x), vreinterpret_u32_u8(y)); x = vreinterpret_u8_u32(t.val[0]); y = vreinterpret_u8_u32(t.val[1]); } + + // sadly can't use interleaved stores here since we only write + // 8 bytes to each scan line! + + // 8x8 8-bit transpose pass 1 + dct_trn8_8(p0, p1); + dct_trn8_8(p2, p3); + dct_trn8_8(p4, p5); + dct_trn8_8(p6, p7); + + // pass 2 + dct_trn8_16(p0, p2); + dct_trn8_16(p1, p3); + dct_trn8_16(p4, p6); + dct_trn8_16(p5, p7); + + // pass 3 + dct_trn8_32(p0, p4); + dct_trn8_32(p1, p5); + dct_trn8_32(p2, p6); + dct_trn8_32(p3, p7); + + // store + vst1_u8(out, p0); out += out_stride; + vst1_u8(out, p1); out += out_stride; + vst1_u8(out, p2); out += out_stride; + vst1_u8(out, p3); out += out_stride; + vst1_u8(out, p4); out += out_stride; + vst1_u8(out, p5); out += out_stride; + vst1_u8(out, p6); out += out_stride; + vst1_u8(out, p7); + +#undef dct_trn8_8 +#undef dct_trn8_16 +#undef dct_trn8_32 + } + +#undef dct_long_mul +#undef dct_long_mac +#undef dct_widen +#undef dct_wadd +#undef dct_wsub +#undef dct_bfly32o +#undef dct_pass +} + +#endif // STBI_NEON + +#define STBI__MARKER_none 0xff +// if there's a pending marker from the entropy stream, return that +// otherwise, fetch from the stream and get a marker. if there's no +// marker, return 0xff, which is never a valid marker value +static stbi_uc stbi__get_marker(stbi__jpeg *j) +{ + stbi_uc x; + if (j->marker != STBI__MARKER_none) { x = j->marker; j->marker = STBI__MARKER_none; return x; } + x = stbi__get8(j->s); + if (x != 0xff) return STBI__MARKER_none; + while (x == 0xff) + x = stbi__get8(j->s); + return x; +} + +// in each scan, we'll have scan_n components, and the order +// of the components is specified by order[] +#define STBI__RESTART(x) ((x) >= 0xd0 && (x) <= 0xd7) + +// after a restart interval, stbi__jpeg_reset the entropy decoder and +// the dc prediction +static void stbi__jpeg_reset(stbi__jpeg *j) +{ + j->code_bits = 0; + j->code_buffer = 0; + j->nomore = 0; + j->img_comp[0].dc_pred = j->img_comp[1].dc_pred = j->img_comp[2].dc_pred = 0; + j->marker = STBI__MARKER_none; + j->todo = j->restart_interval ? j->restart_interval : 0x7fffffff; + j->eob_run = 0; + // no more than 1<<31 MCUs if no restart_interal? that's plenty safe, + // since we don't even allow 1<<30 pixels +} + +static int stbi__parse_entropy_coded_data(stbi__jpeg *z) +{ + stbi__jpeg_reset(z); + if (!z->progressive) { + if (z->scan_n == 1) { + int i,j; + STBI_SIMD_ALIGN(short, data[64]); + int n = z->order[0]; + // non-interleaved data, we just need to process one block at a time, + // in trivial scanline order + // number of blocks to do just depends on how many actual "pixels" this + // component has, independent of interleaved MCU blocking and such + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block(z, data, z->huff_dc+z->img_comp[n].hd, z->huff_ac+ha, z->fast_ac[ha], n, z->dequant[z->img_comp[n].tq])) return 0; + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*j*8+i*8, z->img_comp[n].w2, data); + // every data block is an MCU, so countdown the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + // if it's NOT a restart, then just bail, so we get corrupt data + // rather than no data + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } else { // interleaved + int i,j,k,x,y; + STBI_SIMD_ALIGN(short, data[64]); + for (j=0; j < z->img_mcu_y; ++j) { + for (i=0; i < z->img_mcu_x; ++i) { + // scan an interleaved mcu... process scan_n components in order + for (k=0; k < z->scan_n; ++k) { + int n = z->order[k]; + // scan out an mcu's worth of this component; that's just determined + // by the basic H and V specified for the component + for (y=0; y < z->img_comp[n].v; ++y) { + for (x=0; x < z->img_comp[n].h; ++x) { + int x2 = (i*z->img_comp[n].h + x)*8; + int y2 = (j*z->img_comp[n].v + y)*8; + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block(z, data, z->huff_dc+z->img_comp[n].hd, z->huff_ac+ha, z->fast_ac[ha], n, z->dequant[z->img_comp[n].tq])) return 0; + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*y2+x2, z->img_comp[n].w2, data); + } + } + } + // after all interleaved components, that's an interleaved MCU, + // so now count down the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } + } else { + if (z->scan_n == 1) { + int i,j; + int n = z->order[0]; + // non-interleaved data, we just need to process one block at a time, + // in trivial scanline order + // number of blocks to do just depends on how many actual "pixels" this + // component has, independent of interleaved MCU blocking and such + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + short *data = z->img_comp[n].coeff + 64 * (i + j * z->img_comp[n].coeff_w); + if (z->spec_start == 0) { + if (!stbi__jpeg_decode_block_prog_dc(z, data, &z->huff_dc[z->img_comp[n].hd], n)) + return 0; + } else { + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block_prog_ac(z, data, &z->huff_ac[ha], z->fast_ac[ha])) + return 0; + } + // every data block is an MCU, so countdown the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } else { // interleaved + int i,j,k,x,y; + for (j=0; j < z->img_mcu_y; ++j) { + for (i=0; i < z->img_mcu_x; ++i) { + // scan an interleaved mcu... process scan_n components in order + for (k=0; k < z->scan_n; ++k) { + int n = z->order[k]; + // scan out an mcu's worth of this component; that's just determined + // by the basic H and V specified for the component + for (y=0; y < z->img_comp[n].v; ++y) { + for (x=0; x < z->img_comp[n].h; ++x) { + int x2 = (i*z->img_comp[n].h + x); + int y2 = (j*z->img_comp[n].v + y); + short *data = z->img_comp[n].coeff + 64 * (x2 + y2 * z->img_comp[n].coeff_w); + if (!stbi__jpeg_decode_block_prog_dc(z, data, &z->huff_dc[z->img_comp[n].hd], n)) + return 0; + } + } + } + // after all interleaved components, that's an interleaved MCU, + // so now count down the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } + } +} + +static void stbi__jpeg_dequantize(short *data, stbi_uc *dequant) +{ + int i; + for (i=0; i < 64; ++i) + data[i] *= dequant[i]; +} + +static void stbi__jpeg_finish(stbi__jpeg *z) +{ + if (z->progressive) { + // dequantize and idct the data + int i,j,n; + for (n=0; n < z->s->img_n; ++n) { + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + short *data = z->img_comp[n].coeff + 64 * (i + j * z->img_comp[n].coeff_w); + stbi__jpeg_dequantize(data, z->dequant[z->img_comp[n].tq]); + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*j*8+i*8, z->img_comp[n].w2, data); + } + } + } + } +} + +static int stbi__process_marker(stbi__jpeg *z, int m) +{ + int L; + switch (m) { + case STBI__MARKER_none: // no marker found + return stbi__err("expected marker","Corrupt JPEG"); + + case 0xDD: // DRI - specify restart interval + if (stbi__get16be(z->s) != 4) return stbi__err("bad DRI len","Corrupt JPEG"); + z->restart_interval = stbi__get16be(z->s); + return 1; + + case 0xDB: // DQT - define quantization table + L = stbi__get16be(z->s)-2; + while (L > 0) { + int q = stbi__get8(z->s); + int p = q >> 4; + int t = q & 15,i; + if (p != 0) return stbi__err("bad DQT type","Corrupt JPEG"); + if (t > 3) return stbi__err("bad DQT table","Corrupt JPEG"); + for (i=0; i < 64; ++i) + z->dequant[t][stbi__jpeg_dezigzag[i]] = stbi__get8(z->s); + L -= 65; + } + return L==0; + + case 0xC4: // DHT - define huffman table + L = stbi__get16be(z->s)-2; + while (L > 0) { + stbi_uc *v; + int sizes[16],i,n=0; + int q = stbi__get8(z->s); + int tc = q >> 4; + int th = q & 15; + if (tc > 1 || th > 3) return stbi__err("bad DHT header","Corrupt JPEG"); + for (i=0; i < 16; ++i) { + sizes[i] = stbi__get8(z->s); + n += sizes[i]; + } + L -= 17; + if (tc == 0) { + if (!stbi__build_huffman(z->huff_dc+th, sizes)) return 0; + v = z->huff_dc[th].values; + } else { + if (!stbi__build_huffman(z->huff_ac+th, sizes)) return 0; + v = z->huff_ac[th].values; + } + for (i=0; i < n; ++i) + v[i] = stbi__get8(z->s); + if (tc != 0) + stbi__build_fast_ac(z->fast_ac[th], z->huff_ac + th); + L -= n; + } + return L==0; + } + // check for comment block or APP blocks + if ((m >= 0xE0 && m <= 0xEF) || m == 0xFE) { + stbi__skip(z->s, stbi__get16be(z->s)-2); + return 1; + } + return 0; +} + +// after we see SOS +static int stbi__process_scan_header(stbi__jpeg *z) +{ + int i; + int Ls = stbi__get16be(z->s); + z->scan_n = stbi__get8(z->s); + if (z->scan_n < 1 || z->scan_n > 4 || z->scan_n > (int) z->s->img_n) return stbi__err("bad SOS component count","Corrupt JPEG"); + if (Ls != 6+2*z->scan_n) return stbi__err("bad SOS len","Corrupt JPEG"); + for (i=0; i < z->scan_n; ++i) { + int id = stbi__get8(z->s), which; + int q = stbi__get8(z->s); + for (which = 0; which < z->s->img_n; ++which) + if (z->img_comp[which].id == id) + break; + if (which == z->s->img_n) return 0; // no match + z->img_comp[which].hd = q >> 4; if (z->img_comp[which].hd > 3) return stbi__err("bad DC huff","Corrupt JPEG"); + z->img_comp[which].ha = q & 15; if (z->img_comp[which].ha > 3) return stbi__err("bad AC huff","Corrupt JPEG"); + z->order[i] = which; + } + + { + int aa; + z->spec_start = stbi__get8(z->s); + z->spec_end = stbi__get8(z->s); // should be 63, but might be 0 + aa = stbi__get8(z->s); + z->succ_high = (aa >> 4); + z->succ_low = (aa & 15); + if (z->progressive) { + if (z->spec_start > 63 || z->spec_end > 63 || z->spec_start > z->spec_end || z->succ_high > 13 || z->succ_low > 13) + return stbi__err("bad SOS", "Corrupt JPEG"); + } else { + if (z->spec_start != 0) return stbi__err("bad SOS","Corrupt JPEG"); + if (z->succ_high != 0 || z->succ_low != 0) return stbi__err("bad SOS","Corrupt JPEG"); + z->spec_end = 63; + } + } + + return 1; +} + +static int stbi__process_frame_header(stbi__jpeg *z, int scan) +{ + stbi__context *s = z->s; + int Lf,p,i,q, h_max=1,v_max=1,c; + Lf = stbi__get16be(s); if (Lf < 11) return stbi__err("bad SOF len","Corrupt JPEG"); // JPEG + p = stbi__get8(s); if (p != 8) return stbi__err("only 8-bit","JPEG format not supported: 8-bit only"); // JPEG baseline + s->img_y = stbi__get16be(s); if (s->img_y == 0) return stbi__err("no header height", "JPEG format not supported: delayed height"); // Legal, but we don't handle it--but neither does IJG + s->img_x = stbi__get16be(s); if (s->img_x == 0) return stbi__err("0 width","Corrupt JPEG"); // JPEG requires + c = stbi__get8(s); + if (c != 3 && c != 1) return stbi__err("bad component count","Corrupt JPEG"); // JFIF requires + s->img_n = c; + for (i=0; i < c; ++i) { + z->img_comp[i].data = NULL; + z->img_comp[i].linebuf = NULL; + } + + if (Lf != 8+3*s->img_n) return stbi__err("bad SOF len","Corrupt JPEG"); + + for (i=0; i < s->img_n; ++i) { + z->img_comp[i].id = stbi__get8(s); + if (z->img_comp[i].id != i+1) // JFIF requires + if (z->img_comp[i].id != i) // some version of jpegtran outputs non-JFIF-compliant files! + return stbi__err("bad component ID","Corrupt JPEG"); + q = stbi__get8(s); + z->img_comp[i].h = (q >> 4); if (!z->img_comp[i].h || z->img_comp[i].h > 4) return stbi__err("bad H","Corrupt JPEG"); + z->img_comp[i].v = q & 15; if (!z->img_comp[i].v || z->img_comp[i].v > 4) return stbi__err("bad V","Corrupt JPEG"); + z->img_comp[i].tq = stbi__get8(s); if (z->img_comp[i].tq > 3) return stbi__err("bad TQ","Corrupt JPEG"); + } + + if (scan != STBI__SCAN_load) return 1; + + if ((1 << 30) / s->img_x / s->img_n < s->img_y) return stbi__err("too large", "Image too large to decode"); + + for (i=0; i < s->img_n; ++i) { + if (z->img_comp[i].h > h_max) h_max = z->img_comp[i].h; + if (z->img_comp[i].v > v_max) v_max = z->img_comp[i].v; + } + + // compute interleaved mcu info + z->img_h_max = h_max; + z->img_v_max = v_max; + z->img_mcu_w = h_max * 8; + z->img_mcu_h = v_max * 8; + z->img_mcu_x = (s->img_x + z->img_mcu_w-1) / z->img_mcu_w; + z->img_mcu_y = (s->img_y + z->img_mcu_h-1) / z->img_mcu_h; + + for (i=0; i < s->img_n; ++i) { + // number of effective pixels (e.g. for non-interleaved MCU) + z->img_comp[i].x = (s->img_x * z->img_comp[i].h + h_max-1) / h_max; + z->img_comp[i].y = (s->img_y * z->img_comp[i].v + v_max-1) / v_max; + // to simplify generation, we'll allocate enough memory to decode + // the bogus oversized data from using interleaved MCUs and their + // big blocks (e.g. a 16x16 iMCU on an image of width 33); we won't + // discard the extra data until colorspace conversion + z->img_comp[i].w2 = z->img_mcu_x * z->img_comp[i].h * 8; + z->img_comp[i].h2 = z->img_mcu_y * z->img_comp[i].v * 8; + z->img_comp[i].raw_data = stbi__malloc(z->img_comp[i].w2 * z->img_comp[i].h2+15); + + if (z->img_comp[i].raw_data == NULL) { + for(--i; i >= 0; --i) { + STBI_FREE(z->img_comp[i].raw_data); + z->img_comp[i].raw_data = NULL; + } + return stbi__err("outofmem", "Out of memory"); + } + // align blocks for idct using mmx/sse + z->img_comp[i].data = (stbi_uc*) (((size_t) z->img_comp[i].raw_data + 15) & ~15); + z->img_comp[i].linebuf = NULL; + if (z->progressive) { + z->img_comp[i].coeff_w = (z->img_comp[i].w2 + 7) >> 3; + z->img_comp[i].coeff_h = (z->img_comp[i].h2 + 7) >> 3; + z->img_comp[i].raw_coeff = STBI_MALLOC(z->img_comp[i].coeff_w * z->img_comp[i].coeff_h * 64 * sizeof(short) + 15); + z->img_comp[i].coeff = (short*) (((size_t) z->img_comp[i].raw_coeff + 15) & ~15); + } else { + z->img_comp[i].coeff = 0; + z->img_comp[i].raw_coeff = 0; + } + } + + return 1; +} + +// use comparisons since in some cases we handle more than one case (e.g. SOF) +#define stbi__DNL(x) ((x) == 0xdc) +#define stbi__SOI(x) ((x) == 0xd8) +#define stbi__EOI(x) ((x) == 0xd9) +#define stbi__SOF(x) ((x) == 0xc0 || (x) == 0xc1 || (x) == 0xc2) +#define stbi__SOS(x) ((x) == 0xda) + +#define stbi__SOF_progressive(x) ((x) == 0xc2) + +static int stbi__decode_jpeg_header(stbi__jpeg *z, int scan) +{ + int m; + z->marker = STBI__MARKER_none; // initialize cached marker to empty + m = stbi__get_marker(z); + if (!stbi__SOI(m)) return stbi__err("no SOI","Corrupt JPEG"); + if (scan == STBI__SCAN_type) return 1; + m = stbi__get_marker(z); + while (!stbi__SOF(m)) { + if (!stbi__process_marker(z,m)) return 0; + m = stbi__get_marker(z); + while (m == STBI__MARKER_none) { + // some files have extra padding after their blocks, so ok, we'll scan + if (stbi__at_eof(z->s)) return stbi__err("no SOF", "Corrupt JPEG"); + m = stbi__get_marker(z); + } + } + z->progressive = stbi__SOF_progressive(m); + if (!stbi__process_frame_header(z, scan)) return 0; + return 1; +} + +// decode image to YCbCr format +static int stbi__decode_jpeg_image(stbi__jpeg *j) +{ + int m; + for (m = 0; m < 4; m++) { + j->img_comp[m].raw_data = NULL; + j->img_comp[m].raw_coeff = NULL; + } + j->restart_interval = 0; + if (!stbi__decode_jpeg_header(j, STBI__SCAN_load)) return 0; + m = stbi__get_marker(j); + while (!stbi__EOI(m)) { + if (stbi__SOS(m)) { + if (!stbi__process_scan_header(j)) return 0; + if (!stbi__parse_entropy_coded_data(j)) return 0; + if (j->marker == STBI__MARKER_none ) { + // handle 0s at the end of image data from IP Kamera 9060 + while (!stbi__at_eof(j->s)) { + int x = stbi__get8(j->s); + if (x == 255) { + j->marker = stbi__get8(j->s); + break; + } else if (x != 0) { + return stbi__err("junk before marker", "Corrupt JPEG"); + } + } + // if we reach eof without hitting a marker, stbi__get_marker() below will fail and we'll eventually return 0 + } + } else { + if (!stbi__process_marker(j, m)) return 0; + } + m = stbi__get_marker(j); + } + if (j->progressive) + stbi__jpeg_finish(j); + return 1; +} + +// static jfif-centered resampling (across block boundaries) + +typedef stbi_uc *(*resample_row_func)(stbi_uc *out, stbi_uc *in0, stbi_uc *in1, + int w, int hs); + +#define stbi__div4(x) ((stbi_uc) ((x) >> 2)) + +static stbi_uc *resample_row_1(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + STBI_NOTUSED(out); + STBI_NOTUSED(in_far); + STBI_NOTUSED(w); + STBI_NOTUSED(hs); + return in_near; +} + +static stbi_uc* stbi__resample_row_v_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate two samples vertically for every one in input + int i; + STBI_NOTUSED(hs); + for (i=0; i < w; ++i) + out[i] = stbi__div4(3*in_near[i] + in_far[i] + 2); + return out; +} + +static stbi_uc* stbi__resample_row_h_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate two samples horizontally for every one in input + int i; + stbi_uc *input = in_near; + + if (w == 1) { + // if only one sample, can't do any interpolation + out[0] = out[1] = input[0]; + return out; + } + + out[0] = input[0]; + out[1] = stbi__div4(input[0]*3 + input[1] + 2); + for (i=1; i < w-1; ++i) { + int n = 3*input[i]+2; + out[i*2+0] = stbi__div4(n+input[i-1]); + out[i*2+1] = stbi__div4(n+input[i+1]); + } + out[i*2+0] = stbi__div4(input[w-2]*3 + input[w-1] + 2); + out[i*2+1] = input[w-1]; + + STBI_NOTUSED(in_far); + STBI_NOTUSED(hs); + + return out; +} + +#define stbi__div16(x) ((stbi_uc) ((x) >> 4)) + +static stbi_uc *stbi__resample_row_hv_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate 2x2 samples for every one in input + int i,t0,t1; + if (w == 1) { + out[0] = out[1] = stbi__div4(3*in_near[0] + in_far[0] + 2); + return out; + } + + t1 = 3*in_near[0] + in_far[0]; + out[0] = stbi__div4(t1+2); + for (i=1; i < w; ++i) { + t0 = t1; + t1 = 3*in_near[i]+in_far[i]; + out[i*2-1] = stbi__div16(3*t0 + t1 + 8); + out[i*2 ] = stbi__div16(3*t1 + t0 + 8); + } + out[w*2-1] = stbi__div4(t1+2); + + STBI_NOTUSED(hs); + + return out; +} + +#if defined(STBI_SSE2) || defined(STBI_NEON) +static stbi_uc *stbi__resample_row_hv_2_simd(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate 2x2 samples for every one in input + int i=0,t0,t1; + + if (w == 1) { + out[0] = out[1] = stbi__div4(3*in_near[0] + in_far[0] + 2); + return out; + } + + t1 = 3*in_near[0] + in_far[0]; + // process groups of 8 pixels for as long as we can. + // note we can't handle the last pixel in a row in this loop + // because we need to handle the filter boundary conditions. + for (; i < ((w-1) & ~7); i += 8) { +#if defined(STBI_SSE2) + // load and perform the vertical filtering pass + // this uses 3*x + y = 4*x + (y - x) + __m128i zero = _mm_setzero_si128(); + __m128i farb = _mm_loadl_epi64((__m128i *) (in_far + i)); + __m128i nearb = _mm_loadl_epi64((__m128i *) (in_near + i)); + __m128i farw = _mm_unpacklo_epi8(farb, zero); + __m128i nearw = _mm_unpacklo_epi8(nearb, zero); + __m128i diff = _mm_sub_epi16(farw, nearw); + __m128i nears = _mm_slli_epi16(nearw, 2); + __m128i curr = _mm_add_epi16(nears, diff); // current row + + // horizontal filter works the same based on shifted vers of current + // row. "prev" is current row shifted right by 1 pixel; we need to + // insert the previous pixel value (from t1). + // "next" is current row shifted left by 1 pixel, with first pixel + // of next block of 8 pixels added in. + __m128i prv0 = _mm_slli_si128(curr, 2); + __m128i nxt0 = _mm_srli_si128(curr, 2); + __m128i prev = _mm_insert_epi16(prv0, t1, 0); + __m128i next = _mm_insert_epi16(nxt0, 3*in_near[i+8] + in_far[i+8], 7); + + // horizontal filter, polyphase implementation since it's convenient: + // even pixels = 3*cur + prev = cur*4 + (prev - cur) + // odd pixels = 3*cur + next = cur*4 + (next - cur) + // note the shared term. + __m128i bias = _mm_set1_epi16(8); + __m128i curs = _mm_slli_epi16(curr, 2); + __m128i prvd = _mm_sub_epi16(prev, curr); + __m128i nxtd = _mm_sub_epi16(next, curr); + __m128i curb = _mm_add_epi16(curs, bias); + __m128i even = _mm_add_epi16(prvd, curb); + __m128i odd = _mm_add_epi16(nxtd, curb); + + // interleave even and odd pixels, then undo scaling. + __m128i int0 = _mm_unpacklo_epi16(even, odd); + __m128i int1 = _mm_unpackhi_epi16(even, odd); + __m128i de0 = _mm_srli_epi16(int0, 4); + __m128i de1 = _mm_srli_epi16(int1, 4); + + // pack and write output + __m128i outv = _mm_packus_epi16(de0, de1); + _mm_storeu_si128((__m128i *) (out + i*2), outv); +#elif defined(STBI_NEON) + // load and perform the vertical filtering pass + // this uses 3*x + y = 4*x + (y - x) + uint8x8_t farb = vld1_u8(in_far + i); + uint8x8_t nearb = vld1_u8(in_near + i); + int16x8_t diff = vreinterpretq_s16_u16(vsubl_u8(farb, nearb)); + int16x8_t nears = vreinterpretq_s16_u16(vshll_n_u8(nearb, 2)); + int16x8_t curr = vaddq_s16(nears, diff); // current row + + // horizontal filter works the same based on shifted vers of current + // row. "prev" is current row shifted right by 1 pixel; we need to + // insert the previous pixel value (from t1). + // "next" is current row shifted left by 1 pixel, with first pixel + // of next block of 8 pixels added in. + int16x8_t prv0 = vextq_s16(curr, curr, 7); + int16x8_t nxt0 = vextq_s16(curr, curr, 1); + int16x8_t prev = vsetq_lane_s16(t1, prv0, 0); + int16x8_t next = vsetq_lane_s16(3*in_near[i+8] + in_far[i+8], nxt0, 7); + + // horizontal filter, polyphase implementation since it's convenient: + // even pixels = 3*cur + prev = cur*4 + (prev - cur) + // odd pixels = 3*cur + next = cur*4 + (next - cur) + // note the shared term. + int16x8_t curs = vshlq_n_s16(curr, 2); + int16x8_t prvd = vsubq_s16(prev, curr); + int16x8_t nxtd = vsubq_s16(next, curr); + int16x8_t even = vaddq_s16(curs, prvd); + int16x8_t odd = vaddq_s16(curs, nxtd); + + // undo scaling and round, then store with even/odd phases interleaved + uint8x8x2_t o; + o.val[0] = vqrshrun_n_s16(even, 4); + o.val[1] = vqrshrun_n_s16(odd, 4); + vst2_u8(out + i*2, o); +#endif + + // "previous" value for next iter + t1 = 3*in_near[i+7] + in_far[i+7]; + } + + t0 = t1; + t1 = 3*in_near[i] + in_far[i]; + out[i*2] = stbi__div16(3*t1 + t0 + 8); + + for (++i; i < w; ++i) { + t0 = t1; + t1 = 3*in_near[i]+in_far[i]; + out[i*2-1] = stbi__div16(3*t0 + t1 + 8); + out[i*2 ] = stbi__div16(3*t1 + t0 + 8); + } + out[w*2-1] = stbi__div4(t1+2); + + STBI_NOTUSED(hs); + + return out; +} +#endif + +static stbi_uc *stbi__resample_row_generic(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // resample with nearest-neighbor + int i,j; + STBI_NOTUSED(in_far); + for (i=0; i < w; ++i) + for (j=0; j < hs; ++j) + out[i*hs+j] = in_near[i]; + return out; +} + +#ifdef STBI_JPEG_OLD +// this is the same YCbCr-to-RGB calculation that stb_image has used +// historically before the algorithm changes in 1.49 +#define float2fixed(x) ((int) ((x) * 65536 + 0.5)) +static void stbi__YCbCr_to_RGB_row(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step) +{ + int i; + for (i=0; i < count; ++i) { + int y_fixed = (y[i] << 16) + 32768; // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr*float2fixed(1.40200f); + g = y_fixed - cr*float2fixed(0.71414f) - cb*float2fixed(0.34414f); + b = y_fixed + cb*float2fixed(1.77200f); + r >>= 16; + g >>= 16; + b >>= 16; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#else +// this is a reduced-precision calculation of YCbCr-to-RGB introduced +// to make sure the code produces the same results in both SIMD and scalar +#define float2fixed(x) (((int) ((x) * 4096.0f + 0.5f)) << 8) +static void stbi__YCbCr_to_RGB_row(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step) +{ + int i; + for (i=0; i < count; ++i) { + int y_fixed = (y[i] << 20) + (1<<19); // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr* float2fixed(1.40200f); + g = y_fixed + (cr*-float2fixed(0.71414f)) + ((cb*-float2fixed(0.34414f)) & 0xffff0000); + b = y_fixed + cb* float2fixed(1.77200f); + r >>= 20; + g >>= 20; + b >>= 20; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#endif + +#if defined(STBI_SSE2) || defined(STBI_NEON) +static void stbi__YCbCr_to_RGB_simd(stbi_uc *out, stbi_uc const *y, stbi_uc const *pcb, stbi_uc const *pcr, int count, int step) +{ + int i = 0; + +#ifdef STBI_SSE2 + // step == 3 is pretty ugly on the final interleave, and i'm not convinced + // it's useful in practice (you wouldn't use it for textures, for example). + // so just accelerate step == 4 case. + if (step == 4) { + // this is a fairly straightforward implementation and not super-optimized. + __m128i signflip = _mm_set1_epi8(-0x80); + __m128i cr_const0 = _mm_set1_epi16( (short) ( 1.40200f*4096.0f+0.5f)); + __m128i cr_const1 = _mm_set1_epi16( - (short) ( 0.71414f*4096.0f+0.5f)); + __m128i cb_const0 = _mm_set1_epi16( - (short) ( 0.34414f*4096.0f+0.5f)); + __m128i cb_const1 = _mm_set1_epi16( (short) ( 1.77200f*4096.0f+0.5f)); + __m128i y_bias = _mm_set1_epi8((char) (unsigned char) 128); + __m128i xw = _mm_set1_epi16(255); // alpha channel + + for (; i+7 < count; i += 8) { + // load + __m128i y_bytes = _mm_loadl_epi64((__m128i *) (y+i)); + __m128i cr_bytes = _mm_loadl_epi64((__m128i *) (pcr+i)); + __m128i cb_bytes = _mm_loadl_epi64((__m128i *) (pcb+i)); + __m128i cr_biased = _mm_xor_si128(cr_bytes, signflip); // -128 + __m128i cb_biased = _mm_xor_si128(cb_bytes, signflip); // -128 + + // unpack to short (and left-shift cr, cb by 8) + __m128i yw = _mm_unpacklo_epi8(y_bias, y_bytes); + __m128i crw = _mm_unpacklo_epi8(_mm_setzero_si128(), cr_biased); + __m128i cbw = _mm_unpacklo_epi8(_mm_setzero_si128(), cb_biased); + + // color transform + __m128i yws = _mm_srli_epi16(yw, 4); + __m128i cr0 = _mm_mulhi_epi16(cr_const0, crw); + __m128i cb0 = _mm_mulhi_epi16(cb_const0, cbw); + __m128i cb1 = _mm_mulhi_epi16(cbw, cb_const1); + __m128i cr1 = _mm_mulhi_epi16(crw, cr_const1); + __m128i rws = _mm_add_epi16(cr0, yws); + __m128i gwt = _mm_add_epi16(cb0, yws); + __m128i bws = _mm_add_epi16(yws, cb1); + __m128i gws = _mm_add_epi16(gwt, cr1); + + // descale + __m128i rw = _mm_srai_epi16(rws, 4); + __m128i bw = _mm_srai_epi16(bws, 4); + __m128i gw = _mm_srai_epi16(gws, 4); + + // back to byte, set up for transpose + __m128i brb = _mm_packus_epi16(rw, bw); + __m128i gxb = _mm_packus_epi16(gw, xw); + + // transpose to interleave channels + __m128i t0 = _mm_unpacklo_epi8(brb, gxb); + __m128i t1 = _mm_unpackhi_epi8(brb, gxb); + __m128i o0 = _mm_unpacklo_epi16(t0, t1); + __m128i o1 = _mm_unpackhi_epi16(t0, t1); + + // store + _mm_storeu_si128((__m128i *) (out + 0), o0); + _mm_storeu_si128((__m128i *) (out + 16), o1); + out += 32; + } + } +#endif + +#ifdef STBI_NEON + // in this version, step=3 support would be easy to add. but is there demand? + if (step == 4) { + // this is a fairly straightforward implementation and not super-optimized. + uint8x8_t signflip = vdup_n_u8(0x80); + int16x8_t cr_const0 = vdupq_n_s16( (short) ( 1.40200f*4096.0f+0.5f)); + int16x8_t cr_const1 = vdupq_n_s16( - (short) ( 0.71414f*4096.0f+0.5f)); + int16x8_t cb_const0 = vdupq_n_s16( - (short) ( 0.34414f*4096.0f+0.5f)); + int16x8_t cb_const1 = vdupq_n_s16( (short) ( 1.77200f*4096.0f+0.5f)); + + for (; i+7 < count; i += 8) { + // load + uint8x8_t y_bytes = vld1_u8(y + i); + uint8x8_t cr_bytes = vld1_u8(pcr + i); + uint8x8_t cb_bytes = vld1_u8(pcb + i); + int8x8_t cr_biased = vreinterpret_s8_u8(vsub_u8(cr_bytes, signflip)); + int8x8_t cb_biased = vreinterpret_s8_u8(vsub_u8(cb_bytes, signflip)); + + // expand to s16 + int16x8_t yws = vreinterpretq_s16_u16(vshll_n_u8(y_bytes, 4)); + int16x8_t crw = vshll_n_s8(cr_biased, 7); + int16x8_t cbw = vshll_n_s8(cb_biased, 7); + + // color transform + int16x8_t cr0 = vqdmulhq_s16(crw, cr_const0); + int16x8_t cb0 = vqdmulhq_s16(cbw, cb_const0); + int16x8_t cr1 = vqdmulhq_s16(crw, cr_const1); + int16x8_t cb1 = vqdmulhq_s16(cbw, cb_const1); + int16x8_t rws = vaddq_s16(yws, cr0); + int16x8_t gws = vaddq_s16(vaddq_s16(yws, cb0), cr1); + int16x8_t bws = vaddq_s16(yws, cb1); + + // undo scaling, round, convert to byte + uint8x8x4_t o; + o.val[0] = vqrshrun_n_s16(rws, 4); + o.val[1] = vqrshrun_n_s16(gws, 4); + o.val[2] = vqrshrun_n_s16(bws, 4); + o.val[3] = vdup_n_u8(255); + + // store, interleaving r/g/b/a + vst4_u8(out, o); + out += 8*4; + } + } +#endif + + for (; i < count; ++i) { + int y_fixed = (y[i] << 20) + (1<<19); // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr* float2fixed(1.40200f); + g = y_fixed + cr*-float2fixed(0.71414f) + ((cb*-float2fixed(0.34414f)) & 0xffff0000); + b = y_fixed + cb* float2fixed(1.77200f); + r >>= 20; + g >>= 20; + b >>= 20; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#endif + +// set up the kernels +static void stbi__setup_jpeg(stbi__jpeg *j) +{ + j->idct_block_kernel = stbi__idct_block; + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_row; + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2; + +#ifdef STBI_SSE2 + if (stbi__sse2_available()) { + j->idct_block_kernel = stbi__idct_simd; + #ifndef STBI_JPEG_OLD + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_simd; + #endif + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2_simd; + } +#endif + +#ifdef STBI_NEON + j->idct_block_kernel = stbi__idct_simd; + #ifndef STBI_JPEG_OLD + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_simd; + #endif + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2_simd; +#endif +} + +// clean up the temporary component buffers +static void stbi__cleanup_jpeg(stbi__jpeg *j) +{ + int i; + for (i=0; i < j->s->img_n; ++i) { + if (j->img_comp[i].raw_data) { + STBI_FREE(j->img_comp[i].raw_data); + j->img_comp[i].raw_data = NULL; + j->img_comp[i].data = NULL; + } + if (j->img_comp[i].raw_coeff) { + STBI_FREE(j->img_comp[i].raw_coeff); + j->img_comp[i].raw_coeff = 0; + j->img_comp[i].coeff = 0; + } + if (j->img_comp[i].linebuf) { + STBI_FREE(j->img_comp[i].linebuf); + j->img_comp[i].linebuf = NULL; + } + } +} + +typedef struct +{ + resample_row_func resample; + stbi_uc *line0,*line1; + int hs,vs; // expansion factor in each axis + int w_lores; // horizontal pixels pre-expansion + int ystep; // how far through vertical expansion we are + int ypos; // which pre-expansion row we're on +} stbi__resample; + +static stbi_uc *load_jpeg_image(stbi__jpeg *z, int *out_x, int *out_y, int *comp, int req_comp) +{ + int n, decode_n; + z->s->img_n = 0; // make stbi__cleanup_jpeg safe + + // validate req_comp + if (req_comp < 0 || req_comp > 4) return stbi__errpuc("bad req_comp", "Internal error"); + + // load a jpeg image from whichever source, but leave in YCbCr format + if (!stbi__decode_jpeg_image(z)) { stbi__cleanup_jpeg(z); return NULL; } + + // determine actual number of components to generate + n = req_comp ? req_comp : z->s->img_n; + + if (z->s->img_n == 3 && n < 3) + decode_n = 1; + else + decode_n = z->s->img_n; + + // resample and color-convert + { + int k; + unsigned int i,j; + stbi_uc *output; + stbi_uc *coutput[4]; + + stbi__resample res_comp[4]; + + for (k=0; k < decode_n; ++k) { + stbi__resample *r = &res_comp[k]; + + // allocate line buffer big enough for upsampling off the edges + // with upsample factor of 4 + z->img_comp[k].linebuf = (stbi_uc *) stbi__malloc(z->s->img_x + 3); + if (!z->img_comp[k].linebuf) { stbi__cleanup_jpeg(z); return stbi__errpuc("outofmem", "Out of memory"); } + + r->hs = z->img_h_max / z->img_comp[k].h; + r->vs = z->img_v_max / z->img_comp[k].v; + r->ystep = r->vs >> 1; + r->w_lores = (z->s->img_x + r->hs-1) / r->hs; + r->ypos = 0; + r->line0 = r->line1 = z->img_comp[k].data; + + if (r->hs == 1 && r->vs == 1) r->resample = resample_row_1; + else if (r->hs == 1 && r->vs == 2) r->resample = stbi__resample_row_v_2; + else if (r->hs == 2 && r->vs == 1) r->resample = stbi__resample_row_h_2; + else if (r->hs == 2 && r->vs == 2) r->resample = z->resample_row_hv_2_kernel; + else r->resample = stbi__resample_row_generic; + } + + // can't error after this so, this is safe + output = (stbi_uc *) stbi__malloc(n * z->s->img_x * z->s->img_y + 1); + if (!output) { stbi__cleanup_jpeg(z); return stbi__errpuc("outofmem", "Out of memory"); } + + // now go ahead and resample + for (j=0; j < z->s->img_y; ++j) { + stbi_uc *out = output + n * z->s->img_x * j; + for (k=0; k < decode_n; ++k) { + stbi__resample *r = &res_comp[k]; + int y_bot = r->ystep >= (r->vs >> 1); + coutput[k] = r->resample(z->img_comp[k].linebuf, + y_bot ? r->line1 : r->line0, + y_bot ? r->line0 : r->line1, + r->w_lores, r->hs); + if (++r->ystep >= r->vs) { + r->ystep = 0; + r->line0 = r->line1; + if (++r->ypos < z->img_comp[k].y) + r->line1 += z->img_comp[k].w2; + } + } + if (n >= 3) { + stbi_uc *y = coutput[0]; + if (z->s->img_n == 3) { + z->YCbCr_to_RGB_kernel(out, y, coutput[1], coutput[2], z->s->img_x, n); + } else + for (i=0; i < z->s->img_x; ++i) { + out[0] = out[1] = out[2] = y[i]; + out[3] = 255; // not used if n==3 + out += n; + } + } else { + stbi_uc *y = coutput[0]; + if (n == 1) + for (i=0; i < z->s->img_x; ++i) out[i] = y[i]; + else + for (i=0; i < z->s->img_x; ++i) *out++ = y[i], *out++ = 255; + } + } + stbi__cleanup_jpeg(z); + *out_x = z->s->img_x; + *out_y = z->s->img_y; + if (comp) *comp = z->s->img_n; // report original components, not output + return output; + } +} + +static unsigned char *stbi__jpeg_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi__jpeg j; + j.s = s; + stbi__setup_jpeg(&j); + return load_jpeg_image(&j, x,y,comp,req_comp); +} + +static int stbi__jpeg_test(stbi__context *s) +{ + int r; + stbi__jpeg j; + j.s = s; + stbi__setup_jpeg(&j); + r = stbi__decode_jpeg_header(&j, STBI__SCAN_type); + stbi__rewind(s); + return r; +} + +static int stbi__jpeg_info_raw(stbi__jpeg *j, int *x, int *y, int *comp) +{ + if (!stbi__decode_jpeg_header(j, STBI__SCAN_header)) { + stbi__rewind( j->s ); + return 0; + } + if (x) *x = j->s->img_x; + if (y) *y = j->s->img_y; + if (comp) *comp = j->s->img_n; + return 1; +} + +static int stbi__jpeg_info(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__jpeg j; + j.s = s; + return stbi__jpeg_info_raw(&j, x, y, comp); +} +#endif + +// public domain zlib decode v0.2 Sean Barrett 2006-11-18 +// simple implementation +// - all input must be provided in an upfront buffer +// - all output is written to a single output buffer (can malloc/realloc) +// performance +// - fast huffman + +#ifndef STBI_NO_ZLIB + +// fast-way is faster to check than jpeg huffman, but slow way is slower +#define STBI__ZFAST_BITS 9 // accelerate all cases in default tables +#define STBI__ZFAST_MASK ((1 << STBI__ZFAST_BITS) - 1) + +// zlib-style huffman encoding +// (jpegs packs from left, zlib from right, so can't share code) +typedef struct +{ + stbi__uint16 fast[1 << STBI__ZFAST_BITS]; + stbi__uint16 firstcode[16]; + int maxcode[17]; + stbi__uint16 firstsymbol[16]; + stbi_uc size[288]; + stbi__uint16 value[288]; +} stbi__zhuffman; + +stbi_inline static int stbi__bitreverse16(int n) +{ + n = ((n & 0xAAAA) >> 1) | ((n & 0x5555) << 1); + n = ((n & 0xCCCC) >> 2) | ((n & 0x3333) << 2); + n = ((n & 0xF0F0) >> 4) | ((n & 0x0F0F) << 4); + n = ((n & 0xFF00) >> 8) | ((n & 0x00FF) << 8); + return n; +} + +stbi_inline static int stbi__bit_reverse(int v, int bits) +{ + STBI_ASSERT(bits <= 16); + // to bit reverse n bits, reverse 16 and shift + // e.g. 11 bits, bit reverse and shift away 5 + return stbi__bitreverse16(v) >> (16-bits); +} + +static int stbi__zbuild_huffman(stbi__zhuffman *z, stbi_uc *sizelist, int num) +{ + int i,k=0; + int code, next_code[16], sizes[17]; + + // DEFLATE spec for generating codes + memset(sizes, 0, sizeof(sizes)); + memset(z->fast, 0, sizeof(z->fast)); + for (i=0; i < num; ++i) + ++sizes[sizelist[i]]; + sizes[0] = 0; + for (i=1; i < 16; ++i) + if (sizes[i] > (1 << i)) + return stbi__err("bad sizes", "Corrupt PNG"); + code = 0; + for (i=1; i < 16; ++i) { + next_code[i] = code; + z->firstcode[i] = (stbi__uint16) code; + z->firstsymbol[i] = (stbi__uint16) k; + code = (code + sizes[i]); + if (sizes[i]) + if (code-1 >= (1 << i)) return stbi__err("bad codelengths","Corrupt PNG"); + z->maxcode[i] = code << (16-i); // preshift for inner loop + code <<= 1; + k += sizes[i]; + } + z->maxcode[16] = 0x10000; // sentinel + for (i=0; i < num; ++i) { + int s = sizelist[i]; + if (s) { + int c = next_code[s] - z->firstcode[s] + z->firstsymbol[s]; + stbi__uint16 fastv = (stbi__uint16) ((s << 9) | i); + z->size [c] = (stbi_uc ) s; + z->value[c] = (stbi__uint16) i; + if (s <= STBI__ZFAST_BITS) { + int j = stbi__bit_reverse(next_code[s],s); + while (j < (1 << STBI__ZFAST_BITS)) { + z->fast[j] = fastv; + j += (1 << s); + } + } + ++next_code[s]; + } + } + return 1; +} + +// zlib-from-memory implementation for PNG reading +// because PNG allows splitting the zlib stream arbitrarily, +// and it's annoying structurally to have PNG call ZLIB call PNG, +// we require PNG read all the IDATs and combine them into a single +// memory buffer + +typedef struct +{ + stbi_uc *zbuffer, *zbuffer_end; + int num_bits; + stbi__uint32 code_buffer; + + char *zout; + char *zout_start; + char *zout_end; + int z_expandable; + + stbi__zhuffman z_length, z_distance; +} stbi__zbuf; + +stbi_inline static stbi_uc stbi__zget8(stbi__zbuf *z) +{ + if (z->zbuffer >= z->zbuffer_end) return 0; + return *z->zbuffer++; +} + +static void stbi__fill_bits(stbi__zbuf *z) +{ + do { + STBI_ASSERT(z->code_buffer < (1U << z->num_bits)); + z->code_buffer |= (unsigned int) stbi__zget8(z) << z->num_bits; + z->num_bits += 8; + } while (z->num_bits <= 24); +} + +stbi_inline static unsigned int stbi__zreceive(stbi__zbuf *z, int n) +{ + unsigned int k; + if (z->num_bits < n) stbi__fill_bits(z); + k = z->code_buffer & ((1 << n) - 1); + z->code_buffer >>= n; + z->num_bits -= n; + return k; +} + +static int stbi__zhuffman_decode_slowpath(stbi__zbuf *a, stbi__zhuffman *z) +{ + int b,s,k; + // not resolved by fast table, so compute it the slow way + // use jpeg approach, which requires MSbits at top + k = stbi__bit_reverse(a->code_buffer, 16); + for (s=STBI__ZFAST_BITS+1; ; ++s) + if (k < z->maxcode[s]) + break; + if (s == 16) return -1; // invalid code! + // code size is s, so: + b = (k >> (16-s)) - z->firstcode[s] + z->firstsymbol[s]; + STBI_ASSERT(z->size[b] == s); + a->code_buffer >>= s; + a->num_bits -= s; + return z->value[b]; +} + +stbi_inline static int stbi__zhuffman_decode(stbi__zbuf *a, stbi__zhuffman *z) +{ + int b,s; + if (a->num_bits < 16) stbi__fill_bits(a); + b = z->fast[a->code_buffer & STBI__ZFAST_MASK]; + if (b) { + s = b >> 9; + a->code_buffer >>= s; + a->num_bits -= s; + return b & 511; + } + return stbi__zhuffman_decode_slowpath(a, z); +} + +static int stbi__zexpand(stbi__zbuf *z, char *zout, int n) // need to make room for n bytes +{ + char *q; + int cur, limit, old_limit; + z->zout = zout; + if (!z->z_expandable) return stbi__err("output buffer limit","Corrupt PNG"); + cur = (int) (z->zout - z->zout_start); + limit = old_limit = (int) (z->zout_end - z->zout_start); + while (cur + n > limit) + limit *= 2; + q = (char *) STBI_REALLOC_SIZED(z->zout_start, old_limit, limit); + STBI_NOTUSED(old_limit); + if (q == NULL) return stbi__err("outofmem", "Out of memory"); + z->zout_start = q; + z->zout = q + cur; + z->zout_end = q + limit; + return 1; +} + +static int stbi__zlength_base[31] = { + 3,4,5,6,7,8,9,10,11,13, + 15,17,19,23,27,31,35,43,51,59, + 67,83,99,115,131,163,195,227,258,0,0 }; + +static int stbi__zlength_extra[31]= +{ 0,0,0,0,0,0,0,0,1,1,1,1,2,2,2,2,3,3,3,3,4,4,4,4,5,5,5,5,0,0,0 }; + +static int stbi__zdist_base[32] = { 1,2,3,4,5,7,9,13,17,25,33,49,65,97,129,193, +257,385,513,769,1025,1537,2049,3073,4097,6145,8193,12289,16385,24577,0,0}; + +static int stbi__zdist_extra[32] = +{ 0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13}; + +static int stbi__parse_huffman_block(stbi__zbuf *a) +{ + char *zout = a->zout; + for(;;) { + int z = stbi__zhuffman_decode(a, &a->z_length); + if (z < 256) { + if (z < 0) return stbi__err("bad huffman code","Corrupt PNG"); // error in huffman codes + if (zout >= a->zout_end) { + if (!stbi__zexpand(a, zout, 1)) return 0; + zout = a->zout; + } + *zout++ = (char) z; + } else { + stbi_uc *p; + int len,dist; + if (z == 256) { + a->zout = zout; + return 1; + } + z -= 257; + len = stbi__zlength_base[z]; + if (stbi__zlength_extra[z]) len += stbi__zreceive(a, stbi__zlength_extra[z]); + z = stbi__zhuffman_decode(a, &a->z_distance); + if (z < 0) return stbi__err("bad huffman code","Corrupt PNG"); + dist = stbi__zdist_base[z]; + if (stbi__zdist_extra[z]) dist += stbi__zreceive(a, stbi__zdist_extra[z]); + if (zout - a->zout_start < dist) return stbi__err("bad dist","Corrupt PNG"); + if (zout + len > a->zout_end) { + if (!stbi__zexpand(a, zout, len)) return 0; + zout = a->zout; + } + p = (stbi_uc *) (zout - dist); + if (dist == 1) { // run of one byte; common in images. + stbi_uc v = *p; + if (len) { do *zout++ = v; while (--len); } + } else { + if (len) { do *zout++ = *p++; while (--len); } + } + } + } +} + +static int stbi__compute_huffman_codes(stbi__zbuf *a) +{ + static stbi_uc length_dezigzag[19] = { 16,17,18,0,8,7,9,6,10,5,11,4,12,3,13,2,14,1,15 }; + stbi__zhuffman z_codelength; + stbi_uc lencodes[286+32+137];//padding for maximum single op + stbi_uc codelength_sizes[19]; + int i,n; + + int hlit = stbi__zreceive(a,5) + 257; + int hdist = stbi__zreceive(a,5) + 1; + int hclen = stbi__zreceive(a,4) + 4; + + memset(codelength_sizes, 0, sizeof(codelength_sizes)); + for (i=0; i < hclen; ++i) { + int s = stbi__zreceive(a,3); + codelength_sizes[length_dezigzag[i]] = (stbi_uc) s; + } + if (!stbi__zbuild_huffman(&z_codelength, codelength_sizes, 19)) return 0; + + n = 0; + while (n < hlit + hdist) { + int c = stbi__zhuffman_decode(a, &z_codelength); + if (c < 0 || c >= 19) return stbi__err("bad codelengths", "Corrupt PNG"); + if (c < 16) + lencodes[n++] = (stbi_uc) c; + else if (c == 16) { + c = stbi__zreceive(a,2)+3; + memset(lencodes+n, lencodes[n-1], c); + n += c; + } else if (c == 17) { + c = stbi__zreceive(a,3)+3; + memset(lencodes+n, 0, c); + n += c; + } else { + STBI_ASSERT(c == 18); + c = stbi__zreceive(a,7)+11; + memset(lencodes+n, 0, c); + n += c; + } + } + if (n != hlit+hdist) return stbi__err("bad codelengths","Corrupt PNG"); + if (!stbi__zbuild_huffman(&a->z_length, lencodes, hlit)) return 0; + if (!stbi__zbuild_huffman(&a->z_distance, lencodes+hlit, hdist)) return 0; + return 1; +} + +static int stbi__parse_uncomperssed_block(stbi__zbuf *a) +{ + stbi_uc header[4]; + int len,nlen,k; + if (a->num_bits & 7) + stbi__zreceive(a, a->num_bits & 7); // discard + // drain the bit-packed data into header + k = 0; + while (a->num_bits > 0) { + header[k++] = (stbi_uc) (a->code_buffer & 255); // suppress MSVC run-time check + a->code_buffer >>= 8; + a->num_bits -= 8; + } + STBI_ASSERT(a->num_bits == 0); + // now fill header the normal way + while (k < 4) + header[k++] = stbi__zget8(a); + len = header[1] * 256 + header[0]; + nlen = header[3] * 256 + header[2]; + if (nlen != (len ^ 0xffff)) return stbi__err("zlib corrupt","Corrupt PNG"); + if (a->zbuffer + len > a->zbuffer_end) return stbi__err("read past buffer","Corrupt PNG"); + if (a->zout + len > a->zout_end) + if (!stbi__zexpand(a, a->zout, len)) return 0; + memcpy(a->zout, a->zbuffer, len); + a->zbuffer += len; + a->zout += len; + return 1; +} + +static int stbi__parse_zlib_header(stbi__zbuf *a) +{ + int cmf = stbi__zget8(a); + int cm = cmf & 15; + /* int cinfo = cmf >> 4; */ + int flg = stbi__zget8(a); + if ((cmf*256+flg) % 31 != 0) return stbi__err("bad zlib header","Corrupt PNG"); // zlib spec + if (flg & 32) return stbi__err("no preset dict","Corrupt PNG"); // preset dictionary not allowed in png + if (cm != 8) return stbi__err("bad compression","Corrupt PNG"); // DEFLATE required for png + // window = 1 << (8 + cinfo)... but who cares, we fully buffer output + return 1; +} + +// @TODO: should statically initialize these for optimal thread safety +static stbi_uc stbi__zdefault_length[288], stbi__zdefault_distance[32]; +static void stbi__init_zdefaults(void) +{ + int i; // use <= to match clearly with spec + for (i=0; i <= 143; ++i) stbi__zdefault_length[i] = 8; + for ( ; i <= 255; ++i) stbi__zdefault_length[i] = 9; + for ( ; i <= 279; ++i) stbi__zdefault_length[i] = 7; + for ( ; i <= 287; ++i) stbi__zdefault_length[i] = 8; + + for (i=0; i <= 31; ++i) stbi__zdefault_distance[i] = 5; +} + +static int stbi__parse_zlib(stbi__zbuf *a, int parse_header) +{ + int final, type; + if (parse_header) + if (!stbi__parse_zlib_header(a)) return 0; + a->num_bits = 0; + a->code_buffer = 0; + do { + final = stbi__zreceive(a,1); + type = stbi__zreceive(a,2); + if (type == 0) { + if (!stbi__parse_uncomperssed_block(a)) return 0; + } else if (type == 3) { + return 0; + } else { + if (type == 1) { + // use fixed code lengths + if (!stbi__zdefault_distance[31]) stbi__init_zdefaults(); + if (!stbi__zbuild_huffman(&a->z_length , stbi__zdefault_length , 288)) return 0; + if (!stbi__zbuild_huffman(&a->z_distance, stbi__zdefault_distance, 32)) return 0; + } else { + if (!stbi__compute_huffman_codes(a)) return 0; + } + if (!stbi__parse_huffman_block(a)) return 0; + } + } while (!final); + return 1; +} + +static int stbi__do_zlib(stbi__zbuf *a, char *obuf, int olen, int exp, int parse_header) +{ + a->zout_start = obuf; + a->zout = obuf; + a->zout_end = obuf + olen; + a->z_expandable = exp; + + return stbi__parse_zlib(a, parse_header); +} + +STBIDEF char *stbi_zlib_decode_malloc_guesssize(const char *buffer, int len, int initial_size, int *outlen) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(initial_size); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer + len; + if (stbi__do_zlib(&a, p, initial_size, 1, 1)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF char *stbi_zlib_decode_malloc(char const *buffer, int len, int *outlen) +{ + return stbi_zlib_decode_malloc_guesssize(buffer, len, 16384, outlen); +} + +STBIDEF char *stbi_zlib_decode_malloc_guesssize_headerflag(const char *buffer, int len, int initial_size, int *outlen, int parse_header) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(initial_size); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer + len; + if (stbi__do_zlib(&a, p, initial_size, 1, parse_header)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF int stbi_zlib_decode_buffer(char *obuffer, int olen, char const *ibuffer, int ilen) +{ + stbi__zbuf a; + a.zbuffer = (stbi_uc *) ibuffer; + a.zbuffer_end = (stbi_uc *) ibuffer + ilen; + if (stbi__do_zlib(&a, obuffer, olen, 0, 1)) + return (int) (a.zout - a.zout_start); + else + return -1; +} + +STBIDEF char *stbi_zlib_decode_noheader_malloc(char const *buffer, int len, int *outlen) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(16384); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer+len; + if (stbi__do_zlib(&a, p, 16384, 1, 0)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF int stbi_zlib_decode_noheader_buffer(char *obuffer, int olen, const char *ibuffer, int ilen) +{ + stbi__zbuf a; + a.zbuffer = (stbi_uc *) ibuffer; + a.zbuffer_end = (stbi_uc *) ibuffer + ilen; + if (stbi__do_zlib(&a, obuffer, olen, 0, 0)) + return (int) (a.zout - a.zout_start); + else + return -1; +} +#endif + +// public domain "baseline" PNG decoder v0.10 Sean Barrett 2006-11-18 +// simple implementation +// - only 8-bit samples +// - no CRC checking +// - allocates lots of intermediate memory +// - avoids problem of streaming data between subsystems +// - avoids explicit window management +// performance +// - uses stb_zlib, a PD zlib implementation with fast huffman decoding + +#ifndef STBI_NO_PNG +typedef struct +{ + stbi__uint32 length; + stbi__uint32 type; +} stbi__pngchunk; + +static stbi__pngchunk stbi__get_chunk_header(stbi__context *s) +{ + stbi__pngchunk c; + c.length = stbi__get32be(s); + c.type = stbi__get32be(s); + return c; +} + +static int stbi__check_png_header(stbi__context *s) +{ + static stbi_uc png_sig[8] = { 137,80,78,71,13,10,26,10 }; + int i; + for (i=0; i < 8; ++i) + if (stbi__get8(s) != png_sig[i]) return stbi__err("bad png sig","Not a PNG"); + return 1; +} + +typedef struct +{ + stbi__context *s; + stbi_uc *idata, *expanded, *out; +} stbi__png; + + +enum { + STBI__F_none=0, + STBI__F_sub=1, + STBI__F_up=2, + STBI__F_avg=3, + STBI__F_paeth=4, + // synthetic filters used for first scanline to avoid needing a dummy row of 0s + STBI__F_avg_first, + STBI__F_paeth_first +}; + +static stbi_uc first_row_filter[5] = +{ + STBI__F_none, + STBI__F_sub, + STBI__F_none, + STBI__F_avg_first, + STBI__F_paeth_first +}; + +static int stbi__paeth(int a, int b, int c) +{ + int p = a + b - c; + int pa = abs(p-a); + int pb = abs(p-b); + int pc = abs(p-c); + if (pa <= pb && pa <= pc) return a; + if (pb <= pc) return b; + return c; +} + +static stbi_uc stbi__depth_scale_table[9] = { 0, 0xff, 0x55, 0, 0x11, 0,0,0, 0x01 }; + +// create the png data from post-deflated data +static int stbi__create_png_image_raw(stbi__png *a, stbi_uc *raw, stbi__uint32 raw_len, int out_n, stbi__uint32 x, stbi__uint32 y, int depth, int color) +{ + stbi__context *s = a->s; + stbi__uint32 i,j,stride = x*out_n; + stbi__uint32 img_len, img_width_bytes; + int k; + int img_n = s->img_n; // copy it into a local for later + + STBI_ASSERT(out_n == s->img_n || out_n == s->img_n+1); + a->out = (stbi_uc *) stbi__malloc(x * y * out_n); // extra bytes to write off the end into + if (!a->out) return stbi__err("outofmem", "Out of memory"); + + img_width_bytes = (((img_n * x * depth) + 7) >> 3); + img_len = (img_width_bytes + 1) * y; + if (s->img_x == x && s->img_y == y) { + if (raw_len != img_len) return stbi__err("not enough pixels","Corrupt PNG"); + } else { // interlaced: + if (raw_len < img_len) return stbi__err("not enough pixels","Corrupt PNG"); + } + + for (j=0; j < y; ++j) { + stbi_uc *cur = a->out + stride*j; + stbi_uc *prior = cur - stride; + int filter = *raw++; + int filter_bytes = img_n; + int width = x; + if (filter > 4) + return stbi__err("invalid filter","Corrupt PNG"); + + if (depth < 8) { + STBI_ASSERT(img_width_bytes <= x); + cur += x*out_n - img_width_bytes; // store output to the rightmost img_len bytes, so we can decode in place + filter_bytes = 1; + width = img_width_bytes; + } + + // if first row, use special filter that doesn't sample previous row + if (j == 0) filter = first_row_filter[filter]; + + // handle first byte explicitly + for (k=0; k < filter_bytes; ++k) { + switch (filter) { + case STBI__F_none : cur[k] = raw[k]; break; + case STBI__F_sub : cur[k] = raw[k]; break; + case STBI__F_up : cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + case STBI__F_avg : cur[k] = STBI__BYTECAST(raw[k] + (prior[k]>>1)); break; + case STBI__F_paeth : cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(0,prior[k],0)); break; + case STBI__F_avg_first : cur[k] = raw[k]; break; + case STBI__F_paeth_first: cur[k] = raw[k]; break; + } + } + + if (depth == 8) { + if (img_n != out_n) + cur[img_n] = 255; // first pixel + raw += img_n; + cur += out_n; + prior += out_n; + } else { + raw += 1; + cur += 1; + prior += 1; + } + + // this is a little gross, so that we don't switch per-pixel or per-component + if (depth < 8 || img_n == out_n) { + int nk = (width - 1)*img_n; + #define CASE(f) \ + case f: \ + for (k=0; k < nk; ++k) + switch (filter) { + // "none" filter turns into a memcpy here; make that explicit. + case STBI__F_none: memcpy(cur, raw, nk); break; + CASE(STBI__F_sub) cur[k] = STBI__BYTECAST(raw[k] + cur[k-filter_bytes]); break; + CASE(STBI__F_up) cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + CASE(STBI__F_avg) cur[k] = STBI__BYTECAST(raw[k] + ((prior[k] + cur[k-filter_bytes])>>1)); break; + CASE(STBI__F_paeth) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-filter_bytes],prior[k],prior[k-filter_bytes])); break; + CASE(STBI__F_avg_first) cur[k] = STBI__BYTECAST(raw[k] + (cur[k-filter_bytes] >> 1)); break; + CASE(STBI__F_paeth_first) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-filter_bytes],0,0)); break; + } + #undef CASE + raw += nk; + } else { + STBI_ASSERT(img_n+1 == out_n); + #define CASE(f) \ + case f: \ + for (i=x-1; i >= 1; --i, cur[img_n]=255,raw+=img_n,cur+=out_n,prior+=out_n) \ + for (k=0; k < img_n; ++k) + switch (filter) { + CASE(STBI__F_none) cur[k] = raw[k]; break; + CASE(STBI__F_sub) cur[k] = STBI__BYTECAST(raw[k] + cur[k-out_n]); break; + CASE(STBI__F_up) cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + CASE(STBI__F_avg) cur[k] = STBI__BYTECAST(raw[k] + ((prior[k] + cur[k-out_n])>>1)); break; + CASE(STBI__F_paeth) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-out_n],prior[k],prior[k-out_n])); break; + CASE(STBI__F_avg_first) cur[k] = STBI__BYTECAST(raw[k] + (cur[k-out_n] >> 1)); break; + CASE(STBI__F_paeth_first) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-out_n],0,0)); break; + } + #undef CASE + } + } + + // we make a separate pass to expand bits to pixels; for performance, + // this could run two scanlines behind the above code, so it won't + // intefere with filtering but will still be in the cache. + if (depth < 8) { + for (j=0; j < y; ++j) { + stbi_uc *cur = a->out + stride*j; + stbi_uc *in = a->out + stride*j + x*out_n - img_width_bytes; + // unpack 1/2/4-bit into a 8-bit buffer. allows us to keep the common 8-bit path optimal at minimal cost for 1/2/4-bit + // png guarante byte alignment, if width is not multiple of 8/4/2 we'll decode dummy trailing data that will be skipped in the later loop + stbi_uc scale = (color == 0) ? stbi__depth_scale_table[depth] : 1; // scale grayscale values to 0..255 range + + // note that the final byte might overshoot and write more data than desired. + // we can allocate enough data that this never writes out of memory, but it + // could also overwrite the next scanline. can it overwrite non-empty data + // on the next scanline? yes, consider 1-pixel-wide scanlines with 1-bit-per-pixel. + // so we need to explicitly clamp the final ones + + if (depth == 4) { + for (k=x*img_n; k >= 2; k-=2, ++in) { + *cur++ = scale * ((*in >> 4) ); + *cur++ = scale * ((*in ) & 0x0f); + } + if (k > 0) *cur++ = scale * ((*in >> 4) ); + } else if (depth == 2) { + for (k=x*img_n; k >= 4; k-=4, ++in) { + *cur++ = scale * ((*in >> 6) ); + *cur++ = scale * ((*in >> 4) & 0x03); + *cur++ = scale * ((*in >> 2) & 0x03); + *cur++ = scale * ((*in ) & 0x03); + } + if (k > 0) *cur++ = scale * ((*in >> 6) ); + if (k > 1) *cur++ = scale * ((*in >> 4) & 0x03); + if (k > 2) *cur++ = scale * ((*in >> 2) & 0x03); + } else if (depth == 1) { + for (k=x*img_n; k >= 8; k-=8, ++in) { + *cur++ = scale * ((*in >> 7) ); + *cur++ = scale * ((*in >> 6) & 0x01); + *cur++ = scale * ((*in >> 5) & 0x01); + *cur++ = scale * ((*in >> 4) & 0x01); + *cur++ = scale * ((*in >> 3) & 0x01); + *cur++ = scale * ((*in >> 2) & 0x01); + *cur++ = scale * ((*in >> 1) & 0x01); + *cur++ = scale * ((*in ) & 0x01); + } + if (k > 0) *cur++ = scale * ((*in >> 7) ); + if (k > 1) *cur++ = scale * ((*in >> 6) & 0x01); + if (k > 2) *cur++ = scale * ((*in >> 5) & 0x01); + if (k > 3) *cur++ = scale * ((*in >> 4) & 0x01); + if (k > 4) *cur++ = scale * ((*in >> 3) & 0x01); + if (k > 5) *cur++ = scale * ((*in >> 2) & 0x01); + if (k > 6) *cur++ = scale * ((*in >> 1) & 0x01); + } + if (img_n != out_n) { + int q; + // insert alpha = 255 + cur = a->out + stride*j; + if (img_n == 1) { + for (q=x-1; q >= 0; --q) { + cur[q*2+1] = 255; + cur[q*2+0] = cur[q]; + } + } else { + STBI_ASSERT(img_n == 3); + for (q=x-1; q >= 0; --q) { + cur[q*4+3] = 255; + cur[q*4+2] = cur[q*3+2]; + cur[q*4+1] = cur[q*3+1]; + cur[q*4+0] = cur[q*3+0]; + } + } + } + } + } + + return 1; +} + +static int stbi__create_png_image(stbi__png *a, stbi_uc *image_data, stbi__uint32 image_data_len, int out_n, int depth, int color, int interlaced) +{ + stbi_uc *final; + int p; + if (!interlaced) + return stbi__create_png_image_raw(a, image_data, image_data_len, out_n, a->s->img_x, a->s->img_y, depth, color); + + // de-interlacing + final = (stbi_uc *) stbi__malloc(a->s->img_x * a->s->img_y * out_n); + for (p=0; p < 7; ++p) { + int xorig[] = { 0,4,0,2,0,1,0 }; + int yorig[] = { 0,0,4,0,2,0,1 }; + int xspc[] = { 8,8,4,4,2,2,1 }; + int yspc[] = { 8,8,8,4,4,2,2 }; + int i,j,x,y; + // pass1_x[4] = 0, pass1_x[5] = 1, pass1_x[12] = 1 + x = (a->s->img_x - xorig[p] + xspc[p]-1) / xspc[p]; + y = (a->s->img_y - yorig[p] + yspc[p]-1) / yspc[p]; + if (x && y) { + stbi__uint32 img_len = ((((a->s->img_n * x * depth) + 7) >> 3) + 1) * y; + if (!stbi__create_png_image_raw(a, image_data, image_data_len, out_n, x, y, depth, color)) { + STBI_FREE(final); + return 0; + } + for (j=0; j < y; ++j) { + for (i=0; i < x; ++i) { + int out_y = j*yspc[p]+yorig[p]; + int out_x = i*xspc[p]+xorig[p]; + memcpy(final + out_y*a->s->img_x*out_n + out_x*out_n, + a->out + (j*x+i)*out_n, out_n); + } + } + STBI_FREE(a->out); + image_data += img_len; + image_data_len -= img_len; + } + } + a->out = final; + + return 1; +} + +static int stbi__compute_transparency(stbi__png *z, stbi_uc tc[3], int out_n) +{ + stbi__context *s = z->s; + stbi__uint32 i, pixel_count = s->img_x * s->img_y; + stbi_uc *p = z->out; + + // compute color-based transparency, assuming we've + // already got 255 as the alpha value in the output + STBI_ASSERT(out_n == 2 || out_n == 4); + + if (out_n == 2) { + for (i=0; i < pixel_count; ++i) { + p[1] = (p[0] == tc[0] ? 0 : 255); + p += 2; + } + } else { + for (i=0; i < pixel_count; ++i) { + if (p[0] == tc[0] && p[1] == tc[1] && p[2] == tc[2]) + p[3] = 0; + p += 4; + } + } + return 1; +} + +static int stbi__expand_png_palette(stbi__png *a, stbi_uc *palette, int len, int pal_img_n) +{ + stbi__uint32 i, pixel_count = a->s->img_x * a->s->img_y; + stbi_uc *p, *temp_out, *orig = a->out; + + p = (stbi_uc *) stbi__malloc(pixel_count * pal_img_n); + if (p == NULL) return stbi__err("outofmem", "Out of memory"); + + // between here and free(out) below, exitting would leak + temp_out = p; + + if (pal_img_n == 3) { + for (i=0; i < pixel_count; ++i) { + int n = orig[i]*4; + p[0] = palette[n ]; + p[1] = palette[n+1]; + p[2] = palette[n+2]; + p += 3; + } + } else { + for (i=0; i < pixel_count; ++i) { + int n = orig[i]*4; + p[0] = palette[n ]; + p[1] = palette[n+1]; + p[2] = palette[n+2]; + p[3] = palette[n+3]; + p += 4; + } + } + STBI_FREE(a->out); + a->out = temp_out; + + STBI_NOTUSED(len); + + return 1; +} + +static int stbi__unpremultiply_on_load = 0; +static int stbi__de_iphone_flag = 0; + +STBIDEF void stbi_set_unpremultiply_on_load(int flag_true_if_should_unpremultiply) +{ + stbi__unpremultiply_on_load = flag_true_if_should_unpremultiply; +} + +STBIDEF void stbi_convert_iphone_png_to_rgb(int flag_true_if_should_convert) +{ + stbi__de_iphone_flag = flag_true_if_should_convert; +} + +static void stbi__de_iphone(stbi__png *z) +{ + stbi__context *s = z->s; + stbi__uint32 i, pixel_count = s->img_x * s->img_y; + stbi_uc *p = z->out; + + if (s->img_out_n == 3) { // convert bgr to rgb + for (i=0; i < pixel_count; ++i) { + stbi_uc t = p[0]; + p[0] = p[2]; + p[2] = t; + p += 3; + } + } else { + STBI_ASSERT(s->img_out_n == 4); + if (stbi__unpremultiply_on_load) { + // convert bgr to rgb and unpremultiply + for (i=0; i < pixel_count; ++i) { + stbi_uc a = p[3]; + stbi_uc t = p[0]; + if (a) { + p[0] = p[2] * 255 / a; + p[1] = p[1] * 255 / a; + p[2] = t * 255 / a; + } else { + p[0] = p[2]; + p[2] = t; + } + p += 4; + } + } else { + // convert bgr to rgb + for (i=0; i < pixel_count; ++i) { + stbi_uc t = p[0]; + p[0] = p[2]; + p[2] = t; + p += 4; + } + } + } +} + +#define STBI__PNG_TYPE(a,b,c,d) (((a) << 24) + ((b) << 16) + ((c) << 8) + (d)) + +static int stbi__parse_png_file(stbi__png *z, int scan, int req_comp) +{ + stbi_uc palette[1024], pal_img_n=0; + stbi_uc has_trans=0, tc[3]; + stbi__uint32 ioff=0, idata_limit=0, i, pal_len=0; + int first=1,k,interlace=0, color=0, depth=0, is_iphone=0; + stbi__context *s = z->s; + + z->expanded = NULL; + z->idata = NULL; + z->out = NULL; + + if (!stbi__check_png_header(s)) return 0; + + if (scan == STBI__SCAN_type) return 1; + + for (;;) { + stbi__pngchunk c = stbi__get_chunk_header(s); + switch (c.type) { + case STBI__PNG_TYPE('C','g','B','I'): + is_iphone = 1; + stbi__skip(s, c.length); + break; + case STBI__PNG_TYPE('I','H','D','R'): { + int comp,filter; + if (!first) return stbi__err("multiple IHDR","Corrupt PNG"); + first = 0; + if (c.length != 13) return stbi__err("bad IHDR len","Corrupt PNG"); + s->img_x = stbi__get32be(s); if (s->img_x > (1 << 24)) return stbi__err("too large","Very large image (corrupt?)"); + s->img_y = stbi__get32be(s); if (s->img_y > (1 << 24)) return stbi__err("too large","Very large image (corrupt?)"); + depth = stbi__get8(s); if (depth != 1 && depth != 2 && depth != 4 && depth != 8) return stbi__err("1/2/4/8-bit only","PNG not supported: 1/2/4/8-bit only"); + color = stbi__get8(s); if (color > 6) return stbi__err("bad ctype","Corrupt PNG"); + if (color == 3) pal_img_n = 3; else if (color & 1) return stbi__err("bad ctype","Corrupt PNG"); + comp = stbi__get8(s); if (comp) return stbi__err("bad comp method","Corrupt PNG"); + filter= stbi__get8(s); if (filter) return stbi__err("bad filter method","Corrupt PNG"); + interlace = stbi__get8(s); if (interlace>1) return stbi__err("bad interlace method","Corrupt PNG"); + if (!s->img_x || !s->img_y) return stbi__err("0-pixel image","Corrupt PNG"); + if (!pal_img_n) { + s->img_n = (color & 2 ? 3 : 1) + (color & 4 ? 1 : 0); + if ((1 << 30) / s->img_x / s->img_n < s->img_y) return stbi__err("too large", "Image too large to decode"); + if (scan == STBI__SCAN_header) return 1; + } else { + // if paletted, then pal_n is our final components, and + // img_n is # components to decompress/filter. + s->img_n = 1; + if ((1 << 30) / s->img_x / 4 < s->img_y) return stbi__err("too large","Corrupt PNG"); + // if SCAN_header, have to scan to see if we have a tRNS + } + break; + } + + case STBI__PNG_TYPE('P','L','T','E'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (c.length > 256*3) return stbi__err("invalid PLTE","Corrupt PNG"); + pal_len = c.length / 3; + if (pal_len * 3 != c.length) return stbi__err("invalid PLTE","Corrupt PNG"); + for (i=0; i < pal_len; ++i) { + palette[i*4+0] = stbi__get8(s); + palette[i*4+1] = stbi__get8(s); + palette[i*4+2] = stbi__get8(s); + palette[i*4+3] = 255; + } + break; + } + + case STBI__PNG_TYPE('t','R','N','S'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (z->idata) return stbi__err("tRNS after IDAT","Corrupt PNG"); + if (pal_img_n) { + if (scan == STBI__SCAN_header) { s->img_n = 4; return 1; } + if (pal_len == 0) return stbi__err("tRNS before PLTE","Corrupt PNG"); + if (c.length > pal_len) return stbi__err("bad tRNS len","Corrupt PNG"); + pal_img_n = 4; + for (i=0; i < c.length; ++i) + palette[i*4+3] = stbi__get8(s); + } else { + if (!(s->img_n & 1)) return stbi__err("tRNS with alpha","Corrupt PNG"); + if (c.length != (stbi__uint32) s->img_n*2) return stbi__err("bad tRNS len","Corrupt PNG"); + has_trans = 1; + for (k=0; k < s->img_n; ++k) + tc[k] = (stbi_uc) (stbi__get16be(s) & 255) * stbi__depth_scale_table[depth]; // non 8-bit images will be larger + } + break; + } + + case STBI__PNG_TYPE('I','D','A','T'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (pal_img_n && !pal_len) return stbi__err("no PLTE","Corrupt PNG"); + if (scan == STBI__SCAN_header) { s->img_n = pal_img_n; return 1; } + if ((int)(ioff + c.length) < (int)ioff) return 0; + if (ioff + c.length > idata_limit) { + stbi__uint32 idata_limit_old = idata_limit; + stbi_uc *p; + if (idata_limit == 0) idata_limit = c.length > 4096 ? c.length : 4096; + while (ioff + c.length > idata_limit) + idata_limit *= 2; + STBI_NOTUSED(idata_limit_old); + p = (stbi_uc *) STBI_REALLOC_SIZED(z->idata, idata_limit_old, idata_limit); if (p == NULL) return stbi__err("outofmem", "Out of memory"); + z->idata = p; + } + if (!stbi__getn(s, z->idata+ioff,c.length)) return stbi__err("outofdata","Corrupt PNG"); + ioff += c.length; + break; + } + + case STBI__PNG_TYPE('I','E','N','D'): { + stbi__uint32 raw_len, bpl; + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (scan != STBI__SCAN_load) return 1; + if (z->idata == NULL) return stbi__err("no IDAT","Corrupt PNG"); + // initial guess for decoded data size to avoid unnecessary reallocs + bpl = (s->img_x * depth + 7) / 8; // bytes per line, per component + raw_len = bpl * s->img_y * s->img_n /* pixels */ + s->img_y /* filter mode per row */; + z->expanded = (stbi_uc *) stbi_zlib_decode_malloc_guesssize_headerflag((char *) z->idata, ioff, raw_len, (int *) &raw_len, !is_iphone); + if (z->expanded == NULL) return 0; // zlib should set error + STBI_FREE(z->idata); z->idata = NULL; + if ((req_comp == s->img_n+1 && req_comp != 3 && !pal_img_n) || has_trans) + s->img_out_n = s->img_n+1; + else + s->img_out_n = s->img_n; + if (!stbi__create_png_image(z, z->expanded, raw_len, s->img_out_n, depth, color, interlace)) return 0; + if (has_trans) + if (!stbi__compute_transparency(z, tc, s->img_out_n)) return 0; + if (is_iphone && stbi__de_iphone_flag && s->img_out_n > 2) + stbi__de_iphone(z); + if (pal_img_n) { + // pal_img_n == 3 or 4 + s->img_n = pal_img_n; // record the actual colors we had + s->img_out_n = pal_img_n; + if (req_comp >= 3) s->img_out_n = req_comp; + if (!stbi__expand_png_palette(z, palette, pal_len, s->img_out_n)) + return 0; + } + STBI_FREE(z->expanded); z->expanded = NULL; + return 1; + } + + default: + // if critical, fail + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if ((c.type & (1 << 29)) == 0) { + #ifndef STBI_NO_FAILURE_STRINGS + // not threadsafe + static char invalid_chunk[] = "XXXX PNG chunk not known"; + invalid_chunk[0] = STBI__BYTECAST(c.type >> 24); + invalid_chunk[1] = STBI__BYTECAST(c.type >> 16); + invalid_chunk[2] = STBI__BYTECAST(c.type >> 8); + invalid_chunk[3] = STBI__BYTECAST(c.type >> 0); + #endif + return stbi__err(invalid_chunk, "PNG not supported: unknown PNG chunk type"); + } + stbi__skip(s, c.length); + break; + } + // end of PNG chunk, read and skip CRC + stbi__get32be(s); + } +} + +static unsigned char *stbi__do_png(stbi__png *p, int *x, int *y, int *n, int req_comp) +{ + unsigned char *result=NULL; + if (req_comp < 0 || req_comp > 4) return stbi__errpuc("bad req_comp", "Internal error"); + if (stbi__parse_png_file(p, STBI__SCAN_load, req_comp)) { + result = p->out; + p->out = NULL; + if (req_comp && req_comp != p->s->img_out_n) { + result = stbi__convert_format(result, p->s->img_out_n, req_comp, p->s->img_x, p->s->img_y); + p->s->img_out_n = req_comp; + if (result == NULL) return result; + } + *x = p->s->img_x; + *y = p->s->img_y; + if (n) *n = p->s->img_out_n; + } + STBI_FREE(p->out); p->out = NULL; + STBI_FREE(p->expanded); p->expanded = NULL; + STBI_FREE(p->idata); p->idata = NULL; + + return result; +} + +static unsigned char *stbi__png_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi__png p; + p.s = s; + return stbi__do_png(&p, x,y,comp,req_comp); +} + +static int stbi__png_test(stbi__context *s) +{ + int r; + r = stbi__check_png_header(s); + stbi__rewind(s); + return r; +} + +static int stbi__png_info_raw(stbi__png *p, int *x, int *y, int *comp) +{ + if (!stbi__parse_png_file(p, STBI__SCAN_header, 0)) { + stbi__rewind( p->s ); + return 0; + } + if (x) *x = p->s->img_x; + if (y) *y = p->s->img_y; + if (comp) *comp = p->s->img_n; + return 1; +} + +static int stbi__png_info(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__png p; + p.s = s; + return stbi__png_info_raw(&p, x, y, comp); +} +#endif + +// Microsoft/Windows BMP image + +#ifndef STBI_NO_BMP +static int stbi__bmp_test_raw(stbi__context *s) +{ + int r; + int sz; + if (stbi__get8(s) != 'B') return 0; + if (stbi__get8(s) != 'M') return 0; + stbi__get32le(s); // discard filesize + stbi__get16le(s); // discard reserved + stbi__get16le(s); // discard reserved + stbi__get32le(s); // discard data offset + sz = stbi__get32le(s); + r = (sz == 12 || sz == 40 || sz == 56 || sz == 108 || sz == 124); + return r; +} + +static int stbi__bmp_test(stbi__context *s) +{ + int r = stbi__bmp_test_raw(s); + stbi__rewind(s); + return r; +} + + +// returns 0..31 for the highest set bit +static int stbi__high_bit(unsigned int z) +{ + int n=0; + if (z == 0) return -1; + if (z >= 0x10000) n += 16, z >>= 16; + if (z >= 0x00100) n += 8, z >>= 8; + if (z >= 0x00010) n += 4, z >>= 4; + if (z >= 0x00004) n += 2, z >>= 2; + if (z >= 0x00002) n += 1, z >>= 1; + return n; +} + +static int stbi__bitcount(unsigned int a) +{ + a = (a & 0x55555555) + ((a >> 1) & 0x55555555); // max 2 + a = (a & 0x33333333) + ((a >> 2) & 0x33333333); // max 4 + a = (a + (a >> 4)) & 0x0f0f0f0f; // max 8 per 4, now 8 bits + a = (a + (a >> 8)); // max 16 per 8 bits + a = (a + (a >> 16)); // max 32 per 8 bits + return a & 0xff; +} + +static int stbi__shiftsigned(int v, int shift, int bits) +{ + int result; + int z=0; + + if (shift < 0) v <<= -shift; + else v >>= shift; + result = v; + + z = bits; + while (z < 8) { + result += v >> z; + z += bits; + } + return result; +} + +typedef struct +{ + int bpp, offset, hsz; + unsigned int mr,mg,mb,ma, all_a; +} stbi__bmp_data; + +static void *stbi__bmp_parse_header(stbi__context *s, stbi__bmp_data *info) +{ + int hsz; + if (stbi__get8(s) != 'B' || stbi__get8(s) != 'M') return stbi__errpuc("not BMP", "Corrupt BMP"); + stbi__get32le(s); // discard filesize + stbi__get16le(s); // discard reserved + stbi__get16le(s); // discard reserved + info->offset = stbi__get32le(s); + info->hsz = hsz = stbi__get32le(s); + + if (hsz != 12 && hsz != 40 && hsz != 56 && hsz != 108 && hsz != 124) return stbi__errpuc("unknown BMP", "BMP type not supported: unknown"); + if (hsz == 12) { + s->img_x = stbi__get16le(s); + s->img_y = stbi__get16le(s); + } else { + s->img_x = stbi__get32le(s); + s->img_y = stbi__get32le(s); + } + if (stbi__get16le(s) != 1) return stbi__errpuc("bad BMP", "bad BMP"); + info->bpp = stbi__get16le(s); + if (info->bpp == 1) return stbi__errpuc("monochrome", "BMP type not supported: 1-bit"); + if (hsz != 12) { + int compress = stbi__get32le(s); + if (compress == 1 || compress == 2) return stbi__errpuc("BMP RLE", "BMP type not supported: RLE"); + stbi__get32le(s); // discard sizeof + stbi__get32le(s); // discard hres + stbi__get32le(s); // discard vres + stbi__get32le(s); // discard colorsused + stbi__get32le(s); // discard max important + if (hsz == 40 || hsz == 56) { + if (hsz == 56) { + stbi__get32le(s); + stbi__get32le(s); + stbi__get32le(s); + stbi__get32le(s); + } + if (info->bpp == 16 || info->bpp == 32) { + info->mr = info->mg = info->mb = 0; + if (compress == 0) { + if (info->bpp == 32) { + info->mr = 0xffu << 16; + info->mg = 0xffu << 8; + info->mb = 0xffu << 0; + info->ma = 0xffu << 24; + info->all_a = 0; // if all_a is 0 at end, then we loaded alpha channel but it was all 0 + } else { + info->mr = 31u << 10; + info->mg = 31u << 5; + info->mb = 31u << 0; + } + } else if (compress == 3) { + info->mr = stbi__get32le(s); + info->mg = stbi__get32le(s); + info->mb = stbi__get32le(s); + // not documented, but generated by photoshop and handled by mspaint + if (info->mr == info->mg && info->mg == info->mb) { + // ?!?!? + return stbi__errpuc("bad BMP", "bad BMP"); + } + } else + return stbi__errpuc("bad BMP", "bad BMP"); + } + } else { + int i; + if (hsz != 108 && hsz != 124) + return stbi__errpuc("bad BMP", "bad BMP"); + info->mr = stbi__get32le(s); + info->mg = stbi__get32le(s); + info->mb = stbi__get32le(s); + info->ma = stbi__get32le(s); + stbi__get32le(s); // discard color space + for (i=0; i < 12; ++i) + stbi__get32le(s); // discard color space parameters + if (hsz == 124) { + stbi__get32le(s); // discard rendering intent + stbi__get32le(s); // discard offset of profile data + stbi__get32le(s); // discard size of profile data + stbi__get32le(s); // discard reserved + } + } + } + return (void *) 1; +} + + +static stbi_uc *stbi__bmp_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *out; + unsigned int mr=0,mg=0,mb=0,ma=0, all_a; + stbi_uc pal[256][4]; + int psize=0,i,j,width; + int flip_vertically, pad, target; + stbi__bmp_data info; + + info.all_a = 255; + if (stbi__bmp_parse_header(s, &info) == NULL) + return NULL; // error code already set + + flip_vertically = ((int) s->img_y) > 0; + s->img_y = abs((int) s->img_y); + + mr = info.mr; + mg = info.mg; + mb = info.mb; + ma = info.ma; + all_a = info.all_a; + + if (info.hsz == 12) { + if (info.bpp < 24) + psize = (info.offset - 14 - 24) / 3; + } else { + if (info.bpp < 16) + psize = (info.offset - 14 - info.hsz) >> 2; + } + + s->img_n = ma ? 4 : 3; + if (req_comp && req_comp >= 3) // we can directly decode 3 or 4 + target = req_comp; + else + target = s->img_n; // if they want monochrome, we'll post-convert + + out = (stbi_uc *) stbi__malloc(target * s->img_x * s->img_y); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + if (info.bpp < 16) { + int z=0; + if (psize == 0 || psize > 256) { STBI_FREE(out); return stbi__errpuc("invalid", "Corrupt BMP"); } + for (i=0; i < psize; ++i) { + pal[i][2] = stbi__get8(s); + pal[i][1] = stbi__get8(s); + pal[i][0] = stbi__get8(s); + if (info.hsz != 12) stbi__get8(s); + pal[i][3] = 255; + } + stbi__skip(s, info.offset - 14 - info.hsz - psize * (info.hsz == 12 ? 3 : 4)); + if (info.bpp == 4) width = (s->img_x + 1) >> 1; + else if (info.bpp == 8) width = s->img_x; + else { STBI_FREE(out); return stbi__errpuc("bad bpp", "Corrupt BMP"); } + pad = (-width)&3; + for (j=0; j < (int) s->img_y; ++j) { + for (i=0; i < (int) s->img_x; i += 2) { + int v=stbi__get8(s),v2=0; + if (info.bpp == 4) { + v2 = v & 15; + v >>= 4; + } + out[z++] = pal[v][0]; + out[z++] = pal[v][1]; + out[z++] = pal[v][2]; + if (target == 4) out[z++] = 255; + if (i+1 == (int) s->img_x) break; + v = (info.bpp == 8) ? stbi__get8(s) : v2; + out[z++] = pal[v][0]; + out[z++] = pal[v][1]; + out[z++] = pal[v][2]; + if (target == 4) out[z++] = 255; + } + stbi__skip(s, pad); + } + } else { + int rshift=0,gshift=0,bshift=0,ashift=0,rcount=0,gcount=0,bcount=0,acount=0; + int z = 0; + int easy=0; + stbi__skip(s, info.offset - 14 - info.hsz); + if (info.bpp == 24) width = 3 * s->img_x; + else if (info.bpp == 16) width = 2*s->img_x; + else /* bpp = 32 and pad = 0 */ width=0; + pad = (-width) & 3; + if (info.bpp == 24) { + easy = 1; + } else if (info.bpp == 32) { + if (mb == 0xff && mg == 0xff00 && mr == 0x00ff0000 && ma == 0xff000000) + easy = 2; + } + if (!easy) { + if (!mr || !mg || !mb) { STBI_FREE(out); return stbi__errpuc("bad masks", "Corrupt BMP"); } + // right shift amt to put high bit in position #7 + rshift = stbi__high_bit(mr)-7; rcount = stbi__bitcount(mr); + gshift = stbi__high_bit(mg)-7; gcount = stbi__bitcount(mg); + bshift = stbi__high_bit(mb)-7; bcount = stbi__bitcount(mb); + ashift = stbi__high_bit(ma)-7; acount = stbi__bitcount(ma); + } + for (j=0; j < (int) s->img_y; ++j) { + if (easy) { + for (i=0; i < (int) s->img_x; ++i) { + unsigned char a; + out[z+2] = stbi__get8(s); + out[z+1] = stbi__get8(s); + out[z+0] = stbi__get8(s); + z += 3; + a = (easy == 2 ? stbi__get8(s) : 255); + all_a |= a; + if (target == 4) out[z++] = a; + } + } else { + int bpp = info.bpp; + for (i=0; i < (int) s->img_x; ++i) { + stbi__uint32 v = (bpp == 16 ? (stbi__uint32) stbi__get16le(s) : stbi__get32le(s)); + int a; + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mr, rshift, rcount)); + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mg, gshift, gcount)); + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mb, bshift, bcount)); + a = (ma ? stbi__shiftsigned(v & ma, ashift, acount) : 255); + all_a |= a; + if (target == 4) out[z++] = STBI__BYTECAST(a); + } + } + stbi__skip(s, pad); + } + } + + // if alpha channel is all 0s, replace with all 255s + if (target == 4 && all_a == 0) + for (i=4*s->img_x*s->img_y-1; i >= 0; i -= 4) + out[i] = 255; + + if (flip_vertically) { + stbi_uc t; + for (j=0; j < (int) s->img_y>>1; ++j) { + stbi_uc *p1 = out + j *s->img_x*target; + stbi_uc *p2 = out + (s->img_y-1-j)*s->img_x*target; + for (i=0; i < (int) s->img_x*target; ++i) { + t = p1[i], p1[i] = p2[i], p2[i] = t; + } + } + } + + if (req_comp && req_comp != target) { + out = stbi__convert_format(out, target, req_comp, s->img_x, s->img_y); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + + *x = s->img_x; + *y = s->img_y; + if (comp) *comp = s->img_n; + return out; +} +#endif + +// Targa Truevision - TGA +// by Jonathan Dummer +#ifndef STBI_NO_TGA +// returns STBI_rgb or whatever, 0 on error +static int stbi__tga_get_comp(int bits_per_pixel, int is_grey, int* is_rgb16) +{ + // only RGB or RGBA (incl. 16bit) or grey allowed + if(is_rgb16) *is_rgb16 = 0; + switch(bits_per_pixel) { + case 8: return STBI_grey; + case 16: if(is_grey) return STBI_grey_alpha; + // else: fall-through + case 15: if(is_rgb16) *is_rgb16 = 1; + return STBI_rgb; + case 24: // fall-through + case 32: return bits_per_pixel/8; + default: return 0; + } +} + +static int stbi__tga_info(stbi__context *s, int *x, int *y, int *comp) +{ + int tga_w, tga_h, tga_comp, tga_image_type, tga_bits_per_pixel, tga_colormap_bpp; + int sz, tga_colormap_type; + stbi__get8(s); // discard Offset + tga_colormap_type = stbi__get8(s); // colormap type + if( tga_colormap_type > 1 ) { + stbi__rewind(s); + return 0; // only RGB or indexed allowed + } + tga_image_type = stbi__get8(s); // image type + if ( tga_colormap_type == 1 ) { // colormapped (paletted) image + if (tga_image_type != 1 && tga_image_type != 9) { + stbi__rewind(s); + return 0; + } + stbi__skip(s,4); // skip index of first colormap entry and number of entries + sz = stbi__get8(s); // check bits per palette color entry + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) { + stbi__rewind(s); + return 0; + } + stbi__skip(s,4); // skip image x and y origin + tga_colormap_bpp = sz; + } else { // "normal" image w/o colormap - only RGB or grey allowed, +/- RLE + if ( (tga_image_type != 2) && (tga_image_type != 3) && (tga_image_type != 10) && (tga_image_type != 11) ) { + stbi__rewind(s); + return 0; // only RGB or grey allowed, +/- RLE + } + stbi__skip(s,9); // skip colormap specification and image x/y origin + tga_colormap_bpp = 0; + } + tga_w = stbi__get16le(s); + if( tga_w < 1 ) { + stbi__rewind(s); + return 0; // test width + } + tga_h = stbi__get16le(s); + if( tga_h < 1 ) { + stbi__rewind(s); + return 0; // test height + } + tga_bits_per_pixel = stbi__get8(s); // bits per pixel + stbi__get8(s); // ignore alpha bits + if (tga_colormap_bpp != 0) { + if((tga_bits_per_pixel != 8) && (tga_bits_per_pixel != 16)) { + // when using a colormap, tga_bits_per_pixel is the size of the indexes + // I don't think anything but 8 or 16bit indexes makes sense + stbi__rewind(s); + return 0; + } + tga_comp = stbi__tga_get_comp(tga_colormap_bpp, 0, NULL); + } else { + tga_comp = stbi__tga_get_comp(tga_bits_per_pixel, (tga_image_type == 3) || (tga_image_type == 11), NULL); + } + if(!tga_comp) { + stbi__rewind(s); + return 0; + } + if (x) *x = tga_w; + if (y) *y = tga_h; + if (comp) *comp = tga_comp; + return 1; // seems to have passed everything +} + +static int stbi__tga_test(stbi__context *s) +{ + int res = 0; + int sz, tga_color_type; + stbi__get8(s); // discard Offset + tga_color_type = stbi__get8(s); // color type + if ( tga_color_type > 1 ) goto errorEnd; // only RGB or indexed allowed + sz = stbi__get8(s); // image type + if ( tga_color_type == 1 ) { // colormapped (paletted) image + if (sz != 1 && sz != 9) goto errorEnd; // colortype 1 demands image type 1 or 9 + stbi__skip(s,4); // skip index of first colormap entry and number of entries + sz = stbi__get8(s); // check bits per palette color entry + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) goto errorEnd; + stbi__skip(s,4); // skip image x and y origin + } else { // "normal" image w/o colormap + if ( (sz != 2) && (sz != 3) && (sz != 10) && (sz != 11) ) goto errorEnd; // only RGB or grey allowed, +/- RLE + stbi__skip(s,9); // skip colormap specification and image x/y origin + } + if ( stbi__get16le(s) < 1 ) goto errorEnd; // test width + if ( stbi__get16le(s) < 1 ) goto errorEnd; // test height + sz = stbi__get8(s); // bits per pixel + if ( (tga_color_type == 1) && (sz != 8) && (sz != 16) ) goto errorEnd; // for colormapped images, bpp is size of an index + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) goto errorEnd; + + res = 1; // if we got this far, everything's good and we can return 1 instead of 0 + +errorEnd: + stbi__rewind(s); + return res; +} + +// read 16bit value and convert to 24bit RGB +void stbi__tga_read_rgb16(stbi__context *s, stbi_uc* out) +{ + stbi__uint16 px = stbi__get16le(s); + stbi__uint16 fiveBitMask = 31; + // we have 3 channels with 5bits each + int r = (px >> 10) & fiveBitMask; + int g = (px >> 5) & fiveBitMask; + int b = px & fiveBitMask; + // Note that this saves the data in RGB(A) order, so it doesn't need to be swapped later + out[0] = (r * 255)/31; + out[1] = (g * 255)/31; + out[2] = (b * 255)/31; + + // some people claim that the most significant bit might be used for alpha + // (possibly if an alpha-bit is set in the "image descriptor byte") + // but that only made 16bit test images completely translucent.. + // so let's treat all 15 and 16bit TGAs as RGB with no alpha. +} + +static stbi_uc *stbi__tga_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + // read in the TGA header stuff + int tga_offset = stbi__get8(s); + int tga_indexed = stbi__get8(s); + int tga_image_type = stbi__get8(s); + int tga_is_RLE = 0; + int tga_palette_start = stbi__get16le(s); + int tga_palette_len = stbi__get16le(s); + int tga_palette_bits = stbi__get8(s); + int tga_x_origin = stbi__get16le(s); + int tga_y_origin = stbi__get16le(s); + int tga_width = stbi__get16le(s); + int tga_height = stbi__get16le(s); + int tga_bits_per_pixel = stbi__get8(s); + int tga_comp, tga_rgb16=0; + int tga_inverted = stbi__get8(s); + // int tga_alpha_bits = tga_inverted & 15; // the 4 lowest bits - unused (useless?) + // image data + unsigned char *tga_data; + unsigned char *tga_palette = NULL; + int i, j; + unsigned char raw_data[4]; + int RLE_count = 0; + int RLE_repeating = 0; + int read_next_pixel = 1; + + // do a tiny bit of precessing + if ( tga_image_type >= 8 ) + { + tga_image_type -= 8; + tga_is_RLE = 1; + } + tga_inverted = 1 - ((tga_inverted >> 5) & 1); + + // If I'm paletted, then I'll use the number of bits from the palette + if ( tga_indexed ) tga_comp = stbi__tga_get_comp(tga_palette_bits, 0, &tga_rgb16); + else tga_comp = stbi__tga_get_comp(tga_bits_per_pixel, (tga_image_type == 3), &tga_rgb16); + + if(!tga_comp) // shouldn't really happen, stbi__tga_test() should have ensured basic consistency + return stbi__errpuc("bad format", "Can't find out TGA pixelformat"); + + // tga info + *x = tga_width; + *y = tga_height; + if (comp) *comp = tga_comp; + + tga_data = (unsigned char*)stbi__malloc( (size_t)tga_width * tga_height * tga_comp ); + if (!tga_data) return stbi__errpuc("outofmem", "Out of memory"); + + // skip to the data's starting position (offset usually = 0) + stbi__skip(s, tga_offset ); + + if ( !tga_indexed && !tga_is_RLE && !tga_rgb16 ) { + for (i=0; i < tga_height; ++i) { + int row = tga_inverted ? tga_height -i - 1 : i; + stbi_uc *tga_row = tga_data + row*tga_width*tga_comp; + stbi__getn(s, tga_row, tga_width * tga_comp); + } + } else { + // do I need to load a palette? + if ( tga_indexed) + { + // any data to skip? (offset usually = 0) + stbi__skip(s, tga_palette_start ); + // load the palette + tga_palette = (unsigned char*)stbi__malloc( tga_palette_len * tga_comp ); + if (!tga_palette) { + STBI_FREE(tga_data); + return stbi__errpuc("outofmem", "Out of memory"); + } + if (tga_rgb16) { + stbi_uc *pal_entry = tga_palette; + STBI_ASSERT(tga_comp == STBI_rgb); + for (i=0; i < tga_palette_len; ++i) { + stbi__tga_read_rgb16(s, pal_entry); + pal_entry += tga_comp; + } + } else if (!stbi__getn(s, tga_palette, tga_palette_len * tga_comp)) { + STBI_FREE(tga_data); + STBI_FREE(tga_palette); + return stbi__errpuc("bad palette", "Corrupt TGA"); + } + } + // load the data + for (i=0; i < tga_width * tga_height; ++i) + { + // if I'm in RLE mode, do I need to get a RLE stbi__pngchunk? + if ( tga_is_RLE ) + { + if ( RLE_count == 0 ) + { + // yep, get the next byte as a RLE command + int RLE_cmd = stbi__get8(s); + RLE_count = 1 + (RLE_cmd & 127); + RLE_repeating = RLE_cmd >> 7; + read_next_pixel = 1; + } else if ( !RLE_repeating ) + { + read_next_pixel = 1; + } + } else + { + read_next_pixel = 1; + } + // OK, if I need to read a pixel, do it now + if ( read_next_pixel ) + { + // load however much data we did have + if ( tga_indexed ) + { + // read in index, then perform the lookup + int pal_idx = (tga_bits_per_pixel == 8) ? stbi__get8(s) : stbi__get16le(s); + if ( pal_idx >= tga_palette_len ) { + // invalid index + pal_idx = 0; + } + pal_idx *= tga_comp; + for (j = 0; j < tga_comp; ++j) { + raw_data[j] = tga_palette[pal_idx+j]; + } + } else if(tga_rgb16) { + STBI_ASSERT(tga_comp == STBI_rgb); + stbi__tga_read_rgb16(s, raw_data); + } else { + // read in the data raw + for (j = 0; j < tga_comp; ++j) { + raw_data[j] = stbi__get8(s); + } + } + // clear the reading flag for the next pixel + read_next_pixel = 0; + } // end of reading a pixel + + // copy data + for (j = 0; j < tga_comp; ++j) + tga_data[i*tga_comp+j] = raw_data[j]; + + // in case we're in RLE mode, keep counting down + --RLE_count; + } + // do I need to invert the image? + if ( tga_inverted ) + { + for (j = 0; j*2 < tga_height; ++j) + { + int index1 = j * tga_width * tga_comp; + int index2 = (tga_height - 1 - j) * tga_width * tga_comp; + for (i = tga_width * tga_comp; i > 0; --i) + { + unsigned char temp = tga_data[index1]; + tga_data[index1] = tga_data[index2]; + tga_data[index2] = temp; + ++index1; + ++index2; + } + } + } + // clear my palette, if I had one + if ( tga_palette != NULL ) + { + STBI_FREE( tga_palette ); + } + } + + // swap RGB - if the source data was RGB16, it already is in the right order + if (tga_comp >= 3 && !tga_rgb16) + { + unsigned char* tga_pixel = tga_data; + for (i=0; i < tga_width * tga_height; ++i) + { + unsigned char temp = tga_pixel[0]; + tga_pixel[0] = tga_pixel[2]; + tga_pixel[2] = temp; + tga_pixel += tga_comp; + } + } + + // convert to target component count + if (req_comp && req_comp != tga_comp) + tga_data = stbi__convert_format(tga_data, tga_comp, req_comp, tga_width, tga_height); + + // the things I do to get rid of an error message, and yet keep + // Microsoft's C compilers happy... [8^( + tga_palette_start = tga_palette_len = tga_palette_bits = + tga_x_origin = tga_y_origin = 0; + // OK, done + return tga_data; +} +#endif + +// ************************************************************************************************* +// Photoshop PSD loader -- PD by Thatcher Ulrich, integration by Nicolas Schulz, tweaked by STB + +#ifndef STBI_NO_PSD +static int stbi__psd_test(stbi__context *s) +{ + int r = (stbi__get32be(s) == 0x38425053); + stbi__rewind(s); + return r; +} + +static stbi_uc *stbi__psd_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + int pixelCount; + int channelCount, compression; + int channel, i, count, len; + int bitdepth; + int w,h; + stbi_uc *out; + + // Check identifier + if (stbi__get32be(s) != 0x38425053) // "8BPS" + return stbi__errpuc("not PSD", "Corrupt PSD image"); + + // Check file type version. + if (stbi__get16be(s) != 1) + return stbi__errpuc("wrong version", "Unsupported version of PSD image"); + + // Skip 6 reserved bytes. + stbi__skip(s, 6 ); + + // Read the number of channels (R, G, B, A, etc). + channelCount = stbi__get16be(s); + if (channelCount < 0 || channelCount > 16) + return stbi__errpuc("wrong channel count", "Unsupported number of channels in PSD image"); + + // Read the rows and columns of the image. + h = stbi__get32be(s); + w = stbi__get32be(s); + + // Make sure the depth is 8 bits. + bitdepth = stbi__get16be(s); + if (bitdepth != 8 && bitdepth != 16) + return stbi__errpuc("unsupported bit depth", "PSD bit depth is not 8 or 16 bit"); + + // Make sure the color mode is RGB. + // Valid options are: + // 0: Bitmap + // 1: Grayscale + // 2: Indexed color + // 3: RGB color + // 4: CMYK color + // 7: Multichannel + // 8: Duotone + // 9: Lab color + if (stbi__get16be(s) != 3) + return stbi__errpuc("wrong color format", "PSD is not in RGB color format"); + + // Skip the Mode Data. (It's the palette for indexed color; other info for other modes.) + stbi__skip(s,stbi__get32be(s) ); + + // Skip the image resources. (resolution, pen tool paths, etc) + stbi__skip(s, stbi__get32be(s) ); + + // Skip the reserved data. + stbi__skip(s, stbi__get32be(s) ); + + // Find out if the data is compressed. + // Known values: + // 0: no compression + // 1: RLE compressed + compression = stbi__get16be(s); + if (compression > 1) + return stbi__errpuc("bad compression", "PSD has an unknown compression format"); + + // Create the destination image. + out = (stbi_uc *) stbi__malloc(4 * w*h); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + pixelCount = w*h; + + // Initialize the data to zero. + //memset( out, 0, pixelCount * 4 ); + + // Finally, the image data. + if (compression) { + // RLE as used by .PSD and .TIFF + // Loop until you get the number of unpacked bytes you are expecting: + // Read the next source byte into n. + // If n is between 0 and 127 inclusive, copy the next n+1 bytes literally. + // Else if n is between -127 and -1 inclusive, copy the next byte -n+1 times. + // Else if n is 128, noop. + // Endloop + + // The RLE-compressed data is preceeded by a 2-byte data count for each row in the data, + // which we're going to just skip. + stbi__skip(s, h * channelCount * 2 ); + + // Read the RLE data by channel. + for (channel = 0; channel < 4; channel++) { + stbi_uc *p; + + p = out+channel; + if (channel >= channelCount) { + // Fill this channel with default data. + for (i = 0; i < pixelCount; i++, p += 4) + *p = (channel == 3 ? 255 : 0); + } else { + // Read the RLE data. + count = 0; + while (count < pixelCount) { + len = stbi__get8(s); + if (len == 128) { + // No-op. + } else if (len < 128) { + // Copy next len+1 bytes literally. + len++; + count += len; + while (len) { + *p = stbi__get8(s); + p += 4; + len--; + } + } else if (len > 128) { + stbi_uc val; + // Next -len+1 bytes in the dest are replicated from next source byte. + // (Interpret len as a negative 8-bit int.) + len ^= 0x0FF; + len += 2; + val = stbi__get8(s); + count += len; + while (len) { + *p = val; + p += 4; + len--; + } + } + } + } + } + + } else { + // We're at the raw image data. It's each channel in order (Red, Green, Blue, Alpha, ...) + // where each channel consists of an 8-bit value for each pixel in the image. + + // Read the data by channel. + for (channel = 0; channel < 4; channel++) { + stbi_uc *p; + + p = out + channel; + if (channel >= channelCount) { + // Fill this channel with default data. + stbi_uc val = channel == 3 ? 255 : 0; + for (i = 0; i < pixelCount; i++, p += 4) + *p = val; + } else { + // Read the data. + if (bitdepth == 16) { + for (i = 0; i < pixelCount; i++, p += 4) + *p = (stbi_uc) (stbi__get16be(s) >> 8); + } else { + for (i = 0; i < pixelCount; i++, p += 4) + *p = stbi__get8(s); + } + } + } + } + + if (req_comp && req_comp != 4) { + out = stbi__convert_format(out, 4, req_comp, w, h); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + + if (comp) *comp = 4; + *y = h; + *x = w; + + return out; +} +#endif + +// ************************************************************************************************* +// Softimage PIC loader +// by Tom Seddon +// +// See http://softimage.wiki.softimage.com/index.php/INFO:_PIC_file_format +// See http://ozviz.wasp.uwa.edu.au/~pbourke/dataformats/softimagepic/ + +#ifndef STBI_NO_PIC +static int stbi__pic_is4(stbi__context *s,const char *str) +{ + int i; + for (i=0; i<4; ++i) + if (stbi__get8(s) != (stbi_uc)str[i]) + return 0; + + return 1; +} + +static int stbi__pic_test_core(stbi__context *s) +{ + int i; + + if (!stbi__pic_is4(s,"\x53\x80\xF6\x34")) + return 0; + + for(i=0;i<84;++i) + stbi__get8(s); + + if (!stbi__pic_is4(s,"PICT")) + return 0; + + return 1; +} + +typedef struct +{ + stbi_uc size,type,channel; +} stbi__pic_packet; + +static stbi_uc *stbi__readval(stbi__context *s, int channel, stbi_uc *dest) +{ + int mask=0x80, i; + + for (i=0; i<4; ++i, mask>>=1) { + if (channel & mask) { + if (stbi__at_eof(s)) return stbi__errpuc("bad file","PIC file too short"); + dest[i]=stbi__get8(s); + } + } + + return dest; +} + +static void stbi__copyval(int channel,stbi_uc *dest,const stbi_uc *src) +{ + int mask=0x80,i; + + for (i=0;i<4; ++i, mask>>=1) + if (channel&mask) + dest[i]=src[i]; +} + +static stbi_uc *stbi__pic_load_core(stbi__context *s,int width,int height,int *comp, stbi_uc *result) +{ + int act_comp=0,num_packets=0,y,chained; + stbi__pic_packet packets[10]; + + // this will (should...) cater for even some bizarre stuff like having data + // for the same channel in multiple packets. + do { + stbi__pic_packet *packet; + + if (num_packets==sizeof(packets)/sizeof(packets[0])) + return stbi__errpuc("bad format","too many packets"); + + packet = &packets[num_packets++]; + + chained = stbi__get8(s); + packet->size = stbi__get8(s); + packet->type = stbi__get8(s); + packet->channel = stbi__get8(s); + + act_comp |= packet->channel; + + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (reading packets)"); + if (packet->size != 8) return stbi__errpuc("bad format","packet isn't 8bpp"); + } while (chained); + + *comp = (act_comp & 0x10 ? 4 : 3); // has alpha channel? + + for(y=0; ytype) { + default: + return stbi__errpuc("bad format","packet has bad compression type"); + + case 0: {//uncompressed + int x; + + for(x=0;xchannel,dest)) + return 0; + break; + } + + case 1://Pure RLE + { + int left=width, i; + + while (left>0) { + stbi_uc count,value[4]; + + count=stbi__get8(s); + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (pure read count)"); + + if (count > left) + count = (stbi_uc) left; + + if (!stbi__readval(s,packet->channel,value)) return 0; + + for(i=0; ichannel,dest,value); + left -= count; + } + } + break; + + case 2: {//Mixed RLE + int left=width; + while (left>0) { + int count = stbi__get8(s), i; + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (mixed read count)"); + + if (count >= 128) { // Repeated + stbi_uc value[4]; + + if (count==128) + count = stbi__get16be(s); + else + count -= 127; + if (count > left) + return stbi__errpuc("bad file","scanline overrun"); + + if (!stbi__readval(s,packet->channel,value)) + return 0; + + for(i=0;ichannel,dest,value); + } else { // Raw + ++count; + if (count>left) return stbi__errpuc("bad file","scanline overrun"); + + for(i=0;ichannel,dest)) + return 0; + } + left-=count; + } + break; + } + } + } + } + + return result; +} + +static stbi_uc *stbi__pic_load(stbi__context *s,int *px,int *py,int *comp,int req_comp) +{ + stbi_uc *result; + int i, x,y; + + for (i=0; i<92; ++i) + stbi__get8(s); + + x = stbi__get16be(s); + y = stbi__get16be(s); + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (pic header)"); + if ((1 << 28) / x < y) return stbi__errpuc("too large", "Image too large to decode"); + + stbi__get32be(s); //skip `ratio' + stbi__get16be(s); //skip `fields' + stbi__get16be(s); //skip `pad' + + // intermediate buffer is RGBA + result = (stbi_uc *) stbi__malloc(x*y*4); + memset(result, 0xff, x*y*4); + + if (!stbi__pic_load_core(s,x,y,comp, result)) { + STBI_FREE(result); + result=0; + } + *px = x; + *py = y; + if (req_comp == 0) req_comp = *comp; + result=stbi__convert_format(result,4,req_comp,x,y); + + return result; +} + +static int stbi__pic_test(stbi__context *s) +{ + int r = stbi__pic_test_core(s); + stbi__rewind(s); + return r; +} +#endif + +// ************************************************************************************************* +// GIF loader -- public domain by Jean-Marc Lienher -- simplified/shrunk by stb + +#ifndef STBI_NO_GIF +typedef struct +{ + stbi__int16 prefix; + stbi_uc first; + stbi_uc suffix; +} stbi__gif_lzw; + +typedef struct +{ + int w,h; + stbi_uc *out, *old_out; // output buffer (always 4 components) + int flags, bgindex, ratio, transparent, eflags, delay; + stbi_uc pal[256][4]; + stbi_uc lpal[256][4]; + stbi__gif_lzw codes[4096]; + stbi_uc *color_table; + int parse, step; + int lflags; + int start_x, start_y; + int max_x, max_y; + int cur_x, cur_y; + int line_size; +} stbi__gif; + +static int stbi__gif_test_raw(stbi__context *s) +{ + int sz; + if (stbi__get8(s) != 'G' || stbi__get8(s) != 'I' || stbi__get8(s) != 'F' || stbi__get8(s) != '8') return 0; + sz = stbi__get8(s); + if (sz != '9' && sz != '7') return 0; + if (stbi__get8(s) != 'a') return 0; + return 1; +} + +static int stbi__gif_test(stbi__context *s) +{ + int r = stbi__gif_test_raw(s); + stbi__rewind(s); + return r; +} + +static void stbi__gif_parse_colortable(stbi__context *s, stbi_uc pal[256][4], int num_entries, int transp) +{ + int i; + for (i=0; i < num_entries; ++i) { + pal[i][2] = stbi__get8(s); + pal[i][1] = stbi__get8(s); + pal[i][0] = stbi__get8(s); + pal[i][3] = transp == i ? 0 : 255; + } +} + +static int stbi__gif_header(stbi__context *s, stbi__gif *g, int *comp, int is_info) +{ + stbi_uc version; + if (stbi__get8(s) != 'G' || stbi__get8(s) != 'I' || stbi__get8(s) != 'F' || stbi__get8(s) != '8') + return stbi__err("not GIF", "Corrupt GIF"); + + version = stbi__get8(s); + if (version != '7' && version != '9') return stbi__err("not GIF", "Corrupt GIF"); + if (stbi__get8(s) != 'a') return stbi__err("not GIF", "Corrupt GIF"); + + stbi__g_failure_reason = ""; + g->w = stbi__get16le(s); + g->h = stbi__get16le(s); + g->flags = stbi__get8(s); + g->bgindex = stbi__get8(s); + g->ratio = stbi__get8(s); + g->transparent = -1; + + if (comp != 0) *comp = 4; // can't actually tell whether it's 3 or 4 until we parse the comments + + if (is_info) return 1; + + if (g->flags & 0x80) + stbi__gif_parse_colortable(s,g->pal, 2 << (g->flags & 7), -1); + + return 1; +} + +static int stbi__gif_info_raw(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__gif g; + if (!stbi__gif_header(s, &g, comp, 1)) { + stbi__rewind( s ); + return 0; + } + if (x) *x = g.w; + if (y) *y = g.h; + return 1; +} + +static void stbi__out_gif_code(stbi__gif *g, stbi__uint16 code) +{ + stbi_uc *p, *c; + + // recurse to decode the prefixes, since the linked-list is backwards, + // and working backwards through an interleaved image would be nasty + if (g->codes[code].prefix >= 0) + stbi__out_gif_code(g, g->codes[code].prefix); + + if (g->cur_y >= g->max_y) return; + + p = &g->out[g->cur_x + g->cur_y]; + c = &g->color_table[g->codes[code].suffix * 4]; + + if (c[3] >= 128) { + p[0] = c[2]; + p[1] = c[1]; + p[2] = c[0]; + p[3] = c[3]; + } + g->cur_x += 4; + + if (g->cur_x >= g->max_x) { + g->cur_x = g->start_x; + g->cur_y += g->step; + + while (g->cur_y >= g->max_y && g->parse > 0) { + g->step = (1 << g->parse) * g->line_size; + g->cur_y = g->start_y + (g->step >> 1); + --g->parse; + } + } +} + +static stbi_uc *stbi__process_gif_raster(stbi__context *s, stbi__gif *g) +{ + stbi_uc lzw_cs; + stbi__int32 len, init_code; + stbi__uint32 first; + stbi__int32 codesize, codemask, avail, oldcode, bits, valid_bits, clear; + stbi__gif_lzw *p; + + lzw_cs = stbi__get8(s); + if (lzw_cs > 12) return NULL; + clear = 1 << lzw_cs; + first = 1; + codesize = lzw_cs + 1; + codemask = (1 << codesize) - 1; + bits = 0; + valid_bits = 0; + for (init_code = 0; init_code < clear; init_code++) { + g->codes[init_code].prefix = -1; + g->codes[init_code].first = (stbi_uc) init_code; + g->codes[init_code].suffix = (stbi_uc) init_code; + } + + // support no starting clear code + avail = clear+2; + oldcode = -1; + + len = 0; + for(;;) { + if (valid_bits < codesize) { + if (len == 0) { + len = stbi__get8(s); // start new block + if (len == 0) + return g->out; + } + --len; + bits |= (stbi__int32) stbi__get8(s) << valid_bits; + valid_bits += 8; + } else { + stbi__int32 code = bits & codemask; + bits >>= codesize; + valid_bits -= codesize; + // @OPTIMIZE: is there some way we can accelerate the non-clear path? + if (code == clear) { // clear code + codesize = lzw_cs + 1; + codemask = (1 << codesize) - 1; + avail = clear + 2; + oldcode = -1; + first = 0; + } else if (code == clear + 1) { // end of stream code + stbi__skip(s, len); + while ((len = stbi__get8(s)) > 0) + stbi__skip(s,len); + return g->out; + } else if (code <= avail) { + if (first) return stbi__errpuc("no clear code", "Corrupt GIF"); + + if (oldcode >= 0) { + p = &g->codes[avail++]; + if (avail > 4096) return stbi__errpuc("too many codes", "Corrupt GIF"); + p->prefix = (stbi__int16) oldcode; + p->first = g->codes[oldcode].first; + p->suffix = (code == avail) ? p->first : g->codes[code].first; + } else if (code == avail) + return stbi__errpuc("illegal code in raster", "Corrupt GIF"); + + stbi__out_gif_code(g, (stbi__uint16) code); + + if ((avail & codemask) == 0 && avail <= 0x0FFF) { + codesize++; + codemask = (1 << codesize) - 1; + } + + oldcode = code; + } else { + return stbi__errpuc("illegal code in raster", "Corrupt GIF"); + } + } + } +} + +static void stbi__fill_gif_background(stbi__gif *g, int x0, int y0, int x1, int y1) +{ + int x, y; + stbi_uc *c = g->pal[g->bgindex]; + for (y = y0; y < y1; y += 4 * g->w) { + for (x = x0; x < x1; x += 4) { + stbi_uc *p = &g->out[y + x]; + p[0] = c[2]; + p[1] = c[1]; + p[2] = c[0]; + p[3] = 0; + } + } +} + +// this function is designed to support animated gifs, although stb_image doesn't support it +static stbi_uc *stbi__gif_load_next(stbi__context *s, stbi__gif *g, int *comp, int req_comp) +{ + int i; + stbi_uc *prev_out = 0; + + if (g->out == 0 && !stbi__gif_header(s, g, comp,0)) + return 0; // stbi__g_failure_reason set by stbi__gif_header + + prev_out = g->out; + g->out = (stbi_uc *) stbi__malloc(4 * g->w * g->h); + if (g->out == 0) return stbi__errpuc("outofmem", "Out of memory"); + + switch ((g->eflags & 0x1C) >> 2) { + case 0: // unspecified (also always used on 1st frame) + stbi__fill_gif_background(g, 0, 0, 4 * g->w, 4 * g->w * g->h); + break; + case 1: // do not dispose + if (prev_out) memcpy(g->out, prev_out, 4 * g->w * g->h); + g->old_out = prev_out; + break; + case 2: // dispose to background + if (prev_out) memcpy(g->out, prev_out, 4 * g->w * g->h); + stbi__fill_gif_background(g, g->start_x, g->start_y, g->max_x, g->max_y); + break; + case 3: // dispose to previous + if (g->old_out) { + for (i = g->start_y; i < g->max_y; i += 4 * g->w) + memcpy(&g->out[i + g->start_x], &g->old_out[i + g->start_x], g->max_x - g->start_x); + } + break; + } + + for (;;) { + switch (stbi__get8(s)) { + case 0x2C: /* Image Descriptor */ + { + int prev_trans = -1; + stbi__int32 x, y, w, h; + stbi_uc *o; + + x = stbi__get16le(s); + y = stbi__get16le(s); + w = stbi__get16le(s); + h = stbi__get16le(s); + if (((x + w) > (g->w)) || ((y + h) > (g->h))) + return stbi__errpuc("bad Image Descriptor", "Corrupt GIF"); + + g->line_size = g->w * 4; + g->start_x = x * 4; + g->start_y = y * g->line_size; + g->max_x = g->start_x + w * 4; + g->max_y = g->start_y + h * g->line_size; + g->cur_x = g->start_x; + g->cur_y = g->start_y; + + g->lflags = stbi__get8(s); + + if (g->lflags & 0x40) { + g->step = 8 * g->line_size; // first interlaced spacing + g->parse = 3; + } else { + g->step = g->line_size; + g->parse = 0; + } + + if (g->lflags & 0x80) { + stbi__gif_parse_colortable(s,g->lpal, 2 << (g->lflags & 7), g->eflags & 0x01 ? g->transparent : -1); + g->color_table = (stbi_uc *) g->lpal; + } else if (g->flags & 0x80) { + if (g->transparent >= 0 && (g->eflags & 0x01)) { + prev_trans = g->pal[g->transparent][3]; + g->pal[g->transparent][3] = 0; + } + g->color_table = (stbi_uc *) g->pal; + } else + return stbi__errpuc("missing color table", "Corrupt GIF"); + + o = stbi__process_gif_raster(s, g); + if (o == NULL) return NULL; + + if (prev_trans != -1) + g->pal[g->transparent][3] = (stbi_uc) prev_trans; + + return o; + } + + case 0x21: // Comment Extension. + { + int len; + if (stbi__get8(s) == 0xF9) { // Graphic Control Extension. + len = stbi__get8(s); + if (len == 4) { + g->eflags = stbi__get8(s); + g->delay = stbi__get16le(s); + g->transparent = stbi__get8(s); + } else { + stbi__skip(s, len); + break; + } + } + while ((len = stbi__get8(s)) != 0) + stbi__skip(s, len); + break; + } + + case 0x3B: // gif stream termination code + return (stbi_uc *) s; // using '1' causes warning on some compilers + + default: + return stbi__errpuc("unknown code", "Corrupt GIF"); + } + } + + STBI_NOTUSED(req_comp); +} + +static stbi_uc *stbi__gif_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *u = 0; + stbi__gif g; + memset(&g, 0, sizeof(g)); + + u = stbi__gif_load_next(s, &g, comp, req_comp); + if (u == (stbi_uc *) s) u = 0; // end of animated gif marker + if (u) { + *x = g.w; + *y = g.h; + if (req_comp && req_comp != 4) + u = stbi__convert_format(u, 4, req_comp, g.w, g.h); + } + else if (g.out) + STBI_FREE(g.out); + + return u; +} + +static int stbi__gif_info(stbi__context *s, int *x, int *y, int *comp) +{ + return stbi__gif_info_raw(s,x,y,comp); +} +#endif + +// ************************************************************************************************* +// Radiance RGBE HDR loader +// originally by Nicolas Schulz +#ifndef STBI_NO_HDR +static int stbi__hdr_test_core(stbi__context *s) +{ + const char *signature = "#?RADIANCE\n"; + int i; + for (i=0; signature[i]; ++i) + if (stbi__get8(s) != signature[i]) + return 0; + return 1; +} + +static int stbi__hdr_test(stbi__context* s) +{ + int r = stbi__hdr_test_core(s); + stbi__rewind(s); + return r; +} + +#define STBI__HDR_BUFLEN 1024 +static char *stbi__hdr_gettoken(stbi__context *z, char *buffer) +{ + int len=0; + char c = '\0'; + + c = (char) stbi__get8(z); + + while (!stbi__at_eof(z) && c != '\n') { + buffer[len++] = c; + if (len == STBI__HDR_BUFLEN-1) { + // flush to end of line + while (!stbi__at_eof(z) && stbi__get8(z) != '\n') + ; + break; + } + c = (char) stbi__get8(z); + } + + buffer[len] = 0; + return buffer; +} + +static void stbi__hdr_convert(float *output, stbi_uc *input, int req_comp) +{ + if ( input[3] != 0 ) { + float f1; + // Exponent + f1 = (float) ldexp(1.0f, input[3] - (int)(128 + 8)); + if (req_comp <= 2) + output[0] = (input[0] + input[1] + input[2]) * f1 / 3; + else { + output[0] = input[0] * f1; + output[1] = input[1] * f1; + output[2] = input[2] * f1; + } + if (req_comp == 2) output[1] = 1; + if (req_comp == 4) output[3] = 1; + } else { + switch (req_comp) { + case 4: output[3] = 1; /* fallthrough */ + case 3: output[0] = output[1] = output[2] = 0; + break; + case 2: output[1] = 1; /* fallthrough */ + case 1: output[0] = 0; + break; + } + } +} + +static float *stbi__hdr_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + char buffer[STBI__HDR_BUFLEN]; + char *token; + int valid = 0; + int width, height; + stbi_uc *scanline; + float *hdr_data; + int len; + unsigned char count, value; + int i, j, k, c1,c2, z; + + + // Check identifier + if (strcmp(stbi__hdr_gettoken(s,buffer), "#?RADIANCE") != 0) + return stbi__errpf("not HDR", "Corrupt HDR image"); + + // Parse header + for(;;) { + token = stbi__hdr_gettoken(s,buffer); + if (token[0] == 0) break; + if (strcmp(token, "FORMAT=32-bit_rle_rgbe") == 0) valid = 1; + } + + if (!valid) return stbi__errpf("unsupported format", "Unsupported HDR format"); + + // Parse width and height + // can't use sscanf() if we're not using stdio! + token = stbi__hdr_gettoken(s,buffer); + if (strncmp(token, "-Y ", 3)) return stbi__errpf("unsupported data layout", "Unsupported HDR format"); + token += 3; + height = (int) strtol(token, &token, 10); + while (*token == ' ') ++token; + if (strncmp(token, "+X ", 3)) return stbi__errpf("unsupported data layout", "Unsupported HDR format"); + token += 3; + width = (int) strtol(token, NULL, 10); + + *x = width; + *y = height; + + if (comp) *comp = 3; + if (req_comp == 0) req_comp = 3; + + // Read data + hdr_data = (float *) stbi__malloc(height * width * req_comp * sizeof(float)); + + // Load image data + // image data is stored as some number of sca + if ( width < 8 || width >= 32768) { + // Read flat data + for (j=0; j < height; ++j) { + for (i=0; i < width; ++i) { + stbi_uc rgbe[4]; + main_decode_loop: + stbi__getn(s, rgbe, 4); + stbi__hdr_convert(hdr_data + j * width * req_comp + i * req_comp, rgbe, req_comp); + } + } + } else { + // Read RLE-encoded data + scanline = NULL; + + for (j = 0; j < height; ++j) { + c1 = stbi__get8(s); + c2 = stbi__get8(s); + len = stbi__get8(s); + if (c1 != 2 || c2 != 2 || (len & 0x80)) { + // not run-length encoded, so we have to actually use THIS data as a decoded + // pixel (note this can't be a valid pixel--one of RGB must be >= 128) + stbi_uc rgbe[4]; + rgbe[0] = (stbi_uc) c1; + rgbe[1] = (stbi_uc) c2; + rgbe[2] = (stbi_uc) len; + rgbe[3] = (stbi_uc) stbi__get8(s); + stbi__hdr_convert(hdr_data, rgbe, req_comp); + i = 1; + j = 0; + STBI_FREE(scanline); + goto main_decode_loop; // yes, this makes no sense + } + len <<= 8; + len |= stbi__get8(s); + if (len != width) { STBI_FREE(hdr_data); STBI_FREE(scanline); return stbi__errpf("invalid decoded scanline length", "corrupt HDR"); } + if (scanline == NULL) scanline = (stbi_uc *) stbi__malloc(width * 4); + + for (k = 0; k < 4; ++k) { + i = 0; + while (i < width) { + count = stbi__get8(s); + if (count > 128) { + // Run + value = stbi__get8(s); + count -= 128; + for (z = 0; z < count; ++z) + scanline[i++ * 4 + k] = value; + } else { + // Dump + for (z = 0; z < count; ++z) + scanline[i++ * 4 + k] = stbi__get8(s); + } + } + } + for (i=0; i < width; ++i) + stbi__hdr_convert(hdr_data+(j*width + i)*req_comp, scanline + i*4, req_comp); + } + STBI_FREE(scanline); + } + + return hdr_data; +} + +static int stbi__hdr_info(stbi__context *s, int *x, int *y, int *comp) +{ + char buffer[STBI__HDR_BUFLEN]; + char *token; + int valid = 0; + + if (stbi__hdr_test(s) == 0) { + stbi__rewind( s ); + return 0; + } + + for(;;) { + token = stbi__hdr_gettoken(s,buffer); + if (token[0] == 0) break; + if (strcmp(token, "FORMAT=32-bit_rle_rgbe") == 0) valid = 1; + } + + if (!valid) { + stbi__rewind( s ); + return 0; + } + token = stbi__hdr_gettoken(s,buffer); + if (strncmp(token, "-Y ", 3)) { + stbi__rewind( s ); + return 0; + } + token += 3; + *y = (int) strtol(token, &token, 10); + while (*token == ' ') ++token; + if (strncmp(token, "+X ", 3)) { + stbi__rewind( s ); + return 0; + } + token += 3; + *x = (int) strtol(token, NULL, 10); + *comp = 3; + return 1; +} +#endif // STBI_NO_HDR + +#ifndef STBI_NO_BMP +static int stbi__bmp_info(stbi__context *s, int *x, int *y, int *comp) +{ + void *p; + stbi__bmp_data info; + + info.all_a = 255; + p = stbi__bmp_parse_header(s, &info); + stbi__rewind( s ); + if (p == NULL) + return 0; + *x = s->img_x; + *y = s->img_y; + *comp = info.ma ? 4 : 3; + return 1; +} +#endif + +#ifndef STBI_NO_PSD +static int stbi__psd_info(stbi__context *s, int *x, int *y, int *comp) +{ + int channelCount; + if (stbi__get32be(s) != 0x38425053) { + stbi__rewind( s ); + return 0; + } + if (stbi__get16be(s) != 1) { + stbi__rewind( s ); + return 0; + } + stbi__skip(s, 6); + channelCount = stbi__get16be(s); + if (channelCount < 0 || channelCount > 16) { + stbi__rewind( s ); + return 0; + } + *y = stbi__get32be(s); + *x = stbi__get32be(s); + if (stbi__get16be(s) != 8) { + stbi__rewind( s ); + return 0; + } + if (stbi__get16be(s) != 3) { + stbi__rewind( s ); + return 0; + } + *comp = 4; + return 1; +} +#endif + +#ifndef STBI_NO_PIC +static int stbi__pic_info(stbi__context *s, int *x, int *y, int *comp) +{ + int act_comp=0,num_packets=0,chained; + stbi__pic_packet packets[10]; + + if (!stbi__pic_is4(s,"\x53\x80\xF6\x34")) { + stbi__rewind(s); + return 0; + } + + stbi__skip(s, 88); + + *x = stbi__get16be(s); + *y = stbi__get16be(s); + if (stbi__at_eof(s)) { + stbi__rewind( s); + return 0; + } + if ( (*x) != 0 && (1 << 28) / (*x) < (*y)) { + stbi__rewind( s ); + return 0; + } + + stbi__skip(s, 8); + + do { + stbi__pic_packet *packet; + + if (num_packets==sizeof(packets)/sizeof(packets[0])) + return 0; + + packet = &packets[num_packets++]; + chained = stbi__get8(s); + packet->size = stbi__get8(s); + packet->type = stbi__get8(s); + packet->channel = stbi__get8(s); + act_comp |= packet->channel; + + if (stbi__at_eof(s)) { + stbi__rewind( s ); + return 0; + } + if (packet->size != 8) { + stbi__rewind( s ); + return 0; + } + } while (chained); + + *comp = (act_comp & 0x10 ? 4 : 3); + + return 1; +} +#endif + +// ************************************************************************************************* +// Portable Gray Map and Portable Pixel Map loader +// by Ken Miller +// +// PGM: http://netpbm.sourceforge.net/doc/pgm.html +// PPM: http://netpbm.sourceforge.net/doc/ppm.html +// +// Known limitations: +// Does not support comments in the header section +// Does not support ASCII image data (formats P2 and P3) +// Does not support 16-bit-per-channel + +#ifndef STBI_NO_PNM + +static int stbi__pnm_test(stbi__context *s) +{ + char p, t; + p = (char) stbi__get8(s); + t = (char) stbi__get8(s); + if (p != 'P' || (t != '5' && t != '6')) { + stbi__rewind( s ); + return 0; + } + return 1; +} + +static stbi_uc *stbi__pnm_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *out; + if (!stbi__pnm_info(s, (int *)&s->img_x, (int *)&s->img_y, (int *)&s->img_n)) + return 0; + *x = s->img_x; + *y = s->img_y; + *comp = s->img_n; + + out = (stbi_uc *) stbi__malloc(s->img_n * s->img_x * s->img_y); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + stbi__getn(s, out, s->img_n * s->img_x * s->img_y); + + if (req_comp && req_comp != s->img_n) { + out = stbi__convert_format(out, s->img_n, req_comp, s->img_x, s->img_y); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + return out; +} + +static int stbi__pnm_isspace(char c) +{ + return c == ' ' || c == '\t' || c == '\n' || c == '\v' || c == '\f' || c == '\r'; +} + +static void stbi__pnm_skip_whitespace(stbi__context *s, char *c) +{ + for (;;) { + while (!stbi__at_eof(s) && stbi__pnm_isspace(*c)) + *c = (char) stbi__get8(s); + + if (stbi__at_eof(s) || *c != '#') + break; + + while (!stbi__at_eof(s) && *c != '\n' && *c != '\r' ) + *c = (char) stbi__get8(s); + } +} + +static int stbi__pnm_isdigit(char c) +{ + return c >= '0' && c <= '9'; +} + +static int stbi__pnm_getinteger(stbi__context *s, char *c) +{ + int value = 0; + + while (!stbi__at_eof(s) && stbi__pnm_isdigit(*c)) { + value = value*10 + (*c - '0'); + *c = (char) stbi__get8(s); + } + + return value; +} + +static int stbi__pnm_info(stbi__context *s, int *x, int *y, int *comp) +{ + int maxv; + char c, p, t; + + stbi__rewind( s ); + + // Get identifier + p = (char) stbi__get8(s); + t = (char) stbi__get8(s); + if (p != 'P' || (t != '5' && t != '6')) { + stbi__rewind( s ); + return 0; + } + + *comp = (t == '6') ? 3 : 1; // '5' is 1-component .pgm; '6' is 3-component .ppm + + c = (char) stbi__get8(s); + stbi__pnm_skip_whitespace(s, &c); + + *x = stbi__pnm_getinteger(s, &c); // read width + stbi__pnm_skip_whitespace(s, &c); + + *y = stbi__pnm_getinteger(s, &c); // read height + stbi__pnm_skip_whitespace(s, &c); + + maxv = stbi__pnm_getinteger(s, &c); // read max value + + if (maxv > 255) + return stbi__err("max value > 255", "PPM image not 8-bit"); + else + return 1; +} +#endif + +static int stbi__info_main(stbi__context *s, int *x, int *y, int *comp) +{ + #ifndef STBI_NO_JPEG + if (stbi__jpeg_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PNG + if (stbi__png_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_GIF + if (stbi__gif_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_BMP + if (stbi__bmp_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PSD + if (stbi__psd_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PIC + if (stbi__pic_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PNM + if (stbi__pnm_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_HDR + if (stbi__hdr_info(s, x, y, comp)) return 1; + #endif + + // test tga last because it's a crappy test! + #ifndef STBI_NO_TGA + if (stbi__tga_info(s, x, y, comp)) + return 1; + #endif + return stbi__err("unknown image type", "Image not of any known type, or corrupt"); +} + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_info(char const *filename, int *x, int *y, int *comp) +{ + FILE *f = stbi__fopen(filename, "rb"); + int result; + if (!f) return stbi__err("can't fopen", "Unable to open file"); + result = stbi_info_from_file(f, x, y, comp); + fclose(f); + return result; +} + +STBIDEF int stbi_info_from_file(FILE *f, int *x, int *y, int *comp) +{ + int r; + stbi__context s; + long pos = ftell(f); + stbi__start_file(&s, f); + r = stbi__info_main(&s,x,y,comp); + fseek(f,pos,SEEK_SET); + return r; +} +#endif // !STBI_NO_STDIO + +STBIDEF int stbi_info_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__info_main(&s,x,y,comp); +} + +STBIDEF int stbi_info_from_callbacks(stbi_io_callbacks const *c, void *user, int *x, int *y, int *comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) c, user); + return stbi__info_main(&s,x,y,comp); +} + +#endif // STB_IMAGE_IMPLEMENTATION + +/* + revision history: + 2.10 (2016-01-22) avoid warning introduced in 2.09 by STBI_REALLOC_SIZED + 2.09 (2016-01-16) allow comments in PNM files + 16-bit-per-pixel TGA (not bit-per-component) + info() for TGA could break due to .hdr handling + info() for BMP to shares code instead of sloppy parse + can use STBI_REALLOC_SIZED if allocator doesn't support realloc + code cleanup + 2.08 (2015-09-13) fix to 2.07 cleanup, reading RGB PSD as RGBA + 2.07 (2015-09-13) fix compiler warnings + partial animated GIF support + limited 16-bpc PSD support + #ifdef unused functions + bug with < 92 byte PIC,PNM,HDR,TGA + 2.06 (2015-04-19) fix bug where PSD returns wrong '*comp' value + 2.05 (2015-04-19) fix bug in progressive JPEG handling, fix warning + 2.04 (2015-04-15) try to re-enable SIMD on MinGW 64-bit + 2.03 (2015-04-12) extra corruption checking (mmozeiko) + stbi_set_flip_vertically_on_load (nguillemot) + fix NEON support; fix mingw support + 2.02 (2015-01-19) fix incorrect assert, fix warning + 2.01 (2015-01-17) fix various warnings; suppress SIMD on gcc 32-bit without -msse2 + 2.00b (2014-12-25) fix STBI_MALLOC in progressive JPEG + 2.00 (2014-12-25) optimize JPG, including x86 SSE2 & NEON SIMD (ryg) + progressive JPEG (stb) + PGM/PPM support (Ken Miller) + STBI_MALLOC,STBI_REALLOC,STBI_FREE + GIF bugfix -- seemingly never worked + STBI_NO_*, STBI_ONLY_* + 1.48 (2014-12-14) fix incorrectly-named assert() + 1.47 (2014-12-14) 1/2/4-bit PNG support, both direct and paletted (Omar Cornut & stb) + optimize PNG (ryg) + fix bug in interlaced PNG with user-specified channel count (stb) + 1.46 (2014-08-26) + fix broken tRNS chunk (colorkey-style transparency) in non-paletted PNG + 1.45 (2014-08-16) + fix MSVC-ARM internal compiler error by wrapping malloc + 1.44 (2014-08-07) + various warning fixes from Ronny Chevalier + 1.43 (2014-07-15) + fix MSVC-only compiler problem in code changed in 1.42 + 1.42 (2014-07-09) + don't define _CRT_SECURE_NO_WARNINGS (affects user code) + fixes to stbi__cleanup_jpeg path + added STBI_ASSERT to avoid requiring assert.h + 1.41 (2014-06-25) + fix search&replace from 1.36 that messed up comments/error messages + 1.40 (2014-06-22) + fix gcc struct-initialization warning + 1.39 (2014-06-15) + fix to TGA optimization when req_comp != number of components in TGA; + fix to GIF loading because BMP wasn't rewinding (whoops, no GIFs in my test suite) + add support for BMP version 5 (more ignored fields) + 1.38 (2014-06-06) + suppress MSVC warnings on integer casts truncating values + fix accidental rename of 'skip' field of I/O + 1.37 (2014-06-04) + remove duplicate typedef + 1.36 (2014-06-03) + convert to header file single-file library + if de-iphone isn't set, load iphone images color-swapped instead of returning NULL + 1.35 (2014-05-27) + various warnings + fix broken STBI_SIMD path + fix bug where stbi_load_from_file no longer left file pointer in correct place + fix broken non-easy path for 32-bit BMP (possibly never used) + TGA optimization by Arseny Kapoulkine + 1.34 (unknown) + use STBI_NOTUSED in stbi__resample_row_generic(), fix one more leak in tga failure case + 1.33 (2011-07-14) + make stbi_is_hdr work in STBI_NO_HDR (as specified), minor compiler-friendly improvements + 1.32 (2011-07-13) + support for "info" function for all supported filetypes (SpartanJ) + 1.31 (2011-06-20) + a few more leak fixes, bug in PNG handling (SpartanJ) + 1.30 (2011-06-11) + added ability to load files via callbacks to accomidate custom input streams (Ben Wenger) + removed deprecated format-specific test/load functions + removed support for installable file formats (stbi_loader) -- would have been broken for IO callbacks anyway + error cases in bmp and tga give messages and don't leak (Raymond Barbiero, grisha) + fix inefficiency in decoding 32-bit BMP (David Woo) + 1.29 (2010-08-16) + various warning fixes from Aurelien Pocheville + 1.28 (2010-08-01) + fix bug in GIF palette transparency (SpartanJ) + 1.27 (2010-08-01) + cast-to-stbi_uc to fix warnings + 1.26 (2010-07-24) + fix bug in file buffering for PNG reported by SpartanJ + 1.25 (2010-07-17) + refix trans_data warning (Won Chun) + 1.24 (2010-07-12) + perf improvements reading from files on platforms with lock-heavy fgetc() + minor perf improvements for jpeg + deprecated type-specific functions so we'll get feedback if they're needed + attempt to fix trans_data warning (Won Chun) + 1.23 fixed bug in iPhone support + 1.22 (2010-07-10) + removed image *writing* support + stbi_info support from Jetro Lauha + GIF support from Jean-Marc Lienher + iPhone PNG-extensions from James Brown + warning-fixes from Nicolas Schulz and Janez Zemva (i.stbi__err. Janez (U+017D)emva) + 1.21 fix use of 'stbi_uc' in header (reported by jon blow) + 1.20 added support for Softimage PIC, by Tom Seddon + 1.19 bug in interlaced PNG corruption check (found by ryg) + 1.18 (2008-08-02) + fix a threading bug (local mutable static) + 1.17 support interlaced PNG + 1.16 major bugfix - stbi__convert_format converted one too many pixels + 1.15 initialize some fields for thread safety + 1.14 fix threadsafe conversion bug + header-file-only version (#define STBI_HEADER_FILE_ONLY before including) + 1.13 threadsafe + 1.12 const qualifiers in the API + 1.11 Support installable IDCT, colorspace conversion routines + 1.10 Fixes for 64-bit (don't use "unsigned long") + optimized upsampling by Fabian "ryg" Giesen + 1.09 Fix format-conversion for PSD code (bad global variables!) + 1.08 Thatcher Ulrich's PSD code integrated by Nicolas Schulz + 1.07 attempt to fix C++ warning/errors again + 1.06 attempt to fix C++ warning/errors again + 1.05 fix TGA loading to return correct *comp and use good luminance calc + 1.04 default float alpha is 1, not 255; use 'void *' for stbi_image_free + 1.03 bugfixes to STBI_NO_STDIO, STBI_NO_HDR + 1.02 support for (subset of) HDR files, float interface for preferred access to them + 1.01 fix bug: possible bug in handling right-side up bmps... not sure + fix bug: the stbi__bmp_load() and stbi__tga_load() functions didn't work at all + 1.00 interface to zlib that skips zlib header + 0.99 correct handling of alpha in palette + 0.98 TGA loader by lonesock; dynamically add loaders (untested) + 0.97 jpeg errors on too large a file; also catch another malloc failure + 0.96 fix detection of invalid v value - particleman@mollyrocket forum + 0.95 during header scan, seek to markers in case of padding + 0.94 STBI_NO_STDIO to disable stdio usage; rename all #defines the same + 0.93 handle jpegtran output; verbose errors + 0.92 read 4,8,16,24,32-bit BMP files of several formats + 0.91 output 24-bit Windows 3.0 BMP files + 0.90 fix a few more warnings; bump version number to approach 1.0 + 0.61 bugfixes due to Marc LeBlanc, Christopher Lloyd + 0.60 fix compiling as c++ + 0.59 fix warnings: merge Dave Moore's -Wall fixes + 0.58 fix bug: zlib uncompressed mode len/nlen was wrong endian + 0.57 fix bug: jpg last huffman symbol before marker was >9 bits but less than 16 available + 0.56 fix bug: zlib uncompressed mode len vs. nlen + 0.55 fix bug: restart_interval not initialized to 0 + 0.54 allow NULL for 'int *comp' + 0.53 fix bug in png 3->4; speedup png decoding + 0.52 png handles req_comp=3,4 directly; minor cleanup; jpeg comments + 0.51 obey req_comp requests, 1-component jpegs return as 1-component, + on 'test' only check type, not whether we support this variant + 0.50 (2006-11-19) + first released version +*/ diff --git a/phonelibs/nanovg/stb_truetype.h b/phonelibs/nanovg/stb_truetype.h new file mode 100644 index 0000000000..bfb1841f69 --- /dev/null +++ b/phonelibs/nanovg/stb_truetype.h @@ -0,0 +1,3249 @@ +// stb_truetype.h - v1.09 - public domain +// authored from 2009-2015 by Sean Barrett / RAD Game Tools +// +// This library processes TrueType files: +// parse files +// extract glyph metrics +// extract glyph shapes +// render glyphs to one-channel bitmaps with antialiasing (box filter) +// +// Todo: +// non-MS cmaps +// crashproof on bad data +// hinting? (no longer patented) +// cleartype-style AA? +// optimize: use simple memory allocator for intermediates +// optimize: build edge-list directly from curves +// optimize: rasterize directly from curves? +// +// ADDITIONAL CONTRIBUTORS +// +// Mikko Mononen: compound shape support, more cmap formats +// Tor Andersson: kerning, subpixel rendering +// +// Bug/warning reports/fixes: +// "Zer" on mollyrocket (with fix) +// Cass Everitt +// stoiko (Haemimont Games) +// Brian Hook +// Walter van Niftrik +// David Gow +// David Given +// Ivan-Assen Ivanov +// Anthony Pesch +// Johan Duparc +// Hou Qiming +// Fabian "ryg" Giesen +// Martins Mozeiko +// Cap Petschulat +// Omar Cornut +// github:aloucks +// Peter LaValle +// Sergey Popov +// Giumo X. Clanjor +// Higor Euripedes +// Thomas Fields +// Derek Vinyard +// +// Misc other: +// Ryan Gordon +// +// VERSION HISTORY +// +// 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use allocation userdata properly +// 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges +// 1.07 (2015-08-01) allow PackFontRanges to accept arrays of sparse codepoints; +// variant PackFontRanges to pack and render in separate phases; +// fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); +// fixed an assert() bug in the new rasterizer +// replace assert() with STBTT_assert() in new rasterizer +// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) +// also more precise AA rasterizer, except if shapes overlap +// remove need for STBTT_sort +// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC +// 1.04 (2015-04-15) typo in example +// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes +// +// Full history can be found at the end of this file. +// +// LICENSE +// +// This software is in the public domain. Where that dedication is not +// recognized, you are granted a perpetual, irrevocable license to copy, +// distribute, and modify this file as you see fit. +// +// USAGE +// +// Include this file in whatever places neeed to refer to it. In ONE C/C++ +// file, write: +// #define STB_TRUETYPE_IMPLEMENTATION +// before the #include of this file. This expands out the actual +// implementation into that C/C++ file. +// +// To make the implementation private to the file that generates the implementation, +// #define STBTT_STATIC +// +// Simple 3D API (don't ship this, but it's fine for tools and quick start) +// stbtt_BakeFontBitmap() -- bake a font to a bitmap for use as texture +// stbtt_GetBakedQuad() -- compute quad to draw for a given char +// +// Improved 3D API (more shippable): +// #include "stb_rect_pack.h" -- optional, but you really want it +// stbtt_PackBegin() +// stbtt_PackSetOversample() -- for improved quality on small fonts +// stbtt_PackFontRanges() -- pack and renders +// stbtt_PackEnd() +// stbtt_GetPackedQuad() +// +// "Load" a font file from a memory buffer (you have to keep the buffer loaded) +// stbtt_InitFont() +// stbtt_GetFontOffsetForIndex() -- use for TTC font collections +// +// Render a unicode codepoint to a bitmap +// stbtt_GetCodepointBitmap() -- allocates and returns a bitmap +// stbtt_MakeCodepointBitmap() -- renders into bitmap you provide +// stbtt_GetCodepointBitmapBox() -- how big the bitmap must be +// +// Character advance/positioning +// stbtt_GetCodepointHMetrics() +// stbtt_GetFontVMetrics() +// stbtt_GetCodepointKernAdvance() +// +// Starting with version 1.06, the rasterizer was replaced with a new, +// faster and generally-more-precise rasterizer. The new rasterizer more +// accurately measures pixel coverage for anti-aliasing, except in the case +// where multiple shapes overlap, in which case it overestimates the AA pixel +// coverage. Thus, anti-aliasing of intersecting shapes may look wrong. If +// this turns out to be a problem, you can re-enable the old rasterizer with +// #define STBTT_RASTERIZER_VERSION 1 +// which will incur about a 15% speed hit. +// +// ADDITIONAL DOCUMENTATION +// +// Immediately after this block comment are a series of sample programs. +// +// After the sample programs is the "header file" section. This section +// includes documentation for each API function. +// +// Some important concepts to understand to use this library: +// +// Codepoint +// Characters are defined by unicode codepoints, e.g. 65 is +// uppercase A, 231 is lowercase c with a cedilla, 0x7e30 is +// the hiragana for "ma". +// +// Glyph +// A visual character shape (every codepoint is rendered as +// some glyph) +// +// Glyph index +// A font-specific integer ID representing a glyph +// +// Baseline +// Glyph shapes are defined relative to a baseline, which is the +// bottom of uppercase characters. Characters extend both above +// and below the baseline. +// +// Current Point +// As you draw text to the screen, you keep track of a "current point" +// which is the origin of each character. The current point's vertical +// position is the baseline. Even "baked fonts" use this model. +// +// Vertical Font Metrics +// The vertical qualities of the font, used to vertically position +// and space the characters. See docs for stbtt_GetFontVMetrics. +// +// Font Size in Pixels or Points +// The preferred interface for specifying font sizes in stb_truetype +// is to specify how tall the font's vertical extent should be in pixels. +// If that sounds good enough, skip the next paragraph. +// +// Most font APIs instead use "points", which are a common typographic +// measurement for describing font size, defined as 72 points per inch. +// stb_truetype provides a point API for compatibility. However, true +// "per inch" conventions don't make much sense on computer displays +// since they different monitors have different number of pixels per +// inch. For example, Windows traditionally uses a convention that +// there are 96 pixels per inch, thus making 'inch' measurements have +// nothing to do with inches, and thus effectively defining a point to +// be 1.333 pixels. Additionally, the TrueType font data provides +// an explicit scale factor to scale a given font's glyphs to points, +// but the author has observed that this scale factor is often wrong +// for non-commercial fonts, thus making fonts scaled in points +// according to the TrueType spec incoherently sized in practice. +// +// ADVANCED USAGE +// +// Quality: +// +// - Use the functions with Subpixel at the end to allow your characters +// to have subpixel positioning. Since the font is anti-aliased, not +// hinted, this is very import for quality. (This is not possible with +// baked fonts.) +// +// - Kerning is now supported, and if you're supporting subpixel rendering +// then kerning is worth using to give your text a polished look. +// +// Performance: +// +// - Convert Unicode codepoints to glyph indexes and operate on the glyphs; +// if you don't do this, stb_truetype is forced to do the conversion on +// every call. +// +// - There are a lot of memory allocations. We should modify it to take +// a temp buffer and allocate from the temp buffer (without freeing), +// should help performance a lot. +// +// NOTES +// +// The system uses the raw data found in the .ttf file without changing it +// and without building auxiliary data structures. This is a bit inefficient +// on little-endian systems (the data is big-endian), but assuming you're +// caching the bitmaps or glyph shapes this shouldn't be a big deal. +// +// It appears to be very hard to programmatically determine what font a +// given file is in a general way. I provide an API for this, but I don't +// recommend it. +// +// +// SOURCE STATISTICS (based on v0.6c, 2050 LOC) +// +// Documentation & header file 520 LOC \___ 660 LOC documentation +// Sample code 140 LOC / +// Truetype parsing 620 LOC ---- 620 LOC TrueType +// Software rasterization 240 LOC \ . +// Curve tesselation 120 LOC \__ 550 LOC Bitmap creation +// Bitmap management 100 LOC / +// Baked bitmap interface 70 LOC / +// Font name matching & access 150 LOC ---- 150 +// C runtime library abstraction 60 LOC ---- 60 +// +// +// PERFORMANCE MEASUREMENTS FOR 1.06: +// +// 32-bit 64-bit +// Previous release: 8.83 s 7.68 s +// Pool allocations: 7.72 s 6.34 s +// Inline sort : 6.54 s 5.65 s +// New rasterizer : 5.63 s 5.00 s + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +//// +//// SAMPLE PROGRAMS +//// +// +// Incomplete text-in-3d-api example, which draws quads properly aligned to be lossless +// +#if 0 +#define STB_TRUETYPE_IMPLEMENTATION // force following include to generate implementation +#include "stb_truetype.h" + +unsigned char ttf_buffer[1<<20]; +unsigned char temp_bitmap[512*512]; + +stbtt_bakedchar cdata[96]; // ASCII 32..126 is 95 glyphs +GLuint ftex; + +void my_stbtt_initfont(void) +{ + fread(ttf_buffer, 1, 1<<20, fopen("c:/windows/fonts/times.ttf", "rb")); + stbtt_BakeFontBitmap(ttf_buffer,0, 32.0, temp_bitmap,512,512, 32,96, cdata); // no guarantee this fits! + // can free ttf_buffer at this point + glGenTextures(1, &ftex); + glBindTexture(GL_TEXTURE_2D, ftex); + glTexImage2D(GL_TEXTURE_2D, 0, GL_ALPHA, 512,512, 0, GL_ALPHA, GL_UNSIGNED_BYTE, temp_bitmap); + // can free temp_bitmap at this point + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); +} + +void my_stbtt_print(float x, float y, char *text) +{ + // assume orthographic projection with units = screen pixels, origin at top left + glEnable(GL_TEXTURE_2D); + glBindTexture(GL_TEXTURE_2D, ftex); + glBegin(GL_QUADS); + while (*text) { + if (*text >= 32 && *text < 128) { + stbtt_aligned_quad q; + stbtt_GetBakedQuad(cdata, 512,512, *text-32, &x,&y,&q,1);//1=opengl & d3d10+,0=d3d9 + glTexCoord2f(q.s0,q.t1); glVertex2f(q.x0,q.y0); + glTexCoord2f(q.s1,q.t1); glVertex2f(q.x1,q.y0); + glTexCoord2f(q.s1,q.t0); glVertex2f(q.x1,q.y1); + glTexCoord2f(q.s0,q.t0); glVertex2f(q.x0,q.y1); + } + ++text; + } + glEnd(); +} +#endif +// +// +////////////////////////////////////////////////////////////////////////////// +// +// Complete program (this compiles): get a single bitmap, print as ASCII art +// +#if 0 +#include +#define STB_TRUETYPE_IMPLEMENTATION // force following include to generate implementation +#include "stb_truetype.h" + +char ttf_buffer[1<<25]; + +int main(int argc, char **argv) +{ + stbtt_fontinfo font; + unsigned char *bitmap; + int w,h,i,j,c = (argc > 1 ? atoi(argv[1]) : 'a'), s = (argc > 2 ? atoi(argv[2]) : 20); + + fread(ttf_buffer, 1, 1<<25, fopen(argc > 3 ? argv[3] : "c:/windows/fonts/arialbd.ttf", "rb")); + + stbtt_InitFont(&font, ttf_buffer, stbtt_GetFontOffsetForIndex(ttf_buffer,0)); + bitmap = stbtt_GetCodepointBitmap(&font, 0,stbtt_ScaleForPixelHeight(&font, s), c, &w, &h, 0,0); + + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) + putchar(" .:ioVM@"[bitmap[j*w+i]>>5]); + putchar('\n'); + } + return 0; +} +#endif +// +// Output: +// +// .ii. +// @@@@@@. +// V@Mio@@o +// :i. V@V +// :oM@@M +// :@@@MM@M +// @@o o@M +// :@@. M@M +// @@@o@@@@ +// :M@@V:@@. +// +////////////////////////////////////////////////////////////////////////////// +// +// Complete program: print "Hello World!" banner, with bugs +// +#if 0 +char buffer[24<<20]; +unsigned char screen[20][79]; + +int main(int arg, char **argv) +{ + stbtt_fontinfo font; + int i,j,ascent,baseline,ch=0; + float scale, xpos=2; // leave a little padding in case the character extends left + char *text = "Heljo World!"; // intentionally misspelled to show 'lj' brokenness + + fread(buffer, 1, 1000000, fopen("c:/windows/fonts/arialbd.ttf", "rb")); + stbtt_InitFont(&font, buffer, 0); + + scale = stbtt_ScaleForPixelHeight(&font, 15); + stbtt_GetFontVMetrics(&font, &ascent,0,0); + baseline = (int) (ascent*scale); + + while (text[ch]) { + int advance,lsb,x0,y0,x1,y1; + float x_shift = xpos - (float) floor(xpos); + stbtt_GetCodepointHMetrics(&font, text[ch], &advance, &lsb); + stbtt_GetCodepointBitmapBoxSubpixel(&font, text[ch], scale,scale,x_shift,0, &x0,&y0,&x1,&y1); + stbtt_MakeCodepointBitmapSubpixel(&font, &screen[baseline + y0][(int) xpos + x0], x1-x0,y1-y0, 79, scale,scale,x_shift,0, text[ch]); + // note that this stomps the old data, so where character boxes overlap (e.g. 'lj') it's wrong + // because this API is really for baking character bitmaps into textures. if you want to render + // a sequence of characters, you really need to render each bitmap to a temp buffer, then + // "alpha blend" that into the working buffer + xpos += (advance * scale); + if (text[ch+1]) + xpos += scale*stbtt_GetCodepointKernAdvance(&font, text[ch],text[ch+1]); + ++ch; + } + + for (j=0; j < 20; ++j) { + for (i=0; i < 78; ++i) + putchar(" .:ioVM@"[screen[j][i]>>5]); + putchar('\n'); + } + + return 0; +} +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +//// +//// INTEGRATION WITH YOUR CODEBASE +//// +//// The following sections allow you to supply alternate definitions +//// of C library functions used by stb_truetype. + +#ifdef STB_TRUETYPE_IMPLEMENTATION + // #define your own (u)stbtt_int8/16/32 before including to override this + #ifndef stbtt_uint8 + typedef unsigned char stbtt_uint8; + typedef signed char stbtt_int8; + typedef unsigned short stbtt_uint16; + typedef signed short stbtt_int16; + typedef unsigned int stbtt_uint32; + typedef signed int stbtt_int32; + #endif + + typedef char stbtt__check_size32[sizeof(stbtt_int32)==4 ? 1 : -1]; + typedef char stbtt__check_size16[sizeof(stbtt_int16)==2 ? 1 : -1]; + + // #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h + #ifndef STBTT_ifloor + #include + #define STBTT_ifloor(x) ((int) floor(x)) + #define STBTT_iceil(x) ((int) ceil(x)) + #endif + + #ifndef STBTT_sqrt + #include + #define STBTT_sqrt(x) sqrt(x) + #endif + + // #define your own functions "STBTT_malloc" / "STBTT_free" to avoid malloc.h + #ifndef STBTT_malloc + #include + #define STBTT_malloc(x,u) ((void)(u),malloc(x)) + #define STBTT_free(x,u) ((void)(u),free(x)) + #endif + + #ifndef STBTT_assert + #include + #define STBTT_assert(x) assert(x) + #endif + + #ifndef STBTT_strlen + #include + #define STBTT_strlen(x) strlen(x) + #endif + + #ifndef STBTT_memcpy + #include + #define STBTT_memcpy memcpy + #define STBTT_memset memset + #endif +#endif + +/////////////////////////////////////////////////////////////////////////////// +/////////////////////////////////////////////////////////////////////////////// +//// +//// INTERFACE +//// +//// + +#ifndef __STB_INCLUDE_STB_TRUETYPE_H__ +#define __STB_INCLUDE_STB_TRUETYPE_H__ + +#ifdef STBTT_STATIC +#define STBTT_DEF static +#else +#define STBTT_DEF extern +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// TEXTURE BAKING API +// +// If you use this API, you only have to call two functions ever. +// + +typedef struct +{ + unsigned short x0,y0,x1,y1; // coordinates of bbox in bitmap + float xoff,yoff,xadvance; +} stbtt_bakedchar; + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) + float pixel_height, // height of font in pixels + unsigned char *pixels, int pw, int ph, // bitmap to be filled in + int first_char, int num_chars, // characters to bake + stbtt_bakedchar *chardata); // you allocate this, it's num_chars long +// if return is positive, the first unused row of the bitmap +// if return is negative, returns the negative of the number of characters that fit +// if return is 0, no characters fit and no rows were used +// This uses a very crappy packing. + +typedef struct +{ + float x0,y0,s0,t0; // top-left + float x1,y1,s1,t1; // bottom-right +} stbtt_aligned_quad; + +STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, // same data as above + int char_index, // character to display + float *xpos, float *ypos, // pointers to current position in screen pixel space + stbtt_aligned_quad *q, // output: quad to draw + int opengl_fillrule); // true if opengl fill rule; false if DX9 or earlier +// Call GetBakedQuad with char_index = 'character - first_char', and it +// creates the quad you need to draw and advances the current position. +// +// The coordinate system used assumes y increases downwards. +// +// Characters will extend both above and below the current position; +// see discussion of "BASELINE" above. +// +// It's inefficient; you might want to c&p it and optimize it. + + + +////////////////////////////////////////////////////////////////////////////// +// +// NEW TEXTURE BAKING API +// +// This provides options for packing multiple fonts into one atlas, not +// perfectly but better than nothing. + +typedef struct +{ + unsigned short x0,y0,x1,y1; // coordinates of bbox in bitmap + float xoff,yoff,xadvance; + float xoff2,yoff2; +} stbtt_packedchar; + +typedef struct stbtt_pack_context stbtt_pack_context; +typedef struct stbtt_fontinfo stbtt_fontinfo; +#ifndef STB_RECT_PACK_VERSION +typedef struct stbrp_rect stbrp_rect; +#endif + +STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int width, int height, int stride_in_bytes, int padding, void *alloc_context); +// Initializes a packing context stored in the passed-in stbtt_pack_context. +// Future calls using this context will pack characters into the bitmap passed +// in here: a 1-channel bitmap that is weight x height. stride_in_bytes is +// the distance from one row to the next (or 0 to mean they are packed tightly +// together). "padding" is the amount of padding to leave between each +// character (normally you want '1' for bitmaps you'll use as textures with +// bilinear filtering). +// +// Returns 0 on failure, 1 on success. + +STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc); +// Cleans up the packing context and frees all memory. + +#define STBTT_POINT_SIZE(x) (-(x)) + +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, + int first_unicode_char_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range); +// Creates character bitmaps from the font_index'th font found in fontdata (use +// font_index=0 if you don't know what that is). It creates num_chars_in_range +// bitmaps for characters with unicode values starting at first_unicode_char_in_range +// and increasing. Data for how to render them is stored in chardata_for_range; +// pass these to stbtt_GetPackedQuad to get back renderable quads. +// +// font_size is the full height of the character from ascender to descender, +// as computed by stbtt_ScaleForPixelHeight. To use a point size as computed +// by stbtt_ScaleForMappingEmToPixels, wrap the point size in STBTT_POINT_SIZE() +// and pass that result as 'font_size': +// ..., 20 , ... // font max minus min y is 20 pixels tall +// ..., STBTT_POINT_SIZE(20), ... // 'M' is 20 pixels tall + +typedef struct +{ + float font_size; + int first_unicode_codepoint_in_range; // if non-zero, then the chars are continuous, and this is the first codepoint + int *array_of_unicode_codepoints; // if non-zero, then this is an array of unicode codepoints + int num_chars; + stbtt_packedchar *chardata_for_range; // output + unsigned char h_oversample, v_oversample; // don't set these, they're used internally +} stbtt_pack_range; + +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); +// Creates character bitmaps from multiple ranges of characters stored in +// ranges. This will usually create a better-packed bitmap than multiple +// calls to stbtt_PackFontRange. Note that you can call this multiple +// times within a single PackBegin/PackEnd. + +STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h_oversample, unsigned int v_oversample); +// Oversampling a font increases the quality by allowing higher-quality subpixel +// positioning, and is especially valuable at smaller text sizes. +// +// This function sets the amount of oversampling for all following calls to +// stbtt_PackFontRange(s) or stbtt_PackFontRangesGatherRects for a given +// pack context. The default (no oversampling) is achieved by h_oversample=1 +// and v_oversample=1. The total number of pixels required is +// h_oversample*v_oversample larger than the default; for example, 2x2 +// oversampling requires 4x the storage of 1x1. For best results, render +// oversampled textures with bilinear filtering. Look at the readme in +// stb/tests/oversample for information about oversampled fonts +// +// To use with PackFontRangesGather etc., you must set it before calls +// call to PackFontRangesGatherRects. + +STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, // same data as above + int char_index, // character to display + float *xpos, float *ypos, // pointers to current position in screen pixel space + stbtt_aligned_quad *q, // output: quad to draw + int align_to_integer); + +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects); +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +// Calling these functions in sequence is roughly equivalent to calling +// stbtt_PackFontRanges(). If you more control over the packing of multiple +// fonts, or if you want to pack custom data into a font texture, take a look +// at the source to of stbtt_PackFontRanges() and create a custom version +// using these functions, e.g. call GatherRects multiple times, +// building up a single array of rects, then call PackRects once, +// then call RenderIntoRects repeatedly. This may result in a +// better packing than calling PackFontRanges multiple times +// (or it may not). + +// this is an opaque structure that you shouldn't mess with which holds +// all the context needed from PackBegin to PackEnd. +struct stbtt_pack_context { + void *user_allocator_context; + void *pack_info; + int width; + int height; + int stride_in_bytes; + int padding; + unsigned int h_oversample, v_oversample; + unsigned char *pixels; + void *nodes; +}; + +////////////////////////////////////////////////////////////////////////////// +// +// FONT LOADING +// +// + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index); +// Each .ttf/.ttc file may have more than one font. Each font has a sequential +// index number starting from 0. Call this function to get the font offset for +// a given index; it returns -1 if the index is out of range. A regular .ttf +// file will only define one font and it always be at offset 0, so it will +// return '0' for index 0, and -1 for all other indices. You can just skip +// this step if you know it's that kind of font. + + +// The following structure is defined publically so you can declare one on +// the stack or as a global or etc, but you should treat it as opaque. +typedef struct stbtt_fontinfo +{ + void * userdata; + unsigned char * data; // pointer to .ttf file + int fontstart; // offset of start of font + + int numGlyphs; // number of glyphs, needed for range checking + + int loca,head,glyf,hhea,hmtx,kern; // table locations as offset from start of .ttf + int index_map; // a cmap mapping for our chosen character encoding + int indexToLocFormat; // format needed to map from glyph index to glyph +} stbtt_fontinfo; + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset); +// Given an offset into the file that defines a font, this function builds +// the necessary cached info for the rest of the system. You must allocate +// the stbtt_fontinfo yourself, and stbtt_InitFont will fill it out. You don't +// need to do anything special to free it, because the contents are pure +// value data with no additional data structures. Returns 0 on failure. + + +////////////////////////////////////////////////////////////////////////////// +// +// CHARACTER TO GLYPH-INDEX CONVERSIOn + +STBTT_DEF int stbtt_FindGlyphIndex(const stbtt_fontinfo *info, int unicode_codepoint); +// If you're going to perform multiple operations on the same character +// and you want a speed-up, call this function with the character you're +// going to process, then use glyph-based functions instead of the +// codepoint-based functions. + + +////////////////////////////////////////////////////////////////////////////// +// +// CHARACTER PROPERTIES +// + +STBTT_DEF float stbtt_ScaleForPixelHeight(const stbtt_fontinfo *info, float pixels); +// computes a scale factor to produce a font whose "height" is 'pixels' tall. +// Height is measured as the distance from the highest ascender to the lowest +// descender; in other words, it's equivalent to calling stbtt_GetFontVMetrics +// and computing: +// scale = pixels / (ascent - descent) +// so if you prefer to measure height by the ascent only, use a similar calculation. + +STBTT_DEF float stbtt_ScaleForMappingEmToPixels(const stbtt_fontinfo *info, float pixels); +// computes a scale factor to produce a font whose EM size is mapped to +// 'pixels' tall. This is probably what traditional APIs compute, but +// I'm not positive. + +STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, int *descent, int *lineGap); +// ascent is the coordinate above the baseline the font extends; descent +// is the coordinate below the baseline the font extends (i.e. it is typically negative) +// lineGap is the spacing between one row's descent and the next row's ascent... +// so you should advance the vertical position by "*ascent - *descent + *lineGap" +// these are expressed in unscaled coordinates, so you must multiply by +// the scale factor for a given size + +STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1); +// the bounding box around all possible characters + +STBTT_DEF void stbtt_GetCodepointHMetrics(const stbtt_fontinfo *info, int codepoint, int *advanceWidth, int *leftSideBearing); +// leftSideBearing is the offset from the current horizontal position to the left edge of the character +// advanceWidth is the offset from the current horizontal position to the next horizontal position +// these are expressed in unscaled coordinates + +STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2); +// an additional amount to add to the 'advance' value between ch1 and ch2 + +STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, int *x0, int *y0, int *x1, int *y1); +// Gets the bounding box of the visible part of the glyph, in unscaled coordinates + +STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing); +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2); +STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1); +// as above, but takes one or more glyph indices for greater efficiency + + +////////////////////////////////////////////////////////////////////////////// +// +// GLYPH SHAPES (you probably don't need these, but they have to go before +// the bitmaps for C declaration-order reasons) +// + +#ifndef STBTT_vmove // you can predefine these to use different values (but why?) + enum { + STBTT_vmove=1, + STBTT_vline, + STBTT_vcurve + }; +#endif + +#ifndef stbtt_vertex // you can predefine this to use different values + // (we share this with other code at RAD) + #define stbtt_vertex_type short // can't use stbtt_int16 because that's not visible in the header file + typedef struct + { + stbtt_vertex_type x,y,cx,cy; + unsigned char type,padding; + } stbtt_vertex; +#endif + +STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index); +// returns non-zero if nothing is drawn for this glyph + +STBTT_DEF int stbtt_GetCodepointShape(const stbtt_fontinfo *info, int unicode_codepoint, stbtt_vertex **vertices); +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **vertices); +// returns # of vertices and fills *vertices with the pointer to them +// these are expressed in "unscaled" coordinates +// +// The shape is a series of countours. Each one starts with +// a STBTT_moveto, then consists of a series of mixed +// STBTT_lineto and STBTT_curveto segments. A lineto +// draws a line from previous endpoint to its x,y; a curveto +// draws a quadratic bezier from previous endpoint to +// its x,y, using cx,cy as the bezier control point. + +STBTT_DEF void stbtt_FreeShape(const stbtt_fontinfo *info, stbtt_vertex *vertices); +// frees the data allocated above + +////////////////////////////////////////////////////////////////////////////// +// +// BITMAP RENDERING +// + +STBTT_DEF void stbtt_FreeBitmap(unsigned char *bitmap, void *userdata); +// frees the bitmap allocated below + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int codepoint, int *width, int *height, int *xoff, int *yoff); +// allocates a large-enough single-channel 8bpp bitmap and renders the +// specified character/glyph at the specified scale into it, with +// antialiasing. 0 is no coverage (transparent), 255 is fully covered (opaque). +// *width & *height are filled out with the width & height of the bitmap, +// which is stored left-to-right, top-to-bottom. +// +// xoff/yoff are the offset it pixel space from the glyph origin to the top-left of the bitmap + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint, int *width, int *height, int *xoff, int *yoff); +// the same as stbtt_GetCodepoitnBitmap, but you can specify a subpixel +// shift for the character + +STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int codepoint); +// the same as stbtt_GetCodepointBitmap, but you pass in storage for the bitmap +// in the form of 'output', with row spacing of 'out_stride' bytes. the bitmap +// is clipped to out_w/out_h bytes. Call stbtt_GetCodepointBitmapBox to get the +// width and height and positioning info for it first. + +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint); +// same as stbtt_MakeCodepointBitmap, but you can specify a subpixel +// shift for the character + +STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); +// get the bbox of the bitmap centered around the glyph origin; so the +// bitmap width is ix1-ix0, height is iy1-iy0, and location to place +// the bitmap top left is (leftSideBearing*scale,iy0). +// (Note that the bitmap uses y-increases-down, but the shape uses +// y-increases-up, so CodepointBitmapBox and CodepointBox are inverted.) + +STBTT_DEF void stbtt_GetCodepointBitmapBoxSubpixel(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); +// same as stbtt_GetCodepointBitmapBox, but you can specify a subpixel +// shift for the character + +// the following functions are equivalent to the above functions, but operate +// on glyph indices instead of Unicode codepoints (for efficiency) +STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int glyph, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph); +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph); +STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); +STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); + + +// @TODO: don't expose this structure +typedef struct +{ + int w,h,stride; + unsigned char *pixels; +} stbtt__bitmap; + +// rasterize a shape with quadratic beziers into a bitmap +STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, // 1-channel bitmap to draw into + float flatness_in_pixels, // allowable error of curve in pixels + stbtt_vertex *vertices, // array of vertices defining shape + int num_verts, // number of vertices in above array + float scale_x, float scale_y, // scale applied to input vertices + float shift_x, float shift_y, // translation applied to input vertices + int x_off, int y_off, // another translation applied to input + int invert, // if non-zero, vertically flip shape + void *userdata); // context for to STBTT_MALLOC + +////////////////////////////////////////////////////////////////////////////// +// +// Finding the right font... +// +// You should really just solve this offline, keep your own tables +// of what font is what, and don't try to get it out of the .ttf file. +// That's because getting it out of the .ttf file is really hard, because +// the names in the file can appear in many possible encodings, in many +// possible languages, and e.g. if you need a case-insensitive comparison, +// the details of that depend on the encoding & language in a complex way +// (actually underspecified in truetype, but also gigantic). +// +// But you can use the provided functions in two possible ways: +// stbtt_FindMatchingFont() will use *case-sensitive* comparisons on +// unicode-encoded names to try to find the font you want; +// you can run this before calling stbtt_InitFont() +// +// stbtt_GetFontNameString() lets you get any of the various strings +// from the file yourself and do your own comparisons on them. +// You have to have called stbtt_InitFont() first. + + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *fontdata, const char *name, int flags); +// returns the offset (not index) of the font that matches, or -1 if none +// if you use STBTT_MACSTYLE_DONTCARE, use a font name like "Arial Bold". +// if you use any other flag, use a font name like "Arial"; this checks +// the 'macStyle' header field; i don't know if fonts set this consistently +#define STBTT_MACSTYLE_DONTCARE 0 +#define STBTT_MACSTYLE_BOLD 1 +#define STBTT_MACSTYLE_ITALIC 2 +#define STBTT_MACSTYLE_UNDERSCORE 4 +#define STBTT_MACSTYLE_NONE 8 // <= not same as 0, this makes us check the bitfield is 0 + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2); +// returns 1/0 whether the first string interpreted as utf8 is identical to +// the second string interpreted as big-endian utf16... useful for strings from next func + +STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *length, int platformID, int encodingID, int languageID, int nameID); +// returns the string (which may be big-endian double byte, e.g. for unicode) +// and puts the length in bytes in *length. +// +// some of the values for the IDs are below; for more see the truetype spec: +// http://developer.apple.com/textfonts/TTRefMan/RM06/Chap6name.html +// http://www.microsoft.com/typography/otspec/name.htm + +enum { // platformID + STBTT_PLATFORM_ID_UNICODE =0, + STBTT_PLATFORM_ID_MAC =1, + STBTT_PLATFORM_ID_ISO =2, + STBTT_PLATFORM_ID_MICROSOFT =3 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_UNICODE + STBTT_UNICODE_EID_UNICODE_1_0 =0, + STBTT_UNICODE_EID_UNICODE_1_1 =1, + STBTT_UNICODE_EID_ISO_10646 =2, + STBTT_UNICODE_EID_UNICODE_2_0_BMP=3, + STBTT_UNICODE_EID_UNICODE_2_0_FULL=4 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_MICROSOFT + STBTT_MS_EID_SYMBOL =0, + STBTT_MS_EID_UNICODE_BMP =1, + STBTT_MS_EID_SHIFTJIS =2, + STBTT_MS_EID_UNICODE_FULL =10 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_MAC; same as Script Manager codes + STBTT_MAC_EID_ROMAN =0, STBTT_MAC_EID_ARABIC =4, + STBTT_MAC_EID_JAPANESE =1, STBTT_MAC_EID_HEBREW =5, + STBTT_MAC_EID_CHINESE_TRAD =2, STBTT_MAC_EID_GREEK =6, + STBTT_MAC_EID_KOREAN =3, STBTT_MAC_EID_RUSSIAN =7 +}; + +enum { // languageID for STBTT_PLATFORM_ID_MICROSOFT; same as LCID... + // problematic because there are e.g. 16 english LCIDs and 16 arabic LCIDs + STBTT_MS_LANG_ENGLISH =0x0409, STBTT_MS_LANG_ITALIAN =0x0410, + STBTT_MS_LANG_CHINESE =0x0804, STBTT_MS_LANG_JAPANESE =0x0411, + STBTT_MS_LANG_DUTCH =0x0413, STBTT_MS_LANG_KOREAN =0x0412, + STBTT_MS_LANG_FRENCH =0x040c, STBTT_MS_LANG_RUSSIAN =0x0419, + STBTT_MS_LANG_GERMAN =0x0407, STBTT_MS_LANG_SPANISH =0x0409, + STBTT_MS_LANG_HEBREW =0x040d, STBTT_MS_LANG_SWEDISH =0x041D +}; + +enum { // languageID for STBTT_PLATFORM_ID_MAC + STBTT_MAC_LANG_ENGLISH =0 , STBTT_MAC_LANG_JAPANESE =11, + STBTT_MAC_LANG_ARABIC =12, STBTT_MAC_LANG_KOREAN =23, + STBTT_MAC_LANG_DUTCH =4 , STBTT_MAC_LANG_RUSSIAN =32, + STBTT_MAC_LANG_FRENCH =1 , STBTT_MAC_LANG_SPANISH =6 , + STBTT_MAC_LANG_GERMAN =2 , STBTT_MAC_LANG_SWEDISH =5 , + STBTT_MAC_LANG_HEBREW =10, STBTT_MAC_LANG_CHINESE_SIMPLIFIED =33, + STBTT_MAC_LANG_ITALIAN =3 , STBTT_MAC_LANG_CHINESE_TRAD =19 +}; + +#ifdef __cplusplus +} +#endif + +#endif // __STB_INCLUDE_STB_TRUETYPE_H__ + +/////////////////////////////////////////////////////////////////////////////// +/////////////////////////////////////////////////////////////////////////////// +//// +//// IMPLEMENTATION +//// +//// + +#ifdef STB_TRUETYPE_IMPLEMENTATION + +#ifndef STBTT_MAX_OVERSAMPLE +#define STBTT_MAX_OVERSAMPLE 8 +#endif + +#if STBTT_MAX_OVERSAMPLE > 255 +#error "STBTT_MAX_OVERSAMPLE cannot be > 255" +#endif + +typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERSAMPLE-1)) == 0 ? 1 : -1]; + +#ifndef STBTT_RASTERIZER_VERSION +#define STBTT_RASTERIZER_VERSION 2 +#endif + +////////////////////////////////////////////////////////////////////////// +// +// accessors to parse data from file +// + +// on platforms that don't allow misaligned reads, if we want to allow +// truetype fonts that aren't padded to alignment, define ALLOW_UNALIGNED_TRUETYPE + +#define ttBYTE(p) (* (stbtt_uint8 *) (p)) +#define ttCHAR(p) (* (stbtt_int8 *) (p)) +#define ttFixed(p) ttLONG(p) + +#if defined(STB_TRUETYPE_BIGENDIAN) && !defined(ALLOW_UNALIGNED_TRUETYPE) + + #define ttUSHORT(p) (* (stbtt_uint16 *) (p)) + #define ttSHORT(p) (* (stbtt_int16 *) (p)) + #define ttULONG(p) (* (stbtt_uint32 *) (p)) + #define ttLONG(p) (* (stbtt_int32 *) (p)) + +#else + + static stbtt_uint16 ttUSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } + static stbtt_int16 ttSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } + static stbtt_uint32 ttULONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } + static stbtt_int32 ttLONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } + +#endif + +#define stbtt_tag4(p,c0,c1,c2,c3) ((p)[0] == (c0) && (p)[1] == (c1) && (p)[2] == (c2) && (p)[3] == (c3)) +#define stbtt_tag(p,str) stbtt_tag4(p,str[0],str[1],str[2],str[3]) + +static int stbtt__isfont(const stbtt_uint8 *font) +{ + // check the version number + if (stbtt_tag4(font, '1',0,0,0)) return 1; // TrueType 1 + if (stbtt_tag(font, "typ1")) return 1; // TrueType with type 1 font -- we don't support this! + if (stbtt_tag(font, "OTTO")) return 1; // OpenType with CFF + if (stbtt_tag4(font, 0,1,0,0)) return 1; // OpenType 1.0 + return 0; +} + +// @OPTIMIZE: binary search +static stbtt_uint32 stbtt__find_table(stbtt_uint8 *data, stbtt_uint32 fontstart, const char *tag) +{ + stbtt_int32 num_tables = ttUSHORT(data+fontstart+4); + stbtt_uint32 tabledir = fontstart + 12; + stbtt_int32 i; + for (i=0; i < num_tables; ++i) { + stbtt_uint32 loc = tabledir + 16*i; + if (stbtt_tag(data+loc+0, tag)) + return ttULONG(data+loc+8); + } + return 0; +} + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, int index) +{ + // if it's just a font, there's only one valid index + if (stbtt__isfont(font_collection)) + return index == 0 ? 0 : -1; + + // check if it's a TTC + if (stbtt_tag(font_collection, "ttcf")) { + // version 1? + if (ttULONG(font_collection+4) == 0x00010000 || ttULONG(font_collection+4) == 0x00020000) { + stbtt_int32 n = ttLONG(font_collection+8); + if (index >= n) + return -1; + return ttULONG(font_collection+12+index*4); + } + } + return -1; +} + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, int fontstart) +{ + stbtt_uint8 *data = (stbtt_uint8 *) data2; + stbtt_uint32 cmap, t; + stbtt_int32 i,numTables; + + info->data = data; + info->fontstart = fontstart; + + cmap = stbtt__find_table(data, fontstart, "cmap"); // required + info->loca = stbtt__find_table(data, fontstart, "loca"); // required + info->head = stbtt__find_table(data, fontstart, "head"); // required + info->glyf = stbtt__find_table(data, fontstart, "glyf"); // required + info->hhea = stbtt__find_table(data, fontstart, "hhea"); // required + info->hmtx = stbtt__find_table(data, fontstart, "hmtx"); // required + info->kern = stbtt__find_table(data, fontstart, "kern"); // not required + if (!cmap || !info->loca || !info->head || !info->glyf || !info->hhea || !info->hmtx) + return 0; + + t = stbtt__find_table(data, fontstart, "maxp"); + if (t) + info->numGlyphs = ttUSHORT(data+t+4); + else + info->numGlyphs = 0xffff; + + // find a cmap encoding table we understand *now* to avoid searching + // later. (todo: could make this installable) + // the same regardless of glyph. + numTables = ttUSHORT(data + cmap + 2); + info->index_map = 0; + for (i=0; i < numTables; ++i) { + stbtt_uint32 encoding_record = cmap + 4 + 8 * i; + // find an encoding we understand: + switch(ttUSHORT(data+encoding_record)) { + case STBTT_PLATFORM_ID_MICROSOFT: + switch (ttUSHORT(data+encoding_record+2)) { + case STBTT_MS_EID_UNICODE_BMP: + case STBTT_MS_EID_UNICODE_FULL: + // MS/Unicode + info->index_map = cmap + ttULONG(data+encoding_record+4); + break; + } + break; + case STBTT_PLATFORM_ID_UNICODE: + // Mac/iOS has these + // all the encodingIDs are unicode, so we don't bother to check it + info->index_map = cmap + ttULONG(data+encoding_record+4); + break; + } + } + if (info->index_map == 0) + return 0; + + info->indexToLocFormat = ttUSHORT(data+info->head + 50); + return 1; +} + +STBTT_DEF int stbtt_FindGlyphIndex(const stbtt_fontinfo *info, int unicode_codepoint) +{ + stbtt_uint8 *data = info->data; + stbtt_uint32 index_map = info->index_map; + + stbtt_uint16 format = ttUSHORT(data + index_map + 0); + if (format == 0) { // apple byte encoding + stbtt_int32 bytes = ttUSHORT(data + index_map + 2); + if (unicode_codepoint < bytes-6) + return ttBYTE(data + index_map + 6 + unicode_codepoint); + return 0; + } else if (format == 6) { + stbtt_uint32 first = ttUSHORT(data + index_map + 6); + stbtt_uint32 count = ttUSHORT(data + index_map + 8); + if ((stbtt_uint32) unicode_codepoint >= first && (stbtt_uint32) unicode_codepoint < first+count) + return ttUSHORT(data + index_map + 10 + (unicode_codepoint - first)*2); + return 0; + } else if (format == 2) { + STBTT_assert(0); // @TODO: high-byte mapping for japanese/chinese/korean + return 0; + } else if (format == 4) { // standard mapping for windows fonts: binary search collection of ranges + stbtt_uint16 segcount = ttUSHORT(data+index_map+6) >> 1; + stbtt_uint16 searchRange = ttUSHORT(data+index_map+8) >> 1; + stbtt_uint16 entrySelector = ttUSHORT(data+index_map+10); + stbtt_uint16 rangeShift = ttUSHORT(data+index_map+12) >> 1; + + // do a binary search of the segments + stbtt_uint32 endCount = index_map + 14; + stbtt_uint32 search = endCount; + + if (unicode_codepoint > 0xffff) + return 0; + + // they lie from endCount .. endCount + segCount + // but searchRange is the nearest power of two, so... + if (unicode_codepoint >= ttUSHORT(data + search + rangeShift*2)) + search += rangeShift*2; + + // now decrement to bias correctly to find smallest + search -= 2; + while (entrySelector) { + stbtt_uint16 end; + searchRange >>= 1; + end = ttUSHORT(data + search + searchRange*2); + if (unicode_codepoint > end) + search += searchRange*2; + --entrySelector; + } + search += 2; + + { + stbtt_uint16 offset, start; + stbtt_uint16 item = (stbtt_uint16) ((search - endCount) >> 1); + + STBTT_assert(unicode_codepoint <= ttUSHORT(data + endCount + 2*item)); + start = ttUSHORT(data + index_map + 14 + segcount*2 + 2 + 2*item); + if (unicode_codepoint < start) + return 0; + + offset = ttUSHORT(data + index_map + 14 + segcount*6 + 2 + 2*item); + if (offset == 0) + return (stbtt_uint16) (unicode_codepoint + ttSHORT(data + index_map + 14 + segcount*4 + 2 + 2*item)); + + return ttUSHORT(data + offset + (unicode_codepoint-start)*2 + index_map + 14 + segcount*6 + 2 + 2*item); + } + } else if (format == 12 || format == 13) { + stbtt_uint32 ngroups = ttULONG(data+index_map+12); + stbtt_int32 low,high; + low = 0; high = (stbtt_int32)ngroups; + // Binary search the right group. + while (low < high) { + stbtt_int32 mid = low + ((high-low) >> 1); // rounds down, so low <= mid < high + stbtt_uint32 start_char = ttULONG(data+index_map+16+mid*12); + stbtt_uint32 end_char = ttULONG(data+index_map+16+mid*12+4); + if ((stbtt_uint32) unicode_codepoint < start_char) + high = mid; + else if ((stbtt_uint32) unicode_codepoint > end_char) + low = mid+1; + else { + stbtt_uint32 start_glyph = ttULONG(data+index_map+16+mid*12+8); + if (format == 12) + return start_glyph + unicode_codepoint-start_char; + else // format == 13 + return start_glyph; + } + } + return 0; // not found + } + // @TODO + STBTT_assert(0); + return 0; +} + +STBTT_DEF int stbtt_GetCodepointShape(const stbtt_fontinfo *info, int unicode_codepoint, stbtt_vertex **vertices) +{ + return stbtt_GetGlyphShape(info, stbtt_FindGlyphIndex(info, unicode_codepoint), vertices); +} + +static void stbtt_setvertex(stbtt_vertex *v, stbtt_uint8 type, stbtt_int32 x, stbtt_int32 y, stbtt_int32 cx, stbtt_int32 cy) +{ + v->type = type; + v->x = (stbtt_int16) x; + v->y = (stbtt_int16) y; + v->cx = (stbtt_int16) cx; + v->cy = (stbtt_int16) cy; +} + +static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) +{ + int g1,g2; + + if (glyph_index >= info->numGlyphs) return -1; // glyph index out of range + if (info->indexToLocFormat >= 2) return -1; // unknown index->glyph map format + + if (info->indexToLocFormat == 0) { + g1 = info->glyf + ttUSHORT(info->data + info->loca + glyph_index * 2) * 2; + g2 = info->glyf + ttUSHORT(info->data + info->loca + glyph_index * 2 + 2) * 2; + } else { + g1 = info->glyf + ttULONG (info->data + info->loca + glyph_index * 4); + g2 = info->glyf + ttULONG (info->data + info->loca + glyph_index * 4 + 4); + } + + return g1==g2 ? -1 : g1; // if length is 0, return -1 +} + +STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) +{ + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 0; + + if (x0) *x0 = ttSHORT(info->data + g + 2); + if (y0) *y0 = ttSHORT(info->data + g + 4); + if (x1) *x1 = ttSHORT(info->data + g + 6); + if (y1) *y1 = ttSHORT(info->data + g + 8); + return 1; +} + +STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, int *x0, int *y0, int *x1, int *y1) +{ + return stbtt_GetGlyphBox(info, stbtt_FindGlyphIndex(info,codepoint), x0,y0,x1,y1); +} + +STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index) +{ + stbtt_int16 numberOfContours; + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 1; + numberOfContours = ttSHORT(info->data + g); + return numberOfContours == 0; +} + +static int stbtt__close_shape(stbtt_vertex *vertices, int num_vertices, int was_off, int start_off, + stbtt_int32 sx, stbtt_int32 sy, stbtt_int32 scx, stbtt_int32 scy, stbtt_int32 cx, stbtt_int32 cy) +{ + if (start_off) { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, (cx+scx)>>1, (cy+scy)>>1, cx,cy); + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, sx,sy,scx,scy); + } else { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve,sx,sy,cx,cy); + else + stbtt_setvertex(&vertices[num_vertices++], STBTT_vline,sx,sy,0,0); + } + return num_vertices; +} + +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + stbtt_int16 numberOfContours; + stbtt_uint8 *endPtsOfContours; + stbtt_uint8 *data = info->data; + stbtt_vertex *vertices=0; + int num_vertices=0; + int g = stbtt__GetGlyfOffset(info, glyph_index); + + *pvertices = NULL; + + if (g < 0) return 0; + + numberOfContours = ttSHORT(data + g); + + if (numberOfContours > 0) { + stbtt_uint8 flags=0,flagcount; + stbtt_int32 ins, i,j=0,m,n, next_move, was_off=0, off, start_off=0; + stbtt_int32 x,y,cx,cy,sx,sy, scx,scy; + stbtt_uint8 *points; + endPtsOfContours = (data + g + 10); + ins = ttUSHORT(data + g + 10 + numberOfContours * 2); + points = data + g + 10 + numberOfContours * 2 + 2 + ins; + + n = 1+ttUSHORT(endPtsOfContours + numberOfContours*2-2); + + m = n + 2*numberOfContours; // a loose bound on how many vertices we might need + vertices = (stbtt_vertex *) STBTT_malloc(m * sizeof(vertices[0]), info->userdata); + if (vertices == 0) + return 0; + + next_move = 0; + flagcount=0; + + // in first pass, we load uninterpreted data into the allocated array + // above, shifted to the end of the array so we won't overwrite it when + // we create our final data starting from the front + + off = m - n; // starting offset for uninterpreted data, regardless of how m ends up being calculated + + // first load flags + + for (i=0; i < n; ++i) { + if (flagcount == 0) { + flags = *points++; + if (flags & 8) + flagcount = *points++; + } else + --flagcount; + vertices[off+i].type = flags; + } + + // now load x coordinates + x=0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + if (flags & 2) { + stbtt_int16 dx = *points++; + x += (flags & 16) ? dx : -dx; // ??? + } else { + if (!(flags & 16)) { + x = x + (stbtt_int16) (points[0]*256 + points[1]); + points += 2; + } + } + vertices[off+i].x = (stbtt_int16) x; + } + + // now load y coordinates + y=0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + if (flags & 4) { + stbtt_int16 dy = *points++; + y += (flags & 32) ? dy : -dy; // ??? + } else { + if (!(flags & 32)) { + y = y + (stbtt_int16) (points[0]*256 + points[1]); + points += 2; + } + } + vertices[off+i].y = (stbtt_int16) y; + } + + // now convert them to our format + num_vertices=0; + sx = sy = cx = cy = scx = scy = 0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + x = (stbtt_int16) vertices[off+i].x; + y = (stbtt_int16) vertices[off+i].y; + + if (next_move == i) { + if (i != 0) + num_vertices = stbtt__close_shape(vertices, num_vertices, was_off, start_off, sx,sy,scx,scy,cx,cy); + + // now start the new one + start_off = !(flags & 1); + if (start_off) { + // if we start off with an off-curve point, then when we need to find a point on the curve + // where we can start, and we need to save some state for when we wraparound. + scx = x; + scy = y; + if (!(vertices[off+i+1].type & 1)) { + // next point is also a curve point, so interpolate an on-point curve + sx = (x + (stbtt_int32) vertices[off+i+1].x) >> 1; + sy = (y + (stbtt_int32) vertices[off+i+1].y) >> 1; + } else { + // otherwise just use the next point as our start point + sx = (stbtt_int32) vertices[off+i+1].x; + sy = (stbtt_int32) vertices[off+i+1].y; + ++i; // we're using point i+1 as the starting point, so skip it + } + } else { + sx = x; + sy = y; + } + stbtt_setvertex(&vertices[num_vertices++], STBTT_vmove,sx,sy,0,0); + was_off = 0; + next_move = 1 + ttUSHORT(endPtsOfContours+j*2); + ++j; + } else { + if (!(flags & 1)) { // if it's a curve + if (was_off) // two off-curve control points in a row means interpolate an on-curve midpoint + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, (cx+x)>>1, (cy+y)>>1, cx, cy); + cx = x; + cy = y; + was_off = 1; + } else { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, x,y, cx, cy); + else + stbtt_setvertex(&vertices[num_vertices++], STBTT_vline, x,y,0,0); + was_off = 0; + } + } + } + num_vertices = stbtt__close_shape(vertices, num_vertices, was_off, start_off, sx,sy,scx,scy,cx,cy); + } else if (numberOfContours == -1) { + // Compound shapes. + int more = 1; + stbtt_uint8 *comp = data + g + 10; + num_vertices = 0; + vertices = 0; + while (more) { + stbtt_uint16 flags, gidx; + int comp_num_verts = 0, i; + stbtt_vertex *comp_verts = 0, *tmp = 0; + float mtx[6] = {1,0,0,1,0,0}, m, n; + + flags = ttSHORT(comp); comp+=2; + gidx = ttSHORT(comp); comp+=2; + + if (flags & 2) { // XY values + if (flags & 1) { // shorts + mtx[4] = ttSHORT(comp); comp+=2; + mtx[5] = ttSHORT(comp); comp+=2; + } else { + mtx[4] = ttCHAR(comp); comp+=1; + mtx[5] = ttCHAR(comp); comp+=1; + } + } + else { + // @TODO handle matching point + STBTT_assert(0); + } + if (flags & (1<<3)) { // WE_HAVE_A_SCALE + mtx[0] = mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = mtx[2] = 0; + } else if (flags & (1<<6)) { // WE_HAVE_AN_X_AND_YSCALE + mtx[0] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = mtx[2] = 0; + mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + } else if (flags & (1<<7)) { // WE_HAVE_A_TWO_BY_TWO + mtx[0] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[2] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + } + + // Find transformation scales. + m = (float) STBTT_sqrt(mtx[0]*mtx[0] + mtx[1]*mtx[1]); + n = (float) STBTT_sqrt(mtx[2]*mtx[2] + mtx[3]*mtx[3]); + + // Get indexed glyph. + comp_num_verts = stbtt_GetGlyphShape(info, gidx, &comp_verts); + if (comp_num_verts > 0) { + // Transform vertices. + for (i = 0; i < comp_num_verts; ++i) { + stbtt_vertex* v = &comp_verts[i]; + stbtt_vertex_type x,y; + x=v->x; y=v->y; + v->x = (stbtt_vertex_type)(m * (mtx[0]*x + mtx[2]*y + mtx[4])); + v->y = (stbtt_vertex_type)(n * (mtx[1]*x + mtx[3]*y + mtx[5])); + x=v->cx; y=v->cy; + v->cx = (stbtt_vertex_type)(m * (mtx[0]*x + mtx[2]*y + mtx[4])); + v->cy = (stbtt_vertex_type)(n * (mtx[1]*x + mtx[3]*y + mtx[5])); + } + // Append vertices. + tmp = (stbtt_vertex*)STBTT_malloc((num_vertices+comp_num_verts)*sizeof(stbtt_vertex), info->userdata); + if (!tmp) { + if (vertices) STBTT_free(vertices, info->userdata); + if (comp_verts) STBTT_free(comp_verts, info->userdata); + return 0; + } + if (num_vertices > 0) STBTT_memcpy(tmp, vertices, num_vertices*sizeof(stbtt_vertex)); + STBTT_memcpy(tmp+num_vertices, comp_verts, comp_num_verts*sizeof(stbtt_vertex)); + if (vertices) STBTT_free(vertices, info->userdata); + vertices = tmp; + STBTT_free(comp_verts, info->userdata); + num_vertices += comp_num_verts; + } + // More components ? + more = flags & (1<<5); + } + } else if (numberOfContours < 0) { + // @TODO other compound variations? + STBTT_assert(0); + } else { + // numberOfCounters == 0, do nothing + } + + *pvertices = vertices; + return num_vertices; +} + +STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing) +{ + stbtt_uint16 numOfLongHorMetrics = ttUSHORT(info->data+info->hhea + 34); + if (glyph_index < numOfLongHorMetrics) { + if (advanceWidth) *advanceWidth = ttSHORT(info->data + info->hmtx + 4*glyph_index); + if (leftSideBearing) *leftSideBearing = ttSHORT(info->data + info->hmtx + 4*glyph_index + 2); + } else { + if (advanceWidth) *advanceWidth = ttSHORT(info->data + info->hmtx + 4*(numOfLongHorMetrics-1)); + if (leftSideBearing) *leftSideBearing = ttSHORT(info->data + info->hmtx + 4*numOfLongHorMetrics + 2*(glyph_index - numOfLongHorMetrics)); + } +} + +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +{ + stbtt_uint8 *data = info->data + info->kern; + stbtt_uint32 needle, straw; + int l, r, m; + + // we only look at the first table. it must be 'horizontal' and format 0. + if (!info->kern) + return 0; + if (ttUSHORT(data+2) < 1) // number of tables, need at least 1 + return 0; + if (ttUSHORT(data+8) != 1) // horizontal flag must be set in format + return 0; + + l = 0; + r = ttUSHORT(data+10) - 1; + needle = glyph1 << 16 | glyph2; + while (l <= r) { + m = (l + r) >> 1; + straw = ttULONG(data+18+(m*6)); // note: unaligned read + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else + return ttSHORT(data+22+(m*6)); + } + return 0; +} + +STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2) +{ + if (!info->kern) // if no kerning table, don't waste time looking up both codepoint->glyphs + return 0; + return stbtt_GetGlyphKernAdvance(info, stbtt_FindGlyphIndex(info,ch1), stbtt_FindGlyphIndex(info,ch2)); +} + +STBTT_DEF void stbtt_GetCodepointHMetrics(const stbtt_fontinfo *info, int codepoint, int *advanceWidth, int *leftSideBearing) +{ + stbtt_GetGlyphHMetrics(info, stbtt_FindGlyphIndex(info,codepoint), advanceWidth, leftSideBearing); +} + +STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, int *descent, int *lineGap) +{ + if (ascent ) *ascent = ttSHORT(info->data+info->hhea + 4); + if (descent) *descent = ttSHORT(info->data+info->hhea + 6); + if (lineGap) *lineGap = ttSHORT(info->data+info->hhea + 8); +} + +STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1) +{ + *x0 = ttSHORT(info->data + info->head + 36); + *y0 = ttSHORT(info->data + info->head + 38); + *x1 = ttSHORT(info->data + info->head + 40); + *y1 = ttSHORT(info->data + info->head + 42); +} + +STBTT_DEF float stbtt_ScaleForPixelHeight(const stbtt_fontinfo *info, float height) +{ + int fheight = ttSHORT(info->data + info->hhea + 4) - ttSHORT(info->data + info->hhea + 6); + return (float) height / fheight; +} + +STBTT_DEF float stbtt_ScaleForMappingEmToPixels(const stbtt_fontinfo *info, float pixels) +{ + int unitsPerEm = ttUSHORT(info->data + info->head + 18); + return pixels / unitsPerEm; +} + +STBTT_DEF void stbtt_FreeShape(const stbtt_fontinfo *info, stbtt_vertex *v) +{ + STBTT_free(v, info->userdata); +} + +////////////////////////////////////////////////////////////////////////////// +// +// antialiasing software rasterizer +// + +STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + int x0=0,y0=0,x1,y1; // =0 suppresses compiler warning + if (!stbtt_GetGlyphBox(font, glyph, &x0,&y0,&x1,&y1)) { + // e.g. space character + if (ix0) *ix0 = 0; + if (iy0) *iy0 = 0; + if (ix1) *ix1 = 0; + if (iy1) *iy1 = 0; + } else { + // move to integral bboxes (treating pixels as little squares, what pixels get touched)? + if (ix0) *ix0 = STBTT_ifloor( x0 * scale_x + shift_x); + if (iy0) *iy0 = STBTT_ifloor(-y1 * scale_y + shift_y); + if (ix1) *ix1 = STBTT_iceil ( x1 * scale_x + shift_x); + if (iy1) *iy1 = STBTT_iceil (-y0 * scale_y + shift_y); + } +} + +STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetGlyphBitmapBoxSubpixel(font, glyph, scale_x, scale_y,0.0f,0.0f, ix0, iy0, ix1, iy1); +} + +STBTT_DEF void stbtt_GetCodepointBitmapBoxSubpixel(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetGlyphBitmapBoxSubpixel(font, stbtt_FindGlyphIndex(font,codepoint), scale_x, scale_y,shift_x,shift_y, ix0,iy0,ix1,iy1); +} + +STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetCodepointBitmapBoxSubpixel(font, codepoint, scale_x, scale_y,0.0f,0.0f, ix0,iy0,ix1,iy1); +} + +////////////////////////////////////////////////////////////////////////////// +// +// Rasterizer + +typedef struct stbtt__hheap_chunk +{ + struct stbtt__hheap_chunk *next; +} stbtt__hheap_chunk; + +typedef struct stbtt__hheap +{ + struct stbtt__hheap_chunk *head; + void *first_free; + int num_remaining_in_head_chunk; +} stbtt__hheap; + +static void *stbtt__hheap_alloc(stbtt__hheap *hh, size_t size, void *userdata) +{ + if (hh->first_free) { + void *p = hh->first_free; + hh->first_free = * (void **) p; + return p; + } else { + if (hh->num_remaining_in_head_chunk == 0) { + int count = (size < 32 ? 2000 : size < 128 ? 800 : 100); + stbtt__hheap_chunk *c = (stbtt__hheap_chunk *) STBTT_malloc(sizeof(stbtt__hheap_chunk) + size * count, userdata); + if (c == NULL) + return NULL; + c->next = hh->head; + hh->head = c; + hh->num_remaining_in_head_chunk = count; + } + --hh->num_remaining_in_head_chunk; + return (char *) (hh->head) + size * hh->num_remaining_in_head_chunk; + } +} + +static void stbtt__hheap_free(stbtt__hheap *hh, void *p) +{ + *(void **) p = hh->first_free; + hh->first_free = p; +} + +static void stbtt__hheap_cleanup(stbtt__hheap *hh, void *userdata) +{ + stbtt__hheap_chunk *c = hh->head; + while (c) { + stbtt__hheap_chunk *n = c->next; + STBTT_free(c, userdata); + c = n; + } +} + +typedef struct stbtt__edge { + float x0,y0, x1,y1; + int invert; +} stbtt__edge; + + +typedef struct stbtt__active_edge +{ + struct stbtt__active_edge *next; + #if STBTT_RASTERIZER_VERSION==1 + int x,dx; + float ey; + int direction; + #elif STBTT_RASTERIZER_VERSION==2 + float fx,fdx,fdy; + float direction; + float sy; + float ey; + #else + #error "Unrecognized value of STBTT_RASTERIZER_VERSION" + #endif +} stbtt__active_edge; + +#if STBTT_RASTERIZER_VERSION == 1 +#define STBTT_FIXSHIFT 10 +#define STBTT_FIX (1 << STBTT_FIXSHIFT) +#define STBTT_FIXMASK (STBTT_FIX-1) + +static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, int off_x, float start_point, void *userdata) +{ + stbtt__active_edge *z = (stbtt__active_edge *) stbtt__hheap_alloc(hh, sizeof(*z), userdata); + float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); + STBTT_assert(z != NULL); + if (!z) return z; + + // round dx down to avoid overshooting + if (dxdy < 0) + z->dx = -STBTT_ifloor(STBTT_FIX * -dxdy); + else + z->dx = STBTT_ifloor(STBTT_FIX * dxdy); + + z->x = STBTT_ifloor(STBTT_FIX * e->x0 + z->dx * (start_point - e->y0)); // use z->dx so when we offset later it's by the same amount + z->x -= off_x * STBTT_FIX; + + z->ey = e->y1; + z->next = 0; + z->direction = e->invert ? 1 : -1; + return z; +} +#elif STBTT_RASTERIZER_VERSION == 2 +static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, int off_x, float start_point, void *userdata) +{ + stbtt__active_edge *z = (stbtt__active_edge *) stbtt__hheap_alloc(hh, sizeof(*z), userdata); + float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); + STBTT_assert(z != NULL); + //STBTT_assert(e->y0 <= start_point); + if (!z) return z; + z->fdx = dxdy; + z->fdy = dxdy != 0.0f ? (1.0f/dxdy) : 0.0f; + z->fx = e->x0 + dxdy * (start_point - e->y0); + z->fx -= off_x; + z->direction = e->invert ? 1.0f : -1.0f; + z->sy = e->y0; + z->ey = e->y1; + z->next = 0; + return z; +} +#else +#error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + +#if STBTT_RASTERIZER_VERSION == 1 +// note: this routine clips fills that extend off the edges... ideally this +// wouldn't happen, but it could happen if the truetype glyph bounding boxes +// are wrong, or if the user supplies a too-small bitmap +static void stbtt__fill_active_edges(unsigned char *scanline, int len, stbtt__active_edge *e, int max_weight) +{ + // non-zero winding fill + int x0=0, w=0; + + while (e) { + if (w == 0) { + // if we're currently at zero, we need to record the edge start point + x0 = e->x; w += e->direction; + } else { + int x1 = e->x; w += e->direction; + // if we went to zero, we need to draw + if (w == 0) { + int i = x0 >> STBTT_FIXSHIFT; + int j = x1 >> STBTT_FIXSHIFT; + + if (i < len && j >= 0) { + if (i == j) { + // x0,x1 are the same pixel, so compute combined coverage + scanline[i] = scanline[i] + (stbtt_uint8) ((x1 - x0) * max_weight >> STBTT_FIXSHIFT); + } else { + if (i >= 0) // add antialiasing for x0 + scanline[i] = scanline[i] + (stbtt_uint8) (((STBTT_FIX - (x0 & STBTT_FIXMASK)) * max_weight) >> STBTT_FIXSHIFT); + else + i = -1; // clip + + if (j < len) // add antialiasing for x1 + scanline[j] = scanline[j] + (stbtt_uint8) (((x1 & STBTT_FIXMASK) * max_weight) >> STBTT_FIXSHIFT); + else + j = len; // clip + + for (++i; i < j; ++i) // fill pixels between x0 and x1 + scanline[i] = scanline[i] + (stbtt_uint8) max_weight; + } + } + } + } + + e = e->next; + } +} + +static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) +{ + stbtt__hheap hh = { 0, 0, 0 }; + stbtt__active_edge *active = NULL; + int y,j=0; + int max_weight = (255 / vsubsample); // weight per vertical scanline + int s; // vertical subsample index + unsigned char scanline_data[512], *scanline; + + if (result->w > 512) + scanline = (unsigned char *) STBTT_malloc(result->w, userdata); + else + scanline = scanline_data; + + y = off_y * vsubsample; + e[n].y0 = (off_y + result->h) * (float) vsubsample + 1; + + while (j < result->h) { + STBTT_memset(scanline, 0, result->w); + for (s=0; s < vsubsample; ++s) { + // find center of pixel for this scanline + float scan_y = y + 0.5f; + stbtt__active_edge **step = &active; + + // update all active edges; + // remove all active edges that terminate before the center of this scanline + while (*step) { + stbtt__active_edge * z = *step; + if (z->ey <= scan_y) { + *step = z->next; // delete from list + STBTT_assert(z->direction); + z->direction = 0; + stbtt__hheap_free(&hh, z); + } else { + z->x += z->dx; // advance to position for current scanline + step = &((*step)->next); // advance through list + } + } + + // resort the list if needed + for(;;) { + int changed=0; + step = &active; + while (*step && (*step)->next) { + if ((*step)->x > (*step)->next->x) { + stbtt__active_edge *t = *step; + stbtt__active_edge *q = t->next; + + t->next = q->next; + q->next = t; + *step = q; + changed = 1; + } + step = &(*step)->next; + } + if (!changed) break; + } + + // insert all edges that start before the center of this scanline -- omit ones that also end on this scanline + while (e->y0 <= scan_y) { + if (e->y1 > scan_y) { + stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y, userdata); + if (z != NULL) { + // find insertion point + if (active == NULL) + active = z; + else if (z->x < active->x) { + // insert at front + z->next = active; + active = z; + } else { + // find thing to insert AFTER + stbtt__active_edge *p = active; + while (p->next && p->next->x < z->x) + p = p->next; + // at this point, p->next->x is NOT < z->x + z->next = p->next; + p->next = z; + } + } + } + ++e; + } + + // now process all active edges in XOR fashion + if (active) + stbtt__fill_active_edges(scanline, result->w, active, max_weight); + + ++y; + } + STBTT_memcpy(result->pixels + j * result->stride, scanline, result->w); + ++j; + } + + stbtt__hheap_cleanup(&hh, userdata); + + if (scanline != scanline_data) + STBTT_free(scanline, userdata); +} + +#elif STBTT_RASTERIZER_VERSION == 2 + +// the edge passed in here does not cross the vertical line at x or the vertical line at x+1 +// (i.e. it has already been clipped to those) +static void stbtt__handle_clipped_edge(float *scanline, int x, stbtt__active_edge *e, float x0, float y0, float x1, float y1) +{ + if (y0 == y1) return; + STBTT_assert(y0 < y1); + STBTT_assert(e->sy <= e->ey); + if (y0 > e->ey) return; + if (y1 < e->sy) return; + if (y0 < e->sy) { + x0 += (x1-x0) * (e->sy - y0) / (y1-y0); + y0 = e->sy; + } + if (y1 > e->ey) { + x1 += (x1-x0) * (e->ey - y1) / (y1-y0); + y1 = e->ey; + } + + if (x0 == x) + STBTT_assert(x1 <= x+1); + else if (x0 == x+1) + STBTT_assert(x1 >= x); + else if (x0 <= x) + STBTT_assert(x1 <= x); + else if (x0 >= x+1) + STBTT_assert(x1 >= x+1); + else + STBTT_assert(x1 >= x && x1 <= x+1); + + if (x0 <= x && x1 <= x) + scanline[x] += e->direction * (y1-y0); + else if (x0 >= x+1 && x1 >= x+1) + ; + else { + STBTT_assert(x0 >= x && x0 <= x+1 && x1 >= x && x1 <= x+1); + scanline[x] += e->direction * (y1-y0) * (1-((x0-x)+(x1-x))/2); // coverage = 1 - average x position + } +} + +static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, int len, stbtt__active_edge *e, float y_top) +{ + float y_bottom = y_top+1; + + while (e) { + // brute force every pixel + + // compute intersection points with top & bottom + STBTT_assert(e->ey >= y_top); + + if (e->fdx == 0) { + float x0 = e->fx; + if (x0 < len) { + if (x0 >= 0) { + stbtt__handle_clipped_edge(scanline,(int) x0,e, x0,y_top, x0,y_bottom); + stbtt__handle_clipped_edge(scanline_fill-1,(int) x0+1,e, x0,y_top, x0,y_bottom); + } else { + stbtt__handle_clipped_edge(scanline_fill-1,0,e, x0,y_top, x0,y_bottom); + } + } + } else { + float x0 = e->fx; + float dx = e->fdx; + float xb = x0 + dx; + float x_top, x_bottom; + float sy0,sy1; + float dy = e->fdy; + STBTT_assert(e->sy <= y_bottom && e->ey >= y_top); + + // compute endpoints of line segment clipped to this scanline (if the + // line segment starts on this scanline. x0 is the intersection of the + // line with y_top, but that may be off the line segment. + if (e->sy > y_top) { + x_top = x0 + dx * (e->sy - y_top); + sy0 = e->sy; + } else { + x_top = x0; + sy0 = y_top; + } + if (e->ey < y_bottom) { + x_bottom = x0 + dx * (e->ey - y_top); + sy1 = e->ey; + } else { + x_bottom = xb; + sy1 = y_bottom; + } + + if (x_top >= 0 && x_bottom >= 0 && x_top < len && x_bottom < len) { + // from here on, we don't have to range check x values + + if ((int) x_top == (int) x_bottom) { + float height; + // simple case, only spans one pixel + int x = (int) x_top; + height = sy1 - sy0; + STBTT_assert(x >= 0 && x < len); + scanline[x] += e->direction * (1-((x_top - x) + (x_bottom-x))/2) * height; + scanline_fill[x] += e->direction * height; // everything right of this pixel is filled + } else { + int x,x1,x2; + float y_crossing, step, sign, area; + // covers 2+ pixels + if (x_top > x_bottom) { + // flip scanline vertically; signed area is the same + float t; + sy0 = y_bottom - (sy0 - y_top); + sy1 = y_bottom - (sy1 - y_top); + t = sy0, sy0 = sy1, sy1 = t; + t = x_bottom, x_bottom = x_top, x_top = t; + dx = -dx; + dy = -dy; + t = x0, x0 = xb, xb = t; + } + + x1 = (int) x_top; + x2 = (int) x_bottom; + // compute intersection with y axis at x1+1 + y_crossing = (x1+1 - x0) * dy + y_top; + + sign = e->direction; + // area of the rectangle covered from y0..y_crossing + area = sign * (y_crossing-sy0); + // area of the triangle (x_top,y0), (x+1,y0), (x+1,y_crossing) + scanline[x1] += area * (1-((x_top - x1)+(x1+1-x1))/2); + + step = sign * dy; + for (x = x1+1; x < x2; ++x) { + scanline[x] += area + step/2; + area += step; + } + y_crossing += dy * (x2 - (x1+1)); + + STBTT_assert(fabs(area) <= 1.01f); + + scanline[x2] += area + sign * (1-((x2-x2)+(x_bottom-x2))/2) * (sy1-y_crossing); + + scanline_fill[x2] += sign * (sy1-sy0); + } + } else { + // if edge goes outside of box we're drawing, we require + // clipping logic. since this does not match the intended use + // of this library, we use a different, very slow brute + // force implementation + int x; + for (x=0; x < len; ++x) { + // cases: + // + // there can be up to two intersections with the pixel. any intersection + // with left or right edges can be handled by splitting into two (or three) + // regions. intersections with top & bottom do not necessitate case-wise logic. + // + // the old way of doing this found the intersections with the left & right edges, + // then used some simple logic to produce up to three segments in sorted order + // from top-to-bottom. however, this had a problem: if an x edge was epsilon + // across the x border, then the corresponding y position might not be distinct + // from the other y segment, and it might ignored as an empty segment. to avoid + // that, we need to explicitly produce segments based on x positions. + + // rename variables to clear pairs + float y0 = y_top; + float x1 = (float) (x); + float x2 = (float) (x+1); + float x3 = xb; + float y3 = y_bottom; + float y1,y2; + + // x = e->x + e->dx * (y-y_top) + // (y-y_top) = (x - e->x) / e->dx + // y = (x - e->x) / e->dx + y_top + y1 = (x - x0) / dx + y_top; + y2 = (x+1 - x0) / dx + y_top; + + if (x0 < x1 && x3 > x2) { // three segments descending down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else if (x3 < x1 && x0 > x2) { // three segments descending down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x0 < x1 && x3 > x1) { // two segments across x, down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x3 < x1 && x0 > x1) { // two segments across x, down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x0 < x2 && x3 > x2) { // two segments across x+1, down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else if (x3 < x2 && x0 > x2) { // two segments across x+1, down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else { // one segment + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x3,y3); + } + } + } + } + e = e->next; + } +} + +// directly AA rasterize edges w/o supersampling +static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) +{ + stbtt__hheap hh = { 0, 0, 0 }; + stbtt__active_edge *active = NULL; + int y,j=0, i; + float scanline_data[129], *scanline, *scanline2; + + if (result->w > 64) + scanline = (float *) STBTT_malloc((result->w*2+1) * sizeof(float), userdata); + else + scanline = scanline_data; + + scanline2 = scanline + result->w; + + y = off_y; + e[n].y0 = (float) (off_y + result->h) + 1; + + while (j < result->h) { + // find center of pixel for this scanline + float scan_y_top = y + 0.0f; + float scan_y_bottom = y + 1.0f; + stbtt__active_edge **step = &active; + + STBTT_memset(scanline , 0, result->w*sizeof(scanline[0])); + STBTT_memset(scanline2, 0, (result->w+1)*sizeof(scanline[0])); + + // update all active edges; + // remove all active edges that terminate before the top of this scanline + while (*step) { + stbtt__active_edge * z = *step; + if (z->ey <= scan_y_top) { + *step = z->next; // delete from list + STBTT_assert(z->direction); + z->direction = 0; + stbtt__hheap_free(&hh, z); + } else { + step = &((*step)->next); // advance through list + } + } + + // insert all edges that start before the bottom of this scanline + while (e->y0 <= scan_y_bottom) { + if (e->y0 != e->y1) { + stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y_top, userdata); + if (z != NULL) { + STBTT_assert(z->ey >= scan_y_top); + // insert at front + z->next = active; + active = z; + } + } + ++e; + } + + // now process all active edges + if (active) + stbtt__fill_active_edges_new(scanline, scanline2+1, result->w, active, scan_y_top); + + { + float sum = 0; + for (i=0; i < result->w; ++i) { + float k; + int m; + sum += scanline2[i]; + k = scanline[i] + sum; + k = (float) fabs(k)*255 + 0.5f; + m = (int) k; + if (m > 255) m = 255; + result->pixels[j*result->stride + i] = (unsigned char) m; + } + } + // advance all the edges + step = &active; + while (*step) { + stbtt__active_edge *z = *step; + z->fx += z->fdx; // advance to position for current scanline + step = &((*step)->next); // advance through list + } + + ++y; + ++j; + } + + stbtt__hheap_cleanup(&hh, userdata); + + if (scanline != scanline_data) + STBTT_free(scanline, userdata); +} +#else +#error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + +#define STBTT__COMPARE(a,b) ((a)->y0 < (b)->y0) + +static void stbtt__sort_edges_ins_sort(stbtt__edge *p, int n) +{ + int i,j; + for (i=1; i < n; ++i) { + stbtt__edge t = p[i], *a = &t; + j = i; + while (j > 0) { + stbtt__edge *b = &p[j-1]; + int c = STBTT__COMPARE(a,b); + if (!c) break; + p[j] = p[j-1]; + --j; + } + if (i != j) + p[j] = t; + } +} + +static void stbtt__sort_edges_quicksort(stbtt__edge *p, int n) +{ + /* threshhold for transitioning to insertion sort */ + while (n > 12) { + stbtt__edge t; + int c01,c12,c,m,i,j; + + /* compute median of three */ + m = n >> 1; + c01 = STBTT__COMPARE(&p[0],&p[m]); + c12 = STBTT__COMPARE(&p[m],&p[n-1]); + /* if 0 >= mid >= end, or 0 < mid < end, then use mid */ + if (c01 != c12) { + /* otherwise, we'll need to swap something else to middle */ + int z; + c = STBTT__COMPARE(&p[0],&p[n-1]); + /* 0>mid && midn => n; 0 0 */ + /* 0n: 0>n => 0; 0 n */ + z = (c == c12) ? 0 : n-1; + t = p[z]; + p[z] = p[m]; + p[m] = t; + } + /* now p[m] is the median-of-three */ + /* swap it to the beginning so it won't move around */ + t = p[0]; + p[0] = p[m]; + p[m] = t; + + /* partition loop */ + i=1; + j=n-1; + for(;;) { + /* handling of equality is crucial here */ + /* for sentinels & efficiency with duplicates */ + for (;;++i) { + if (!STBTT__COMPARE(&p[i], &p[0])) break; + } + for (;;--j) { + if (!STBTT__COMPARE(&p[0], &p[j])) break; + } + /* make sure we haven't crossed */ + if (i >= j) break; + t = p[i]; + p[i] = p[j]; + p[j] = t; + + ++i; + --j; + } + /* recurse on smaller side, iterate on larger */ + if (j < (n-i)) { + stbtt__sort_edges_quicksort(p,j); + p = p+i; + n = n-i; + } else { + stbtt__sort_edges_quicksort(p+i, n-i); + n = j; + } + } +} + +static void stbtt__sort_edges(stbtt__edge *p, int n) +{ + stbtt__sort_edges_quicksort(p, n); + stbtt__sort_edges_ins_sort(p, n); +} + +typedef struct +{ + float x,y; +} stbtt__point; + +static void stbtt__rasterize(stbtt__bitmap *result, stbtt__point *pts, int *wcount, int windings, float scale_x, float scale_y, float shift_x, float shift_y, int off_x, int off_y, int invert, void *userdata) +{ + float y_scale_inv = invert ? -scale_y : scale_y; + stbtt__edge *e; + int n,i,j,k,m; +#if STBTT_RASTERIZER_VERSION == 1 + int vsubsample = result->h < 8 ? 15 : 5; +#elif STBTT_RASTERIZER_VERSION == 2 + int vsubsample = 1; +#else + #error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + // vsubsample should divide 255 evenly; otherwise we won't reach full opacity + + // now we have to blow out the windings into explicit edge lists + n = 0; + for (i=0; i < windings; ++i) + n += wcount[i]; + + e = (stbtt__edge *) STBTT_malloc(sizeof(*e) * (n+1), userdata); // add an extra one as a sentinel + if (e == 0) return; + n = 0; + + m=0; + for (i=0; i < windings; ++i) { + stbtt__point *p = pts + m; + m += wcount[i]; + j = wcount[i]-1; + for (k=0; k < wcount[i]; j=k++) { + int a=k,b=j; + // skip the edge if horizontal + if (p[j].y == p[k].y) + continue; + // add edge from j to k to the list + e[n].invert = 0; + if (invert ? p[j].y > p[k].y : p[j].y < p[k].y) { + e[n].invert = 1; + a=j,b=k; + } + e[n].x0 = p[a].x * scale_x + shift_x; + e[n].y0 = (p[a].y * y_scale_inv + shift_y) * vsubsample; + e[n].x1 = p[b].x * scale_x + shift_x; + e[n].y1 = (p[b].y * y_scale_inv + shift_y) * vsubsample; + ++n; + } + } + + // now sort the edges by their highest point (should snap to integer, and then by x) + //STBTT_sort(e, n, sizeof(e[0]), stbtt__edge_compare); + stbtt__sort_edges(e, n); + + // now, traverse the scanlines and find the intersections on each scanline, use xor winding rule + stbtt__rasterize_sorted_edges(result, e, n, vsubsample, off_x, off_y, userdata); + + STBTT_free(e, userdata); +} + +static void stbtt__add_point(stbtt__point *points, int n, float x, float y) +{ + if (!points) return; // during first pass, it's unallocated + points[n].x = x; + points[n].y = y; +} + +// tesselate until threshhold p is happy... @TODO warped to compensate for non-linear stretching +static int stbtt__tesselate_curve(stbtt__point *points, int *num_points, float x0, float y0, float x1, float y1, float x2, float y2, float objspace_flatness_squared, int n) +{ + // midpoint + float mx = (x0 + 2*x1 + x2)/4; + float my = (y0 + 2*y1 + y2)/4; + // versus directly drawn line + float dx = (x0+x2)/2 - mx; + float dy = (y0+y2)/2 - my; + if (n > 16) // 65536 segments on one curve better be enough! + return 1; + if (dx*dx+dy*dy > objspace_flatness_squared) { // half-pixel error allowed... need to be smaller if AA + stbtt__tesselate_curve(points, num_points, x0,y0, (x0+x1)/2.0f,(y0+y1)/2.0f, mx,my, objspace_flatness_squared,n+1); + stbtt__tesselate_curve(points, num_points, mx,my, (x1+x2)/2.0f,(y1+y2)/2.0f, x2,y2, objspace_flatness_squared,n+1); + } else { + stbtt__add_point(points, *num_points,x2,y2); + *num_points = *num_points+1; + } + return 1; +} + +// returns number of contours +static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, float objspace_flatness, int **contour_lengths, int *num_contours, void *userdata) +{ + stbtt__point *points=0; + int num_points=0; + + float objspace_flatness_squared = objspace_flatness * objspace_flatness; + int i,n=0,start=0, pass; + + // count how many "moves" there are to get the contour count + for (i=0; i < num_verts; ++i) + if (vertices[i].type == STBTT_vmove) + ++n; + + *num_contours = n; + if (n == 0) return 0; + + *contour_lengths = (int *) STBTT_malloc(sizeof(**contour_lengths) * n, userdata); + + if (*contour_lengths == 0) { + *num_contours = 0; + return 0; + } + + // make two passes through the points so we don't need to realloc + for (pass=0; pass < 2; ++pass) { + float x=0,y=0; + if (pass == 1) { + points = (stbtt__point *) STBTT_malloc(num_points * sizeof(points[0]), userdata); + if (points == NULL) goto error; + } + num_points = 0; + n= -1; + for (i=0; i < num_verts; ++i) { + switch (vertices[i].type) { + case STBTT_vmove: + // start the next contour + if (n >= 0) + (*contour_lengths)[n] = num_points - start; + ++n; + start = num_points; + + x = vertices[i].x, y = vertices[i].y; + stbtt__add_point(points, num_points++, x,y); + break; + case STBTT_vline: + x = vertices[i].x, y = vertices[i].y; + stbtt__add_point(points, num_points++, x, y); + break; + case STBTT_vcurve: + stbtt__tesselate_curve(points, &num_points, x,y, + vertices[i].cx, vertices[i].cy, + vertices[i].x, vertices[i].y, + objspace_flatness_squared, 0); + x = vertices[i].x, y = vertices[i].y; + break; + } + } + (*contour_lengths)[n] = num_points - start; + } + + return points; +error: + STBTT_free(points, userdata); + STBTT_free(*contour_lengths, userdata); + *contour_lengths = 0; + *num_contours = 0; + return NULL; +} + +STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, stbtt_vertex *vertices, int num_verts, float scale_x, float scale_y, float shift_x, float shift_y, int x_off, int y_off, int invert, void *userdata) +{ + float scale = scale_x > scale_y ? scale_y : scale_x; + int winding_count, *winding_lengths; + stbtt__point *windings = stbtt_FlattenCurves(vertices, num_verts, flatness_in_pixels / scale, &winding_lengths, &winding_count, userdata); + if (windings) { + stbtt__rasterize(result, windings, winding_lengths, winding_count, scale_x, scale_y, shift_x, shift_y, x_off, y_off, invert, userdata); + STBTT_free(winding_lengths, userdata); + STBTT_free(windings, userdata); + } +} + +STBTT_DEF void stbtt_FreeBitmap(unsigned char *bitmap, void *userdata) +{ + STBTT_free(bitmap, userdata); +} + +STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff) +{ + int ix0,iy0,ix1,iy1; + stbtt__bitmap gbm; + stbtt_vertex *vertices; + int num_verts = stbtt_GetGlyphShape(info, glyph, &vertices); + + if (scale_x == 0) scale_x = scale_y; + if (scale_y == 0) { + if (scale_x == 0) return NULL; + scale_y = scale_x; + } + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale_x, scale_y, shift_x, shift_y, &ix0,&iy0,&ix1,&iy1); + + // now we get the size + gbm.w = (ix1 - ix0); + gbm.h = (iy1 - iy0); + gbm.pixels = NULL; // in case we error + + if (width ) *width = gbm.w; + if (height) *height = gbm.h; + if (xoff ) *xoff = ix0; + if (yoff ) *yoff = iy0; + + if (gbm.w && gbm.h) { + gbm.pixels = (unsigned char *) STBTT_malloc(gbm.w * gbm.h, info->userdata); + if (gbm.pixels) { + gbm.stride = gbm.w; + + stbtt_Rasterize(&gbm, 0.35f, vertices, num_verts, scale_x, scale_y, shift_x, shift_y, ix0, iy0, 1, info->userdata); + } + } + STBTT_free(vertices, info->userdata); + return gbm.pixels; +} + +STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int glyph, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y, 0.0f, 0.0f, glyph, width, height, xoff, yoff); +} + +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph) +{ + int ix0,iy0; + stbtt_vertex *vertices; + int num_verts = stbtt_GetGlyphShape(info, glyph, &vertices); + stbtt__bitmap gbm; + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale_x, scale_y, shift_x, shift_y, &ix0,&iy0,0,0); + gbm.pixels = output; + gbm.w = out_w; + gbm.h = out_h; + gbm.stride = out_stride; + + if (gbm.w && gbm.h) + stbtt_Rasterize(&gbm, 0.35f, vertices, num_verts, scale_x, scale_y, shift_x, shift_y, ix0,iy0, 1, info->userdata); + + STBTT_free(vertices, info->userdata); +} + +STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph) +{ + stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, 0.0f,0.0f, glyph); +} + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y,shift_x,shift_y, stbtt_FindGlyphIndex(info,codepoint), width,height,xoff,yoff); +} + +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint) +{ + stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, stbtt_FindGlyphIndex(info,codepoint)); +} + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int codepoint, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetCodepointBitmapSubpixel(info, scale_x, scale_y, 0.0f,0.0f, codepoint, width,height,xoff,yoff); +} + +STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int codepoint) +{ + stbtt_MakeCodepointBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, 0.0f,0.0f, codepoint); +} + +////////////////////////////////////////////////////////////////////////////// +// +// bitmap baking +// +// This is SUPER-CRAPPY packing to keep source code small + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) + float pixel_height, // height of font in pixels + unsigned char *pixels, int pw, int ph, // bitmap to be filled in + int first_char, int num_chars, // characters to bake + stbtt_bakedchar *chardata) +{ + float scale; + int x,y,bottom_y, i; + stbtt_fontinfo f; + f.userdata = NULL; + if (!stbtt_InitFont(&f, data, offset)) + return -1; + STBTT_memset(pixels, 0, pw*ph); // background of 0 around pixels + x=y=1; + bottom_y = 1; + + scale = stbtt_ScaleForPixelHeight(&f, pixel_height); + + for (i=0; i < num_chars; ++i) { + int advance, lsb, x0,y0,x1,y1,gw,gh; + int g = stbtt_FindGlyphIndex(&f, first_char + i); + stbtt_GetGlyphHMetrics(&f, g, &advance, &lsb); + stbtt_GetGlyphBitmapBox(&f, g, scale,scale, &x0,&y0,&x1,&y1); + gw = x1-x0; + gh = y1-y0; + if (x + gw + 1 >= pw) + y = bottom_y, x = 1; // advance to next row + if (y + gh + 1 >= ph) // check if it fits vertically AFTER potentially moving to next row + return -i; + STBTT_assert(x+gw < pw); + STBTT_assert(y+gh < ph); + stbtt_MakeGlyphBitmap(&f, pixels+x+y*pw, gw,gh,pw, scale,scale, g); + chardata[i].x0 = (stbtt_int16) x; + chardata[i].y0 = (stbtt_int16) y; + chardata[i].x1 = (stbtt_int16) (x + gw); + chardata[i].y1 = (stbtt_int16) (y + gh); + chardata[i].xadvance = scale * advance; + chardata[i].xoff = (float) x0; + chardata[i].yoff = (float) y0; + x = x + gw + 1; + if (y+gh+1 > bottom_y) + bottom_y = y+gh+1; + } + return bottom_y; +} + +STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) +{ + float d3d_bias = opengl_fillrule ? 0 : -0.5f; + float ipw = 1.0f / pw, iph = 1.0f / ph; + stbtt_bakedchar *b = chardata + char_index; + int round_x = STBTT_ifloor((*xpos + b->xoff) + 0.5f); + int round_y = STBTT_ifloor((*ypos + b->yoff) + 0.5f); + + q->x0 = round_x + d3d_bias; + q->y0 = round_y + d3d_bias; + q->x1 = round_x + b->x1 - b->x0 + d3d_bias; + q->y1 = round_y + b->y1 - b->y0 + d3d_bias; + + q->s0 = b->x0 * ipw; + q->t0 = b->y0 * iph; + q->s1 = b->x1 * ipw; + q->t1 = b->y1 * iph; + + *xpos += b->xadvance; +} + +////////////////////////////////////////////////////////////////////////////// +// +// rectangle packing replacement routines if you don't have stb_rect_pack.h +// + +#ifndef STB_RECT_PACK_VERSION +#ifdef _MSC_VER +#define STBTT__NOTUSED(v) (void)(v) +#else +#define STBTT__NOTUSED(v) (void)sizeof(v) +#endif + +typedef int stbrp_coord; + +//////////////////////////////////////////////////////////////////////////////////// +// // +// // +// COMPILER WARNING ?!?!? // +// // +// // +// if you get a compile warning due to these symbols being defined more than // +// once, move #include "stb_rect_pack.h" before #include "stb_truetype.h" // +// // +//////////////////////////////////////////////////////////////////////////////////// + +typedef struct +{ + int width,height; + int x,y,bottom_y; +} stbrp_context; + +typedef struct +{ + unsigned char x; +} stbrp_node; + +struct stbrp_rect +{ + stbrp_coord x,y; + int id,w,h,was_packed; +}; + +static void stbrp_init_target(stbrp_context *con, int pw, int ph, stbrp_node *nodes, int num_nodes) +{ + con->width = pw; + con->height = ph; + con->x = 0; + con->y = 0; + con->bottom_y = 0; + STBTT__NOTUSED(nodes); + STBTT__NOTUSED(num_nodes); +} + +static void stbrp_pack_rects(stbrp_context *con, stbrp_rect *rects, int num_rects) +{ + int i; + for (i=0; i < num_rects; ++i) { + if (con->x + rects[i].w > con->width) { + con->x = 0; + con->y = con->bottom_y; + } + if (con->y + rects[i].h > con->height) + break; + rects[i].x = con->x; + rects[i].y = con->y; + rects[i].was_packed = 1; + con->x += rects[i].w; + if (con->y + rects[i].h > con->bottom_y) + con->bottom_y = con->y + rects[i].h; + } + for ( ; i < num_rects; ++i) + rects[i].was_packed = 0; +} +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// bitmap baking +// +// This is SUPER-AWESOME (tm Ryan Gordon) packing using stb_rect_pack.h. If +// stb_rect_pack.h isn't available, it uses the BakeFontBitmap strategy. + +STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int pw, int ph, int stride_in_bytes, int padding, void *alloc_context) +{ + stbrp_context *context = (stbrp_context *) STBTT_malloc(sizeof(*context) ,alloc_context); + int num_nodes = pw - padding; + stbrp_node *nodes = (stbrp_node *) STBTT_malloc(sizeof(*nodes ) * num_nodes,alloc_context); + + if (context == NULL || nodes == NULL) { + if (context != NULL) STBTT_free(context, alloc_context); + if (nodes != NULL) STBTT_free(nodes , alloc_context); + return 0; + } + + spc->user_allocator_context = alloc_context; + spc->width = pw; + spc->height = ph; + spc->pixels = pixels; + spc->pack_info = context; + spc->nodes = nodes; + spc->padding = padding; + spc->stride_in_bytes = stride_in_bytes != 0 ? stride_in_bytes : pw; + spc->h_oversample = 1; + spc->v_oversample = 1; + + stbrp_init_target(context, pw-padding, ph-padding, nodes, num_nodes); + + if (pixels) + STBTT_memset(pixels, 0, pw*ph); // background of 0 around pixels + + return 1; +} + +STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc) +{ + STBTT_free(spc->nodes , spc->user_allocator_context); + STBTT_free(spc->pack_info, spc->user_allocator_context); +} + +STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h_oversample, unsigned int v_oversample) +{ + STBTT_assert(h_oversample <= STBTT_MAX_OVERSAMPLE); + STBTT_assert(v_oversample <= STBTT_MAX_OVERSAMPLE); + if (h_oversample <= STBTT_MAX_OVERSAMPLE) + spc->h_oversample = h_oversample; + if (v_oversample <= STBTT_MAX_OVERSAMPLE) + spc->v_oversample = v_oversample; +} + +#define STBTT__OVER_MASK (STBTT_MAX_OVERSAMPLE-1) + +static void stbtt__h_prefilter(unsigned char *pixels, int w, int h, int stride_in_bytes, unsigned int kernel_width) +{ + unsigned char buffer[STBTT_MAX_OVERSAMPLE]; + int safe_w = w - kernel_width; + int j; + STBTT_memset(buffer, 0, STBTT_MAX_OVERSAMPLE); // suppress bogus warning from VS2013 -analyze + for (j=0; j < h; ++j) { + int i; + unsigned int total; + STBTT_memset(buffer, 0, kernel_width); + + total = 0; + + // make kernel_width a constant in common cases so compiler can optimize out the divide + switch (kernel_width) { + case 2: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 2); + } + break; + case 3: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 3); + } + break; + case 4: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 4); + } + break; + case 5: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 5); + } + break; + default: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / kernel_width); + } + break; + } + + for (; i < w; ++i) { + STBTT_assert(pixels[i] == 0); + total -= buffer[i & STBTT__OVER_MASK]; + pixels[i] = (unsigned char) (total / kernel_width); + } + + pixels += stride_in_bytes; + } +} + +static void stbtt__v_prefilter(unsigned char *pixels, int w, int h, int stride_in_bytes, unsigned int kernel_width) +{ + unsigned char buffer[STBTT_MAX_OVERSAMPLE]; + int safe_h = h - kernel_width; + int j; + STBTT_memset(buffer, 0, STBTT_MAX_OVERSAMPLE); // suppress bogus warning from VS2013 -analyze + for (j=0; j < w; ++j) { + int i; + unsigned int total; + STBTT_memset(buffer, 0, kernel_width); + + total = 0; + + // make kernel_width a constant in common cases so compiler can optimize out the divide + switch (kernel_width) { + case 2: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 2); + } + break; + case 3: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 3); + } + break; + case 4: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 4); + } + break; + case 5: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 5); + } + break; + default: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / kernel_width); + } + break; + } + + for (; i < h; ++i) { + STBTT_assert(pixels[i*stride_in_bytes] == 0); + total -= buffer[i & STBTT__OVER_MASK]; + pixels[i*stride_in_bytes] = (unsigned char) (total / kernel_width); + } + + pixels += 1; + } +} + +static float stbtt__oversample_shift(int oversample) +{ + if (!oversample) + return 0.0f; + + // The prefilter is a box filter of width "oversample", + // which shifts phase by (oversample - 1)/2 pixels in + // oversampled space. We want to shift in the opposite + // direction to counter this. + return (float)-(oversample - 1) / (2.0f * (float)oversample); +} + +// rects array must be big enough to accommodate all characters in the given ranges +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +{ + int i,j,k; + + k=0; + for (i=0; i < num_ranges; ++i) { + float fh = ranges[i].font_size; + float scale = fh > 0 ? stbtt_ScaleForPixelHeight(info, fh) : stbtt_ScaleForMappingEmToPixels(info, -fh); + ranges[i].h_oversample = (unsigned char) spc->h_oversample; + ranges[i].v_oversample = (unsigned char) spc->v_oversample; + for (j=0; j < ranges[i].num_chars; ++j) { + int x0,y0,x1,y1; + int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; + int glyph = stbtt_FindGlyphIndex(info, codepoint); + stbtt_GetGlyphBitmapBoxSubpixel(info,glyph, + scale * spc->h_oversample, + scale * spc->v_oversample, + 0,0, + &x0,&y0,&x1,&y1); + rects[k].w = (stbrp_coord) (x1-x0 + spc->padding + spc->h_oversample-1); + rects[k].h = (stbrp_coord) (y1-y0 + spc->padding + spc->v_oversample-1); + ++k; + } + } + + return k; +} + +// rects array must be big enough to accommodate all characters in the given ranges +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +{ + int i,j,k, return_value = 1; + + // save current values + int old_h_over = spc->h_oversample; + int old_v_over = spc->v_oversample; + + k = 0; + for (i=0; i < num_ranges; ++i) { + float fh = ranges[i].font_size; + float scale = fh > 0 ? stbtt_ScaleForPixelHeight(info, fh) : stbtt_ScaleForMappingEmToPixels(info, -fh); + float recip_h,recip_v,sub_x,sub_y; + spc->h_oversample = ranges[i].h_oversample; + spc->v_oversample = ranges[i].v_oversample; + recip_h = 1.0f / spc->h_oversample; + recip_v = 1.0f / spc->v_oversample; + sub_x = stbtt__oversample_shift(spc->h_oversample); + sub_y = stbtt__oversample_shift(spc->v_oversample); + for (j=0; j < ranges[i].num_chars; ++j) { + stbrp_rect *r = &rects[k]; + if (r->was_packed) { + stbtt_packedchar *bc = &ranges[i].chardata_for_range[j]; + int advance, lsb, x0,y0,x1,y1; + int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; + int glyph = stbtt_FindGlyphIndex(info, codepoint); + stbrp_coord pad = (stbrp_coord) spc->padding; + + // pad on left and top + r->x += pad; + r->y += pad; + r->w -= pad; + r->h -= pad; + stbtt_GetGlyphHMetrics(info, glyph, &advance, &lsb); + stbtt_GetGlyphBitmapBox(info, glyph, + scale * spc->h_oversample, + scale * spc->v_oversample, + &x0,&y0,&x1,&y1); + stbtt_MakeGlyphBitmapSubpixel(info, + spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w - spc->h_oversample+1, + r->h - spc->v_oversample+1, + spc->stride_in_bytes, + scale * spc->h_oversample, + scale * spc->v_oversample, + 0,0, + glyph); + + if (spc->h_oversample > 1) + stbtt__h_prefilter(spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w, r->h, spc->stride_in_bytes, + spc->h_oversample); + + if (spc->v_oversample > 1) + stbtt__v_prefilter(spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w, r->h, spc->stride_in_bytes, + spc->v_oversample); + + bc->x0 = (stbtt_int16) r->x; + bc->y0 = (stbtt_int16) r->y; + bc->x1 = (stbtt_int16) (r->x + r->w); + bc->y1 = (stbtt_int16) (r->y + r->h); + bc->xadvance = scale * advance; + bc->xoff = (float) x0 * recip_h + sub_x; + bc->yoff = (float) y0 * recip_v + sub_y; + bc->xoff2 = (x0 + r->w) * recip_h + sub_x; + bc->yoff2 = (y0 + r->h) * recip_v + sub_y; + } else { + return_value = 0; // if any fail, report failure + } + + ++k; + } + } + + // restore original values + spc->h_oversample = old_h_over; + spc->v_oversample = old_v_over; + + return return_value; +} + +STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects) +{ + stbrp_pack_rects((stbrp_context *) spc->pack_info, rects, num_rects); +} + +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) +{ + stbtt_fontinfo info; + int i,j,n, return_value = 1; + //stbrp_context *context = (stbrp_context *) spc->pack_info; + stbrp_rect *rects; + + // flag all characters as NOT packed + for (i=0; i < num_ranges; ++i) + for (j=0; j < ranges[i].num_chars; ++j) + ranges[i].chardata_for_range[j].x0 = + ranges[i].chardata_for_range[j].y0 = + ranges[i].chardata_for_range[j].x1 = + ranges[i].chardata_for_range[j].y1 = 0; + + n = 0; + for (i=0; i < num_ranges; ++i) + n += ranges[i].num_chars; + + rects = (stbrp_rect *) STBTT_malloc(sizeof(*rects) * n, spc->user_allocator_context); + if (rects == NULL) + return 0; + + info.userdata = spc->user_allocator_context; + stbtt_InitFont(&info, fontdata, stbtt_GetFontOffsetForIndex(fontdata,font_index)); + + n = stbtt_PackFontRangesGatherRects(spc, &info, ranges, num_ranges, rects); + + stbtt_PackFontRangesPackRects(spc, rects, n); + + return_value = stbtt_PackFontRangesRenderIntoRects(spc, &info, ranges, num_ranges, rects); + + STBTT_free(rects, spc->user_allocator_context); + return return_value; +} + +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, + int first_unicode_codepoint_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range) +{ + stbtt_pack_range range; + range.first_unicode_codepoint_in_range = first_unicode_codepoint_in_range; + range.array_of_unicode_codepoints = NULL; + range.num_chars = num_chars_in_range; + range.chardata_for_range = chardata_for_range; + range.font_size = font_size; + return stbtt_PackFontRanges(spc, fontdata, font_index, &range, 1); +} + +STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) +{ + float ipw = 1.0f / pw, iph = 1.0f / ph; + stbtt_packedchar *b = chardata + char_index; + + if (align_to_integer) { + float x = (float) STBTT_ifloor((*xpos + b->xoff) + 0.5f); + float y = (float) STBTT_ifloor((*ypos + b->yoff) + 0.5f); + q->x0 = x; + q->y0 = y; + q->x1 = x + b->xoff2 - b->xoff; + q->y1 = y + b->yoff2 - b->yoff; + } else { + q->x0 = *xpos + b->xoff; + q->y0 = *ypos + b->yoff; + q->x1 = *xpos + b->xoff2; + q->y1 = *ypos + b->yoff2; + } + + q->s0 = b->x0 * ipw; + q->t0 = b->y0 * iph; + q->s1 = b->x1 * ipw; + q->t1 = b->y1 * iph; + + *xpos += b->xadvance; +} + + +////////////////////////////////////////////////////////////////////////////// +// +// font name matching -- recommended not to use this +// + +// check if a utf8 string contains a prefix which is the utf16 string; if so return length of matching utf8 string +static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 *s1, stbtt_int32 len1, const stbtt_uint8 *s2, stbtt_int32 len2) +{ + stbtt_int32 i=0; + + // convert utf16 to utf8 and compare the results while converting + while (len2) { + stbtt_uint16 ch = s2[0]*256 + s2[1]; + if (ch < 0x80) { + if (i >= len1) return -1; + if (s1[i++] != ch) return -1; + } else if (ch < 0x800) { + if (i+1 >= len1) return -1; + if (s1[i++] != 0xc0 + (ch >> 6)) return -1; + if (s1[i++] != 0x80 + (ch & 0x3f)) return -1; + } else if (ch >= 0xd800 && ch < 0xdc00) { + stbtt_uint32 c; + stbtt_uint16 ch2 = s2[2]*256 + s2[3]; + if (i+3 >= len1) return -1; + c = ((ch - 0xd800) << 10) + (ch2 - 0xdc00) + 0x10000; + if (s1[i++] != 0xf0 + (c >> 18)) return -1; + if (s1[i++] != 0x80 + ((c >> 12) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((c >> 6) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((c ) & 0x3f)) return -1; + s2 += 2; // plus another 2 below + len2 -= 2; + } else if (ch >= 0xdc00 && ch < 0xe000) { + return -1; + } else { + if (i+2 >= len1) return -1; + if (s1[i++] != 0xe0 + (ch >> 12)) return -1; + if (s1[i++] != 0x80 + ((ch >> 6) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((ch ) & 0x3f)) return -1; + } + s2 += 2; + len2 -= 2; + } + return i; +} + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +{ + return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((const stbtt_uint8*) s1, len1, (const stbtt_uint8*) s2, len2); +} + +// returns results in whatever encoding you request... but note that 2-byte encodings +// will be BIG-ENDIAN... use stbtt_CompareUTF8toUTF16_bigendian() to compare +STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *length, int platformID, int encodingID, int languageID, int nameID) +{ + stbtt_int32 i,count,stringOffset; + stbtt_uint8 *fc = font->data; + stbtt_uint32 offset = font->fontstart; + stbtt_uint32 nm = stbtt__find_table(fc, offset, "name"); + if (!nm) return NULL; + + count = ttUSHORT(fc+nm+2); + stringOffset = nm + ttUSHORT(fc+nm+4); + for (i=0; i < count; ++i) { + stbtt_uint32 loc = nm + 6 + 12 * i; + if (platformID == ttUSHORT(fc+loc+0) && encodingID == ttUSHORT(fc+loc+2) + && languageID == ttUSHORT(fc+loc+4) && nameID == ttUSHORT(fc+loc+6)) { + *length = ttUSHORT(fc+loc+8); + return (const char *) (fc+stringOffset+ttUSHORT(fc+loc+10)); + } + } + return NULL; +} + +static int stbtt__matchpair(stbtt_uint8 *fc, stbtt_uint32 nm, stbtt_uint8 *name, stbtt_int32 nlen, stbtt_int32 target_id, stbtt_int32 next_id) +{ + stbtt_int32 i; + stbtt_int32 count = ttUSHORT(fc+nm+2); + stbtt_int32 stringOffset = nm + ttUSHORT(fc+nm+4); + + for (i=0; i < count; ++i) { + stbtt_uint32 loc = nm + 6 + 12 * i; + stbtt_int32 id = ttUSHORT(fc+loc+6); + if (id == target_id) { + // find the encoding + stbtt_int32 platform = ttUSHORT(fc+loc+0), encoding = ttUSHORT(fc+loc+2), language = ttUSHORT(fc+loc+4); + + // is this a Unicode encoding? + if (platform == 0 || (platform == 3 && encoding == 1) || (platform == 3 && encoding == 10)) { + stbtt_int32 slen = ttUSHORT(fc+loc+8); + stbtt_int32 off = ttUSHORT(fc+loc+10); + + // check if there's a prefix match + stbtt_int32 matchlen = stbtt__CompareUTF8toUTF16_bigendian_prefix(name, nlen, fc+stringOffset+off,slen); + if (matchlen >= 0) { + // check for target_id+1 immediately following, with same encoding & language + if (i+1 < count && ttUSHORT(fc+loc+12+6) == next_id && ttUSHORT(fc+loc+12) == platform && ttUSHORT(fc+loc+12+2) == encoding && ttUSHORT(fc+loc+12+4) == language) { + slen = ttUSHORT(fc+loc+12+8); + off = ttUSHORT(fc+loc+12+10); + if (slen == 0) { + if (matchlen == nlen) + return 1; + } else if (matchlen < nlen && name[matchlen] == ' ') { + ++matchlen; + if (stbtt_CompareUTF8toUTF16_bigendian((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) + return 1; + } + } else { + // if nothing immediately following + if (matchlen == nlen) + return 1; + } + } + } + + // @TODO handle other encodings + } + } + return 0; +} + +static int stbtt__matches(stbtt_uint8 *fc, stbtt_uint32 offset, stbtt_uint8 *name, stbtt_int32 flags) +{ + stbtt_int32 nlen = (stbtt_int32) STBTT_strlen((char *) name); + stbtt_uint32 nm,hd; + if (!stbtt__isfont(fc+offset)) return 0; + + // check italics/bold/underline flags in macStyle... + if (flags) { + hd = stbtt__find_table(fc, offset, "head"); + if ((ttUSHORT(fc+hd+44) & 7) != (flags & 7)) return 0; + } + + nm = stbtt__find_table(fc, offset, "name"); + if (!nm) return 0; + + if (flags) { + // if we checked the macStyle flags, then just check the family and ignore the subfamily + if (stbtt__matchpair(fc, nm, name, nlen, 16, -1)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 1, -1)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 3, -1)) return 1; + } else { + if (stbtt__matchpair(fc, nm, name, nlen, 16, 17)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 1, 2)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 3, -1)) return 1; + } + + return 0; +} + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const char *name_utf8, stbtt_int32 flags) +{ + stbtt_int32 i; + for (i=0;;++i) { + stbtt_int32 off = stbtt_GetFontOffsetForIndex(font_collection, i); + if (off < 0) return off; + if (stbtt__matches((stbtt_uint8 *) font_collection, off, (stbtt_uint8*) name_utf8, flags)) + return off; + } +} + +#endif // STB_TRUETYPE_IMPLEMENTATION + + +// FULL VERSION HISTORY +// +// 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use alloc userdata for PackFontRanges +// 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges +// 1.07 (2015-08-01) allow PackFontRanges to accept arrays of sparse codepoints; +// allow PackFontRanges to pack and render in separate phases; +// fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); +// fixed an assert() bug in the new rasterizer +// replace assert() with STBTT_assert() in new rasterizer +// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) +// also more precise AA rasterizer, except if shapes overlap +// remove need for STBTT_sort +// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC +// 1.04 (2015-04-15) typo in example +// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes +// 1.02 (2014-12-10) fix various warnings & compile issues w/ stb_rect_pack, C++ +// 1.01 (2014-12-08) fix subpixel position when oversampling to exactly match +// non-oversampled; STBTT_POINT_SIZE for packed case only +// 1.00 (2014-12-06) add new PackBegin etc. API, w/ support for oversampling +// 0.99 (2014-09-18) fix multiple bugs with subpixel rendering (ryg) +// 0.9 (2014-08-07) support certain mac/iOS fonts without an MS platformID +// 0.8b (2014-07-07) fix a warning +// 0.8 (2014-05-25) fix a few more warnings +// 0.7 (2013-09-25) bugfix: subpixel glyph bug fixed in 0.5 had come back +// 0.6c (2012-07-24) improve documentation +// 0.6b (2012-07-20) fix a few more warnings +// 0.6 (2012-07-17) fix warnings; added stbtt_ScaleForMappingEmToPixels, +// stbtt_GetFontBoundingBox, stbtt_IsGlyphEmpty +// 0.5 (2011-12-09) bugfixes: +// subpixel glyph renderer computed wrong bounding box +// first vertex of shape can be off-curve (FreeSans) +// 0.4b (2011-12-03) fixed an error in the font baking example +// 0.4 (2011-12-01) kerning, subpixel rendering (tor) +// bugfixes for: +// codepoint-to-glyph conversion using table fmt=12 +// codepoint-to-glyph conversion using table fmt=4 +// stbtt_GetBakedQuad with non-square texture (Zer) +// updated Hello World! sample to use kerning and subpixel +// fixed some warnings +// 0.3 (2009-06-24) cmap fmt=12, compound shapes (MM) +// userdata, malloc-from-userdata, non-zero fill (stb) +// 0.2 (2009-03-11) Fix unsigned/signed char warnings +// 0.1 (2009-03-09) First public release +// diff --git a/selfdrive/__init__.py b/selfdrive/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/assets/Roboto-Bold.ttf b/selfdrive/assets/Roboto-Bold.ttf new file mode 100644 index 0000000000..a355c27cde Binary files /dev/null and b/selfdrive/assets/Roboto-Bold.ttf differ diff --git a/selfdrive/assets/courbd.ttf b/selfdrive/assets/courbd.ttf new file mode 100644 index 0000000000..a4f26b4b5e Binary files /dev/null and b/selfdrive/assets/courbd.ttf differ diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile new file mode 100644 index 0000000000..4e0c00c6c7 --- /dev/null +++ b/selfdrive/boardd/Makefile @@ -0,0 +1,73 @@ +CC = clang +CXX = clang++ + +ARCH := $(shell uname -m) + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +EXTRA_LIBS = -lusb + +ifeq ($(ARCH),x86_64) +ZMQ_LIBS = -L$(HOME)/drive/external/zmq/lib/ \ + -l:libczmq.a -l:libzmq.a +CEREAL_LIBS = -L$(HOME)/drive/external/capnp/lib/ \ + -l:libcapnp.a -l:libkj.a +EXTRA_LIBS = -lusb-1.0 -lpthread +endif + + +OBJS = boardd.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: boardd + +boardd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + $(EXTRA_LIBS) + +boardd.o: boardd.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + + +.PHONY: clean +clean: + rm -f boardd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/boardd/__init__.py b/selfdrive/boardd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc new file mode 100644 index 0000000000..da3b458943 --- /dev/null +++ b/selfdrive/boardd/boardd.cc @@ -0,0 +1,322 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/timing.h" + +int do_exit = 0; + +libusb_context *ctx = NULL; +libusb_device_handle *dev_handle; +pthread_mutex_t usb_lock; + +// double the FIFO size +#define RECV_SIZE (0x1000) +#define TIMEOUT 0 + +#define DEBUG_BOARDD +#ifdef DEBUG_BOARDD +#define DPRINTF(fmt, ...) printf("boardd: " fmt, ## __VA_ARGS__) +#else +#define DPRINTF(fmt, ...) +#endif + +bool usb_connect() { + int err; + + dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); + if (dev_handle == NULL) { return false; } + + err = libusb_set_configuration(dev_handle, 1); + if (err != 0) { return false; } + + err = libusb_claim_interface(dev_handle, 0); + if (err != 0) { return false; } + + return true; +} + + +void handle_usb_issue(int err, const char func[]) { + DPRINTF("usb error %d \"%s\" in %s\n", err, libusb_strerror((enum libusb_error)err), func); + if (err == -4) { + while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } + } + // TODO: check other errors, is simply retrying okay? +} + +void can_recv(void *s) { + int err; + uint32_t data[RECV_SIZE/4]; + int recv; + uint32_t f1, f2; + + // do recv + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); + if (err != 0) { handle_usb_issue(err, __func__); } + if (err == -8) { DPRINTF("overflow got 0x%x\n", recv); }; + + // timeout is okay to exit, recv still happened + if (err == -7) { break; } + } while(err != 0); + + pthread_mutex_unlock(&usb_lock); + + // return if length is 0 + if (recv <= 0) { + return; + } + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto canData = event.initCan(recv/0x10); + + // populate message + for (int i = 0; i<(recv/0x10); i++) { + if (data[i*4] & 4) { + // extended + canData[i].setAddress(data[i*4] >> 3); + //printf("got extended: %x\n", data[i*4] >> 3); + } else { + // normal + canData[i].setAddress(data[i*4] >> 21); + } + canData[i].setBusTime(data[i*4+1] >> 16); + int len = data[i*4+1]&0xF; + canData[i].setDat(kj::arrayPtr((uint8_t*)&data[i*4+2], len)); + canData[i].setSrc((data[i*4+1] >> 4) & 3); + } + + // send to can + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + +void can_health(void *s) { + int cnt; + + // copied from board/main.c + struct health { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + } health; + + // recv from board + pthread_mutex_lock(&usb_lock); + + do { + cnt = libusb_control_transfer(dev_handle, 0xc0, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), TIMEOUT); + if (cnt != sizeof(health)) { handle_usb_issue(cnt, __func__); } + } while(cnt != sizeof(health)); + + pthread_mutex_unlock(&usb_lock); + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto healthData = event.initHealth(); + + // set fields + healthData.setVoltage(health.voltage); + healthData.setCurrent(health.current); + healthData.setStarted(health.started); + healthData.setControlsAllowed(health.controls_allowed); + healthData.setGasInterceptorDetected(health.gas_interceptor_detected); + + // send to health + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + + +void can_send(void *s) { + int err; + + // recv from sendcan + zmq_msg_t msg; + zmq_msg_init(&msg); + err = zmq_msg_recv(&msg, s, 0); + assert(err >= 0); + + // format for board + auto amsg = kj::arrayPtr((const capnp::word*)zmq_msg_data(&msg), zmq_msg_size(&msg)); + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + int msg_count = event.getCan().size(); + + uint32_t *send = (uint32_t*)malloc(msg_count*0x10); + memset(send, 0, msg_count*0x10); + + for (int i = 0; i < msg_count; i++) { + auto cmsg = event.getCan()[i]; + if (cmsg.getAddress() >= 0x800) { + // extended + send[i*4] = (cmsg.getAddress() << 3) | 5; + } else { + // normal + send[i*4] = (cmsg.getAddress() << 21) | 1; + } + assert(cmsg.getDat().size() <= 8); + send[i*4+1] = cmsg.getDat().size() | (cmsg.getSrc() << 4); + memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); + } + + //DPRINTF("got send message: %d\n", msg_count); + + // release msg + zmq_msg_close(&msg); + + // send to board + int sent; + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); + if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); } + } while(err != 0); + + pthread_mutex_unlock(&usb_lock); + + // done + free(send); +} + + +// **** threads **** + +void *can_send_thread(void *crap) { + DPRINTF("start send thread\n"); + + // sendcan = 8017 + void *context = zmq_ctx_new(); + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8017"); + + // run as fast as messages come in + while (!do_exit) { + can_send(subscriber); + } + return NULL; +} + +void *can_recv_thread(void *crap) { + DPRINTF("start recv thread\n"); + + // can = 8006 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8006"); + + // run at ~200hz + while (!do_exit) { + can_recv(publisher); + // 5ms + usleep(5*1000); + } + return NULL; +} + +void *can_health_thread(void *crap) { + DPRINTF("start health thread\n"); + + // health = 8011 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8011"); + + // run at 1hz + while (!do_exit) { + can_health(publisher); + usleep(1000*1000); + } + return NULL; +} + +int main() { + int err; + printf("boardd: starting boardd\n"); + + // set process priority + err = setpriority(PRIO_PROCESS, 0, -4); + printf("boardd: setpriority returns %d\n", err); + + // connect to the board + err = libusb_init(&ctx); + assert(err == 0); + libusb_set_debug(ctx, 3); + + // TODO: duplicate code from error handling + while (!usb_connect()) { DPRINTF("attempting to connect\n"); usleep(100*1000); } + + /*int config; + err = libusb_get_configuration(dev_handle, &config); + assert(err == 0); + DPRINTF("configuration is %d\n", config);*/ + + /*err = libusb_set_interface_alt_setting(dev_handle, 0, 0); + assert(err == 0);*/ + + // create threads + + pthread_t can_health_thread_handle; + err = pthread_create(&can_health_thread_handle, NULL, + can_health_thread, NULL); + assert(err == 0); + + pthread_t can_send_thread_handle; + err = pthread_create(&can_send_thread_handle, NULL, + can_send_thread, NULL); + assert(err == 0); + + pthread_t can_recv_thread_handle; + err = pthread_create(&can_recv_thread_handle, NULL, + can_recv_thread, NULL); + assert(err == 0); + + // join threads + + err = pthread_join(can_recv_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_send_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_health_thread_handle, NULL); + assert(err == 0); + + // destruct libusb + + libusb_close(dev_handle); + libusb_exit(ctx); +} + diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py new file mode 100755 index 0000000000..50d4aacc6e --- /dev/null +++ b/selfdrive/boardd/boardd.py @@ -0,0 +1,179 @@ +#!/usr/bin/env python +import os +import struct +import zmq + +import selfdrive.messaging as messaging +from common.realtime import Ratekeeper +from common.services import service_list +from selfdrive.swaglog import cloudlog + +# USB is optional +try: + import usb1 + from usb1 import USBErrorIO, USBErrorOverflow +except Exception: + pass + +# TODO: rewrite in C to save CPU + +# *** serialization functions *** +def can_list_to_can_capnp(can_msgs): + dat = messaging.new_message() + dat.init('can', len(can_msgs)) + for i, can_msg in enumerate(can_msgs): + dat.can[i].address = can_msg[0] + dat.can[i].busTime = can_msg[1] + dat.can[i].dat = can_msg[2] + dat.can[i].src = can_msg[3] + return dat + +def can_capnp_to_can_list_old(dat, src_filter=[]): + ret = [] + for msg in dat.can: + if msg.src in src_filter: + ret.append([msg.address, msg.busTime, msg.dat.encode("hex")]) + return ret + +def can_capnp_to_can_list(dat): + ret = [] + for msg in dat.can: + ret.append([msg.address, msg.busTime, msg.dat, msg.src]) + return ret + +# *** can driver *** +def can_health(): + while 1: + try: + dat = handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd2, 0, 0, 0x10) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD HEALTH, RETRYING") + v, i, started = struct.unpack("IIB", dat[0:9]) + # TODO: units + return {"voltage": v, "current": i, "started": bool(started)} + +def __parse_can_buffer(dat): + ret = [] + for j in range(0, len(dat), 0x10): + ddat = dat[j:j+0x10] + f1, f2 = struct.unpack("II", ddat[0:8]) + ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&3)) + return ret + +def can_send_many(arr): + snds = [] + for addr, _, dat, alt in arr: + snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat + snd = snd.ljust(0x10, '\x00') + snds.append(snd) + while 1: + try: + handle.bulkWrite(3, ''.join(snds)) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD SEND MANY, RETRYING") + +def can_recv(): + dat = "" + while 1: + try: + dat = handle.bulkRead(1, 0x10*256) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD RECV, RETRYING") + return __parse_can_buffer(dat) + +def can_init(): + global handle, context + cloudlog.info("attempting can init") + + context = usb1.USBContext() + #context.setDebug(9) + + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: + handle = device.open() + handle.claimInterface(0) + + if handle is None: + print "CAN NOT FOUND" + exit(-1) + + print "got handle" + cloudlog.info("can init done") + +def boardd_mock_loop(): + context = zmq.Context() + can_init() + + logcan = messaging.sub_sock(context, service_list['can'].port) + + while 1: + tsc = messaging.drain_sock(logcan, wait_for_one=True) + snds = map(can_capnp_to_can_list, tsc) + snd = [] + for s in snds: + snd += s + snd = filter(lambda x: x[-1] <= 1, snd) + can_send_many(snd) + + # recv @ 100hz + can_msgs = can_recv() + print "sent %d got %d" % (len(snd), len(can_msgs)) + + #print can_msgs + +# *** main loop *** +def boardd_loop(rate=200): + rk = Ratekeeper(rate) + context = zmq.Context() + + can_init() + + # *** publishes can and health + logcan = messaging.pub_sock(context, service_list['can'].port) + health_sock = messaging.pub_sock(context, service_list['health'].port) + + # *** subscribes to can send + sendcan = messaging.sub_sock(context, service_list['sendcan'].port) + + while 1: + # health packet @ 1hz + if (rk.frame%rate) == 0: + health = can_health() + msg = messaging.new_message() + msg.init('health') + + # store the health to be logged + msg.health.voltage = health['voltage'] + msg.health.current = health['current'] + msg.health.started = health['started'] + + health_sock.send(msg.to_bytes()) + + # recv @ 100hz + can_msgs = can_recv() + + # publish to logger + # TODO: refactor for speed + if len(can_msgs) > 0: + dat = can_list_to_can_capnp(can_msgs) + logcan.send(dat.to_bytes()) + + # send can if we have a packet + tsc = messaging.recv_sock(sendcan) + if tsc is not None: + can_send_many(can_capnp_to_can_list(tsc)) + + rk.keep_time() + +def main(gctx=None): + if os.getenv("MOCK") is not None: + boardd_mock_loop() + else: + boardd_loop() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/calibrationd/__init__.py b/selfdrive/calibrationd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/calibrationd/calibration.py b/selfdrive/calibrationd/calibration.py new file mode 100644 index 0000000000..cd5daa6ff4 --- /dev/null +++ b/selfdrive/calibrationd/calibration.py @@ -0,0 +1,208 @@ +import numpy as np + +import common.filters as filters +from selfdrive.controls.lib.latcontrol import calc_curvature + + +# Calibration Status +class CalibStatus(object): + INCOMPLETE = 0 + VALID = 1 + INVALID = 2 + + +def line_intersection(line1, line2, no_int_sub = [0,0]): + xdiff = (line1[0][0] - line1[1][0], line2[0][0] - line2[1][0]) + ydiff = (line1[0][1] - line1[1][1], line2[0][1] - line2[1][1]) + + def det(a, b): + return a[0] * b[1] - a[1] * b[0] + + div = det(xdiff, ydiff) + if div == 0: + # since we are in float domain, this should really never happen + return no_int_sub + + d = (det(*line1), det(*line2)) + x = det(d, xdiff) / div + y = det(d, ydiff) / div + return [x, y] + +def points_inside_hit_box(pts, box): + """Determine which points lie inside a box. + + Inputs: + pts: An nx2 array of points to hit test. + box: An array [[x_left, y_top], [x_right, y_bottom]] describing a box to + use for hit testing. + Returns: + A logical array with true for every member of pts inside box. + """ + hits = np.all(np.logical_and(pts > box[0, :], pts < box[1, :]), axis=1) + return hits + +def warp_points(pt_s, warp_matrix): + # pt_s are the source points, nx2 array. + pt_d = np.dot(warp_matrix[:, :2], pt_s.T) + warp_matrix[:, 2][:, np.newaxis] + + # divide by third dimension for representation in image space. + return (pt_d[:2, :] / pt_d[2, :]).T + +class ViewCalibrator(object): + def __init__(self, box_size, big_box_size, vp_r, warp_matrix_start, vp_f=None, cal_cycle=0, cal_status=0): + self.calibration_threshold = 3000 + self.box_size = box_size + self.big_box_size = big_box_size + + self.warp_matrix_start = warp_matrix_start + self.vp_r = list(vp_r) + + if vp_f is None: + self.vp_f = list(vp_r) + else: + self.vp_f = list(vp_f) + + # slow filter fot the vanishing point + vp_fr = 0.005 # Hz, slow filter + self.dt = 0.05 # camera runs at 20Hz + + self.update_warp_matrix() + + self.vp_x_filter = filters.FirstOrderLowpassFilter(vp_fr, self.dt, self.vp_f[0]) + self.vp_y_filter = filters.FirstOrderLowpassFilter(vp_fr, self.dt, self.vp_f[1]) + + self.cal_cycle = cal_cycle + self.cal_status = cal_status + self.cal_perc = int(np.minimum(self.cal_cycle*100./self.calibration_threshold, 100)) + + def vanishing_point_process(self, old_ps, new_ps, v_ego, steer_angle, VP): + # correct diffs by yaw rate + cam_fov = 23.06*np.pi/180. # deg + curvature = calc_curvature(v_ego, steer_angle, VP) + yaw_rate = curvature * v_ego + hor_angle_shift = yaw_rate * self.dt * self.box_size[0] / cam_fov + old_ps += [hor_angle_shift, 0] # old points have moved in the image due to yaw rate + + pos_ps = [None]*len(new_ps) + for ii in range(len(old_ps)): + xo = old_ps[ii][0] + yo = old_ps[ii][1] + yn = new_ps[ii][1] + + # don't consider points with low flow in y + if abs(yn - yo) > 1: + if xo > (self.vp_f[0] + 20): + pos_ps[ii] = 'r' # right lane point + elif xo < (self.vp_f[0] - 20): + pos_ps[ii] = 'l' # left lane point + + # intersect all the right lines with the left lines + idxs_l = [i for i, x in enumerate(pos_ps) if x == 'l'] + idxs_r = [i for i, x in enumerate(pos_ps) if x == 'r'] + + old_ps_l, new_ps_l = old_ps[idxs_l], new_ps[idxs_l] + old_ps_r, new_ps_r = old_ps[idxs_r], new_ps[idxs_r] + # return None if there is one side with no lines, the speed is low or the steer angle is high + if len(old_ps_l) == 0 or len(old_ps_r) == 0 or v_ego < 20 or abs(steer_angle) > 5: + return None + + int_ps = [[None] * len(old_ps_r)] * len(old_ps_l) + for ll in range(len(old_ps_l)): + for rr in range(len(old_ps_r)): + old_p_l, old_p_r, new_p_l, new_p_r = old_ps_l[ll], old_ps_r[ + rr], new_ps_l[ll], new_ps_r[rr] + line_l = [[old_p_l[0], old_p_l[1]], [new_p_l[0], new_p_l[1]]] + line_r = [[old_p_r[0], old_p_r[1]], [new_p_r[0], new_p_r[1]]] + int_ps[ll][rr] = line_intersection( + line_l, line_r, no_int_sub=self.vp_f) + # saturate outliers that are too far from the estimated vp + int_ps[ll][rr][0] = np.clip(int_ps[ll][rr][0], self.vp_f[0] - 20, self.vp_f[0] + 20) + int_ps[ll][rr][1] = np.clip(int_ps[ll][rr][1], self.vp_f[1] - 30, self.vp_f[1] + 30) + vp = np.mean(np.mean(np.array(int_ps), axis=0), axis=0) + + return vp + + def calibration_validity(self): + # this function sanity checks that the small box is contained in the big box. + # otherwise the warp function will generate black spots on the small box + cp = np.asarray([[0, 0], + [self.box_size[0], 0], + [self.box_size[0], self.box_size[1]], + [0, self.box_size[1]]]) + + cpw = warp_points(cp, self.warp_matrix) + + # pixel margin for validity hysteresys: + # - if calibration is good, keep it good until small box is inside the big box + # - if calibration isn't good, then make it good again if small box is in big box with margin + margin_px = 0 if self.cal_status == CalibStatus.VALID else 5 + big_hit_box = np.asarray( + [[margin_px, margin_px], + [self.big_box_size[0], self.big_box_size[1] - margin_px]]) + + cpw_outside_big_box = np.logical_not(points_inside_hit_box(cpw, big_hit_box)) + return not np.any(cpw_outside_big_box) + + + def get_calibration_hit_box(self): + """Returns an axis-aligned hit box in canonical image space. + Points which do not fall within this box should not be used for + calibration. + + Returns: + An array [[x_left, y_top], [x_right, y_bottom]] describing a box inside + which all calibration points should lie. + """ + # We mainly care about feature from lanes, so removed points from sky. + y_filter = 50. + return np.asarray([[0, y_filter], [self.box_size[0], self.box_size[1]]]) + + + def update_warp_matrix(self): + translation_matrix = np.asarray( + [[1, 0, self.vp_f[0] - self.vp_r[0]], + [0, 1, self.vp_f[1] - self.vp_r[1]], + [0, 0, 1]]) + self.warp_matrix = np.dot(translation_matrix, self.warp_matrix_start) + self.warp_matrix_inv = np.linalg.inv(self.warp_matrix) + + def calibration(self, p0, p1, st, v_ego, steer_angle, VP): + # convert to np array first thing + p0 = np.asarray(p0) + p1 = np.asarray(p1) + st = np.asarray(st) + + p0 = p0.reshape((-1,2)) + p1 = p1.reshape((-1,2)) + + # filter out pts with bad status + p0 = p0[st==1] + p1 = p1[st==1] + + calib_hit_box = self.get_calibration_hit_box() + # remove all the points outside the small box and above the horizon line + good_idxs = points_inside_hit_box( + warp_points(p0, self.warp_matrix_inv), calib_hit_box) + p0 = p0[good_idxs] + p1 = p1[good_idxs] + + # print("unwarped points: {}".format(warp_points(p0, self.warp_matrix_inv))) + # print("good_idxs {}:".format(good_idxs)) + + # get instantaneous vp + vp = self.vanishing_point_process(p0, p1, v_ego, steer_angle, VP) + + if vp is not None: + # filter the vanishing point + self.vp_f = [self.vp_x_filter(vp[0]), self.vp_y_filter(vp[1])] + self.cal_cycle += 1 + + if not self.calibration_validity(): + self.cal_status = CalibStatus.INVALID + else: + # 10 minutes @5Hz TODO: make this threshold function of convergency speed + self.cal_status = CalibStatus.VALID + #self.cal_status = CalibStatus.VALID if self.cal_cycle > self.calibration_threshold else CalibStatus.INCOMPLETE + self.cal_perc = int(np.minimum(self.cal_cycle*100./self.calibration_threshold, 100)) + + self.update_warp_matrix() diff --git a/selfdrive/calibrationd/calibrationd.py b/selfdrive/calibrationd/calibrationd.py new file mode 100755 index 0000000000..779cb4723f --- /dev/null +++ b/selfdrive/calibrationd/calibrationd.py @@ -0,0 +1,116 @@ +#!/usr/bin/env python +import os +import numpy as np +import zmq + +from common.services import service_list +import selfdrive.messaging as messaging +from selfdrive.config import ImageParams, VehicleParams +from selfdrive.calibrationd.calibration import ViewCalibrator, CalibStatus + +CALIBRATION_FILE = "/sdcard/calibration_param" + +def load_calibration(gctx): + # calibration initialization + I = ImageParams() + vp_guess = None + + if gctx is not None: + warp_matrix_start = np.array( + gctx['calibration']["initial_homography"]).reshape(3, 3) + big_box_size = [560, 304] + else: + warp_matrix_start = np.array([[1., 0., I.SX_R], + [0., 1., I.SY_R], + [0., 0., 1.]]) + big_box_size = [640, 480] + + # translate the vanishing point into phone image space + vp_box = (I.VPX_R-I.SX_R, I.VPY_R-I.SY_R) + vp_trans = np.dot(warp_matrix_start, vp_box+(1.,)) + vp_img = (vp_trans[0]/vp_trans[2], vp_trans[1]/vp_trans[2]) + + # load calibration data + if os.path.isfile(CALIBRATION_FILE): + # if the calibration file exist, start from the last cal values + with open(CALIBRATION_FILE, "r") as cal_file: + data = [float(l.strip()) for l in cal_file.readlines()] + calib = ViewCalibrator((I.X, I.Y), + big_box_size, + vp_img, + warp_matrix_start, + vp_f=[data[2], data[3]], + cal_cycle=data[0], + cal_status=data[1]) + + if calib.cal_status == CalibStatus.INCOMPLETE: + print "CALIBRATION IN PROGRESS", calib.cal_cycle + else: + print "NO CALIBRATION FILE" + calib = ViewCalibrator((I.X, I.Y), + big_box_size, + vp_img, + warp_matrix_start, + vp_f=vp_guess) + + return calib + +def calibrationd_thread(gctx): + context = zmq.Context() + + features = messaging.sub_sock(context, service_list['features'].port) + live100 = messaging.sub_sock(context, service_list['live100'].port) + + livecalibration = messaging.pub_sock(context, service_list['liveCalibration'].port) + + # subscribe to stats about the car + VP = VehicleParams(False) + + v_ego = None + + calib = load_calibration(gctx) + last_cal_cycle = calib.cal_cycle + + while 1: + # calibration at the end so it does not delay radar processing above + ft = messaging.recv_sock(features, wait=True) + + # get latest here + l100 = messaging.recv_sock(live100) + if l100 is not None: + v_ego = l100.live100.vEgo + steer_angle = l100.live100.angleSteers + + if v_ego is None: + continue + + p0 = ft.features.p0 + p1 = ft.features.p1 + st = ft.features.status + + calib.calibration(p0, p1, st, v_ego, steer_angle, VP) + + # write a new calibration every 100 cal cycle + if calib.cal_cycle - last_cal_cycle >= 100: + print "writing cal", calib.cal_cycle + with open(CALIBRATION_FILE, "w") as cal_file: + cal_file.write(str(calib.cal_cycle)+'\n') + cal_file.write(str(calib.cal_status)+'\n') + cal_file.write(str(calib.vp_f[0])+'\n') + cal_file.write(str(calib.vp_f[1])+'\n') + last_cal_cycle = calib.cal_cycle + + warp_matrix = map(float, calib.warp_matrix.reshape(9).tolist()) + dat = messaging.new_message() + dat.init('liveCalibration') + dat.liveCalibration.warpMatrix = warp_matrix + dat.liveCalibration.calStatus = calib.cal_status + dat.liveCalibration.calCycle = calib.cal_cycle + dat.liveCalibration.calPerc = calib.cal_perc + livecalibration.send(dat.to_bytes()) + +def main(gctx=None): + calibrationd_thread(gctx) + +if __name__ == "__main__": + main() diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc new file mode 100644 index 0000000000..4b13b644d4 --- /dev/null +++ b/selfdrive/common/framebuffer.cc @@ -0,0 +1,135 @@ + +#include +#include +#include + +#include + +#include +#include +#include + + +#include +#include + +#define BACKLIGHT_CONTROL "/sys/class/leds/lcd-backlight/brightness" +#define BACKLIGHT_LEVEL "205" + +using namespace android; + +struct FramebufferState { + sp session; + sp dtoken; + DisplayInfo dinfo; + sp control; + + sp s; + EGLDisplay display; + + EGLint egl_major, egl_minor; + EGLConfig config; + EGLSurface surface; + EGLContext context; +}; + +extern "C" FramebufferState* framebuffer_init( + const char* name, int32_t layer, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h) { + status_t status; + int success; + + FramebufferState *s = new FramebufferState; + + s->session = new SurfaceComposerClient(); + assert(s->session != NULL); + + s->dtoken = SurfaceComposerClient::getBuiltInDisplay( + ISurfaceComposer::eDisplayIdMain); + assert(s->dtoken != NULL); + + status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo); + assert(status == 0); + + int orientation = 3; // rotate framebuffer 270 degrees + if(orientation == 1 || orientation == 3) { + int temp = s->dinfo.h; + s->dinfo.h = s->dinfo.w; + s->dinfo.w = temp; + } + + printf("dinfo %dx%d\n", s->dinfo.w, s->dinfo.h); + + Rect destRect(s->dinfo.w, s->dinfo.h); + s->session->setDisplayProjection(s->dtoken, orientation, destRect, destRect); + + s->control = s->session->createSurface(String8(name), + s->dinfo.w, s->dinfo.h, PIXEL_FORMAT_RGBX_8888); + assert(s->control != NULL); + + SurfaceComposerClient::openGlobalTransaction(); + status = s->control->setLayer(layer); + SurfaceComposerClient::closeGlobalTransaction(); + assert(status == 0); + + s->s = s->control->getSurface(); + assert(s->s != NULL); + + // init opengl and egl + const EGLint attribs[] = { + EGL_RED_SIZE, 8, + EGL_GREEN_SIZE, 8, + EGL_BLUE_SIZE, 8, + EGL_DEPTH_SIZE, 0, + EGL_STENCIL_SIZE, 8, + EGL_RENDERABLE_TYPE, EGL_OPENGL_ES3_BIT_KHR, + EGL_NONE, + }; + + s->display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(s->display != EGL_NO_DISPLAY); + + success = eglInitialize(s->display, &s->egl_major, &s->egl_minor); + assert(success); + + printf("egl version %d.%d\n", s->egl_major, s->egl_minor); + + EGLint num_configs; + success = eglChooseConfig(s->display, attribs, &s->config, 1, &num_configs); + assert(success); + + s->surface = eglCreateWindowSurface(s->display, s->config, s->s.get(), NULL); + assert(s->surface != EGL_NO_SURFACE); + + const EGLint context_attribs[] = { + EGL_CONTEXT_CLIENT_VERSION, 3, + EGL_NONE, + }; + s->context = eglCreateContext(s->display, s->config, NULL, context_attribs); + assert(s->context != EGL_NO_CONTEXT); + + EGLint w, h; + eglQuerySurface(s->display, s->surface, EGL_WIDTH, &w); + eglQuerySurface(s->display, s->surface, EGL_HEIGHT, &h); + printf("egl w %d h %d\n", w, h); + + success = eglMakeCurrent(s->display, s->surface, s->surface, s->context); + assert(success); + + printf("gl version %s\n", glGetString(GL_VERSION)); + + + // set brightness + int brightness_fd = open(BACKLIGHT_CONTROL, O_RDWR); + const char brightness_level[] = BACKLIGHT_LEVEL; + write(brightness_fd, brightness_level, strlen(brightness_level)); + + + if (out_display) *out_display = s->display; + if (out_surface) *out_surface = s->surface; + if (out_w) *out_w = w; + if (out_h) *out_h = h; + + return s; +} diff --git a/selfdrive/common/framebuffer.h b/selfdrive/common/framebuffer.h new file mode 100644 index 0000000000..cac8590398 --- /dev/null +++ b/selfdrive/common/framebuffer.h @@ -0,0 +1,21 @@ +#ifndef FRAMEBUFFER_H +#define FRAMEBUFFER_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct FramebufferState FramebufferState; + +FramebufferState* framebuffer_init( + const char* name, int32_t layer, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h); + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/mat.h b/selfdrive/common/mat.h new file mode 100644 index 0000000000..f429b0c5d3 --- /dev/null +++ b/selfdrive/common/mat.h @@ -0,0 +1,68 @@ +#ifndef COMMON_MAT_H +#define COMMON_MAT_H + +typedef struct vec3 { + float v[3]; +} vec3; + +typedef struct vec4 { + float v[4]; +} vec4; + +typedef struct mat3 { + float v[3*3]; +} mat3; + +typedef struct mat4 { + float v[4*4]; +} mat4; + +static inline mat3 matmul3(const mat3 a, const mat3 b) { + mat3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + float v = 0.0; + for (int k=0; k<3; k++) { + v += a.v[r*3+k] * b.v[k*3+c]; + } + ret.v[r*3+c] = v; + } + } + return ret; +} + +static inline vec3 matvecmul3(const mat3 a, const vec3 b) { + vec3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + ret.v[r] += a.v[r*3+c] * b.v[c]; + } + } + return ret; +} + +static inline mat4 matmul(const mat4 a, const mat4 b) { + mat4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + float v = 0.0; + for (int k=0; k<4; k++) { + v += a.v[r*4+k] * b.v[k*4+c]; + } + ret.v[r*4+c] = v; + } + } + return ret; +} + +static inline vec4 matvecmul(const mat4 a, const vec4 b) { + vec4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + ret.v[r] += a.v[r*4+c] * b.v[c]; + } + } + return ret; +} + +#endif diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h new file mode 100644 index 0000000000..521767775f --- /dev/null +++ b/selfdrive/common/modeldata.h @@ -0,0 +1,23 @@ +#ifndef MODELDATA_H +#define MODELDATA_H + +typedef struct PathData { + float points[50]; + float prob; + float std; +} PathData; + +typedef struct LeadData { + float dist; + float prob; + float std; +} LeadData; + +typedef struct ModelData { + PathData path; + PathData left_lane; + PathData right_lane; + LeadData lead; +} ModelData; + +#endif diff --git a/selfdrive/common/mutex.h b/selfdrive/common/mutex.h new file mode 100644 index 0000000000..ef01359357 --- /dev/null +++ b/selfdrive/common/mutex.h @@ -0,0 +1,13 @@ +#ifndef COMMON_MUTEX_H +#define COMMON_MUTEX_H + +#include + +static inline void mutex_init_reentrant(pthread_mutex_t *mutex) { + pthread_mutexattr_t attr; + pthread_mutexattr_init(&attr); + pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE); + pthread_mutex_init(mutex, &attr); +} + +#endif diff --git a/selfdrive/common/swaglog.c b/selfdrive/common/swaglog.c new file mode 100644 index 0000000000..8fc64aed8e --- /dev/null +++ b/selfdrive/common/swaglog.c @@ -0,0 +1,90 @@ +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "common/timing.h" + +#include "swaglog.h" + +typedef struct LogState { + pthread_mutex_t lock; + bool inited; + JsonNode *ctx_j; + void *zctx; + void *sock; +} LogState; + +static LogState s = { + .lock = PTHREAD_MUTEX_INITIALIZER, +}; + +static void cloudlog_init() { + if (s.inited) return; + s.ctx_j = json_mkobject(); + s.zctx = zmq_ctx_new(); + s.sock = zmq_socket(s.zctx, ZMQ_PUSH); + zmq_connect(s.sock, "ipc:///tmp/logmessage"); + s.inited = true; +} + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, + const char* fmt, ...) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + + char* msg_buf = NULL; + va_list args; + va_start(args, fmt); + vasprintf(&msg_buf, fmt, args); + va_end(args); + + if (!msg_buf) { + pthread_mutex_unlock(&s.lock); + return; + } + + if (levelnum >= CLOUDLOG_PRINT_LEVEL) { + printf("%s: %s\n", filename, msg_buf); + } + + JsonNode *log_j = json_mkobject(); + assert(log_j); + + json_append_member(log_j, "msg", json_mkstring(msg_buf)); + json_append_member(log_j, "ctx", s.ctx_j); + json_append_member(log_j, "levelnum", json_mknumber(levelnum)); + json_append_member(log_j, "filename", json_mkstring(filename)); + json_append_member(log_j, "lineno", json_mknumber(lineno)); + json_append_member(log_j, "funcname", json_mkstring(func)); + json_append_member(log_j, "srctime", json_mkstring(srctime)); + json_append_member(log_j, "created", json_mknumber(seconds_since_epoch())); + + char* log_s = json_encode(log_j); + assert(log_s); + + json_remove_from_parent(s.ctx_j); + + json_delete(log_j); + free(msg_buf); + + char levelnum_c = levelnum; + zmq_send(s.sock, &levelnum_c, 1, ZMQ_NOBLOCK | ZMQ_SNDMORE); + zmq_send(s.sock, log_s, strlen(log_s), ZMQ_NOBLOCK); + free(log_s); + + pthread_mutex_unlock(&s.lock); +} + +void cloudlog_bind(const char* k, const char* v) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + json_append_member(s.ctx_j, k, json_mkstring(v)); + pthread_mutex_unlock(&s.lock); +} diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h new file mode 100644 index 0000000000..50b01da66f --- /dev/null +++ b/selfdrive/common/swaglog.h @@ -0,0 +1,26 @@ +#ifndef SWAGLOG_H +#define SWAGLOG_H + +#define CLOUDLOG_DEBUG 10 +#define CLOUDLOG_INFO 20 +#define CLOUDLOG_WARNING 30 +#define CLOUDLOG_ERROR 40 +#define CLOUDLOG_CRITICAL 50 + +#define CLOUDLOG_PRINT_LEVEL CLOUDLOG_WARNING + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* srctime, + const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; + +void cloudlog_bind(const char* k, const char* v); + +#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ + __func__, __DATE__ " " __TIME__, \ + fmt, ## __VA_ARGS__) + +#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#endif diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h new file mode 100644 index 0000000000..f682c35dee --- /dev/null +++ b/selfdrive/common/timing.h @@ -0,0 +1,31 @@ +#ifndef COMMON_TIMING_H +#define COMMON_TIMING_H + +#include +#include + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double millis_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000.0 + t.tv_nsec / 1000000.0; +} + +static inline uint64_t nanos_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double seconds_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return (double)t.tv_sec + t.tv_nsec / 1000000000.0; +} + +#endif diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h new file mode 100644 index 0000000000..3bf3e9e387 --- /dev/null +++ b/selfdrive/common/util.h @@ -0,0 +1,22 @@ +#ifndef COMMON_UTIL_H +#define COMMON_UTIL_H + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#define clamp(a,b,c) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + __typeof__ (c) _c = (c); \ + _a < _b ? _b : (_a > _c ? _c : _a); }) + +#define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) + +#endif diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c new file mode 100644 index 0000000000..44463b4c94 --- /dev/null +++ b/selfdrive/common/visionipc.c @@ -0,0 +1,127 @@ +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "visionipc.h" + +typedef struct VisionPacketWire { + int type; + VisionPacketData d; +} VisionPacketWire; + +int vipc_connect() { + int err; + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + assert(sock >= 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + .sun_path = VIPC_SOCKET_PATH, + }; + err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (err != 0) { + close(sock); + return -1; + } + + return sock; +} + +static int sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds) { + int err; + + char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; + memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); + + struct iovec iov = { + .iov_base = buf, + .iov_len = buf_size, + }; + struct msghdr msg = { + .msg_iov = &iov, + .msg_iovlen = 1, + }; + + if (num_fds > 0) { + assert(fds); + + msg.msg_control = control_buf; + msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); + } + + if (send) { + if (num_fds) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + cmsg->cmsg_level = SOL_SOCKET; + cmsg->cmsg_type = SCM_RIGHTS; + cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); + memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); + // printf("send clen %d -> %d\n", num_fds, cmsg->cmsg_len); + } + return sendmsg(fd, &msg, 0); + } else { + int r = recvmsg(fd, &msg, 0); + if (r < 0) return r; + + int recv_fds = 0; + if (msg.msg_controllen > 0) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); + recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); + assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); + recv_fds /= sizeof(int); + // printf("recv clen %d -> %d\n", cmsg->cmsg_len, recv_fds); + // assert(cmsg->cmsg_len == CMSG_LEN(sizeof(int) * num_fds)); + + assert(fds && recv_fds <= num_fds); + memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); + } + + if (msg.msg_flags) { + for (int i=0; i 950 for t in cpu_temps) + + # *** getting model logic *** + PP.update(cur_time, CS.v_ego) + + if rk.frame % 5 == 2: + # *** run this at 20hz again *** + angle_offset = learn_angle_offset(enabled, CS.v_ego, angle_offset, np.asarray(PP.d_poly), LaC.y_des, CS.steer_override) + + # to avoid race conditions, check if control has been disabled for at least 0.2s + mismatch_ctrl = not CC.controls_allowed and enabled + mismatch_pcm = (not CS.pcm_acc_status and (not apply_brake or CS.v_ego < 0.1)) and enabled + + # keep resetting start timer if mismatch isn't true + if not mismatch_ctrl: + no_mismatch_ctrl_last = cur_time + if not mismatch_pcm or not CS.brake_only: + no_mismatch_pcm_last = cur_time + + #*** v_cruise logic *** + if CS.brake_only: + v_cruise = int(CS.v_cruise_pcm) # TODO: why sometimes v_cruise_pcm is long type? + else: + if CS.prev_cruise_buttons == 0 and CS.cruise_buttons == CruiseButtons.RES_ACCEL and enabled: + v_cruise = v_cruise - (v_cruise % v_cruise_delta) + v_cruise_delta + elif CS.prev_cruise_buttons == 0 and CS.cruise_buttons == CruiseButtons.DECEL_SET and enabled: + v_cruise = v_cruise + (v_cruise % v_cruise_delta) - v_cruise_delta + + # *** enabling/disabling logic *** + enable_pressed = (CS.prev_cruise_buttons == CruiseButtons.DECEL_SET or CS.prev_cruise_buttons == CruiseButtons.RES_ACCEL) \ + and CS.cruise_buttons == 0 + + if enable_pressed: + print "enabled pressed at", cur_time + last_enable_pressed = cur_time + + # if pcm does speed control than we need to wait on pcm to enable + if CS.brake_only: + enable_condition = (cur_time - last_enable_pressed) < 0.2 and CS.pcm_acc_status + else: + enable_condition = enable_pressed + + # always clear the alert at every cycle + alert_id = [] + + # check for PCM not enabling + if CS.brake_only and (cur_time - last_enable_pressed) < 0.2 and not CS.pcm_acc_status: + print "waiting for PCM to enable" + + # check for denied enabling + if enable_pressed and not enabled: + deny_enable = \ + [(AI.SEATBELT, not CS.seatbelt), + (AI.DOOR_OPEN, not CS.door_all_closed), + (AI.ESP_OFF, CS.esp_disabled), + (AI.STEER_ERROR, CS.steer_error), + (AI.BRAKE_ERROR, CS.brake_error), + (AI.GEAR_NOT_D, not CS.gear_shifter_valid), + (AI.MAIN_OFF, not CS.main_on), + (AI.PEDAL_PRESSED, CS.user_gas_pressed or CS.brake_pressed or (CS.pedal_gas > 0 and CS.brake_only)), + (AI.HIGH_SPEED, CS.v_ego > max_enable_speed), + (AI.OVERHEAT, overtemp), + (AI.COMM_ISSUE, PP.dead or AC.dead), + (AI.CONTROLSD_LAG, rk.remaining < -0.2)] + for alertn, cond in deny_enable: + if cond: + alert_id += [alertn] + + # check for soft disables + if enabled: + soft_disable = \ + [(AI.SEATBELT_SD, not CS.seatbelt), + (AI.DOOR_OPEN_SD, not CS.door_all_closed), + (AI.ESP_OFF_SD, CS.esp_disabled), + (AI.OVERHEAT_SD, overtemp), + (AI.COMM_ISSUE_SD, PP.dead or AC.dead), + (AI.CONTROLSD_LAG_SD, rk.remaining < -0.2)] + sounding = False + for alertn, cond in soft_disable: + if cond: + alert_id += [alertn] + sounding = True + # soft disengagement expired, user need to take control + if (cur_time - soft_disable_start) > 3.: + enabled = False + v_cruise = 255 + if not sounding: + soft_disable_start = cur_time + + # check for immediate disables + if enabled: + immediate_disable = \ + [(AI.PCM_LOW_SPEED, (cur_time > no_mismatch_pcm_last > 0.2) and CS.v_ego < pcm_threshold), + (AI.STEER_ERROR_ID, CS.steer_error), + (AI.BRAKE_ERROR_ID, CS.brake_error), + (AI.CTRL_MISMATCH_ID, (cur_time - no_mismatch_ctrl_last) > 0.2), + (AI.PCM_MISMATCH_ID, (cur_time - no_mismatch_pcm_last) > 0.2)] + for alertn, cond in immediate_disable: + if cond: + alert_id += [alertn] + # immediate turn off control + enabled = False + v_cruise = 255 + + # user disabling + if enabled and (CS.user_gas_pressed or CS.brake_pressed or not CS.gear_shifter_valid or \ + (CS.cruise_buttons == CruiseButtons.CANCEL and CS.prev_cruise_buttons == 0) or \ + not CS.main_on or (CS.pedal_gas > 0 and CS.brake_only)): + enabled = False + v_cruise = 255 + alert_id += [AI.DISABLE] + + # enabling + if enable_condition and not enabled and len(alert_id) == 0: + print "*** enabling controls" + + #enable both lateral and longitudinal controls + enabled = True + counter_pcm_enabled = CS.counter_pcm + # on activation, let's always set v_cruise from where we are, even if PCM ACC is active + # what we want to be displayed in mph + v_cruise_mph = round(CS.v_ego * CV.MS_TO_MPH * CS.ui_speed_fudge) + # what we need to send to have that displayed + v_cruise = int(round(np.maximum(v_cruise_mph * CV.MPH_TO_KPH, v_cruise_enable_min))) + + # 6 minutes driver you're on + awareness_status = 1.0 + + # reset the PID loops + LaC.reset() + # start long control at actual speed + LoC.reset(v_pid = CS.v_ego) + + alert_id += [AI.ENABLE] + + if v_cruise != 255 and not CS.brake_only: + v_cruise = np.clip(v_cruise, v_cruise_min, v_cruise_max) + + # **** awareness status manager **** + if enabled: + # gives the user 6 minutes + awareness_status -= 1.0/(100*60*6) + # reset on steering, blinker, or cruise buttons + if CS.steer_override or CS.blinker_on or CS.cruise_buttons or CS.cruise_setting: + awareness_status = 1.0 + if awareness_status <= 0.: + alert_id += [AI.DRIVER_DISTRACTED] + + # ****** initial actuators commands *** + # *** gas/brake PID loop *** + AC.update(cur_time, CS.v_ego, CS.angle_steers, LoC.v_pid, awareness_status, CS.VP) + final_gas, final_brake = LoC.update(enabled, CS, v_cruise, AC.v_target_lead, AC.a_target, AC.jerk_factor) + pcm_accel = int(np.clip(AC.a_pcm/1.4,0,1)*0xc6) # TODO: perc of max accel in ACC? + + # *** steering PID loop *** + final_steer, sat_flag = LaC.update(enabled, CS, PP.d_poly, angle_offset) + + # this needs to stay before hysteresis logic to avoid pcm staying on control during brake hysteresis + pcm_override = True # this is always True + pcm_cancel_cmd = False + if CS.brake_only and final_brake == 0.: + pcm_speed = LoC.v_pid - .3 # FIXME: just for exp + else: + pcm_speed = 0 + + # ***** handle alerts **** + # send a "steering required alert" if saturation count has reached the limit + if sat_flag: + alert_id += [AI.STEER_SATURATED] + + # process the alert, based on id + alert, chime, beep, hud_alert, alert_text, sound_exp, hud_exp, text_exp, alert_p = \ + process_alert(alert_id, alert, cur_time, sound_exp, hud_exp, text_exp, alert_p) + + # alerts pub + if len(alert_id) != 0: + print alert_id, alert_text + + # *** process for hud display *** + if not enabled or (hud_v_cruise == 255 and CS.counter_pcm == counter_pcm_enabled): + hud_v_cruise = 255 + else: + hud_v_cruise = v_cruise + + # *** actually do can sends *** + CC.update(sendcan, enabled, CS, rk.frame, \ + final_gas, final_brake, final_steer, \ + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + hud_v_cruise, hud_show_lanes = enabled, \ + hud_show_car = AC.has_lead, \ + hud_alert = hud_alert, \ + snd_beep = beep, snd_chime = chime) + + # ***** publish state to logger ***** + + # publish controls state at 100Hz + dat = messaging.new_message() + dat.init('live100') + + # move liveUI into live100 + dat.live100.rearViewCam = bool(rear_view_cam) + dat.live100.alertText1 = alert_text[0] + dat.live100.alertText2 = alert_text[1] + dat.live100.awarenessStatus = max(awareness_status, 0.0) if enabled else 0.0 + + # what packets were used to process + dat.live100.canMonoTimes = canMonoTimes + dat.live100.mdMonoTime = PP.logMonoTime + dat.live100.l20MonoTime = AC.logMonoTime + + # if controls is enabled + dat.live100.enabled = enabled + + # car state + dat.live100.vEgo = float(CS.v_ego) + dat.live100.aEgo = float(CS.a_ego) + dat.live100.angleSteers = float(CS.angle_steers) + dat.live100.hudLead = CS.hud_lead + dat.live100.steerOverride = CS.steer_override + + # longitudinal control state + dat.live100.vPid = float(LoC.v_pid) + dat.live100.vCruise = float(v_cruise) + dat.live100.upAccelCmd = float(LoC.Up_accel_cmd) + dat.live100.uiAccelCmd = float(LoC.Ui_accel_cmd) + + # lateral control state + dat.live100.yActual = float(LaC.y_actual) + dat.live100.yDes = float(LaC.y_des) + dat.live100.upSteer = float(LaC.Up_steer) + dat.live100.uiSteer = float(LaC.Ui_steer) + + # processed radar state, should add a_pcm? + dat.live100.vTargetLead = float(AC.v_target_lead) + dat.live100.aTargetMin = float(AC.a_target[0]) + dat.live100.aTargetMax = float(AC.a_target[1]) + dat.live100.jerkFactor = float(AC.jerk_factor) + + # lag + dat.live100.cumLagMs = -rk.remaining*1000. + + live100.send(dat.to_bytes()) + + # *** run loop at fixed rate *** + rk.keep_time() + +def main(gctx=None): + controlsd_thread(gctx, 100) + +if __name__ == "__main__": + main() diff --git a/selfdrive/controls/lib/__init__.py b/selfdrive/controls/lib/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/controls/lib/adaptivecruise.py b/selfdrive/controls/lib/adaptivecruise.py new file mode 100644 index 0000000000..bf940e0e1b --- /dev/null +++ b/selfdrive/controls/lib/adaptivecruise.py @@ -0,0 +1,332 @@ +import selfdrive.messaging as messaging +import numpy as np + +# lookup tables VS speed to determine min and max accels in cruise +_A_CRUISE_MIN_V = np.asarray([-1.0, -.8, -.67, -.5, -.30]) +_A_CRUISE_MIN_BP = np.asarray([ 0., 5., 10., 20., 40.]) + +# need fast accel at very low speed for stop and go +_A_CRUISE_MAX_V = np.asarray([1., 1., .8, .5, .30]) +_A_CRUISE_MAX_BP = np.asarray([0., 5., 10., 20., 40.]) + +def calc_cruise_accel_limits(v_ego): + a_cruise_min = np.interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) + a_cruise_max = np.interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V) + + a_pcm = 1. # always 1 for now + return np.vstack([a_cruise_min, a_cruise_max]), a_pcm + +_A_TOTAL_MAX_V = np.asarray([1.5, 1.9, 3.2]) +_A_TOTAL_MAX_BP = np.asarray([0., 20., 40.]) + +def limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP): + #*** this function returns a limited long acceleration allowed, depending on the existing lateral acceleration + # this should avoid accelerating when losing the target in turns + deg_to_rad = np.pi / 180. # from can reading to rad + + a_total_max = np.interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) + a_y = v_ego**2 * angle_steers * deg_to_rad / (VP.steer_ratio * VP.wheelbase) + a_x_allowed = np.sqrt(np.maximum(a_total_max**2 - a_y**2, 0.)) + + a_target[1] = np.minimum(a_target[1], a_x_allowed) + a_pcm = np.minimum(a_pcm, a_x_allowed) + return a_target, a_pcm + +def process_a_lead(a_lead): + # soft threshold of 0.5m/s^2 applied to a_lead to reject noise, also not considered positive a_lead + a_lead_threshold = 0.5 + a_lead = np.minimum(a_lead + a_lead_threshold, 0) + return a_lead + +def calc_desired_distance(v_lead): + #*** compute desired distance *** + t_gap = 1.7 # good to be far away + d_offset = 4 # distance when at zero speed + return d_offset + v_lead * t_gap + + +#linear slope +_L_SLOPE_V = np.asarray([0.40, 0.10]) +_L_SLOPE_BP = np.asarray([0., 40]) + +# parabola slope +_P_SLOPE_V = np.asarray([1.0, 0.25]) +_P_SLOPE_BP = np.asarray([0., 40]) + +def calc_desired_speed(d_lead, d_des, v_lead, a_lead): + #*** compute desired speed *** + # the desired speed curve is divided in 4 portions: + # 1-constant + # 2-linear to regain distance + # 3-linear to shorten distance + # 4-parabolic (constant decel) + + max_runaway_speed = -2. # no slower than 2m/s over the lead + + # interpolate the lookups to find the slopes for a give lead speed + l_slope = np.interp(v_lead, _L_SLOPE_BP, _L_SLOPE_V) + p_slope = np.interp(v_lead, _P_SLOPE_BP, _P_SLOPE_V) + + # this is where parabola and linear curves are tangents + x_linear_to_parabola = p_slope / l_slope**2 + + # parabola offset to have the parabola being tangent to the linear curve + x_parabola_offset = p_slope / (2 * l_slope**2) + + if d_lead < d_des: + # calculate v_rel_des on the line that connects 0m at max_runaway_speed to d_des + v_rel_des_1 = (- max_runaway_speed) / d_des * (d_lead - d_des) + # calculate v_rel_des on one third of the linear slope + v_rel_des_2 = (d_lead - d_des) * l_slope / 3. + # take the min of the 2 above + v_rel_des = np.minimum(v_rel_des_1, v_rel_des_2) + v_rel_des = np.maximum(v_rel_des, max_runaway_speed) + elif d_lead < d_des + x_linear_to_parabola: + v_rel_des = (d_lead - d_des) * l_slope + v_rel_des = np.maximum(v_rel_des, max_runaway_speed) + else: + v_rel_des = np.sqrt(2 * (d_lead - d_des - x_parabola_offset) * p_slope) + + # compute desired speed + v_target = v_rel_des + v_lead + + # compute v_coast: above this speed we want to coast + t_lookahead = 1. # how far in time we consider a_lead to anticipate the coast region + v_coast_shift = np.maximum(a_lead * t_lookahead, - v_lead) # don't consider projections that would make v_lead<0 + v_coast = (v_lead + v_target)/2 + v_coast_shift # no accel allowed above this line + v_coast = np.minimum(v_coast, v_target) + + return v_target, v_coast + +def calc_critical_decel(d_lead, v_rel, d_offset, v_offset): + # this function computes the required decel to avoid crashing, given safety offsets + a_critical = - np.maximum(0., v_rel + v_offset)**2/np.maximum(2*(d_lead - d_offset), 0.5) + return a_critical + + +# maximum acceleration adjustment +_A_CORR_BY_SPEED_V = np.asarray([0.4, 0.4, 0]) +# speeds +_A_CORR_BY_SPEED_BP = np.asarray([0., 5., 20.]) + +def calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_ref, v_rel_ref, v_coast, v_target, a_lead_contr, a_max): + a_coast_min = -1.0 # never coast faster then -1m/s^2 + # coasting behavior above v_coast. Forcing a_max to be negative will force the pid_speed to decrease, + # regardless v_target + if v_ref > np.minimum(v_coast, v_target): + # for smooth coast we can be agrressive and target a point where car would actually crash + v_offset_coast = 0. + d_offset_coast = d_des/2. - 4. + + # acceleration value to smoothly coast until we hit v_target + if d_lead > d_offset_coast + 0.1: + a_coast = calc_critical_decel(d_lead, v_rel_ref, d_offset_coast, v_offset_coast) + # if lead is decelerating, then offset the coast decel + a_coast += a_lead_contr + a_max = np.maximum(a_coast, a_coast_min) + else: + a_max = a_coast_min + else: + # same as cruise accel, but add a small correction based on lead acceleration at low speeds + # when lead car accelerates faster, we can do the same, and vice versa + + a_max = a_max + np.interp(v_ego, _A_CORR_BY_SPEED_BP, _A_CORR_BY_SPEED_V) \ + * np.clip(-v_rel / 4., -.5, 1) + return a_max + +# arbitrary limits to avoid too high accel being computed +_A_SAT = np.asarray([-10., 5.]) + +# do not consider a_lead at 0m/s, fully consider it at 10m/s +_A_LEAD_LOW_SPEED_V = np.asarray([0., 1.]) + +# speed break points +_A_LEAD_LOW_SPEED_BP = np.asarray([0., 10.]) + +# add a small offset to the desired decel, just for safety margin +_DECEL_OFFSET_V = np.asarray([-0.3, -0.5, -0.5, -0.4, -0.3]) + +# speed bp: different offset based on the likelyhood that lead decels abruptly +_DECEL_OFFSET_BP = np.asarray([0., 4., 15., 30, 40.]) + + +def calc_acc_accel_limits(d_lead, d_des, v_ego, v_pid, v_lead, v_rel, a_lead, + v_target, v_coast, a_target, a_pcm): + #*** compute max accel *** + # v_rel is now your velocity in lead car frame + v_rel = -v_rel # this simplifiess things when thinking in d_rel-v_rel diagram + + v_rel_pid = v_pid - v_lead + + # this is how much lead accel we consider in assigning the desired decel + a_lead_contr = a_lead * np.interp(v_lead, _A_LEAD_LOW_SPEED_BP, + _A_LEAD_LOW_SPEED_V) * 0.8 + + # first call of calc_positive_accel_limit is used to shape v_pid + a_target[1] = calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_pid, + v_rel_pid, v_coast, v_target, + a_lead_contr, a_target[1]) + # second call of calc_positive_accel_limit is used to limit the pcm throttle + # control (only useful when we don't control throttle directly) + a_pcm = calc_positive_accel_limit(d_lead, d_des, v_ego, v_rel, v_ego, v_rel, + v_coast, v_target, a_lead_contr, a_pcm) + + #*** compute max decel *** + v_offset = 1. # assume the car is 1m/s slower + d_offset = 1. # assume the distance is 1m lower + if v_target - v_ego > 0.5: + pass # acc target speed is above vehicle speed, so we can use the cruise limits + elif d_lead > d_offset + 0.01: # add small value to avoid by zero divisions + # compute needed accel to get to 1m distance with -1m/s rel speed + decel_offset = np.interp(v_lead, _DECEL_OFFSET_BP, _DECEL_OFFSET_V) + + critical_decel = calc_critical_decel(d_lead, v_rel, d_offset, v_offset) + a_target[0] = np.minimum(decel_offset + critical_decel + a_lead_contr, + a_target[0]) + else: + a_target[0] = _A_SAT[0] + # a_min can't be higher than a_max + a_target[0] = np.minimum(a_target[0], a_target[1]) + # final check on limits + a_target = np.clip(a_target, _A_SAT[0], _A_SAT[1]) + a_target = a_target.tolist() + return a_target, a_pcm + +def calc_jerk_factor(d_lead, v_rel): + # we don't have an explicit jerk limit, so this function calculates a factor + # that is used by the PID controller to scale the gains. Not the cleanest solution + # but we need this for the demo. + # TODO: Calculate Kp and Ki directly in this function. + + # the higher is the decel required to avoid a crash, the higher is the PI factor scaling + d_offset = 0.5 + v_offset = 2. + a_offset = 1. + jerk_factor_max = 1.0 # can't increase Kp and Ki more than double. + if d_lead < d_offset + 0.1: # add small value to avoid by zero divisions + jerk_factor = jerk_factor_max + else: + a_critical = - calc_critical_decel(d_lead, -v_rel, d_offset, v_offset) + # increase Kp and Ki by 20% for every 1m/s2 of decel required above 1m/s2 + jerk_factor = np.maximum(a_critical - a_offset, 0.)/5. + jerk_factor = np.minimum(jerk_factor, jerk_factor_max) + return jerk_factor + + +def calc_ttc(d_rel, v_rel, a_rel, v_lead): + # this function returns the time to collision (ttc), assuming that a_rel will stay constant + # TODO: Review these assumptions. + # change sign to rel quantities as it's going to be easier for calculations + v_rel = -v_rel + a_rel = -a_rel + + # assuming that closing gap a_rel comes from lead vehicle decel, then limit a_rel so that v_lead will get to zero in no sooner than t_decel + # this helps overweighting a_rel when v_lead is close to zero. + t_decel = 2. + a_rel = np.minimum(a_rel, v_lead/t_decel) + + delta = v_rel**2 + 2 * d_rel * a_rel + # assign an arbitrary high ttc value if there is no solution to ttc + if delta < 0.1: + ttc = 5. + elif np.sqrt(delta) + v_rel < 0.1: + ttc = 5. + else: + ttc = 2 * d_rel / (np.sqrt(delta) + v_rel) + return ttc + + +def limit_accel_driver_awareness(v_ego, a_target, a_pcm, awareness_status): + decel_bp = [0. , 40.] + decel_v = [-0.3, -0.2] + decel = np.interp(v_ego, decel_bp, decel_v) + # gives 18 seconds before decel begins (w 6 minute timeout) + if awareness_status < -0.05: + a_target[1] = np.minimum(a_target[1], decel) + a_target[0] = np.minimum(a_target[1], a_target[0]) + a_pcm = 0. + return a_target, a_pcm + +MAX_SPEED_POSSIBLE = 55. + +def compute_speed_with_leads(v_ego, angle_steers, v_pid, l1, l2, awareness_status, VP): + # drive limits + # TODO: Make lims function of speed (more aggressive at low speed). + a_lim = [-3., 1.5] + + #*** set target speed pretty high, as lead hasn't been considered yet + v_target_lead = MAX_SPEED_POSSIBLE + + #*** set accel limits as cruise accel/decel limits *** + a_target, a_pcm = calc_cruise_accel_limits(v_ego) + #*** limit max accel in sharp turns + a_target, a_pcm = limit_accel_in_turns(v_ego, angle_steers, a_target, a_pcm, VP) + jerk_factor = 0. + + if l1 is not None and l1.status: + #*** process noisy a_lead signal from radar processing *** + a_lead_p = process_a_lead(l1.aLeadK) + + #*** compute desired distance *** + d_des = calc_desired_distance(l1.vLead) + + #*** compute desired speed *** + v_target_lead, v_coast = calc_desired_speed(l1.dRel, d_des, l1.vLead, a_lead_p) + + if l2 is not None and l2.status: + #*** process noisy a_lead signal from radar processing *** + a_lead_p2 = process_a_lead(l2.aLeadK) + + #*** compute desired distance *** + d_des2 = calc_desired_distance(l2.vLead) + + #*** compute desired speed *** + v_target_lead2, v_coast2 = calc_desired_speed(l2.dRel, d_des2, l2.vLead, a_lead_p2) + + # listen to lead that makes you go slower + if v_target_lead2 < v_target_lead: + l1 = l2 + d_des, a_lead_p, v_target_lead, v_coast = d_des2, a_lead_p2, v_target_lead2, v_coast2 + + # l1 is the main lead now + + #*** compute accel limits *** + a_target1, a_pcm1 = calc_acc_accel_limits(l1.dRel, d_des, v_ego, v_pid, l1.vLead, + l1.vRel, a_lead_p, v_target_lead, v_coast, a_target, a_pcm) + + # we can now limit a_target to a_lim + a_target = np.clip(a_target1, a_lim[0], a_lim[1]) + a_pcm = np.clip(a_pcm1, a_lim[0], a_lim[1]).tolist() + + #*** compute max factor *** + jerk_factor = calc_jerk_factor(l1.dRel, l1.vRel) + + # force coasting decel if driver hasn't been controlling car in a while + a_target, a_pcm = limit_accel_driver_awareness(v_ego, a_target, a_pcm, awareness_status) + + return v_target_lead, a_target, a_pcm, jerk_factor + + +class AdaptiveCruise(object): + def __init__(self, live20): + self.live20 = live20 + self.last_cal = 0. + self.l1, self.l2 = None, None + self.logMonoTime = 0 + self.dead = True + def update(self, cur_time, v_ego, angle_steers, v_pid, awareness_status, VP): + l20 = messaging.recv_sock(self.live20) + if l20 is not None: + self.l1 = l20.live20.leadOne + self.l2 = l20.live20.leadTwo + self.logMonoTime = l20.logMonoTime + + # TODO: no longer has anything to do with calibration + self.last_cal = cur_time + self.dead = False + elif cur_time - self.last_cal > 0.5: + self.dead = True + + self.v_target_lead, self.a_target, self.a_pcm, self.jerk_factor = \ + compute_speed_with_leads(v_ego, angle_steers, v_pid, self.l1, self.l2, awareness_status, VP) + self.has_lead = self.v_target_lead != MAX_SPEED_POSSIBLE diff --git a/selfdrive/controls/lib/alert_database.py b/selfdrive/controls/lib/alert_database.py new file mode 100644 index 0000000000..7b74afb641 --- /dev/null +++ b/selfdrive/controls/lib/alert_database.py @@ -0,0 +1,178 @@ +alerts = [] +keys = ["id", + "chime", + "beep", + "hud_alert", + "screen_chime", + "priority", + "text_line_1", + "text_line_2", + "duration_sound", + "duration_hud_alert", + "duration_text"] + + +#car chimes: enumeration from dbc file. Chimes are for alerts and warnings +class CM: + MUTE = 0 + SINGLE = 3 + DOUBLE = 4 + REPEATED = 1 + CONTINUOUS = 2 + + +#car beepss: enumeration from dbc file. Beeps are for activ and deactiv +class BP: + MUTE = 0 + SINGLE = 3 + TRIPLE = 2 + REPEATED = 1 + + +# lert ids +class AI: + ENABLE = 0 + DISABLE = 1 + SEATBELT = 2 + DOOR_OPEN = 3 + PEDAL_PRESSED = 4 + COMM_ISSUE = 5 + ESP_OFF = 6 + FCW = 7 + STEER_ERROR = 8 + BRAKE_ERROR = 9 + CALIB_INCOMPLETE = 10 + CALIB_INVALID = 11 + GEAR_NOT_D = 12 + MAIN_OFF = 13 + STEER_SATURATED = 14 + PCM_LOW_SPEED = 15 + THERMAL_DEAD = 16 + OVERHEAT = 17 + HIGH_SPEED = 18 + CONTROLSD_LAG = 19 + STEER_ERROR_ID = 100 + BRAKE_ERROR_ID = 101 + PCM_MISMATCH_ID = 102 + CTRL_MISMATCH_ID = 103 + SEATBELT_SD = 200 + DOOR_OPEN_SD = 201 + COMM_ISSUE_SD = 202 + ESP_OFF_SD = 203 + THERMAL_DEAD_SD = 204 + OVERHEAT_SD = 205 + CONTROLSD_LAG_SD = 206 + CALIB_INCOMPLETE_SD = 207 + CALIB_INVALID_SD = 208 + DRIVER_DISTRACTED = 300 + +class AH: + #[alert_idx, value] + # See dbc files for info on values" + NONE = [0, 0] + FCW = [1, 0x8] + STEER = [2, 1] + BRAKE_PRESSED = [3, 10] + GEAR_NOT_D = [4, 6] + SEATBELT = [5, 5] + SPEED_TOO_HIGH = [6, 8] + +class ET: + ENABLE = 0 + NO_ENTRY = 1 + WARNING = 2 + SOFT_DISABLE = 3 + IMMEDIATE_DISABLE = 4 + USER_DISABLE = 5 + +def process_alert(alert_id, alert, cur_time, sound_exp, hud_exp, text_exp, alert_p): + # INPUTS: + # alert_id is mapped to the alert properties in alert_database + # cur_time is current time + # sound_exp is when the alert beep/chime is supposed to end + # hud_exp is when the hud visual is supposed to end + # text_exp is when the alert text is supposed to disappear + # alert_p is the priority of the current alert + # CM, BP, AH are classes defined in alert_database and they respresents chimes, beeps and hud_alerts + if len(alert_id) > 0: + # take the alert with higher priority + alerts_present = filter(lambda a_id: a_id['id'] in alert_id, alerts) + alert = sorted(alerts_present, key=lambda k: k['priority'])[-1] + # check if we have a more important alert + if alert['priority'] > alert_p: + alert_p = alert['priority'] + sound_exp = cur_time + alert['duration_sound'] + hud_exp = cur_time + alert['duration_hud_alert'] + text_exp = cur_time + alert['duration_text'] + + chime = CM.MUTE + beep = BP.MUTE + if cur_time < sound_exp: + chime = alert['chime'] + beep = alert['beep'] + + hud_alert = AH.NONE + if cur_time < hud_exp: + hud_alert = alert['hud_alert'] + + alert_text = ["", ""] + if cur_time < text_exp: + alert_text = [alert['text_line_1'], alert['text_line_2']] + + if chime == CM.MUTE and beep == BP.MUTE and hud_alert == AH.NONE: #and alert_text[0] is None and alert_text[1] is None: + alert_p = 0 + return alert, chime, beep, hud_alert, alert_text, sound_exp, hud_exp, text_exp, alert_p + +def process_hud_alert(hud_alert): + # initialize to no alert + fcw_display = 0 + steer_required = 0 + acc_alert = 0 + if hud_alert == AH.NONE: # no alert + pass + elif hud_alert == AH.FCW: # FCW + fcw_display = hud_alert[1] + elif hud_alert == AH.STEER: # STEER + steer_required = hud_alert[1] + else: # any other ACC alert + acc_alert = hud_alert[1] + + return fcw_display, steer_required, acc_alert + +def app_alert(alert_add): + alerts.append(dict(zip(keys, alert_add))) + +app_alert([AI.ENABLE, CM.MUTE, BP.SINGLE, AH.NONE, ET.ENABLE, 2, "", "", .2, 0., 0.]) +app_alert([AI.DISABLE, CM.MUTE, BP.SINGLE, AH.NONE, ET.USER_DISABLE, 2, "", "", .2, 0., 0.]) +app_alert([AI.SEATBELT, CM.DOUBLE, BP.MUTE, AH.SEATBELT, ET.NO_ENTRY, 1, "Comma Unavailable", "Seatbelt Unlatched", .4, 2., 3.]) +app_alert([AI.DOOR_OPEN, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Door Open", .4, 0., 3.]) +app_alert([AI.PEDAL_PRESSED, CM.DOUBLE, BP.MUTE, AH.BRAKE_PRESSED, ET.NO_ENTRY, 1, "Comma Unavailable", "Pedal Pressed", .4, 2., 3.]) +app_alert([AI.COMM_ISSUE, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Communcation Issues", .4, 0., 3.]) +app_alert([AI.ESP_OFF, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "ESP Off", .4, 0., 3.]) +app_alert([AI.FCW, CM.REPEATED, BP.MUTE, AH.FCW, ET.WARNING, 3, "Risk of Collision", "", 1., 2., 3.]) +app_alert([AI.STEER_ERROR, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Steer Error", .4, 0., 3.]) +app_alert([AI.BRAKE_ERROR, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Brake Error", .4, 0., 3.]) +app_alert([AI.CALIB_INCOMPLETE, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Calibration in Progress", .4, 0., 3.]) +app_alert([AI.CALIB_INVALID, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Calibration Error", .4, 0., 3.]) +app_alert([AI.GEAR_NOT_D, CM.DOUBLE, BP.MUTE, AH.GEAR_NOT_D, ET.NO_ENTRY, 1, "Comma Unavailable", "Gear not in D", .4, 2., 3.]) +app_alert([AI.MAIN_OFF, CM.MUTE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Main Switch Off", .4, 0., 3.]) +app_alert([AI.STEER_SATURATED, CM.SINGLE, BP.MUTE, AH.STEER, ET.WARNING, 2, "Take Control", "Steer Control Saturated", 1., 2., 3.]) +app_alert([AI.PCM_LOW_SPEED, CM.MUTE, BP.SINGLE, AH.STEER, ET.WARNING, 2, "Comma disengaged", "Speed too low", .2, 2., 3.]) +app_alert([AI.THERMAL_DEAD, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Thermal Unavailable", .4, 0., 3.]) +app_alert([AI.OVERHEAT, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "System Overheated", .4, 0., 3.]) +app_alert([AI.HIGH_SPEED, CM.DOUBLE, BP.MUTE, AH.SPEED_TOO_HIGH, ET.NO_ENTRY, 1, "Comma Unavailable", "Speed Too High", .4, 2., 3.]) +app_alert([AI.CONTROLSD_LAG, CM.DOUBLE, BP.MUTE, AH.NONE, ET.NO_ENTRY, 1, "Comma Unavailable", "Controls Lagging", .4, 0., 3.]) +app_alert([AI.STEER_ERROR_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Steer Error", 1., 3., 3.]) +app_alert([AI.BRAKE_ERROR_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Brake Error", 1., 3., 3.]) +app_alert([AI.PCM_MISMATCH_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Pcm Mismatch", 1., 3., 3.]) +app_alert([AI.CTRL_MISMATCH_ID, CM.REPEATED, BP.MUTE, AH.STEER, ET.IMMEDIATE_DISABLE, 3, "Take Control Immediately", "Ctrl Mismatch", 1., 3., 3.]) +app_alert([AI.SEATBELT_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Seatbelt Unlatched", 1., 3., 3.]) +app_alert([AI.DOOR_OPEN_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Door Open", 1., 3., 3.]) +app_alert([AI.COMM_ISSUE_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Technical Issues", 1., 3., 3.]) +app_alert([AI.ESP_OFF_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "ESP Off", 1., 3., 3.]) +app_alert([AI.THERMAL_DEAD_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Thermal Unavailable", 1., 3., 3.]) +app_alert([AI.OVERHEAT_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "System Overheated", 1., 3., 3.]) +app_alert([AI.CONTROLSD_LAG_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Controls Lagging", 1., 3., 3.]) +app_alert([AI.CALIB_INCOMPLETE_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Calibration in Progress", 1., 3., 3.]) +app_alert([AI.CALIB_INVALID_SD, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 3, "Take Control Immediately", "Calibration Error", 1., 3., 3.]) +app_alert([AI.DRIVER_DISTRACTED, CM.REPEATED, BP.MUTE, AH.STEER, ET.SOFT_DISABLE, 2, "Take Control to Regain Speed", "User Distracted", 1., 1., 1.]) diff --git a/selfdrive/controls/lib/can_parser.py b/selfdrive/controls/lib/can_parser.py new file mode 100644 index 0000000000..7bd8dd54ee --- /dev/null +++ b/selfdrive/controls/lib/can_parser.py @@ -0,0 +1,123 @@ +import os +import dbcs +from collections import defaultdict + +from selfdrive.controls.lib.hondacan import fix +from common.realtime import sec_since_boot +from common.dbc import dbc + +class CANParser(object): + def __init__(self, dbc_f, signals, checks=[]): + ### input: + # dbc_f : dbc file + # signals : List of tuples (name, address, ival) where + # - name is the signal name. + # - address is the corresponding message address. + # - ival is the initial value. + # checks : List of pairs (address, frequency) where + # - address is the message address of a message for which health should be + # monitored. + # - frequency is the frequency at which health should be monitored. + + self.msgs_ck = [check[0] for check in checks] + self.frqs = [check[1] for check in checks] + self.can_valid = False # start with False CAN assumption + self.msgs_upd = [] # list of updated messages + # list of received msg we want to monitor counter and checksum for + # read dbc file + self.can_dbc = dbc(os.path.join(dbcs.DBC_PATH, dbc_f)) + # initialize variables to initial values + self.vl = {} # signal values + self.ts = {} # time stamp recorded in log + self.ct = {} # current time stamp + self.ok = {} # valid message? + self.cn = {} # message counter + self.cn_vl = {} # message counter mismatch value + self.ck = {} # message checksum status + + for _, addr, _ in signals: + self.vl[addr] = {} + self.ts[addr] = 0 + self.ct[addr] = sec_since_boot() + self.ok[addr] = False + self.cn[addr] = 0 + self.cn_vl[addr] = 0 + self.ck[addr] = False + + for name, addr, ival in signals: + self.vl[addr][name] = ival + + self._msgs = [s[1] for s in signals] + self._sgs = [s[0] for s in signals] + + self._message_indices = defaultdict(list) + for i, x in enumerate(self._msgs): + self._message_indices[x].append(i) + + def update_can(self, can_recv): + self.msgs_upd = [] + cn_vl_max = 5 # no more than 5 wrong counter checks + + # we are subscribing to PID_XXX, else data from USB + for msg, ts, cdat in can_recv: + idxs = self._message_indices[msg] + if idxs: + self.msgs_upd += [msg] + # read the entire message + out = self.can_dbc.decode([msg, 0, cdat])[1] + # checksum check + self.ck[msg] = True + if "CHECKSUM" in out.keys() and msg in self.msgs_ck: + # remove checksum (half byte) + ck_portion = (''.join((cdat[:-1], '0'))).decode('hex') + # recalculate checksum + msg_vl = fix(ck_portion, msg) + # compare recalculated vs received checksum + if msg_vl != cdat.decode('hex'): + print hex(msg), "CHECKSUM FAIL" + self.ck[msg] = False + self.ok[msg] = False + # counter check + cn = 0 + if "COUNTER" in out.keys(): + cn = out["COUNTER"] + # check counter validity if it's a relevant message + if cn != ((self.cn[msg] + 1) % 4) and msg in self.msgs_ck and "COUNTER" in out.keys(): + #print hex(msg), "FAILED COUNTER!" + self.cn_vl[msg] += 1 # counter check failed + else: + self.cn_vl[msg] -= 1 # counter check passed + # message status is invalid if we received too many wrong counter values + if self.cn_vl[msg] >= cn_vl_max: + self.ok[msg] = False + + # update msg time stamps and counter value + self.ts[msg] = ts + self.ct[msg] = sec_since_boot() + self.cn[msg] = cn + self.cn_vl[msg] = min(max(self.cn_vl[msg], 0), cn_vl_max) + + # set msg valid status if checksum is good and wrong counter counter is zero + if self.ck[msg] and self.cn_vl[msg] == 0: + self.ok[msg] = True + + # update value of signals in the + for ii in idxs: + sg = self._sgs[ii] + self.vl[msg][sg] = out[sg] + + # for each message, check if it's too long since last time we received it + self._check_dead_msgs() + + # assess overall can validity: if there is one relevant message invalid, then set can validity flag to False + self.can_valid = True + if False in self.ok.values(): + print "CAN INVALID!" + self.can_valid = False + + def _check_dead_msgs(self): + ### input: + ## simple stuff for now: msg is not valid if a message isn't received for 10 consecutive steps + for msg in set(self._msgs): + if msg in self.msgs_ck and sec_since_boot() - self.ct[msg] > 10./self.frqs[self.msgs_ck.index(msg)]: + self.ok[msg] = False diff --git a/selfdrive/controls/lib/carcontroller.py b/selfdrive/controls/lib/carcontroller.py new file mode 100644 index 0000000000..6c3766d387 --- /dev/null +++ b/selfdrive/controls/lib/carcontroller.py @@ -0,0 +1,185 @@ +from collections import namedtuple + +import common.numpy_fast as np +import selfdrive.controls.lib.hondacan as hondacan +from common.realtime import sec_since_boot +from selfdrive.config import CruiseButtons +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.controls.lib.alert_database import process_hud_alert +from selfdrive.controls.lib.drive_helpers import actuator_hystereses, rate_limit + +HUDData = namedtuple("HUDData", + ["pcm_accel", "v_cruise", "X2", "car", "X4", "X5", + "lanes", "beep", "X8", "chime", "acc_alert"]) + +class CarController(object): + def __init__(self): + self.controls_allowed = False + self.mismatch_start, self.pcm_mismatch_start = 0, 0 + self.braking = False + self.brake_steady = 0. + self.final_brake_last = 0. + + def update(self, sendcan, enabled, CS, frame, final_gas, final_brake, final_steer, \ + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \ + snd_beep, snd_chime): + """ Controls thread """ + + # *** apply brake hysteresis *** + final_brake, self.braking, self.brake_steady = actuator_hystereses(final_brake, self.braking, self.brake_steady, CS.v_ego, CS.civic) + + # *** no output if not enabled *** + if not enabled: + final_gas = 0. + final_brake = 0. + final_steer = 0. + # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated + if CS.pcm_acc_status: + pcm_cancel_cmd = True + + # *** rate limit after the enable check *** + final_brake = rate_limit(final_brake, self.final_brake_last, -2., 1./100) + self.final_brake_last = final_brake + + # vehicle hud display, wait for one update from 10Hz 0x304 msg + #TODO: use enum!! + if hud_show_lanes: + hud_lanes = 0x04 + else: + hud_lanes = 0x00 + + # TODO: factor this out better + if enabled: + if hud_show_car: + hud_car = 0xe0 + else: + hud_car = 0xd0 + else: + hud_car = 0xc0 + + #print chime, alert_id, hud_alert + fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) + + hud = HUDData(pcm_accel, hud_v_cruise, 0x41, hud_car, + 0xc1, 0x41, hud_lanes + steer_required, + snd_beep, 0x48, (snd_chime << 5) + fcw_display, acc_alert) + + if not all(isinstance(x, int) and 0 <= x < 256 for x in hud): + print "INVALID HUD", hud + hud = HUDData(0xc6, 255, 64, 0xc0, 209, 0x41, 0x40, 0, 0x48, 0, 0) + + # **** process the car messages **** + + user_brake_ctrl = CS.user_brake/0.015625 # FIXME: factor needed to convert to old scale + + # *** compute control surfaces *** + tt = sec_since_boot() + GAS_MAX = 1004 + BRAKE_MAX = 1024/4 + #STEER_MAX = 0xF00 if not CS.torque_mod else 0xF00/4 # ilx has 8x steering torque limit, used as a 2x + STEER_MAX = 0xF00 # ilx has 8x steering torque limit, used as a 2x + GAS_OFFSET = 328 + + # steer torque is converted back to CAN reference (positive when steering right) + apply_gas = int(np.clip(final_gas*GAS_MAX, 0, GAS_MAX-1)) + apply_brake = int(np.clip(final_brake*BRAKE_MAX, 0, BRAKE_MAX-1)) + apply_steer = int(np.clip(-final_steer*STEER_MAX, -STEER_MAX, STEER_MAX)) + + # no gas if you are hitting the brake or the user is + if apply_gas > 0 and (apply_brake != 0 or user_brake_ctrl > 10): + print "CANCELLING GAS", apply_brake, user_brake_ctrl + apply_gas = 0 + + # no computer brake if the user is hitting the gas + # if the computer is trying to brake, it can't be hitting the gas + # TODO: car_gas can override brakes without canceling... this is bad + if CS.car_gas > 0 and apply_brake != 0: + apply_brake = 0 + + if (CS.prev_cruise_buttons == CruiseButtons.DECEL_SET or CS.prev_cruise_buttons == CruiseButtons.RES_ACCEL) and \ + CS.cruise_buttons == 0 and not self.controls_allowed: + print "CONTROLS ARE LIVE" + self.controls_allowed = True + + # to avoid race conditions, check if control has been disabled for at least 0.2s + # keep resetting start timer if mismatch isn't true + if not (self.controls_allowed and not enabled): + self.mismatch_start = tt + + # to avoid race conditions, check if control is disabled but pcm control is on for at least 0.2s + if not (not self.controls_allowed and CS.pcm_acc_status): + self.pcm_mismatch_start = tt + + # something is very wrong, since pcm control is active but controls should not be allowed; TODO: send pcm fault cmd? + if (tt - self.pcm_mismatch_start) > 0.2: + pcm_cancel_cmd = True + + # TODO: clean up gear condition, ideally only D (and P for debug) shall be valid gears + if (CS.cruise_buttons == CruiseButtons.CANCEL or CS.brake_pressed or + CS.user_gas_pressed or (tt - self.mismatch_start) > 0.2 or + not CS.main_on or not CS.gear_shifter_valid or + (CS.pedal_gas > 0 and CS.brake_only)) and self.controls_allowed: + self.controls_allowed = False + + # 5 is a permanent fault, no torque request will be fullfilled + if CS.steer_error: + print "STEER ERROR" + self.controls_allowed = False + + # any other cp.vl[0x18F]['STEER_STATUS'] is common and can happen during user override. sending 0 torque to avoid EPS sending error 5 + elif CS.steer_not_allowed: + print "STEER ALERT, TORQUE INHIBITED" + apply_steer = 0 + + if CS.brake_error: + print "BRAKE ERROR" + self.controls_allowed = False + + if not CS.can_valid and self.controls_allowed: # 200 ms + print "CAN INVALID" + self.controls_allowed = False + + if not self.controls_allowed: + apply_steer = 0 + apply_gas = 0 + apply_brake = 0 + pcm_speed = 0 # make sure you send 0 target speed to pcm + #pcm_cancel_cmd = 1 # prevent pcm control from turning on. FIXME: we can't just do this + + # Send CAN commands. + can_sends = [] + + # Send steering command. + idx = frame % 4 + can_sends.append(hondacan.create_steering_control(apply_steer, idx)) + + # Send gas and brake commands. + if (frame % 2) == 0: + idx = (frame / 2) % 4 + can_sends.append( + hondacan.create_brake_command(apply_brake, pcm_override, + pcm_cancel_cmd, hud.chime, idx)) + + if not CS.brake_only: + # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. + # This prevents unexpected pedal range rescaling + gas_amount = (apply_gas + GAS_OFFSET) * (apply_gas > 0) + can_sends.append(hondacan.create_gas_command(gas_amount, idx)) + + # Send dashboard UI commands. + if (frame % 10) == 0: + idx = (frame/10) % 4 + can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.civic, idx)) + + # radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug) + if CS.civic: + radar_send_step = 5 + else: + radar_send_step = 2 + + if (frame % radar_send_step) == 0: + idx = (frame/radar_send_step) % 4 + can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.civic, idx)) + + sendcan.send(can_list_to_can_capnp(can_sends).to_bytes()) diff --git a/selfdrive/controls/lib/carstate.py b/selfdrive/controls/lib/carstate.py new file mode 100644 index 0000000000..5ac3b138ef --- /dev/null +++ b/selfdrive/controls/lib/carstate.py @@ -0,0 +1,275 @@ +import numpy as np + +import selfdrive.messaging as messaging +from selfdrive.boardd.boardd import can_capnp_to_can_list_old, can_capnp_to_can_list +from selfdrive.controls.lib.can_parser import CANParser +from selfdrive.controls.lib.fingerprints import fingerprints +from selfdrive.config import VehicleParams +from common.realtime import sec_since_boot + + +def get_can_parser(civic, brake_only): + # this function generates lists for signal, messages and initial values + if civic: + dbc_f = 'honda_civic_touring_2016_can.dbc' + signals = [ + ("XMISSION_SPEED", 0x158, 0), + ("WHEEL_SPEED_FL", 0x1d0, 0), + ("WHEEL_SPEED_FR", 0x1d0, 0), + ("WHEEL_SPEED_RL", 0x1d0, 0), + ("STEER_ANGLE", 0x14a, 0), + ("STEER_TORQUE_SENSOR", 0x18f, 0), + ("GEAR", 0x191, 0), + ("WHEELS_MOVING", 0x1b0, 1), + ("DOOR_OPEN_FL", 0x405, 1), + ("DOOR_OPEN_FR", 0x405, 1), + ("DOOR_OPEN_RL", 0x405, 1), + ("DOOR_OPEN_RR", 0x405, 1), + ("CRUISE_SPEED_PCM", 0x324, 0), + ("SEATBELT_DRIVER_LAMP", 0x305, 1), + ("SEATBELT_DRIVER_LATCHED", 0x305, 0), + ("BRAKE_PRESSED", 0x17c, 0), + ("CAR_GAS", 0x130, 0), + ("CRUISE_BUTTONS", 0x296, 0), + ("ESP_DISABLED", 0x1a4, 1), + ("HUD_LEAD", 0x30c, 0), + ("USER_BRAKE", 0x1a4, 0), + ("STEER_STATUS", 0x18f, 5), + ("WHEEL_SPEED_RR", 0x1d0, 0), + ("BRAKE_ERROR_1", 0x1b0, 1), + ("BRAKE_ERROR_2", 0x1b0, 1), + ("GEAR_SHIFTER", 0x191, 0), + ("MAIN_ON", 0x326, 0), + ("ACC_STATUS", 0x17c, 0), + ("PEDAL_GAS", 0x17c, 0), + ("CRUISE_SETTING", 0x296, 0), + ("LEFT_BLINKER", 0x326, 0), + ("RIGHT_BLINKER", 0x326, 0), + ("COUNTER", 0x324, 0), + ] + checks = [ + (0x14a, 100), + (0x158, 100), + (0x17c, 100), + (0x191, 100), + (0x1a4, 50), + (0x326, 10), + (0x1b0, 50), + (0x1d0, 50), + (0x305, 10), + (0x324, 10), + (0x405, 3), + ] + + else: + dbc_f = 'acura_ilx_2016_can.dbc' + signals = [ + ("XMISSION_SPEED", 0x158, 0), + ("WHEEL_SPEED_FL", 0x1d0, 0), + ("WHEEL_SPEED_FR", 0x1d0, 0), + ("WHEEL_SPEED_RL", 0x1d0, 0), + ("STEER_ANGLE", 0x156, 0), + ("STEER_TORQUE_SENSOR", 0x18f, 0), + ("GEAR", 0x1a3, 0), + ("WHEELS_MOVING", 0x1b0, 1), + ("DOOR_OPEN_FL", 0x405, 1), + ("DOOR_OPEN_FR", 0x405, 1), + ("DOOR_OPEN_RL", 0x405, 1), + ("DOOR_OPEN_RR", 0x405, 1), + ("CRUISE_SPEED_PCM", 0x324, 0), + ("SEATBELT_DRIVER_LAMP", 0x305, 1), + ("SEATBELT_DRIVER_LATCHED", 0x305, 0), + ("BRAKE_PRESSED", 0x17c, 0), + ("CAR_GAS", 0x130, 0), + ("CRUISE_BUTTONS", 0x1a6, 0), + ("ESP_DISABLED", 0x1a4, 1), + ("HUD_LEAD", 0x30c, 0), + ("USER_BRAKE", 0x1a4, 0), + ("STEER_STATUS", 0x18f, 5), + ("WHEEL_SPEED_RR", 0x1d0, 0), + ("BRAKE_ERROR_1", 0x1b0, 1), + ("BRAKE_ERROR_2", 0x1b0, 1), + ("GEAR_SHIFTER", 0x1a3, 0), + ("MAIN_ON", 0x1a6, 0), + ("ACC_STATUS", 0x17c, 0), + ("PEDAL_GAS", 0x17c, 0), + ("CRUISE_SETTING", 0x1a6, 0), + ("LEFT_BLINKER", 0x294, 0), + ("RIGHT_BLINKER", 0x294, 0), + ("COUNTER", 0x324, 0), + ] + checks = [ + (0x156, 100), + (0x158, 100), + (0x17c, 100), + (0x1a3, 50), + (0x1a4, 50), + (0x1a6, 50), + (0x1b0, 50), + (0x1d0, 50), + (0x305, 10), + (0x324, 10), + (0x405, 3), + ] + + # add gas interceptor reading if we are using it + if not brake_only: + signals.append(("INTERCEPTOR_GAS", 0x201, 0)) + checks.append((0x201, 50)) + + return CANParser(dbc_f, signals, checks) + +def fingerprint(logcan): + print "waiting for fingerprint..." + brake_only = True + + finger = {} + st = None + while 1: + possible_cars = [] + for a in messaging.drain_sock(logcan, wait_for_one=True): + if st is None: + st = sec_since_boot() + for adr, _, msg, idx in can_capnp_to_can_list(a): + # pedal + if adr == 0x201 and idx == 0: + brake_only = False + if idx == 0: + finger[adr] = len(msg) + + # check for a single match + for f in fingerprints: + is_possible = True + for adr in finger: + # confirm all messages we have seen match + if adr not in fingerprints[f] or fingerprints[f][adr] != finger[adr]: + #print "mismatch", f, adr + is_possible = False + break + if is_possible: + possible_cars.append(f) + + # if we only have one car choice and it's been 100ms since we got our first message, exit + if len(possible_cars) == 1 and st is not None and (sec_since_boot()-st) > 0.1: + break + elif len(possible_cars) == 0: + raise Exception("car doesn't match any fingerprints") + + print "fingerprinted", possible_cars[0] + return brake_only, possible_cars[0] + +class CarState(object): + def __init__(self, logcan): + self.torque_mod = False + self.brake_only, self.car_type = fingerprint(logcan) + + # assuming if you have a pedal interceptor you also have a torque mod + if not self.brake_only: + self.torque_mod = True + + if self.car_type == "HONDA CIVIC 2016 TOURING": + self.civic = True + elif self.car_type == "ACURA ILX 2016 ACURAWATCH PLUS": + self.civic = False + else: + raise ValueError("unsupported car %s" % self.car_type) + + # initialize can parser + self.cp = get_can_parser(self.civic, self.brake_only) + + self.user_gas, self.user_gas_pressed = 0., 0 + + self.cruise_buttons = 0 + self.cruise_setting = 0 + self.blinker_on = 0 + + # TODO: actually make this work + self.a_ego = 0. + + # speed in UI is shown as few % higher + self.ui_speed_fudge = 1.01 if self.civic else 1.025 + + # load vehicle params + self.VP = VehicleParams(self.civic) + + def update(self, logcan): + # ******************* do can recv ******************* + can_pub_main = [] + canMonoTimes = [] + for a in messaging.drain_sock(logcan): + canMonoTimes.append(a.logMonoTime) + can_pub_main.extend(can_capnp_to_can_list_old(a, [0,2])) + + cp = self.cp + cp.update_can(can_pub_main) + + # copy can_valid + self.can_valid = cp.can_valid + + # car params + v_weight_v = [0., 1. ] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero + + # update prevs, update must run once per loop + self.prev_cruise_buttons = self.cruise_buttons + self.prev_cruise_setting = self.cruise_setting + self.prev_blinker_on = self.blinker_on + + # ******************* parse out can ******************* + self.door_all_closed = not any([cp.vl[0x405]['DOOR_OPEN_FL'], cp.vl[0x405]['DOOR_OPEN_FR'], + cp.vl[0x405]['DOOR_OPEN_RL'], cp.vl[0x405]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl[0x305]['SEATBELT_DRIVER_LAMP'] and cp.vl[0x305]['SEATBELT_DRIVER_LATCHED'] + # error 2 = temporary + # error 4 = temporary, hit a bump + # error 5 (permanent) + # error 6 = temporary + # error 7 (permanent) + #self.steer_error = cp.vl[0x18F]['STEER_STATUS'] in [5,7] + # whitelist instead of blacklist, safer at the expense of disengages + self.steer_error = cp.vl[0x18F]['STEER_STATUS'] not in [0,2,4,6] + self.steer_not_allowed = cp.vl[0x18F]['STEER_STATUS'] != 0 + if cp.vl[0x18F]['STEER_STATUS'] != 0: + print cp.vl[0x18F]['STEER_STATUS'] + self.brake_error = cp.vl[0x1B0]['BRAKE_ERROR_1'] or cp.vl[0x1B0]['BRAKE_ERROR_2'] + self.esp_disabled = cp.vl[0x1A4]['ESP_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel = ( + cp.vl[0x1D0]['WHEEL_SPEED_FL'] + cp.vl[0x1D0]['WHEEL_SPEED_FR'] + + cp.vl[0x1D0]['WHEEL_SPEED_RL'] + cp.vl[0x1D0]['WHEEL_SPEED_RR']) / 4. + # blend in transmission speed at low speed, since it has more low speed accuracy + self.v_weight = np.interp(self.v_wheel, v_weight_bp, v_weight_v) + self.v_ego = (1. - self.v_weight) * cp.vl[0x158]['XMISSION_SPEED'] + self.v_weight * self.v_wheel + if not self.brake_only: + self.user_gas = cp.vl[0x201]['INTERCEPTOR_GAS'] + self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change + #print user_gas, user_gas_pressed + if self.civic: + self.gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] + self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] + self.gear = 0 # TODO: civic has CVT... needs rev engineering + self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] + self.main_on = cp.vl[0x326]['MAIN_ON'] + self.gear_shifter_valid = self.gear_shifter in [1,8] # TODO: 1/P allowed for debug + self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] + else: + self.gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] + self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] + self.gear = cp.vl[0x1A3]['GEAR'] + self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] + self.main_on = cp.vl[0x1A6]['MAIN_ON'] + self.gear_shifter_valid = self.gear_shifter in [1,4] # TODO: 1/P allowed for debug + self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] + self.car_gas = cp.vl[0x130]['CAR_GAS'] + self.brake_pressed = cp.vl[0x17C]['BRAKE_PRESSED'] + self.user_brake = cp.vl[0x1A4]['USER_BRAKE'] + self.standstill = not cp.vl[0x1B0]['WHEELS_MOVING'] + self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 + self.v_cruise_pcm = cp.vl[0x324]['CRUISE_SPEED_PCM'] + self.pcm_acc_status = cp.vl[0x17C]['ACC_STATUS'] + self.pedal_gas = cp.vl[0x17C]['PEDAL_GAS'] + self.hud_lead = cp.vl[0x30C]['HUD_LEAD'] + self.counter_pcm = cp.vl[0x324]['COUNTER'] + + return canMonoTimes diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py new file mode 100644 index 0000000000..a2c4917dc1 --- /dev/null +++ b/selfdrive/controls/lib/drive_helpers.py @@ -0,0 +1,52 @@ +import numpy as np + +def rate_limit(new_value, last_value, dw_step, up_step): + return np.clip(new_value, last_value + dw_step, last_value + up_step) + +def learn_angle_offset(lateral_control, v_ego, angle_offset, d_poly, y_des, steer_override): + # simple integral controller that learns how much steering offset to put to have the car going straight + min_offset = -1. # deg + max_offset = 1. # deg + alpha = 1./36000. # correct by 1 deg in 2 mins, at 30m/s, with 50cm of error, at 20Hz + min_learn_speed = 1. + + # learn less at low speed or when turning + alpha_v = alpha*(np.maximum(v_ego - min_learn_speed, 0.))/(1. + 0.5*abs(y_des)) + + # only learn if lateral control is active and if driver is not overriding: + if lateral_control and not steer_override: + angle_offset += d_poly[3] * alpha_v + angle_offset = np.clip(angle_offset, min_offset, max_offset) + + return angle_offset + +def actuator_hystereses(final_brake, braking, brake_steady, v_ego, civic): + # hyst params... TODO: move these to VehicleParams + brake_hyst_on = 0.055 if civic else 0.1 # to activate brakes exceed this value + brake_hyst_off = 0.005 # to deactivate brakes below this value + brake_hyst_gap = 0.01 # don't change brake command for small ocilalitons within this value + + #*** histeresys logic to avoid brake blinking. go above 0.1 to trigger + if (final_brake < brake_hyst_on and not braking) or final_brake < brake_hyst_off: + final_brake = 0. + braking = final_brake > 0. + + # for small brake oscillations within brake_hyst_gap, don't change the brake command + if final_brake == 0.: + brake_steady = 0. + elif final_brake > brake_steady + brake_hyst_gap: + brake_steady = final_brake - brake_hyst_gap + elif final_brake < brake_steady - brake_hyst_gap: + brake_steady = final_brake + brake_hyst_gap + final_brake = brake_steady + + if not civic: + brake_on_offset_v = [.25, .15] # min brake command on brake activation. below this no decel is perceived + brake_on_offset_bp = [15., 30.] # offset changes VS speed to not have too abrupt decels at high speeds + # offset the brake command for threshold in the brake system. no brake torque perceived below it + brake_on_offset = np.interp(v_ego, brake_on_offset_bp, brake_on_offset_v) + brake_offset = brake_on_offset - brake_hyst_on + if final_brake > 0.0: + final_brake += brake_offset + + return final_brake, braking, brake_steady diff --git a/selfdrive/controls/lib/fingerprints.py b/selfdrive/controls/lib/fingerprints.py new file mode 100644 index 0000000000..f3363c2d89 --- /dev/null +++ b/selfdrive/controls/lib/fingerprints.py @@ -0,0 +1,8 @@ +fingerprints = { + "ACURA ILX 2016 ACURAWATCH PLUS": { + 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5 + }, + "HONDA CIVIC 2016 TOURING": { + 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5 + } +} diff --git a/selfdrive/controls/lib/hondacan.py b/selfdrive/controls/lib/hondacan.py new file mode 100644 index 0000000000..fe6d9e79d9 --- /dev/null +++ b/selfdrive/controls/lib/hondacan.py @@ -0,0 +1,88 @@ +import struct + +import common.numpy_fast as np +from selfdrive.config import Conversions as CV + + +# *** Honda specific *** +def can_cksum(mm): + s = 0 + for c in mm: + c = ord(c) + s += (c>>4) + s += c & 0xF + s = 8-s + s %= 0x10 + return s + +def fix(msg, addr): + msg2 = msg[0:-1] + chr(ord(msg[-1]) | can_cksum(struct.pack("I", addr)+msg)) + return msg2 + +def make_can_msg(addr, dat, idx, alt): + if idx is not None: + dat += chr(idx << 4) + dat = fix(dat, addr) + return [addr, 0, dat, alt] + +def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx): + """Creates a CAN message for the Honda DBC BRAKE_COMMAND.""" + pump_on = apply_brake > 0 + brakelights = apply_brake > 0 + brake_rq = apply_brake > 0 + + pcm_fault_cmd = False + amount = struct.pack("!H", (apply_brake << 6) + pump_on) + msg = amount + struct.pack("BBB", (pcm_override << 4) | + (pcm_fault_cmd << 2) | + (pcm_cancel_cmd << 1) | brake_rq, 0x80, + brakelights << 7) + chr(chime) + "\x00" + return make_can_msg(0x1fa, msg, idx, 0) + +def create_gas_command(gas_amount, idx): + """Creates a CAN message for the Honda DBC GAS_COMMAND.""" + msg = struct.pack("!H", gas_amount) + return make_can_msg(0x200, msg, idx, 0) + +def create_steering_control(apply_steer, idx): + """Creates a CAN message for the Honda DBC STEERING_CONTROL.""" + msg = struct.pack("!h", apply_steer) + ("\x80\x00" if apply_steer != 0 else "\x00\x00") + return make_can_msg(0xe4, msg, idx, 0) + +def create_ui_commands(pcm_speed, hud, civic, idx): + """Creates an iterable of CAN messages for the UIs.""" + commands = [] + pcm_speed_real = np.clip(int(round(pcm_speed / 0.002763889)), 0, + 64000) # conversion factor from dbc file + msg_0x30c = struct.pack("!HBBBBB", pcm_speed_real, hud.pcm_accel, + hud.v_cruise, hud.X2, hud.car, hud.X4) + commands.append(make_can_msg(0x30c, msg_0x30c, idx, 0)) + + msg_0x33d = chr(hud.X5) + chr(hud.lanes) + chr(hud.beep) + chr(hud.X8) + commands.append(make_can_msg(0x33d, msg_0x33d, idx, 0)) + if civic: # 2 more msgs + msg_0x35e = chr(0) * 7 + commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0)) + msg_0x39f = ( + chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0) + ) + commands.append(make_can_msg(0x39f, msg_0x39f, idx, 0)) + return commands + +def create_radar_commands(v_ego, civic, idx): + """Creates an iterable of CAN messages for the radar system.""" + commands = [] + v_ego_kph = np.clip(int(round(v_ego * CV.MS_TO_KPH)), 0, 255) + speed = struct.pack('!B', v_ego_kph) + msg_0x300 = ("\xf9" + speed + "\x8a\xd0" +\ + ("\x20" if idx == 0 or idx == 3 else "\x00") +\ + "\x00\x00") + if civic: + msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" + # add 8 on idx. + commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) + else: + msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00" + commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) + commands.append(make_can_msg(0x301, msg_0x301, idx, 1)) + return commands diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py new file mode 100644 index 0000000000..3a77a16cdd --- /dev/null +++ b/selfdrive/controls/lib/latcontrol.py @@ -0,0 +1,120 @@ +import numpy as np + +def calc_curvature(v_ego, angle_steers, VP, angle_offset=0): + deg_to_rad = np.pi/180. + angle_steers_rad = (angle_steers - angle_offset) * deg_to_rad + curvature = angle_steers_rad/(VP.steer_ratio * VP.wheelbase * (1. + VP.slip_factor * v_ego**2)) + return curvature + +def calc_d_lookahead(v_ego): + #*** this function computes how far too look for lateral control + # howfar we look ahead is function of speed + offset_lookahead = 1. + coeff_lookahead = 4.4 + # sqrt on speed is needed to keep, for a given curvature, the y_offset + # proportional to speed. Indeed, y_offset is prop to d_lookahead^2 + # 26m at 25m/s + d_lookahead = offset_lookahead + np.sqrt(np.maximum(v_ego, 0)) * coeff_lookahead + return d_lookahead + +def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VP, angle_offset): + #*** this function return teh lateral offset given the steering angle, speed and the lookahead distance + curvature = calc_curvature(v_ego, angle_steers, VP, angle_offset) + + # clip is to avoid arcsin NaNs due to too sharp turns + y_actual = d_lookahead * np.tan(np.arcsin(np.clip(d_lookahead * curvature, -0.999, 0.999))/2.) + return y_actual, curvature + +def pid_lateral_control(v_ego, y_actual, y_des, Ui_steer, steer_max, + steer_override, sat_count, enabled, half_pid, rate): + + sat_count_rate = 1./rate + sat_count_limit = 0.8 # after 0.8s of continuous saturation, an alert will be sent + + error_steer = y_des - y_actual + Ui_unwind_speed = 0.3/rate #.3 per second + if not half_pid: + Kp, Ki = 12.0, 1.0 + else: + Kp, Ki = 6.0, .5 # 2x limit in ILX + Up_steer = error_steer*Kp + Ui_steer_new = Ui_steer + error_steer*Ki * 1./rate + output_steer_new = Ui_steer_new + Up_steer + + # Anti-wind up for integrator: do not integrate if we are against the steer limits + if ( + (error_steer >= 0. and (output_steer_new < steer_max or Ui_steer < 0)) or + (error_steer <= 0. and + (output_steer_new > -steer_max or Ui_steer > 0))) and not steer_override: + #update integrator + Ui_steer = Ui_steer_new + # unwind integrator if driver is maneuvering the steering wheel + elif steer_override: + Ui_steer -= Ui_unwind_speed * np.sign(Ui_steer) + + # still, intergral term should not be bigger then limits + Ui_steer = np.clip(Ui_steer, -steer_max, steer_max) + + output_steer = Up_steer + Ui_steer + + # don't run steer control if at very low speed + if v_ego < 0.3 or not enabled: + output_steer = 0. + Ui_steer = 0. + + # useful to know if control is against the limit + lateral_control_sat = False + if abs(output_steer) > steer_max: + lateral_control_sat = True + + output_steer = np.clip(output_steer, -steer_max, steer_max) + + # if lateral control is saturated for a certain period of time, send an alert for taking control of the car + # wind + if lateral_control_sat and not steer_override and v_ego > 10 and abs(error_steer) > 0.1: + sat_count += sat_count_rate + # unwind + else: + sat_count -= sat_count_rate + + sat_flag = False + if sat_count >= sat_count_limit: + sat_flag = True + + sat_count = np.clip(sat_count, 0, 1) + + return output_steer, Up_steer, Ui_steer, lateral_control_sat, sat_count, sat_flag + +class LatControl(object): + def __init__(self): + self.Up_steer = 0. + self.sat_count = 0 + self.y_des = 0.0 + self.lateral_control_sat = False + self.Ui_steer = 0. + self.reset() + + def reset(self): + self.Ui_steer = 0. + + def update(self, enabled, CS, d_poly, angle_offset): + rate = 100 + + steer_max = 1.0 + + # how far we look ahead is function of speed + d_lookahead = calc_d_lookahead(CS.v_ego) + + # calculate actual offset at the lookahead point + self.y_actual, _ = calc_lookahead_offset(CS.v_ego, CS.angle_steers, + d_lookahead, CS.VP, angle_offset) + + # desired lookahead offset + self.y_des = np.polyval(d_poly, d_lookahead) + + output_steer, self.Up_steer, self.Ui_steer, self.lateral_control_sat, self.sat_count, sat_flag = pid_lateral_control( + CS.v_ego, self.y_actual, self.y_des, self.Ui_steer, steer_max, + CS.steer_override, self.sat_count, enabled, CS.torque_mod, rate) + + final_steer = np.clip(output_steer, -steer_max, steer_max) + return final_steer, sat_flag diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py new file mode 100644 index 0000000000..819d4807a4 --- /dev/null +++ b/selfdrive/controls/lib/longcontrol.py @@ -0,0 +1,232 @@ +import numpy as np +from selfdrive.config import Conversions as CV + +class LongCtrlState: + #*** this function handles the long control state transitions + # long_control_state labels: + off = 0 # Off + pid = 1 # moving and tracking targets, with PID control running + stopping = 2 # stopping and changing controls to almost open loop as PID does not fit well at such a low speed + starting = 3 # starting and releasing brakes in open loop before giving back to PID + +def long_control_state_trans(enabled, long_control_state, v_ego, v_target, v_pid, output_gb): + + stopping_speed = 0.5 + stopping_target_speed = 0.3 + starting_target_speed = 0.5 + brake_threshold_to_pid = 0.2 + + stopping_condition = ((v_ego < stopping_speed) and (v_pid < stopping_target_speed) and (v_target < stopping_target_speed)) + + if not enabled: + long_control_state = LongCtrlState.off + else: + if long_control_state == LongCtrlState.off: + if enabled: + long_control_state = LongCtrlState.pid + elif long_control_state == LongCtrlState.pid: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif long_control_state == LongCtrlState.stopping: + if (v_target > starting_target_speed): + long_control_state = LongCtrlState.starting + elif long_control_state == LongCtrlState.starting: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif output_gb >= -brake_threshold_to_pid: + long_control_state = LongCtrlState.pid + + return long_control_state + +def get_compute_gb(): + # see debug/dump_accel_from_fiber.py + w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], + [ 1.03691769, 0.78210306, -0.41343188]]) + b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) + w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], + [ 0.79973811, 0.13178682, 0.08550351], + [-0.15651935, -0.44360259, 0.76910877]]) + b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) + w4 = np.array([[-0.31521443], + [-0.38626176], + [ 0.52667892]]) + b4 = np.array([-0.02922216]) + + def compute_output(dat, w0, b0, w2, b2, w4, b4): + m0 = np.dot(dat, w0) + b0 + m0 = leakyrelu(m0, 0.1) + m2 = np.dot(m0, w2) + b2 + m2 = leakyrelu(m2, 0.1) + m4 = np.dot(m2, w4) + b4 + return m4 + + def leakyrelu(x, alpha): + return np.maximum(x, alpha * x) + + def _compute_gb(dat): + #linearly extrap below v1 using v1 and v2 data + v1 = 5. + v2 = 10. + vx = dat[1] + if vx > 5.: + m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) + else: + dat[1] = v1 + m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) + dat[1] = v2 + m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) + m4 = (vx - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 + return m4 + return _compute_gb + +# takes in [desired_accel, current_speed] -> [-1.0, 1.0] where -1.0 is max brake and 1.0 is max gas +compute_gb = get_compute_gb() + +def pid_long_control(v_ego, v_pid, Ui_accel_cmd, gas_max, brake_max, jerk_factor, gear, rate): + #*** This function compute the gb pedal positions in order to track the desired speed + # proportional and integral terms. More precision at low speed + Kp_v = [1.2, 0.8, 0.5] + Kp_bp = [0., 5., 35.] + Kp = np.interp(v_ego, Kp_bp, Kp_v) + Ki_v = [0.18, 0.12] + Ki_bp = [0., 35.] + Ki = np.interp(v_ego, Ki_bp, Ki_v) + + # scle Kp and Ki by jerk factor drom drive_thread + Kp = (1. + jerk_factor)*Kp + Ki = (1. + jerk_factor)*Ki + + # this is ugly but can speed reports 0 when speed<0.3m/s and we can't have that jump + v_ego_min = 0.3 + v_ego = np.maximum(v_ego, v_ego_min) + + v_error = v_pid - v_ego + + Up_accel_cmd = v_error*Kp + Ui_accel_cmd_new = Ui_accel_cmd + v_error*Ki*1.0/rate + accel_cmd_new = Ui_accel_cmd_new + Up_accel_cmd + output_gb_new = compute_gb([accel_cmd_new, v_ego]) + + # Anti-wind up for integrator: only update integrator if we not against the thottle and brake limits + # do not wind up if we are changing gear and we are on the gas pedal + if (((v_error >= 0. and (output_gb_new < gas_max or Ui_accel_cmd < 0)) or + (v_error <= 0. and (output_gb_new > - brake_max or Ui_accel_cmd > 0))) and + not (v_error >= 0. and gear == 11 and output_gb_new > 0)): + #update integrator + Ui_accel_cmd = Ui_accel_cmd_new + + accel_cmd = Ui_accel_cmd + Up_accel_cmd + + # go from accel to pedals + output_gb = compute_gb([accel_cmd, v_ego]) + output_gb = output_gb[0] + + # useful to know if control is against the limit + long_control_sat = False + if output_gb > gas_max or output_gb < -brake_max: + long_control_sat = True + + output_gb = np.clip(output_gb, -brake_max, gas_max) + + return output_gb, Up_accel_cmd, Ui_accel_cmd, long_control_sat + + +stopping_brake_rate = 0.2 # brake_travel/s while trying to stop +starting_brake_rate = 0.6 # brake_travel/s while releasing on restart +starting_Ui = 0.5 # Since we don't have much info about acceleration at this point, be conservative +brake_stopping_target = 0.5 # apply at least this amount of brake to maintain the vehicle stationary + +max_speed_error_v = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp +max_speed_error_bp = [0., 30.] # speed breakpoints + +class LongControl(object): + def __init__(self): + self.long_control_state = LongCtrlState.off # initialized to off + self.long_control_sat = False + self.Up_accel_cmd = 0. + self.last_output_gb = 0. + self.reset(0.) + + def reset(self, v_pid): + self.Ui_accel_cmd = 0. + self.v_pid = v_pid + + def update(self, enabled, CS, v_cruise, v_target_lead, a_target, jerk_factor): + # TODO: not every time + if CS.brake_only: + gas_max_v = [0, 0] # values + else: + gas_max_v = [0.6, 0.6] # values + gas_max_bp = [0., 100.] # speeds + brake_max_v = [1.0, 1.0, 0.8, 0.8] # values + brake_max_bp = [0., 5., 20., 100.] # speeds + + # brake and gas limits + brake_max = np.interp(CS.v_ego, brake_max_bp, brake_max_v) + gas_max = np.interp(CS.v_ego, gas_max_bp, gas_max_v) + + overshoot_allowance = 2.0 # overshoot allowed when changing accel sign + + output_gb = self.last_output_gb + rate = 100 + + # limit max target speed based on cruise setting: + v_cruise_mph = round(v_cruise * CV.KPH_TO_MPH) # what's displayed in mph on the IC + v_target = np.minimum(v_target_lead, v_cruise_mph * CV.MPH_TO_MS / CS.ui_speed_fudge) + + max_speed_delta_up = a_target[1]*1.0/rate + max_speed_delta_down = a_target[0]*1.0/rate + + # *** long control substate transitions + self.long_control_state = long_control_state_trans(enabled, self.long_control_state, CS.v_ego, v_target, self.v_pid, output_gb) + + # *** long control behavior based on state + # TODO: move this to drive_helpers + # disabled + if self.long_control_state == LongCtrlState.off: + self.v_pid = CS.v_ego # do nothing + output_gb = 0. + self.Ui_accel_cmd = 0. + # tracking objects and driving + elif self.long_control_state == LongCtrlState.pid: + #reset v_pid close to v_ego if it was too far and new v_target is closer to v_ego + if ((self.v_pid > CS.v_ego + overshoot_allowance) and + (v_target < self.v_pid)): + self.v_pid = np.maximum(v_target, CS.v_ego + overshoot_allowance) + elif ((self.v_pid < CS.v_ego - overshoot_allowance) and + (v_target > self.v_pid)): + self.v_pid = np.minimum(v_target, CS.v_ego - overshoot_allowance) + + # move v_pid no faster than allowed accel limits + if (v_target > self.v_pid + max_speed_delta_up): + self.v_pid += max_speed_delta_up + elif (v_target < self.v_pid + max_speed_delta_down): + self.v_pid += max_speed_delta_down + else: + self.v_pid = v_target + + # to avoid too much wind up on acceleration, limit positive speed error + if not CS.brake_only: + max_speed_error = np.interp(CS.v_ego, max_speed_error_bp, max_speed_error_v) + self.v_pid = np.minimum(self.v_pid, CS.v_ego + max_speed_error) + + output_gb, self.Up_accel_cmd, self.Ui_accel_cmd, self.long_control_sat = pid_long_control(CS.v_ego, self.v_pid, \ + self.Ui_accel_cmd, gas_max, brake_max, jerk_factor, CS.gear, rate) + # intention is to stop, switch to a different brake control until we stop + elif self.long_control_state == LongCtrlState.stopping: + if CS.v_ego > 0. or output_gb > -brake_stopping_target or not CS.standstill: + output_gb -= stopping_brake_rate/rate + output_gb = np.clip(output_gb, -brake_max, gas_max) + self.v_pid = CS.v_ego + self.Ui_accel_cmd = 0. + # intention is to move again, release brake fast before handling control to PID + elif self.long_control_state == LongCtrlState.starting: + if output_gb < -0.2: + output_gb += starting_brake_rate/rate + self.v_pid = CS.v_ego + self.Ui_accel_cmd = starting_Ui + + self.last_output_gb = output_gb + final_gas = np.clip(output_gb, 0., gas_max) + final_brake = -np.clip(output_gb, -brake_max, 0.) + return final_gas, final_brake diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py new file mode 100644 index 0000000000..49e5eb2e3e --- /dev/null +++ b/selfdrive/controls/lib/pathplanner.py @@ -0,0 +1,63 @@ +import selfdrive.messaging as messaging +import numpy as np +X_PATH = np.arange(0.0, 50.0) + +def model_polyfit(points): + return np.polyfit(X_PATH, map(float, points), 3) + +# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm +_LANE_WIDTH_V = np.asarray([3., 3.8]) + +# break points of speed +_LANE_WIDTH_BP = np.asarray([0., 31.]) + +def calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, speed): + #*** this function computes the poly for the center of the lane, averaging left and right polys + lane_width = np.interp(speed, _LANE_WIDTH_BP, _LANE_WIDTH_V) + + # lanes in US are ~3.6m wide + half_lane_poly = np.array([0., 0., 0., lane_width / 2.]) + if l_prob + r_prob > 0.01: + c_poly = ((l_poly - half_lane_poly) * l_prob + + (r_poly + half_lane_poly) * r_prob) / (l_prob + r_prob) + c_prob = np.sqrt((l_prob**2 + r_prob**2) / 2.) + else: + c_poly = np.zeros(4) + c_prob = 0. + + p_weight = 1. # predicted path weight relatively to the center of the lane + d_poly = list((c_poly*c_prob + p_poly*p_prob*p_weight ) / (c_prob + p_prob*p_weight)) + return d_poly, c_poly, c_prob + +class PathPlanner(object): + def __init__(self, model): + self.model = model + self.dead = True + self.d_poly = [0., 0., 0., 0.] + self.last_model = 0. + self.logMonoTime = 0 + self.lead_dist, self.lead_prob, self.lead_var = 0, 0, 1 + + def update(self, cur_time, v_ego): + md = messaging.recv_sock(self.model) + + if md is not None: + self.logMonoTime = md.logMonoTime + p_poly = model_polyfit(md.model.path.points) # predicted path + p_prob = 1. # model does not tell this probability yet, so set to 1 for now + l_poly = model_polyfit(md.model.leftLane.points) # left line + l_prob = md.model.leftLane.prob # left line prob + r_poly = model_polyfit(md.model.rightLane.points) # right line + r_prob = md.model.rightLane.prob # right line prob + + self.lead_dist = md.model.lead.dist + self.lead_prob = md.model.lead.prob + self.lead_var = md.model.lead.std**2 + + #*** compute target path *** + self.d_poly, _, _ = calc_desired_path(l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, v_ego) + + self.last_model = cur_time + self.dead = False + elif cur_time - self.last_model > 0.5: + self.dead = True diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py new file mode 100644 index 0000000000..f7759a4d4d --- /dev/null +++ b/selfdrive/controls/lib/radar_helpers.py @@ -0,0 +1,256 @@ +import numpy as np +import platform +import os +import sys + +from common.kalman.ekf import FastEKF1D, SimpleSensor + +# radar tracks +SPEED, ACCEL = 0, 1 # Kalman filter states enum + +rate, ratev = 20., 20. # model and radar are both at 20Hz +ts = 1./rate +freq_v_lat = 0.2 # Hz +k_v_lat = 2*np.pi*freq_v_lat*ts / (1 + 2*np.pi*freq_v_lat*ts) + +freq_a_lead = .5 # Hz +k_a_lead = 2*np.pi*freq_a_lead*ts / (1 + 2*np.pi*freq_a_lead*ts) + +# stationary qualification parameters +v_stationary_thr = 4. # objects moving below this speed are classified as stationary +v_oncoming_thr = -3.9 # needs to be a bit lower in abs value than v_stationary_thr to not leave "holes" +v_ego_stationary = 4. # no stationary object flag below this speed + +class Track(object): + def __init__(self): + self.ekf = None + self.stationary = True + self.initted = False + + def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned): + if self.initted: + self.dPathPrev = self.dPath + self.vLeadPrev = self.vLead + self.vRelPrev = self.vRel + + # relative values, copy + self.dRel = d_rel # LONG_DIST + self.yRel = y_rel # -LAT_DIST + self.vRel = v_rel # REL_SPEED + + # compute distance to path + self.dPath = d_path + + # computed velocity and accelerations + self.vLead = self.vRel + v_ego_t_aligned + + if not self.initted: + self.aRel = 0. # nidec gives no information about this + self.vLat = 0. + self.aLead = 0. + else: + # estimate acceleration + a_rel_unfilt = (self.vRel - self.vRelPrev) / ts + a_rel_unfilt = np.clip(a_rel_unfilt, -10., 10.) + self.aRel = k_a_lead * a_rel_unfilt + (1 - k_a_lead) * self.aRel + + v_lat_unfilt = (self.dPath - self.dPathPrev) / ts + self.vLat = k_v_lat * v_lat_unfilt + (1 - k_v_lat) * self.vLat + + a_lead_unfilt = (self.vLead - self.vLeadPrev) / ts + a_lead_unfilt = np.clip(a_lead_unfilt, -10., 10.) + self.aLead = k_a_lead * a_lead_unfilt + (1 - k_a_lead) * self.aLead + + if self.stationary: + # stationary objects can become non stationary, but not the other way around + self.stationary = v_ego_t_aligned > v_ego_stationary and abs(self.vLead) < v_stationary_thr + self.oncoming = self.vLead < v_oncoming_thr + + if self.ekf is None: + self.ekf = FastEKF1D(ts, 1e3, [0.1, 1]) + self.ekf.state[SPEED] = self.vLead + self.ekf.state[ACCEL] = 0 + self.lead_sensor = SimpleSensor(SPEED, 1, 2) + + self.vLeadK = self.vLead + self.aLeadK = self.aLead + else: + self.ekf.update_scalar(self.lead_sensor.read(self.vLead)) + self.ekf.predict(ts) + self.vLeadK = float(self.ekf.state[SPEED]) + self.aLeadK = float(self.ekf.state[ACCEL]) + + if not self.initted: + self.cnt = 1 + self.vision_cnt = 0 + else: + self.cnt += 1 + + self.initted = True + self.vision = False + + def mix_vision(self, dist_to_vision, rel_speed_diff): + # rel speed is very hard to estimate from vision + if dist_to_vision < 4.0 and rel_speed_diff < 10.: + # vision point is never stationary + self.stationary = False + self.vision = True + self.vision_cnt += 1 + + def get_key_for_cluster(self): + # Weigh y higher since radar is inaccurate in this dimension + return [self.dRel, self.dPath*2, self.vRel] + +# ******************* Cluster ******************* + +if platform.machine() == 'aarch64': + for x in sys.path: + pp = os.path.join(x, "phonelibs/hierarchy/lib") + if os.path.isfile(os.path.join(pp, "_hierarchy.so")): + sys.path.append(pp) + break + import _hierarchy +else: + from scipy.cluster import _hierarchy + +def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None): + # supersimplified function to get fast clustering. Got it from scipy + Z = np.asarray(Z, order='c') + n = Z.shape[0] + 1 + T = np.zeros((n,), dtype='i') + _hierarchy.cluster_dist(Z, T, float(t), int(n)) + return T + +RDR_TO_LDR = 2.7 + +def mean(l): + return sum(l)/len(l) + +class Cluster(object): + def __init__(self): + self.tracks = set() + + def add(self, t): + # add the first track + self.tracks.add(t) + + # TODO: make generic + @property + def dRel(self): + return mean([t.dRel for t in self.tracks]) + + @property + def yRel(self): + return mean([t.yRel for t in self.tracks]) + + @property + def vRel(self): + return mean([t.vRel for t in self.tracks]) + + @property + def aRel(self): + return mean([t.aRel for t in self.tracks]) + + @property + def vLead(self): + return mean([t.vLead for t in self.tracks]) + + @property + def aLead(self): + return mean([t.aLead for t in self.tracks]) + + @property + def dPath(self): + return mean([t.dPath for t in self.tracks]) + + @property + def vLat(self): + return mean([t.vLat for t in self.tracks]) + + @property + def vLeadK(self): + return mean([t.vLeadK for t in self.tracks]) + + @property + def aLeadK(self): + return mean([t.aLeadK for t in self.tracks]) + + @property + def vision(self): + return any([t.vision for t in self.tracks]) + + @property + def vision_cnt(self): + return max([t.vision_cnt for t in self.tracks]) + + @property + def stationary(self): + return all([t.stationary for t in self.tracks]) + + @property + def oncoming(self): + return all([t.oncoming for t in self.tracks]) + + def toLive20(self, lead): + lead.dRel = float(self.dRel) - RDR_TO_LDR + lead.yRel = float(self.yRel) + lead.vRel = float(self.vRel) + lead.aRel = float(self.aRel) + lead.vLead = float(self.vLead) + lead.aLead = float(self.aLead) + lead.dPath = float(self.dPath) + lead.vLat = float(self.vLat) + lead.vLeadK = float(self.vLeadK) + lead.aLeadK = float(self.aLeadK) + lead.status = True + lead.fcw = False + + def __str__(self): + ret = "x: %7.2f y: %7.2f v: %7.2f a: %7.2f" % (self.dRel, self.yRel, self.vRel, self.aRel) + if self.stationary: + ret += " stationary" + if self.vision: + ret += " vision" + if self.oncoming: + ret += " oncoming" + if self.vision_cnt > 0: + ret += " vision_cnt: %6.0f" % self.vision_cnt + return ret + + def is_potential_lead(self, v_ego, enabled): + # predict cut-ins by extrapolating lateral speed by a lookahead time + # lookahead time depends on cut-in distance. more attentive for close cut-ins + # also, above 50 meters the predicted path isn't very reliable + + # the distance at which v_lat matters is higher at higher speed + lookahead_dist = 40. + v_ego/1.2 #40m at 0mph, ~70m at 80mph + + t_lookahead_v = [1., 0.] + t_lookahead_bp = [10., lookahead_dist] + + # average dist + d_path = self.dPath + + if enabled: + t_lookahead = np.interp(self.dRel, t_lookahead_bp, t_lookahead_v) + # correct d_path for lookahead time, considering only cut-ins and no more than 1m impact + lat_corr = np.clip(t_lookahead * self.vLat, -1, 0) + else: + lat_corr = 0. + d_path = np.maximum(d_path + lat_corr, 0) + + if d_path < 1.5 and not self.stationary and not self.oncoming: + return True + else: + return False + + def is_potential_lead2(self, lead_clusters): + if len(lead_clusters) > 0: + lead_cluster = lead_clusters[0] + # check if the new lead is too close and roughly at the same speed of the first lead: it might just be the second axle of the same vehicle + if (self.dRel - lead_cluster.dRel) < 8. and abs(self.vRel - lead_cluster.vRel) < 1.: + return False + else: + return True + else: + return False diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py new file mode 100755 index 0000000000..2ee244d3cd --- /dev/null +++ b/selfdrive/controls/radard.py @@ -0,0 +1,268 @@ +#!/usr/bin/env python +import zmq +import numpy as np +import numpy.matlib +from collections import defaultdict + +from fastcluster import linkage_vector + +import selfdrive.messaging as messaging +from selfdrive.boardd.boardd import can_capnp_to_can_list_old +from selfdrive.controls.lib.latcontrol import calc_lookahead_offset +from selfdrive.controls.lib.can_parser import CANParser +from selfdrive.controls.lib.pathplanner import PathPlanner +from selfdrive.config import VehicleParams +from selfdrive.controls.lib.radar_helpers import Track, Cluster, fcluster, RDR_TO_LDR + +from common.services import service_list +from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper +from common.kalman.ekf import EKF, SimpleSensor + +#vision point +DIMSV = 2 +XV, SPEEDV = 0, 1 +VISION_POINT = 1 + +class EKFV1D(EKF): + def __init__(self): + super(EKFV1D, self).__init__(False) + self.identity = np.matlib.identity(DIMSV) + self.state = np.matlib.zeros((DIMSV, 1)) + self.var_init = 1e2 # ~ model variance when probability is 70%, so good starting point + self.covar = self.identity * self.var_init + + # self.process_noise = np.asmatrix(np.diag([100, 10])) + self.process_noise = np.matlib.diag([0.5, 1]) + + def calc_transfer_fun(self, dt): + tf = np.matlib.identity(DIMSV) + tf[XV, SPEEDV] = dt + tfj = tf + return tf, tfj + + +# nidec radar decoding +def nidec_decode(cp, ar_pts): + for ii in cp.msgs_upd: + # filter points with very big distance, as fff (~255) is invalid. FIXME: use VAL tables from dbc + if cp.vl[ii]['LONG_DIST'] < 255: + ar_pts[ii] = [cp.vl[ii]['LONG_DIST'] + RDR_TO_LDR, + -cp.vl[ii]['LAT_DIST'], cp.vl[ii]['REL_SPEED'], np.nan, + cp.ts[ii], cp.vl[ii]['NEW_TRACK'], cp.ct[ii]] + elif ii in ar_pts: + del ar_pts[ii] + return ar_pts + + +def _create_radard_can_parser(): + dbc_f = 'acura_ilx_2016_nidec.dbc' + radar_messages = range(0x430, 0x43A) + range(0x440, 0x446) + signals = zip(['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + ['REL_SPEED'] * 16, radar_messages * 4, + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) + checks = zip(radar_messages, [20]*16) + + return CANParser(dbc_f, signals, checks) + + +# fuses camera and radar data for best lead detection +def radard_thread(gctx=None): + set_realtime_priority(1) + + context = zmq.Context() + + # *** subscribe to features and model from visiond + model = messaging.sub_sock(context, service_list['model'].port) + logcan = messaging.sub_sock(context, service_list['can'].port) + live100 = messaging.sub_sock(context, service_list['live100'].port) + + PP = PathPlanner(model) + + # *** publish live20 and liveTracks + live20 = messaging.pub_sock(context, service_list['live20'].port) + liveTracks = messaging.pub_sock(context, service_list['liveTracks'].port) + + # subscribe to stats about the car + # TODO: move this to new style packet + VP = VehicleParams(False) # same for ILX and civic + + ar_pts = {} + path_x = np.arange(0.0, 140.0, 0.1) # 140 meters is max + + # Time-alignment + rate = 20. # model and radar are both at 20Hz + tsv = 1./rate + rdr_delay = 0.10 # radar data delay in s + v_len = 20 # how many speed data points to remember for t alignment with rdr data + + enabled = 0 + steer_angle = 0. + + tracks = defaultdict(dict) + + # Nidec + cp = _create_radard_can_parser() + + # Kalman filter stuff: + ekfv = EKFV1D() + speedSensorV = SimpleSensor(XV, 1, 2) + + # v_ego + v_ego = None + v_ego_array = np.zeros([2, v_len]) + v_ego_t_aligned = 0. + + rk = Ratekeeper(rate, print_delay_threshold=np.inf) + while 1: + canMonoTimes = [] + can_pub_radar = [] + for a in messaging.drain_sock(logcan, wait_for_one=True): + canMonoTimes.append(a.logMonoTime) + can_pub_radar.extend(can_capnp_to_can_list_old(a, [1, 3])) + + # only run on the 0x445 packets, used for timing + if not any(x[0] == 0x445 for x in can_pub_radar): + continue + + cp.update_can(can_pub_radar) + + if not cp.can_valid: + # TODO: handle this + pass + + ar_pts = nidec_decode(cp, ar_pts) + + # receive the live100s + l100 = messaging.recv_sock(live100) + if l100 is not None: + enabled = l100.live100.enabled + v_ego = l100.live100.vEgo + steer_angle = l100.live100.angleSteers + + v_ego_array = np.append(v_ego_array, [[v_ego], [float(rk.frame)/rate]], 1) + v_ego_array = v_ego_array[:, 1:] + + if v_ego is None: + continue + + # *** get path prediction from the model *** + PP.update(sec_since_boot(), v_ego) + + # run kalman filter only if prob is high enough + if PP.lead_prob > 0.7: + ekfv.update(speedSensorV.read(PP.lead_dist, covar=PP.lead_var)) + ekfv.predict(tsv) + ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])), + float(ekfv.state[SPEEDV]), np.nan, PP.logMonoTime, np.nan, sec_since_boot()) + else: + ekfv.state[XV] = PP.lead_dist + ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) + ekfv.state[SPEEDV] = 0. + if VISION_POINT in ar_pts: + del ar_pts[VISION_POINT] + + # *** compute the likely path_y *** + if enabled: # use path from model path_poly + path_y = np.polyval(PP.d_poly, path_x) + else: # use path from steer, set angle_offset to 0 since calibration does not exactly report the physical offset + path_y = calc_lookahead_offset(v_ego, steer_angle, path_x, VP, angle_offset=0)[0] + + # *** remove missing points from meta data *** + for ids in tracks.keys(): + if ids not in ar_pts: + tracks.pop(ids, None) + + # *** compute the tracks *** + for ids in ar_pts: + # ignore the vision point for now + if ids == VISION_POINT: + continue + rpt = ar_pts[ids] + + # align v_ego by a fixed time to align it with the radar measurement + cur_time = float(rk.frame)/rate + v_ego_t_aligned = np.interp(cur_time - rdr_delay, v_ego_array[1], v_ego_array[0]) + d_path = np.sqrt(np.amin((path_x - rpt[0]) ** 2 + (path_y - rpt[1]) ** 2)) + + # create the track + if ids not in tracks or rpt[5] == 1: + tracks[ids] = Track() + tracks[ids].update(rpt[0], rpt[1], rpt[2], d_path, v_ego_t_aligned) + + # allow the vision model to remove the stationary flag if distance and rel speed roughly match + if VISION_POINT in ar_pts: + dist_to_vision = np.sqrt((0.5*(ar_pts[VISION_POINT][0] - rpt[0])) ** 2 + (2*(ar_pts[VISION_POINT][1] - rpt[1])) ** 2) + rel_speed_diff = abs(ar_pts[VISION_POINT][2] - rpt[2]) + tracks[ids].mix_vision(dist_to_vision, rel_speed_diff) + + # publish tracks (debugging) + dat = messaging.new_message() + dat.init('liveTracks', len(tracks)) + for cnt, ids in enumerate(tracks.keys()): + dat.liveTracks[cnt].trackId = ids + dat.liveTracks[cnt].dRel = float(tracks[ids].dRel) + dat.liveTracks[cnt].yRel = float(tracks[ids].yRel) + dat.liveTracks[cnt].vRel = float(tracks[ids].vRel) + dat.liveTracks[cnt].aRel = float(tracks[ids].aRel) + dat.liveTracks[cnt].stationary = tracks[ids].stationary + dat.liveTracks[cnt].oncoming = tracks[ids].oncoming + liveTracks.send(dat.to_bytes()) + + idens = tracks.keys() + track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens]) + + # If we have multiple points, cluster them + if len(track_pts) > 1: + link = linkage_vector(track_pts, method='centroid') + cluster_idxs = fcluster(link, 2.5, criterion='distance') + clusters = [None]*max(cluster_idxs) + + for idx in xrange(len(track_pts)): + cluster_i = cluster_idxs[idx]-1 + + if clusters[cluster_i] == None: + clusters[cluster_i] = Cluster() + clusters[cluster_i].add(tracks[idens[idx]]) + elif len(track_pts) == 1: + # TODO: why do we need this? + clusters = [Cluster()] + clusters[0].add(tracks[idens[0]]) + else: + clusters = [] + + # *** extract the lead car *** + lead_clusters = [c for c in clusters + if c.is_potential_lead(v_ego, enabled)] + lead_clusters.sort(key=lambda x: x.dRel) + lead_len = len(lead_clusters) + + # *** extract the second lead from the whole set of leads *** + lead2_clusters = [c for c in lead_clusters + if c.is_potential_lead2(lead_clusters)] + lead2_clusters.sort(key=lambda x: x.dRel) + lead2_len = len(lead2_clusters) + + # *** publish live20 *** + dat = messaging.new_message() + dat.init('live20') + dat.live20.mdMonoTime = PP.logMonoTime + dat.live20.canMonoTimes = canMonoTimes + if lead_len > 0: + lead_clusters[0].toLive20(dat.live20.leadOne) + if lead2_len > 0: + lead2_clusters[0].toLive20(dat.live20.leadTwo) + else: + dat.live20.leadTwo.status = False + else: + dat.live20.leadOne.status = False + + dat.live20.cumLagMs = -rk.remaining*1000. + live20.send(dat.to_bytes()) + + rk.monitor_time() + +def main(gctx=None): + radard_thread(gctx) + +if __name__ == "__main__": + main() diff --git a/selfdrive/logcatd/Makefile b/selfdrive/logcatd/Makefile new file mode 100644 index 0000000000..610ca25676 --- /dev/null +++ b/selfdrive/logcatd/Makefile @@ -0,0 +1,58 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +OBJS = logcatd.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: logcatd + +logcatd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -llog + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f logcatd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/logcatd/logcatd.cc b/selfdrive/logcatd/logcatd.cc new file mode 100644 index 0000000000..c2f688fd59 --- /dev/null +++ b/selfdrive/logcatd/logcatd.cc @@ -0,0 +1,68 @@ +#include +#include +#include + +#include +#include +#include + +#include +#include +#include "common/timing.h" +#include "cereal/gen/cpp/log.capnp.h" + +int main() { + int err; + + struct logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0); + assert(logger_list); + struct logger *main_logger = android_logger_open(logger_list, LOG_ID_MAIN); + assert(main_logger); + struct logger *radio_logger = android_logger_open(logger_list, LOG_ID_RADIO); + assert(radio_logger); + struct logger *system_logger = android_logger_open(logger_list, LOG_ID_SYSTEM); + assert(system_logger); + struct logger *crash_logger = android_logger_open(logger_list, LOG_ID_CRASH); + assert(crash_logger); + struct logger *kernel_logger = android_logger_open(logger_list, LOG_ID_KERNEL); + assert(kernel_logger); + + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + err = zmq_bind(publisher, "tcp://*:8020"); + assert(err == 0); + + while (1) { + log_msg log_msg; + err = android_logger_list_read(logger_list, &log_msg); + if (err <= 0) { + break; + } + + AndroidLogEntry entry; + err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); + if (err < 0) { + continue; + } + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto androidEntry = event.initAndroidLogEntry(); + androidEntry.setId(log_msg.id()); + androidEntry.setTs(entry.tv_sec * 1000000000ULL + entry.tv_nsec); + androidEntry.setPriority(entry.priority); + androidEntry.setPid(entry.pid); + androidEntry.setTid(entry.tid); + androidEntry.setTag(entry.tag); + androidEntry.setMessage(entry.message); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + } + + android_logger_list_close(logger_list); + + return 0; +} \ No newline at end of file diff --git a/selfdrive/loggerd/__init__.py b/selfdrive/loggerd/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py new file mode 100644 index 0000000000..ffba77d078 --- /dev/null +++ b/selfdrive/loggerd/config.py @@ -0,0 +1,9 @@ +import os + +# fetch from environment +DONGLE_ID = os.getenv("DONGLE_ID") +DONGLE_SECRET = os.getenv("DONGLE_SECRET") + +ROOT = '/sdcard/realdata/' + +SEGMENT_LENGTH = 60 diff --git a/selfdrive/loggerd/logger.py b/selfdrive/loggerd/logger.py new file mode 100644 index 0000000000..78af9d4740 --- /dev/null +++ b/selfdrive/loggerd/logger.py @@ -0,0 +1,65 @@ +import os +import time + + +class Logger(object): + def __init__(self, root, init_data): + self.root = root + self.init_data = init_data + + self.part = None + self.data_dir = None + self.cur_dir = None + self.log_file = None + self.started = False + self.log_path = None + self.lock_path = None + self.log_file = None + + def open(self): + self.data_dir = self.cur_dir + "--" + str(self.part) + + try: + os.makedirs(self.data_dir) + except OSError: + pass + + self.log_path = os.path.join(self.data_dir, "rlog") + self.lock_path = self.log_path + ".lock" + + open(self.lock_path, "wb").close() + self.log_file = open(self.log_path, "wb") + self.log_file.write(self.init_data) + + def start(self): + self.part = 0 + self.cur_dir = self.root + time.strftime("%Y-%m-%d--%H-%M-%S") + + self.open() + + self.started = True + + return self.data_dir, self.part + + def stop(self): + if not self.started: + return + self.log_file.close() + os.unlink(self.lock_path) + self.started = False + + def rotate(self): + old_lock_path = self.lock_path + old_log_file = self.log_file + self.part += 1 + self.open() + + old_log_file.close() + os.unlink(old_lock_path) + + return self.data_dir, self.part + + def log_data(self, d): + if not self.started: + return + self.log_file.write(d) diff --git a/selfdrive/loggerd/loggerd.py b/selfdrive/loggerd/loggerd.py new file mode 100755 index 0000000000..2e7985ba0d --- /dev/null +++ b/selfdrive/loggerd/loggerd.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python +import os +import json +import zmq + +import common.realtime as realtime +from common.services import service_list +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging + +import uploader +from logger import Logger + +from selfdrive.loggerd.config import ROOT, SEGMENT_LENGTH + + +def gen_init_data(gctx): + msg = messaging.new_message() + + kernel_args = open("/proc/cmdline", "r").read().strip().split(" ") + msg.initData.kernelArgs = kernel_args + + msg.initData.gctx = json.dumps(gctx) + if os.getenv('DONGLE_ID'): + msg.initData.dongleId = os.getenv('DONGLE_ID') + + return msg.to_bytes() + +def main(gctx=None): + logger = Logger(ROOT, gen_init_data(gctx)) + + context = zmq.Context() + poller = zmq.Poller() + + # we push messages to visiond to rotate image recordings + vision_control_sock = context.socket(zmq.PUSH) + vision_control_sock.connect("tcp://127.0.0.1:8001") + + # register listeners for all services + for service in service_list.itervalues(): + if service.should_log and service.port is not None: + messaging.sub_sock(context, service.port, poller) + + uploader.clear_locks(ROOT) + + cur_dir, cur_part = logger.start() + try: + cloudlog.info("starting in dir %r", cur_dir) + + rotate_msg = messaging.log.LogRotate.new_message() + rotate_msg.segmentNum = cur_part + rotate_msg.path = cur_dir + vision_control_sock.send(rotate_msg.to_bytes()) + + last_rotate = realtime.sec_since_boot() + while True: + polld = poller.poll(timeout=1000) + for sock, mode in polld: + if mode != zmq.POLLIN: + continue + dat = sock.recv() + + # print "got", len(dat), realtime.sec_since_boot() + # logevent = log_capnp.Event.from_bytes(dat) + # print str(logevent) + logger.log_data(dat) + + t = realtime.sec_since_boot() + if (t - last_rotate) > SEGMENT_LENGTH: + last_rotate += SEGMENT_LENGTH + + cur_dir, cur_part = logger.rotate() + cloudlog.info("rotated to %r", cur_dir) + + rotate_msg = messaging.log.LogRotate.new_message() + rotate_msg.segmentNum = cur_part + rotate_msg.path = cur_dir + + vision_control_sock.send(rotate_msg.to_bytes()) + + finally: + logger.stop() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py new file mode 100755 index 0000000000..246d45342c --- /dev/null +++ b/selfdrive/loggerd/uploader.py @@ -0,0 +1,238 @@ +#!/usr/bin/env python +import os +import time +import stat +import random +import ctypes +import inspect +import requests +import traceback +import threading + +from selfdrive.swaglog import cloudlog +from selfdrive.loggerd.config import DONGLE_ID, DONGLE_SECRET, ROOT + +from common.api import api_get + +def raise_on_thread(t, exctype): + for ctid, tobj in threading._active.items(): + if tobj is t: + tid = ctid + break + else: + raise Exception("Could not find thread") + + '''Raises an exception in the threads with id tid''' + if not inspect.isclass(exctype): + raise TypeError("Only types can be raised (not instances)") + + res = ctypes.pythonapi.PyThreadState_SetAsyncExc(ctypes.c_long(tid), + ctypes.py_object(exctype)) + if res == 0: + raise ValueError("invalid thread id") + elif res != 1: + # "if it returns a number greater than one, you're in trouble, + # and you should call it again with exc=NULL to revert the effect" + ctypes.pythonapi.PyThreadState_SetAsyncExc(tid, 0) + raise SystemError("PyThreadState_SetAsyncExc failed") + +def listdir_with_creation_date(d): + lst = os.listdir(d) + for fn in lst: + try: + st = os.stat(os.path.join(d, fn)) + ctime = st[stat.ST_CTIME] + yield (ctime, fn) + except OSError: + cloudlog.exception("listdir_with_creation_date: stat failed?") + yield (None, fn) + +def listdir_by_creation_date(d): + times_and_paths = list(listdir_with_creation_date(d)) + return [path for _, path in sorted(times_and_paths)] + +def clear_locks(root): + for logname in os.listdir(root): + path = os.path.join(root, logname) + try: + for fname in os.listdir(path): + if fname.endswith(".lock"): + os.unlink(os.path.join(path, fname)) + except OSError: + cloudlog.exception("clear_locks failed") + + +class Uploader(object): + def __init__(self, dongle_id, dongle_secret, root): + self.dongle_id = dongle_id + self.dongle_secret = dongle_secret + self.root = root + + self.upload_thread = None + + self.last_resp = None + self.last_exc = None + + def clean_dirs(self): + try: + for logname in os.listdir(self.root): + path = os.path.join(self.root, logname) + # remove empty directories + if not os.listdir(path): + os.rmdir(path) + except OSError: + cloudlog.exception("clean_dirs failed") + + def gen_upload_files(self): + for logname in listdir_by_creation_date(self.root): + path = os.path.join(self.root, logname) + names = os.listdir(path) + if any(name.endswith(".lock") for name in names): + continue + + for name in names: + key = os.path.join(logname, name) + fn = os.path.join(path, name) + + yield (name, key, fn) + + def next_file_to_upload(self): + # try to upload log files first + for name, key, fn in self.gen_upload_files(): + if name in ["rlog", "rlog.bz2"]: + return (key, fn, 0) + + # then upload camera files no not on wifi + for name, key, fn in self.gen_upload_files(): + if not name.endswith('.lock') and not name.endswith(".tmp"): + return (key, fn, 1) + + return None + + + def do_upload(self, key, fn): + try: + url_resp = api_get("upload_url", timeout=2, + id=self.dongle_id, secret=self.dongle_secret, + path=key) + url = url_resp.text + cloudlog.info({"upload_url", url}) + + with open(fn, "rb") as f: + self.last_resp = requests.put(url, data=f) + except Exception as e: + self.last_exc = (e, traceback.format_exc()) + raise + + def normal_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + try: + self.do_upload(key, fn) + except Exception: + pass + + return self.last_resp + + def killable_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + self.upload_thread = threading.Thread(target=lambda: self.do_upload(key, fn)) + self.upload_thread.start() + self.upload_thread.join() + self.upload_thread = None + + return self.last_resp + + def abort_upload(self): + thread = self.upload_thread + if thread is None: + return + if not thread.is_alive(): + return + raise_on_thread(thread, SystemExit) + thread.join() + + def upload(self, key, fn): + # write out the bz2 compress + if fn.endswith("log"): + ext = ".bz2" + cloudlog.info("compressing %r to %r", fn, fn+ext) + if os.system("nice -n 19 bzip2 -c %s > %s.tmp && mv %s.tmp %s%s && rm %s" % (fn, fn, fn, fn, ext, fn)) != 0: + cloudlog.exception("upload: bzip2 compression failed") + return False + + # assuming file is named properly + key += ext + fn += ext + + try: + sz = os.path.getsize(fn) + except OSError: + cloudlog.exception("upload: getsize failed") + return False + + cloudlog.event("upload", key=key, fn=fn, sz=sz) + + cloudlog.info("checking %r with size %r", key, sz) + + if sz == 0: + # can't upload files of 0 size + os.unlink(fn) # delete the file + success = True + else: + cloudlog.info("uploading %r", fn) + # stat = self.killable_upload(key, fn) + stat = self.normal_upload(key, fn) + if stat is not None and stat.status_code == 200: + cloudlog.event("upload_success", key=key, fn=fn, sz=sz) + os.unlink(fn) # delete the file + success = True + else: + cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz) + success = False + + self.clean_dirs() + + return success + + + +def uploader_fn(exit_event): + cloudlog.info("uploader_fn") + + uploader = Uploader(DONGLE_ID, DONGLE_SECRET, ROOT) + + while True: + backoff = 0.1 + while True: + + if exit_event.is_set(): + return + + d = uploader.next_file_to_upload() + if d is None: + break + + key, fn, _ = d + + cloudlog.info("to upload %r", d) + success = uploader.upload(key, fn) + if success: + backoff = 0.1 + else: + cloudlog.info("backoff %r", backoff) + time.sleep(backoff + random.uniform(0, backoff)) + backoff *= 2 + cloudlog.info("upload done, success=%r", success) + + time.sleep(5) + +def main(gctx=None): + uploader_fn(threading.Event()) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/logmessaged.py b/selfdrive/logmessaged.py new file mode 100755 index 0000000000..2e49df417c --- /dev/null +++ b/selfdrive/logmessaged.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python +import zmq +from logentries import LogentriesHandler +from common.services import service_list +import selfdrive.messaging as messaging + +def main(gctx): + # setup logentries. we forward log messages to it + le_token = "bc65354a-b887-4ef4-8525-15dd51230e8c" + le_handler = LogentriesHandler(le_token, use_tls=False) + + le_level = 20 #logging.INFO + + ctx = zmq.Context() + sock = ctx.socket(zmq.PULL) + sock.bind("ipc:///tmp/logmessage") + + # and we publish them + pub_sock = messaging.pub_sock(ctx, service_list['logMessage'].port) + + while True: + dat = ''.join(sock.recv_multipart()) + + # print "RECV", repr(dat) + + levelnum = ord(dat[0]) + dat = dat[1:] + + if levelnum >= le_level: + # push to logentries + le_handler.emit_raw(dat) + + # then we publish them + msg = messaging.new_message() + msg.logMessage = dat + pub_sock.send(msg.to_bytes()) + +if __name__ == "__main__": + main(None) diff --git a/selfdrive/manager.py b/selfdrive/manager.py new file mode 100755 index 0000000000..93eae5be2c --- /dev/null +++ b/selfdrive/manager.py @@ -0,0 +1,278 @@ +#!/usr/bin/env python +import os +import sys +import time +import importlib +import subprocess +import signal +import traceback +import usb1 +from multiprocessing import Process +from common.services import service_list + +import zmq + +from setproctitle import setproctitle + +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging +from selfdrive.thermal import read_thermal +from selfdrive.registration import register + +import common.crash + +# comment out anything you don't want to run +managed_processes = { + "uploader": "selfdrive.loggerd.uploader", + "controlsd": "selfdrive.controls.controlsd", + "radard": "selfdrive.controls.radard", + "calibrationd": "selfdrive.calibrationd.calibrationd", + "loggerd": "selfdrive.loggerd.loggerd", + "logmessaged": "selfdrive.logmessaged", + #"boardd": "selfdrive.boardd.boardd", + "logcatd": ("logcatd", ["./logcatd"]), + "boardd": ("boardd", ["./boardd"]), # switch to c++ boardd + "ui": ("ui", ["./ui"]), + "visiond": ("visiond", ["./visiond"]), + "sensord": ("sensord", ["./sensord"]), } + +running = {} + +car_started_processes = ['controlsd', 'loggerd', 'visiond', 'sensord', 'radard', 'calibrationd'] + + +# ****************** process management functions ****************** +def launcher(proc, gctx): + try: + # unset the signals + signal.signal(signal.SIGINT, signal.SIG_DFL) + signal.signal(signal.SIGTERM, signal.SIG_DFL) + + # import the process + mod = importlib.import_module(proc) + + # rename the process + setproctitle(proc) + + # exec the process + mod.main(gctx) + except Exception: + # can't install the crash handler becuase sys.excepthook doesn't play nice + # with threads, so catch it here. + common.crash.capture_exception() + raise + +def nativelauncher(pargs, cwd): + # exec the process + os.chdir(cwd) + + # because when extracted from pex zips permissions get lost -_- + os.chmod(pargs[0], 0o700) + + os.execvp(pargs[0], pargs) + +def start_managed_process(name): + if name in running or name not in managed_processes: + return + proc = managed_processes[name] + if isinstance(proc, basestring): + cloudlog.info("starting python %s" % proc) + running[name] = Process(name=name, target=launcher, args=(proc, gctx)) + else: + pdir, pargs = proc + cwd = os.path.dirname(os.path.realpath(__file__)) + if pdir is not None: + cwd = os.path.join(cwd, pdir) + cloudlog.info("starting process %s" % name) + running[name] = Process(name=name, target=nativelauncher, args=(pargs, cwd)) + running[name].start() + +def kill_managed_process(name): + if name not in running or name not in managed_processes: + return + cloudlog.info("killing %s" % name) + running[name].terminate() + running[name].join(5.0) + if running[name].exitcode is None: + cloudlog.info("killing %s with SIGKILL" % name) + os.kill(running[name].pid, signal.SIGKILL) + running[name].join() + cloudlog.info("%s is finally dead" % name) + else: + cloudlog.info("%s is dead with %d" % (name, running[name].exitcode)) + del running[name] + +def cleanup_all_processes(signal, frame): + cloudlog.info("caught ctrl-c %s %s" % (signal, frame)) + for name in running.keys(): + kill_managed_process(name) + sys.exit(0) + +# ****************** run loop ****************** + +def manager_init(): + global gctx + + reg_res = register() + if reg_res: + dongle_id, dongle_secret = reg_res + else: + raise Exception("server registration failed") + + # set dongle id + cloudlog.info("dongle id is " + dongle_id) + os.environ['DONGLE_ID'] = dongle_id + os.environ['DONGLE_SECRET'] = dongle_secret + + cloudlog.bind_global(dongle_id=dongle_id) + + # set gctx + gctx = { + "calibration": { + "initial_homography": [1.15728010e+00, -4.69379619e-02, 7.46450623e+01, + 7.99253014e-02, 1.06372458e+00, 5.77762553e+01, + 9.35543519e-05, -1.65429898e-04, 9.98062699e-01] + } + } + + # hook to kill all processes + signal.signal(signal.SIGINT, cleanup_all_processes) + signal.signal(signal.SIGTERM, cleanup_all_processes) + +def manager_thread(): + # now loop + context = zmq.Context() + thermal_sock = messaging.pub_sock(context, service_list['thermal'].port) + health_sock = messaging.sub_sock(context, service_list['health'].port) + + cloudlog.info("manager start") + + start_managed_process("logmessaged") + start_managed_process("logcatd") + start_managed_process("uploader") + start_managed_process("ui") + + # *** wait for the board *** + wait_for_device() + + # flash the device + if os.getenv("NOPROG") is None: + boarddir = os.path.dirname(os.path.abspath(__file__))+"/../board/" + os.system("cd %s && make" % boarddir) + + start_managed_process("boardd") + + if os.getenv("STARTALL") is not None: + for p in car_started_processes: + start_managed_process(p) + + while 1: + # get health of board, log this in "thermal" + td = messaging.recv_sock(health_sock, wait=True) + print td + + # replace thermald + msg = read_thermal() + thermal_sock.send(msg.to_bytes()) + print msg + + # TODO: add car battery voltage check + max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, + msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + + # uploader is gated based on the phone temperature + if max_temp > 85.0: + cloudlog.info("over temp: %r", max_temp) + kill_managed_process("uploader") + elif max_temp < 70.0: + start_managed_process("uploader") + + # start constellation of processes when the car starts + if td.health.started: + for p in car_started_processes: + start_managed_process(p) + else: + for p in car_started_processes: + kill_managed_process(p) + + # check the status of all processes, did any of them die? + for p in running: + cloudlog.info(" running %s %s" % (p, running[p])) + + +# optional, build the c++ binaries and preimport the python for speed +def manager_prepare(): + for p in managed_processes: + proc = managed_processes[p] + if isinstance(proc, basestring): + # import this python + cloudlog.info("preimporting %s" % proc) + importlib.import_module(proc) + else: + # build this process + cloudlog.info("building %s" % (proc,)) + try: + subprocess.check_call(["make", "-j4"], cwd=proc[0]) + except subprocess.CalledProcessError: + # make clean if the build failed + cloudlog.info("building %s failed, make clean" % (proc, )) + subprocess.check_call(["make", "clean"], cwd=proc[0]) + subprocess.check_call(["make", "-j4"], cwd=proc[0]) + +def manager_test(): + global managed_processes + managed_processes = {} + managed_processes["test1"] = ("test", ["./test.py"]) + managed_processes["test2"] = ("test", ["./test.py"]) + managed_processes["test3"] = "selfdrive.test.test" + manager_prepare() + start_managed_process("test1") + start_managed_process("test2") + start_managed_process("test3") + print running + time.sleep(3) + kill_managed_process("test1") + kill_managed_process("test2") + kill_managed_process("test3") + print running + time.sleep(10) + +def wait_for_device(): + while 1: + try: + context = usb1.USBContext() + for device in context.getDeviceList(skip_on_error=True): + if (device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc) or \ + (device.getVendorID() == 0x0483 and device.getProductID() == 0xdf11): + handle = device.open() + handle.claimInterface(0) + cloudlog.info("found board") + handle.close() + return + except Exception as e: + print "exception", e, + print "waiting..." + time.sleep(1) + +def main(): + if os.getenv("NOLOG") is not None: + del managed_processes['loggerd'] + if os.getenv("NOBOARD") is not None: + del managed_processes['boardd'] + + manager_init() + + if len(sys.argv) > 1 and sys.argv[1] == "test": + manager_test() + else: + manager_prepare() + try: + manager_thread() + except Exception: + traceback.print_exc() + common.crash.capture_exception() + finally: + cleanup_all_processes(None, None) + +if __name__ == "__main__": + main() diff --git a/selfdrive/messaging.py b/selfdrive/messaging.py new file mode 100644 index 0000000000..cb5c27b891 --- /dev/null +++ b/selfdrive/messaging.py @@ -0,0 +1,52 @@ +import zmq + +from cereal import log +from common import realtime + +def new_message(): + dat = log.Event.new_message() + dat.logMonoTime = int(realtime.sec_since_boot() * 1e9) + return dat + +def pub_sock(context, port, addr="*"): + sock = context.socket(zmq.PUB) + sock.bind("tcp://%s:%d" % (addr, port)) + return sock + +def sub_sock(context, port, poller=None, addr="127.0.0.1"): + sock = context.socket(zmq.SUB) + sock.connect("tcp://%s:%d" % (addr, port)) + sock.setsockopt(zmq.SUBSCRIBE, "") + if poller is not None: + poller.register(sock, zmq.POLLIN) + return sock + +def drain_sock(sock, wait_for_one=False): + ret = [] + while 1: + try: + if wait_for_one and len(ret) == 0: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + dat = log.Event.from_bytes(dat) + ret.append(dat) + except zmq.error.Again: + break + return ret + + +# TODO: print when we drop packets? +def recv_sock(sock, wait=False): + dat = None + while 1: + try: + if wait and dat is None: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + except zmq.error.Again: + break + if dat is not None: + dat = log.Event.from_bytes(dat) + return dat diff --git a/selfdrive/registration.py b/selfdrive/registration.py new file mode 100644 index 0000000000..b2dc5d0146 --- /dev/null +++ b/selfdrive/registration.py @@ -0,0 +1,38 @@ +import os +import json +import subprocess + +from selfdrive.swaglog import cloudlog +from common.api import api_get + +DONGLEAUTH_PATH = "/sdcard/dongleauth" + +def get_imei(): + # Telephony.getDeviceId() + result = subprocess.check_output(["service", "call", "phone", "130"]).strip().split("\n") + hex_data = ''.join(l[14:49] for l in result[1:]).replace(" ", "") + data = hex_data.decode("hex") + + imei_str = data[8:-4].replace("\x00", "") + return imei_str + +def get_serial(): + return subprocess.check_output(["getprop", "ro.serialno"]).strip() + +def register(): + try: + if os.path.exists(DONGLEAUTH_PATH): + dongleauth = json.load(open(DONGLEAUTH_PATH)) + else: + resp = api_get("pilot_auth", method='POST', imei=get_imei(), serial=get_serial()) + resp = resp.text + dongleauth = json.loads(resp) + open(DONGLEAUTH_PATH, "w").write(resp) + return dongleauth["dongle_id"], dongleauth["dongle_secret"] + except Exception: + cloudlog.exception("failed to authenticate") + return None + +if __name__ == "__main__": + print api_get("").text + print register() diff --git a/selfdrive/sensord/Makefile b/selfdrive/sensord/Makefile new file mode 100644 index 0000000000..e6ad07817e --- /dev/null +++ b/selfdrive/sensord/Makefile @@ -0,0 +1,60 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_FLAGS = -I$(PHONELIBS)/capnp-cpp/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -l:libcapnp.a -l:libkj.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +OBJS = sensors.o \ + log.capnp.o + +DEPS := $(OBJS:.o=.d) + +all: sensord + +sensord: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -lhardware + +sensors.o: sensors.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_FLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_FLAGS) \ + -c -o '$@' '$<' + + +.PHONY: clean +clean: + rm -f sensord $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/sensord/sensors.cc b/selfdrive/sensord/sensors.cc new file mode 100644 index 0000000000..774b9afc26 --- /dev/null +++ b/selfdrive/sensord/sensors.cc @@ -0,0 +1,227 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +#include + +#include "common/timing.h" + +#include "cereal/gen/cpp/log.capnp.h" + +// zmq output +static void *gps_publisher; + +#define SENSOR_ACCELEROMETER 1 +#define SENSOR_MAGNETOMETER 2 +#define SENSOR_GYRO 4 + +void sensor_loop() { + printf("*** sensor loop\n"); + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // required + struct sensor_t const* list; + int count = module->get_sensors_list(module, &list); + printf("%d sensors found\n", count); + + device->activate(device, SENSOR_ACCELEROMETER, 0); + device->activate(device, SENSOR_MAGNETOMETER, 0); + device->activate(device, SENSOR_GYRO, 0); + + device->activate(device, SENSOR_ACCELEROMETER, 1); + device->activate(device, SENSOR_MAGNETOMETER, 1); + device->activate(device, SENSOR_GYRO, 1); + + device->setDelay(device, SENSOR_ACCELEROMETER, ms2ns(10)); + device->setDelay(device, SENSOR_GYRO, ms2ns(10)); + device->setDelay(device, SENSOR_MAGNETOMETER, ms2ns(100)); + + static const size_t numEvents = 16; + sensors_event_t buffer[numEvents]; + + // zmq output + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8003"); + + while (1) { + int n = device->poll(device, buffer, numEvents); + if (n == 0) continue; + if (n < 0) { + printf("sensor_loop poll failed: %d\n", n); + continue; + } + + uint64_t log_time = nanos_since_boot(); + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(log_time); + + auto sensorEvents = event.initSensorEvents(n); + + for (int i = 0; i < n; i++) { + + const sensors_event_t& data = buffer[i]; + + sensorEvents[i].setVersion(data.version); + sensorEvents[i].setSensor(data.sensor); + sensorEvents[i].setType(data.type); + sensorEvents[i].setTimestamp(data.timestamp); + + switch (data.type) { + case SENSOR_TYPE_ACCELEROMETER: { + auto svec = sensorEvents[i].initAcceleration(); + kj::ArrayPtr vs(&data.acceleration.v[0], 3); + svec.setV(vs); + svec.setStatus(data.acceleration.status); + break; + } + case SENSOR_TYPE_MAGNETIC_FIELD: { + auto svec = sensorEvents[i].initMagnetic(); + kj::ArrayPtr vs(&data.magnetic.v[0], 3); + svec.setV(vs); + svec.setStatus(data.magnetic.status); + break; + } + case SENSOR_TYPE_GYROSCOPE: { + auto svec = sensorEvents[i].initGyro(); + kj::ArrayPtr vs(&data.gyro.v[0], 3); + svec.setV(vs); + svec.setStatus(data.gyro.status); + break; + } + default: + continue; + } + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + // printf("send %d\n", bytes.size()); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + + } +} + +static const GpsInterface* gGpsInterface = NULL; +static const AGpsInterface* gAGpsInterface = NULL; +static const GpsMeasurementInterface* gGpsMeasurementInterface = NULL; + +static void nmea_callback(GpsUtcTime timestamp, const char* nmea, int length) { + + uint64_t log_time = nanos_since_boot(); + uint64_t log_time_wall = nanos_since_epoch(); + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(log_time); + + auto nmeaData = event.initGpsNMEA(); + nmeaData.setTimestamp(timestamp); + nmeaData.setLocalWallTime(log_time_wall); + nmeaData.setNmea(nmea); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + // printf("gps send %d\n", bytes.size()); + zmq_send(gps_publisher, bytes.begin(), bytes.size(), 0); +} + +static pthread_t create_thread_callback(const char* name, void (*start)(void *), void* arg) { + printf("creating thread: %s\n", name); + pthread_t thread; + pthread_attr_t attr; + int err; + + err = pthread_attr_init(&attr); + err = pthread_create(&thread, &attr, (void*(*)(void*))start, arg); + + return thread; +} + +static GpsCallbacks gps_callbacks = { + sizeof(GpsCallbacks), + NULL, + NULL, + NULL, + nmea_callback, + NULL, + NULL, + NULL, + create_thread_callback, +}; + +static void agps_status_cb(AGpsStatus *status) { + switch (status->status) { + case GPS_REQUEST_AGPS_DATA_CONN: + fprintf(stdout, "*** data_conn_open\n"); + gAGpsInterface->data_conn_open("internet"); + break; + case GPS_RELEASE_AGPS_DATA_CONN: + fprintf(stdout, "*** data_conn_closed\n"); + gAGpsInterface->data_conn_closed(); + break; + } +} + +static AGpsCallbacks agps_callbacks = { + agps_status_cb, + create_thread_callback, +}; + + + +static void gps_init() { + printf("*** init GPS\n"); + hw_module_t* module; + hw_get_module(GPS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + + hw_device_t* device; + module->methods->open(module, GPS_HARDWARE_MODULE_ID, &device); + + // ** get gps interface ** + gps_device_t* gps_device = (gps_device_t *)device; + gGpsInterface = gps_device->get_gps_interface(gps_device); + gAGpsInterface = (const AGpsInterface*)gGpsInterface->get_extension(AGPS_INTERFACE); + + + + gGpsInterface->init(&gps_callbacks); + gAGpsInterface->init(&agps_callbacks); + gAGpsInterface->set_server(AGPS_TYPE_SUPL, "supl.google.com", 7276); + + gGpsInterface->delete_aiding_data(GPS_DELETE_ALL); + gGpsInterface->start(); + gGpsInterface->set_position_mode(GPS_POSITION_MODE_MS_BASED, + GPS_POSITION_RECURRENCE_PERIODIC, + 1000, 0, 0); + void *gps_context = zmq_ctx_new(); + gps_publisher = zmq_socket(gps_context, ZMQ_PUB); + zmq_bind(gps_publisher, "tcp://*:8004"); +} + +int main(int argc, char *argv[]) { + gps_init(); + sensor_loop(); +} + diff --git a/selfdrive/swaglog.py b/selfdrive/swaglog.py new file mode 100644 index 0000000000..012bb93806 --- /dev/null +++ b/selfdrive/swaglog.py @@ -0,0 +1,38 @@ +import os +import logging + +import zmq + +from common.logging_extra import SwagLogger, SwagFormatter + +class LogMessageHandler(logging.Handler): + def __init__(self, formatter): + logging.Handler.__init__(self) + self.setFormatter(formatter) + self.pid = None + + def connect(self): + self.zctx = zmq.Context() + self.sock = self.zctx.socket(zmq.PUSH) + self.sock.connect("ipc:///tmp/logmessage") + self.pid = os.getpid() + + def emit(self, record): + if os.getpid() != self.pid: + self.connect() + + msg = self.format(record).rstrip('\n') + # print "SEND", repr(msg) + try: + self.sock.send(chr(record.levelno)+msg, zmq.NOBLOCK) + except zmq.error.Again: + # drop :/ + pass + +cloudlog = log = SwagLogger() +log.setLevel(logging.DEBUG) + +outhandler = logging.StreamHandler() +log.addHandler(outhandler) + +log.addHandler(LogMessageHandler(SwagFormatter(log))) diff --git a/selfdrive/thermal.py b/selfdrive/thermal.py new file mode 100644 index 0000000000..f89f358d48 --- /dev/null +++ b/selfdrive/thermal.py @@ -0,0 +1,19 @@ +"""Methods for reading system thermal information.""" +import selfdrive.messaging as messaging + +def read_tz(x): + with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: + ret = int(f.read()) + return ret + +def read_thermal(): + dat = messaging.new_message() + dat.init('thermal') + dat.thermal.cpu0 = read_tz(5) + dat.thermal.cpu1 = read_tz(7) + dat.thermal.cpu2 = read_tz(10) + dat.thermal.cpu3 = read_tz(12) + dat.thermal.mem = read_tz(2) + dat.thermal.gpu = read_tz(16) + dat.thermal.bat = read_tz(29) + return dat diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile new file mode 100644 index 0000000000..e4549e1183 --- /dev/null +++ b/selfdrive/ui/Makefile @@ -0,0 +1,73 @@ +CC = clang +CXX = clang++ + + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-c/aarch64/lib -l:libcapn.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +NANOVG_FLAGS = -I$(PHONELIBS)/nanovg + +OPENGL_LIBS = -lGLESv3 + +FRAMEBUFFER_LIBS = -lutils -lgui -lEGL + +OBJS = ui.o \ + touch.o \ + ../common/visionipc.o \ + ../common/framebuffer.o \ + $(PHONELIBS)/nanovg/nanovg.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +all: ui + +ui: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(FRAMEBUFFER_LIBS) \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -L/system/vendor/lib64 \ + $(OPENGL_LIBS) \ + -lcutils -lm -llog + +../common/framebuffer.o: ../common/framebuffer.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -I$(PHONELIBS)/android_frameworks_native/include \ + -I$(PHONELIBS)/android_system_core/include \ + -I$(PHONELIBS)/android_hardware_libhardware/include \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I.. -I../.. \ + $(NANOVG_FLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CFLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f ui $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/ui/touch.c b/selfdrive/ui/touch.c new file mode 100644 index 0000000000..a1b6a683af --- /dev/null +++ b/selfdrive/ui/touch.c @@ -0,0 +1,63 @@ +#include +#include +#include +#include +#include +#include + +#include "touch.h" + +void touch_init(TouchState *s) { + // synaptics touch screen on oneplus 3 + s->fd = open("/dev/input/event4", O_RDONLY); + assert(s->fd >= 0); +} + +int touch_poll(TouchState *s, int* out_x, int* out_y) { + assert(out_x && out_y); + bool up = false; + while (true) { + struct pollfd polls[] = {{ + .fd = s->fd, + .events = POLLIN, + }}; + int err = poll(polls, 1, 0); + if (err < 0) { + return -1; + } + if (!(polls[0].revents & POLLIN)) { + break; + } + + struct input_event event; + err = read(polls[0].fd, &event, sizeof(event)); + if (err < sizeof(event)) { + return -1; + } + + switch (event.type) { + case EV_ABS: + if (event.code == ABS_MT_POSITION_X) { + s->last_x = event.value; + } else if (event.code == ABS_MT_POSITION_Y) { + s->last_y = event.value; + } + break; + case EV_KEY: + if (event.code == BTN_TOOL_FINGER && event.value == 0) { + // finger up + up = true; + } + break; + default: + break; + } + } + if (up) { + // adjust for landscape + *out_x = 1920 - s->last_y; + *out_y = s->last_x; + } + return up; +} + diff --git a/selfdrive/ui/touch.h b/selfdrive/ui/touch.h new file mode 100644 index 0000000000..de89a71c5f --- /dev/null +++ b/selfdrive/ui/touch.h @@ -0,0 +1,12 @@ +#ifndef TOUCH_H +#define TOUCH_H + +typedef struct TouchState { + int fd; + int last_x, last_y; +} TouchState; + +void touch_init(TouchState *s); +int touch_poll(TouchState *s, int *out_x, int *out_y); + +#endif diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c new file mode 100644 index 0000000000..a5b9e63cde --- /dev/null +++ b/selfdrive/ui/ui.c @@ -0,0 +1,1325 @@ +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include + +#include "nanovg.h" +#define NANOVG_GLES3_IMPLEMENTATION +#include "nanovg_gl.h" +#include "nanovg_gl_utils.h" + +#include "common/timing.h" +#include "common/util.h" +#include "common/mat.h" + +#include "common/framebuffer.h" +#include "common/visionipc.h" +#include "common/modeldata.h" + +#include "cereal/gen/c/log.capnp.h" + +#include "touch.h" + +#define UI_BUF_COUNT 4 +typedef struct UIBuf { + int fd; + size_t len; + void* addr; +} UIBuf; + +typedef struct UIScene { + + int frontview; + + uint8_t *bgr_ptr; + int big_box_x, big_box_y, big_box_width, big_box_height; + + int transformed_width, transformed_height; + + uint64_t model_ts; + ModelData model; + + mat3 big_box_transform; // transformed box -> big box + + float v_cruise; + float v_ego; + float angle_steers; + int engaged; + + int lead_status; + float lead_d_rel, lead_y_rel, lead_v_rel; + + uint8_t *bgr_front_ptr; + int front_box_x, front_box_y, front_box_width, front_box_height; + + char alert_text1[1024]; + char alert_text2[1024]; + + float awareness_status; +} UIScene; + + +typedef struct UIState { + pthread_mutex_t lock; + + TouchState touch; + + FramebufferState *fb; + + int fb_w, fb_h; + EGLDisplay display; + EGLSurface surface; + + NVGcontext *vg; + int font; + + + + zsock_t *model_sock; + void* model_sock_raw; + zsock_t *live100_sock; + void* live100_sock_raw; + zsock_t *livecalibration_sock; + void* livecalibration_sock_raw; + zsock_t *live20_sock; + void* live20_sock_raw; + + // base ui + uint64_t last_base_update; + uint64_t last_rx_bytes; + uint64_t last_tx_bytes; + char serial[4096]; + const char* dongle_id; + char base_text[4096]; + int wifi_enabled; + int ap_enabled; + int board_connected; + + // vision state + + bool vision_connected; + bool vision_connect_firstrun; + int ipc_fd; + + VisionUIBufs vision_bufs; + UIBuf bufs[UI_BUF_COUNT]; + UIBuf front_bufs[UI_BUF_COUNT]; + int cur_vision_idx; + int cur_vision_front_idx; + + GLuint frame_program; + + GLuint frame_tex; + GLint frame_pos_loc, frame_texcoord_loc; + GLint frame_texture_loc, frame_transform_loc; + + GLuint line_program; + GLint line_pos_loc, line_color_loc; + GLint line_transform_loc; + + unsigned int rgb_width, rgb_height; + mat4 rgb_transform; + + unsigned int rgb_front_width, rgb_front_height; + GLuint frame_front_tex; + + UIScene scene; + + +} UIState; + + +static bool activity_running() { + return system("dumpsys activity activities | grep mFocusedActivity > /dev/null") == 0; +} + +static void start_settings_activity(const char* name) { + char launch_cmd[1024]; + snprintf(launch_cmd, sizeof(launch_cmd), + "am start -W --ez :settings:show_fragment_as_subsetting true -n 'com.android.settings/.%s'", name); + system(launch_cmd); +} + +static void wifi_pressed() { + start_settings_activity("Settings$WifiSettingsActivity"); +} +static void ap_pressed() { + start_settings_activity("Settings$TetherSettingsActivity"); +} + +static int wifi_enabled(UIState *s) { + return s->wifi_enabled; +} + +static int ap_enabled(UIState *s) { + return s->ap_enabled; +} + +typedef struct Button { + const char* label; + int x, y, w, h; + void (*pressed)(void); + int (*enabled)(UIState *); +} Button; +static const Button buttons[] = { + { + .label = "wifi", + .x = 400, .y = 700, .w = 250, .h = 250, + .pressed = wifi_pressed, + .enabled = wifi_enabled, + }, + { + .label = "ap", + .x = 1300, .y = 700, .w = 250, .h = 250, + .pressed = ap_pressed, + .enabled = ap_enabled, + } +}; + +// transform from road space into little-box (used for drawing path) +static const mat3 path_transform = {{ + 1.29149378e+00, -2.30320967e-01, -3.02391994e+01, + -1.72449331e-15, -2.12045399e-02, 5.03539175e+01, + -3.24378996e-17, -1.38821089e-03, 1.06663412e+00, +}}; + +static const char frame_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aTexCoord;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vTexCoord = aTexCoord;\n" + "}\n"; + +static const char frame_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_FragColor = texture2D(uTexture, vTexCoord.xy);\n" + "}\n"; + +static const char line_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aColor;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vColor = aColor;\n" + "}\n"; + +static const char line_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_FragColor = vColor;\n" + "}\n"; + +static GLuint load_shader(GLenum shaderType, const char *src) { + GLint status = 0, len = 0; + GLuint shader; + + if (!(shader = glCreateShader(shaderType))) + return 0; + + glShaderSource(shader, 1, &src, NULL); + glCompileShader(shader); + glGetShaderiv(shader, GL_COMPILE_STATUS, &status); + + if (status) + return shader; + + glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *msg = malloc(len); + if (msg) { + glGetShaderInfoLog(shader, len, NULL, msg); + msg[len-1] = 0; + fprintf(stderr, "error compiling shader:\n%s\n", msg); + free(msg); + } + } + glDeleteShader(shader); + return 0; +} + +static GLuint load_program(const char *vert_src, const char *frag_src) { + GLuint vert, frag, prog; + GLint status = 0, len = 0; + + if (!(vert = load_shader(GL_VERTEX_SHADER, vert_src))) + return 0; + if (!(frag = load_shader(GL_FRAGMENT_SHADER, frag_src))) + goto fail_frag; + if (!(prog = glCreateProgram())) + goto fail_prog; + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + glLinkProgram(prog); + + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status) + return prog; + + glGetProgramiv(prog, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *buf = (char*) malloc(len); + if (buf) { + glGetProgramInfoLog(prog, len, NULL, buf); + buf[len-1] = 0; + fprintf(stderr, "error linking program:\n%s\n", buf); + free(buf); + } + } + glDeleteProgram(prog); +fail_prog: + glDeleteShader(frag); +fail_frag: + glDeleteShader(vert); + return 0; +} + +static const mat4 device_transform = {{ + 1.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +// frame from 4/3 to 16/9 with a 2x zoon +static const mat4 frame_transform = {{ + 2*(4./3.)/(16./9.), 0.0, 0.0, 0.0, + 0.0, 2.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + + + +static void ui_init(UIState *s) { + memset(s, 0, sizeof(UIState)); + + pthread_mutex_init(&s->lock, NULL); + + // init connections + s->model_sock = zsock_new_sub(">tcp://127.0.0.1:8009", ""); + assert(s->model_sock); + s->model_sock_raw = zsock_resolve(s->model_sock); + + s->live100_sock = zsock_new_sub(">tcp://127.0.0.1:8007", ""); + assert(s->live100_sock); + s->live100_sock_raw = zsock_resolve(s->live100_sock); + + s->livecalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", ""); + assert(s->livecalibration_sock); + s->livecalibration_sock_raw = zsock_resolve(s->livecalibration_sock); + + s->live20_sock = zsock_new_sub(">tcp://127.0.0.1:8012", ""); + assert(s->live20_sock); + s->live20_sock_raw = zsock_resolve(s->live20_sock); + + s->ipc_fd = -1; + + touch_init(&s->touch); + + // init display + s->fb = framebuffer_init("ui", 0x00001000, + &s->display, &s->surface, &s->fb_w, &s->fb_h); + assert(s->fb); + + + // init base + property_get("ro.serialno", s->serial, ""); + + s->dongle_id = getenv("DONGLE_ID"); + if (!s->dongle_id) s->dongle_id = "(null)"; + + + // init drawing + s->vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG); + assert(s->vg); + //s->font = nvgCreateFont(s->vg, "sans-bold", "../assets/Roboto-Bold.ttf"); + s->font = nvgCreateFont(s->vg, "Bold", "../assets/courbd.ttf"); + assert(s->font >= 0); + + // init gl + + s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader); + assert(s->frame_program); + + s->frame_pos_loc = glGetAttribLocation(s->frame_program, "aPosition"); + s->frame_texcoord_loc = glGetAttribLocation(s->frame_program, "aTexCoord"); + + s->frame_texture_loc = glGetUniformLocation(s->frame_program, "uTexture"); + s->frame_transform_loc = glGetUniformLocation(s->frame_program, "uTransform"); + + + s->line_program = load_program(line_vertex_shader, line_fragment_shader); + assert(s->line_program); + + s->line_pos_loc = glGetAttribLocation(s->line_program, "aPosition"); + s->line_color_loc = glGetAttribLocation(s->line_program, "aColor"); + s->line_transform_loc = glGetUniformLocation(s->line_program, "uTransform"); + + glViewport(0, 0, s->fb_w, s->fb_h); + + glDisable(GL_DEPTH_TEST); + + assert(glGetError() == GL_NO_ERROR); +} + + +static void ui_init_vision(UIState *s, const VisionUIBufs vision_bufs, const int* fds) { + assert(vision_bufs.num_bufs == UI_BUF_COUNT); + assert(vision_bufs.num_front_bufs == UI_BUF_COUNT); + + for (int i=0; ibufs[i].addr) { + munmap(s->bufs[i].addr, vision_bufs.buf_len); + s->bufs[i].addr = NULL; + close(s->bufs[i].fd); + } + s->bufs[i].fd = fds[i]; + s->bufs[i].len = vision_bufs.buf_len; + s->bufs[i].addr = mmap(NULL, s->bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, s->bufs[i].fd, 0); + // printf("b %d %p\n", bufs[i].fd, bufs[i].addr); + assert(s->bufs[i].addr != MAP_FAILED); + } + for (int i=0; ifront_bufs[i].addr) { + munmap(s->front_bufs[i].addr, vision_bufs.buf_len); + s->front_bufs[i].addr = NULL; + close(s->front_bufs[i].fd); + } + s->front_bufs[i].fd = fds[vision_bufs.num_bufs + i]; + s->front_bufs[i].len = vision_bufs.front_buf_len; + s->front_bufs[i].addr = mmap(NULL, s->front_bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, s->front_bufs[i].fd, 0); + // printf("f %d %p\n", front_bufs[i].fd, front_bufs[i].addr); + assert(s->front_bufs[i].addr != MAP_FAILED); + } + + s->cur_vision_idx = -1; + s->cur_vision_front_idx = -1; + + s->scene = (UIScene){ + .frontview = 0, + .big_box_x = vision_bufs.big_box_x, + .big_box_y = vision_bufs.big_box_y, + .big_box_width = vision_bufs.big_box_width, + .big_box_height = vision_bufs.big_box_height, + .transformed_width = vision_bufs.transformed_width, + .transformed_height = vision_bufs.transformed_height, + .front_box_x = vision_bufs.front_box_x, + .front_box_y = vision_bufs.front_box_y, + .front_box_width = vision_bufs.front_box_width, + .front_box_height = vision_bufs.front_box_height, + + // only used when ran without controls. overwridden by liveCalibration messages. + .big_box_transform = (mat3){{ + 1.16809241e+00, -3.18601797e-02, 7.42513711e+01, + 7.97437780e-02, 1.09117765e+00, 5.71824220e+01, + 8.67937981e-05, -7.68221181e-05, 1.00196836e+00, + }}, + }; + + s->vision_bufs = vision_bufs; + + s->rgb_width = vision_bufs.width; + s->rgb_height = vision_bufs.height; + + s->rgb_front_width = vision_bufs.front_width; + s->rgb_front_height = vision_bufs.front_height; + + s->rgb_transform = (mat4){{ + 2.0/s->rgb_width, 0.0, 0.0, -1.0, + 0.0, 2.0/s->rgb_height, 0.0, -1.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; +} + +static void ui_update_frame(UIState *s) { + assert(glGetError() == GL_NO_ERROR); + + UIScene *scene = &s->scene; + + if (scene->frontview && scene->bgr_front_ptr) { + // load front frame texture + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, + s->rgb_front_width, s->rgb_front_height, + GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_front_ptr); + } else if (!scene->frontview && scene->bgr_ptr) { + // load frame texture + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, + s->rgb_width, s->rgb_height, + GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_ptr); + } + + assert(glGetError() == GL_NO_ERROR); +} + +static void draw_rgb_box(UIState *s, int x, int y, int w, int h, uint32_t color) { + const struct { + uint32_t x, y, color; + } verts[] = { + {x, y, color}, + {x+w, y, color}, + {x+w, y+h, color}, + {x, y+h, color}, + {x, y, color}, + }; + + glUseProgram(s->line_program); + + mat4 out_mat = matmul(device_transform, + matmul(frame_transform, s->rgb_transform)); + glUniformMatrix4fv(s->line_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->line_pos_loc); + glVertexAttribPointer(s->line_pos_loc, 2, GL_UNSIGNED_INT, GL_FALSE, sizeof(verts[0]), &verts[0].x); + + glEnableVertexAttribArray(s->line_color_loc); + glVertexAttribPointer(s->line_color_loc, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(verts[0]), &verts[0].color); + + assert(glGetError() == GL_NO_ERROR); + glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); +} + +static void ui_draw_transformed_box(UIState *s, uint32_t color) { + const UIScene *scene = &s->scene; + + const mat3 bbt = scene->big_box_transform; + + struct { + vec3 pos; + uint32_t color; + } verts[] = { + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + }; + + for (int i=0; ibig_box_x + verts[i].pos.v[0] / verts[i].pos.v[2]; + verts[i].pos.v[1] = scene->big_box_y + verts[i].pos.v[1] / verts[i].pos.v[2]; + verts[i].pos.v[1] = s->rgb_height - verts[i].pos.v[1]; + } + + glUseProgram(s->line_program); + + mat4 out_mat = matmul(device_transform, + matmul(frame_transform, s->rgb_transform)); + glUniformMatrix4fv(s->line_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->line_pos_loc); + glVertexAttribPointer(s->line_pos_loc, 2, GL_FLOAT, GL_FALSE, sizeof(verts[0]), &verts[0].pos.v[0]); + + glEnableVertexAttribArray(s->line_color_loc); + glVertexAttribPointer(s->line_color_loc, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(verts[0]), &verts[0].color); + + assert(glGetError() == GL_NO_ERROR); + glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); +} + +// TODO: refactor with draw_path +static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor color) { + const UIScene *scene = &s->scene; + + const float meter_width = 20; + const float car_x = 160; + const float car_y = 570 + meter_width * 8; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, color); + nvgStrokeWidth(s->vg, 5); + + float px = -y_in * meter_width + car_x; + float py = x_in * -meter_width + car_y; + + vec3 dxy = matvecmul3(path_transform, (vec3){{px, py, 1.0}}); + dxy.v[0] /= dxy.v[2]; dxy.v[1] /= dxy.v[2]; dxy.v[2] = 1.0f; //paranoia + vec3 bbpos = matvecmul3(scene->big_box_transform, dxy); + + float x = scene->big_box_x + bbpos.v[0]/bbpos.v[2]; + float y = scene->big_box_y + bbpos.v[1]/bbpos.v[2]; + + nvgMoveTo(s->vg, x-sz, y); + nvgLineTo(s->vg, x+sz, y); + + nvgMoveTo(s->vg, x, y-sz); + nvgLineTo(s->vg, x, y+sz); + + nvgStroke(s->vg); + + nvgRestore(s->vg); +} + +static void draw_path(UIState *s, const float* points, float off, NVGcolor color) { + const UIScene *scene = &s->scene; + + const float meter_width = 20; + const float car_x = 160; + const float car_y = 570 + meter_width * 8; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, color); + nvgStrokeWidth(s->vg, 5); + + for (int i=0; i<50; i++) { + float px = (-points[i] + off) * meter_width + car_x; + float py = (float)i * -meter_width + car_y; + + vec3 dxy = matvecmul3(path_transform, (vec3){{px, py, 1.0}}); + dxy.v[0] /= dxy.v[2]; dxy.v[1] /= dxy.v[2]; dxy.v[2] = 1.0f; //paranoia + vec3 bbpos = matvecmul3(scene->big_box_transform, dxy); + + float x = scene->big_box_x + bbpos.v[0]/bbpos.v[2]; + float y = scene->big_box_y + bbpos.v[1]/bbpos.v[2]; + + if (i == 0) { + nvgMoveTo(s->vg, x, y); + } else { + nvgLineTo(s->vg, x, y); + } + } + + nvgStroke(s->vg); + + nvgRestore(s->vg); +} + +static void draw_model_path(UIState *s, const PathData path, NVGcolor color) { + float var = min(path.std, 0.7); + draw_path(s, path.points, 0.0, color); + color.a /= 4; + draw_path(s, path.points, -var, color); + draw_path(s, path.points, var, color); +} + +static double calc_curvature(float v_ego, float angle_steers) { + const double deg_to_rad = M_PI / 180.0f; + const double slip_fator = 0.0014; + const double steer_ratio = 15.3; + const double wheel_base = 2.67; + + const double angle_offset = 0.0; + + double angle_steers_rad = (angle_steers - angle_offset) * deg_to_rad; + double curvature = angle_steers_rad/(steer_ratio * wheel_base * (1. + slip_fator * v_ego*v_ego)); + return curvature; +} + +static void draw_steering(UIState *s, float v_ego, float angle_steers) { + double curvature = calc_curvature(v_ego, angle_steers); + + float points[50]; + for (int i=0; i<50; i++) { + float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999))/2.); + points[i] = y_actual; + } + + draw_path(s, points, 0.0, nvgRGBA(0, 0, 255, 128)); +} + +static void draw_frame(UIState *s) { + // draw frame texture + const UIScene *scene = &s->scene; + + mat4 out_mat; + float x1, x2, y1, y2; + if (s->scene.frontview) { + out_mat = device_transform; // full 16/9 + + // flip horizontally so it looks like a mirror + x2 = (float)scene->front_box_x / s->rgb_front_width; + x1 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width; + + y1 = (float)scene->front_box_y / s->rgb_front_height; + y2 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height; + } else { + out_mat = matmul(device_transform, frame_transform); + + x1 = 0.0; + x2 = 1.0; + y1 = 0.0; + y2 = 1.0; + } + + const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; + const float frame_coords[4][4] = { + {-1.0, -1.0, x2, y1}, //bl + {-1.0, 1.0, x2, y2}, //tl + { 1.0, 1.0, x1, y2}, //tr + { 1.0, -1.0, x1, y1}, //br + }; + + glActiveTexture(GL_TEXTURE0); + if (s->scene.frontview) { + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + } else { + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + } + + glUseProgram(s->frame_program); + + glUniform1i(s->frame_texture_loc, 0); + glUniformMatrix4fv(s->frame_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->frame_pos_loc); + glVertexAttribPointer(s->frame_pos_loc, 2, GL_FLOAT, GL_FALSE, sizeof(frame_coords[0]), frame_coords); + + glEnableVertexAttribArray(s->frame_texcoord_loc); + glVertexAttribPointer(s->frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, sizeof(frame_coords[0]), &frame_coords[0][2]); + + assert(glGetError() == GL_NO_ERROR); + glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, &frame_indicies[0]); +} + +static void ui_draw_vision(UIState *s) { + const UIScene *scene = &s->scene; + + if (scene->engaged) { + glClearColor(1.0, 0.5, 0.0, 1.0); + } else { + glClearColor(0.1, 0.1, 0.1, 1.0); + } + glClear(GL_COLOR_BUFFER_BIT); + + draw_frame(s); + + if (!scene->frontview) { + draw_rgb_box(s, scene->big_box_x, s->rgb_height-scene->big_box_height-scene->big_box_y, + scene->big_box_width, scene->big_box_height, + 0xFF0000FF); + + ui_draw_transformed_box(s, 0xFF00FF00); + + // nvg drawings + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + // glEnable(GL_CULL_FACE); + + + glClear(GL_STENCIL_BUFFER_BIT); + + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + + draw_steering(s, scene->v_ego, scene->angle_steers); + + // draw paths + + if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) { + draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(128, 0, 255, 255)); + + draw_model_path(s, scene->model.left_lane, nvgRGBA(0, (int)(255 * scene->model.left_lane.prob), 0, 128)); + draw_model_path(s, scene->model.right_lane, nvgRGBA(0, (int)(255 * scene->model.right_lane.prob), 0, 128)); + } + + // draw speed + char speed_str[16]; + nvgFontSize(s->vg, 128.0f); + + if (scene->engaged) { + nvgFillColor(s->vg, nvgRGBA(255,128,0,192)); + } else { + nvgFillColor(s->vg, nvgRGBA(64,64,64,192)); + } + + if (scene->v_cruise != 255 && scene->v_cruise != 0) { + // Convert KPH to MPH. + snprintf(speed_str, sizeof(speed_str), "%3d MPH", (int)(scene->v_cruise * 0.621371 + 0.5)); + nvgTextAlign(s->vg, NVG_ALIGN_RIGHT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 500, 150, speed_str, NULL); + } + + nvgFillColor(s->vg, nvgRGBA(255,255,255,192)); + snprintf(speed_str, sizeof(speed_str), "%3d MPH", (int)(scene->v_ego * 2.237 + 0.5)); + nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 1920-500, 150, speed_str, NULL); + + /*nvgFontSize(s->vg, 64.0f); + nvgTextAlign(s->vg, NVG_ALIGN_RIGHT | NVG_ALIGN_BASELINE); + nvgText(s->vg, 100+450-20, 1080-100, "mph", NULL);*/ + + if (scene->lead_status) { + char radar_str[16]; + int lead_v_rel = (int)(2.236 * scene->lead_v_rel); + snprintf(radar_str, sizeof(radar_str), "%3d m %+d mph", (int)(scene->lead_d_rel), lead_v_rel); + nvgFontSize(s->vg, 96.0f); + nvgFillColor(s->vg, nvgRGBA(128,128,0,192)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); + nvgText(s->vg, 1920/2, 150, radar_str, NULL); + + // 2.7 m fudge factor + draw_cross(s, scene->lead_d_rel + 2.7, scene->lead_y_rel, 15, nvgRGBA(255, 0, 0, 128)); + } + + + // draw alert text + if (strlen(scene->alert_text1) > 0) { + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, 100, 200, 1700, 800, 40); + nvgFillColor(s->vg, nvgRGBA(10,10,10,220)); + nvgFill(s->vg); + + nvgFontSize(s->vg, 200.0f); + nvgFillColor(s->vg, nvgRGBA(255,0,0,255)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); + nvgTextBox(s->vg, 100+50, 200+50, 1700-50, scene->alert_text1, NULL); + + if (strlen(scene->alert_text2) > 0) { + nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); + nvgFontSize(s->vg, 100.0f); + nvgText(s->vg, 100+1700/2, 200+500, scene->alert_text2, NULL); + } + } + + if (scene->awareness_status > 0) { + nvgBeginPath(s->vg); + int bar_height = scene->awareness_status*700; + nvgRect(s->vg, 100, 300+(700-bar_height), 50, bar_height); + nvgFillColor(s->vg, nvgRGBA(255*(1-scene->awareness_status),255*scene->awareness_status,0,128)); + nvgFill(s->vg); + } + + nvgEndFrame(s->vg); + + glDisable(GL_BLEND); + glDisable(GL_CULL_FACE); + } +} + +static void ui_draw_base(UIState *s) { + glClearColor(0.1, 0.1, 0.1, 1.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + + nvgFontSize(s->vg, 96.0f); + nvgFillColor(s->vg, nvgRGBA(255,255,255,255)); + nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE); + nvgTextBox(s->vg, 50, 100, s->fb_w, s->base_text, NULL); + + // draw buttons + for (int i=0; ivg); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + nvgRoundedRect(s->vg, b->x, b->y, b->w, b->h, 20); + nvgFill(s->vg); + + if (b->label) { + if (b->enabled && b->enabled(s)) { + nvgFillColor(s->vg, nvgRGBA(0, 255, 0, 255)); + } else { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE); + nvgText(s->vg, b->x+b->w/2, b->y+b->h/2, b->label, NULL); + } + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgStrokeWidth(s->vg, 5); + nvgRoundedRect(s->vg, b->x, b->y, b->w, b->h, 20); + nvgStroke(s->vg); + } + + nvgEndFrame(s->vg); + + glDisable(GL_BLEND); +} + +static void ui_draw(UIState *s) { + + if (s->vision_connected) { + ui_draw_vision(s); + } else { + ui_draw_base(s); + } + + eglSwapBuffers(s->display, s->surface); + assert(glGetError() == GL_NO_ERROR); +} + + +static PathData read_path(cereal_ModelData_PathData_ptr pathp) { + PathData ret = {0}; + + struct cereal_ModelData_PathData pathd; + cereal_read_ModelData_PathData(&pathd, pathp); + + ret.prob = pathd.prob; + ret.std = pathd.std; + + capn_list32 pointl = pathd.points; + capn_resolve(&pointl.p); + for (int i=0; i<50; i++) { + ret.points[i] = capn_to_f32(capn_get32(pointl, i)); + } + + return ret; +} + +static ModelData read_model(cereal_ModelData_ptr modelp) { + struct cereal_ModelData modeld; + cereal_read_ModelData(&modeld, modelp); + + ModelData d = {0}; + + d.path = read_path(modeld.path); + d.left_lane = read_path(modeld.leftLane); + d.right_lane = read_path(modeld.rightLane); + + struct cereal_ModelData_LeadData leadd; + cereal_read_ModelData_LeadData(&leadd, modeld.lead); + d.lead = (LeadData){ + .dist = leadd.dist, + .prob = leadd.prob, + .std = leadd.std, + }; + + return d; +} + +static char* read_file(const char* path) { + FILE* f = fopen(path, "r"); + if (!f) { + return NULL; + } + fseek(f, 0, SEEK_END); + long f_len = ftell(f); + rewind(f); + + char* buf = (char *)malloc(f_len+1); + assert(buf); + memset(buf, 0, f_len+1); + fread(buf, f_len, 1, f); + fclose(f); + + for (int i=f_len; i>=0; i--) { + if (buf[i] == '\n') buf[i] = 0; + else if (buf[i] != 0) break; + } + + return buf; +} + +static int pending_uploads() { + DIR *dirp = opendir("/sdcard/realdata"); + if (!dirp) return -1; + int cnt = 0; + struct dirent *entry = NULL; + while ((entry = readdir(dirp))) { + if (entry->d_name[0] != '.') { + cnt++; + } + } + closedir(dirp); + return cnt; +} + + +static void ui_update(UIState *s) { + int err; + + if (s->vision_connect_firstrun) { + // cant run this in connector thread because opengl. + // do this here for now in lieu of a run_on_main_thread event + + // setup frame texture + glDeleteTextures(1, &s->frame_tex); //silently ignores a 0 texture + glGenTextures(1, &s->frame_tex); + glBindTexture(GL_TEXTURE_2D, s->frame_tex); + glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_width, s->rgb_height); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + + // front + glDeleteTextures(1, &s->frame_front_tex); + glGenTextures(1, &s->frame_front_tex); + glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); + glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_front_width, s->rgb_front_height); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + + assert(glGetError() == GL_NO_ERROR); + + s->vision_connect_firstrun = false; + } + + // poll for events + while (true) { + + zmq_pollitem_t polls[5] = {{0}}; + polls[0].socket = s->live100_sock_raw; + polls[0].events = ZMQ_POLLIN; + polls[1].socket = s->livecalibration_sock_raw; + polls[1].events = ZMQ_POLLIN; + polls[2].socket = s->model_sock_raw; + polls[2].events = ZMQ_POLLIN; + polls[3].socket = s->live20_sock_raw; + polls[3].events = ZMQ_POLLIN; + + int num_polls = 4; + if (s->vision_connected) { + assert(s->ipc_fd >= 0); + polls[4].fd = s->ipc_fd; + polls[4].events = ZMQ_POLLIN; + num_polls++; + } + + int ret = zmq_poll(polls, num_polls, 0); + if (ret < 0) { + printf("poll failed (%d)\n", ret); + break; + } + if (ret == 0) { + break; + } + + if (s->vision_connected && polls[4].revents) { + // vision ipc event + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + printf("vision disconnected\n"); + close(s->ipc_fd); + s->ipc_fd = -1; + s->vision_connected = false; + continue; + } + if (rp.type == VISION_UI_ACQUIRE) { + bool front = rp.d.ui_acq.front; + int idx = rp.d.ui_acq.idx; + int release_idx; + if (front) { + release_idx = s->cur_vision_front_idx; + } else { + release_idx = s->cur_vision_idx; + } + if (release_idx >= 0) { + VisionPacket rep = { + .type = VISION_UI_RELEASE, + .d = { .ui_rel = { + .front = front, + .idx = release_idx, + }}, + }; + vipc_send(s->ipc_fd, rep); + } + + if (front) { + assert(idx < s->vision_bufs.num_front_bufs); + s->cur_vision_front_idx = idx; + s->scene.bgr_front_ptr = s->front_bufs[idx].addr; + } else { + assert(idx < s->vision_bufs.num_bufs); + s->cur_vision_idx = idx; + s->scene.bgr_ptr = s->bufs[idx].addr; + // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); + } + if (front == s->scene.frontview) { + ui_update_frame(s); + } + + } else { + assert(false); + } + } else { + // zmq messages + void* which = NULL; + for (int i=0; i<4; i++) { + if (polls[i].revents) { + which = polls[i].socket; + break; + } + } + if (which == NULL) { + continue; + } + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + err = zmq_msg_recv(&msg, which, 0); + assert(err >= 0); + + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + if (eventd.which == cereal_Event_live100) { + struct cereal_Live100Data datad; + cereal_read_Live100Data(&datad, eventd.live100); + + s->scene.v_cruise = datad.vCruise; + s->scene.v_ego = datad.vEgo; + s->scene.angle_steers = datad.angleSteers; + s->scene.engaged = (datad.hudLead == 1) || (datad.hudLead == 2); + // printf("recv %f\n", datad.vEgo); + + s->scene.frontview = datad.rearViewCam; + if (datad.alertText1.str) { + snprintf(s->scene.alert_text1, sizeof(s->scene.alert_text1), "%s", datad.alertText1.str); + } else { + s->scene.alert_text1[0] = '\0'; + } + if (datad.alertText2.str) { + snprintf(s->scene.alert_text2, sizeof(s->scene.alert_text2), "%s", datad.alertText2.str); + } else { + s->scene.alert_text2[0] = '\0'; + } + s->scene.awareness_status = datad.awarenessStatus; + } else if (eventd.which == cereal_Event_live20) { + struct cereal_Live20Data datad; + cereal_read_Live20Data(&datad, eventd.live20); + struct cereal_Live20Data_LeadData leaddatad; + cereal_read_Live20Data_LeadData(&leaddatad, datad.leadOne); + s->scene.lead_status = leaddatad.status; + s->scene.lead_d_rel = leaddatad.dRel; + s->scene.lead_y_rel = leaddatad.yRel; + s->scene.lead_v_rel = leaddatad.vRel; + } else if (eventd.which == cereal_Event_liveCalibration) { + struct cereal_LiveCalibrationData datad; + cereal_read_LiveCalibrationData(&datad, eventd.liveCalibration); + + // should we still even have this? + + capn_list32 warpl = datad.warpMatrix; + capn_resolve(&warpl.p); //is this a bug? + // pthread_mutex_lock(&s->transform_lock); + for (int i=0; i<3*3; i++) { + s->scene.big_box_transform.v[i] = capn_to_f32(capn_get32(warpl, i)); + } + // pthread_mutex_unlock(&s->transform_lock); + + // printf("recv %f\n", datad.vEgo); + } else if (eventd.which == cereal_Event_model) { + s->scene.model_ts = eventd.logMonoTime; + s->scene.model = read_model(eventd.model); + } + + capn_free(&ctx); + + zmq_msg_close(&msg); + + } + + } + + // update base ui + uint64_t ts = nanos_since_boot(); + if (!s->vision_connected && ts - s->last_base_update > 1000000000ULL) { + char* bat_cap = read_file("/sys/class/power_supply/battery/capacity"); + char* bat_stat = read_file("/sys/class/power_supply/battery/status"); + + int tx_rate = 0; + int rx_rate = 0; + char* rx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/rx_bytes"); + char* tx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/tx_bytes"); + if (rx_bytes && tx_bytes) { + uint64_t rx_bytes_n = atoll(rx_bytes); + rx_rate = rx_bytes_n - s->last_rx_bytes; + s->last_rx_bytes = rx_bytes_n; + + uint64_t tx_bytes_n = atoll(tx_bytes); + tx_rate = tx_bytes_n - s->last_tx_bytes; + s->last_tx_bytes = tx_bytes_n; + } + if (rx_bytes) free(rx_bytes); + if (tx_bytes) free(tx_bytes); + + int pending = pending_uploads(); + + // service call wifi 20 # getWifiEnabledState + // Result: Parcel(00000000 00000003 '........') = enabled + s->wifi_enabled = !system("service call wifi 20 | grep 00000003 > /dev/null"); + + // service call wifi 38 # getWifiApEnabledState + // Result: Parcel(00000000 0000000d '........') = enabled + s->ap_enabled = !system("service call wifi 38 | grep 0000000d > /dev/null"); + + s->board_connected = !system("lsusb | grep bbaa > /dev/null"); + + snprintf(s->base_text, sizeof(s->base_text), + "serial: %s\n dongle id: %s\n battery: %s %s\npending: %d\nrx %.1fkiB/s tx %.1fkiB/s\nboard: %s", + s->serial, s->dongle_id, bat_cap ? bat_cap : "(null)", bat_stat ? bat_stat : "(null)", + pending, rx_rate / 1024.0, tx_rate / 1024.0, s->board_connected ? "found" : "NOT FOUND"); + + if (bat_cap) free(bat_cap); + if (bat_stat) free(bat_stat); + + s->last_base_update = ts; + } + + if (!s->vision_connected) { + // baseui interaction + + int touch_x = -1, touch_y = -1; + err = touch_poll(&s->touch, &touch_x, &touch_y); + if (err == 1) { + // press buttons + for (int i=0; i= b->x && touch_x < b->x+b->w + && touch_y >= b->y && touch_y < b->y+b->h) { + if (b->pressed && !activity_running()) { + b->pressed(); + break; + } + } + } + } + } + +} + +volatile int do_exit = 0; +static void set_do_exit(int sig) { + do_exit = 1; +} + + +static void* vision_connect_thread(void *args) { + int err; + + UIState *s = args; + while (!do_exit) { + usleep(100000); + pthread_mutex_lock(&s->lock); + bool connected = s->vision_connected; + pthread_mutex_unlock(&s->lock); + if (connected) continue; + + int fd = vipc_connect(); + if (fd < 0) continue; + + VisionPacket p = { + .type = VISION_UI_SUBSCRIBE, + }; + err = vipc_send(fd, p); + if (err < 0) { + close(fd); + continue; + } + + // printf("init recv\n"); + VisionPacket rp; + err = vipc_recv(fd, &rp); + if (err <= 0) { + close(fd); + continue; + } + + assert(rp.type == VISION_UI_BUFS); + assert(rp.num_fds == rp.d.ui_bufs.num_bufs + rp.d.ui_bufs.num_front_bufs); + + pthread_mutex_lock(&s->lock); + assert(!s->vision_connected); + s->ipc_fd = fd; + ui_init_vision(s, rp.d.ui_bufs, rp.fds); + s->vision_connected = true; + s->vision_connect_firstrun = true; + pthread_mutex_unlock(&s->lock); + } + return NULL; +} + +int main() { + int err; + + zsys_handler_set(NULL); + signal(SIGINT, (sighandler_t)set_do_exit); + + UIState uistate; + UIState *s = &uistate; + ui_init(s); + + pthread_t connect_thread_handle; + err = pthread_create(&connect_thread_handle, NULL, + vision_connect_thread, s); + assert(err == 0); + + while (!do_exit) { + pthread_mutex_lock(&s->lock); + ui_update(s); + ui_draw(s); + pthread_mutex_unlock(&s->lock); + + // no simple way to do 30fps vsync with surfaceflinger... + usleep(30000); + } + + err = pthread_join(connect_thread_handle, NULL); + assert(err == 0); + + return 0; +} diff --git a/selfdrive/visiond/Makefile b/selfdrive/visiond/Makefile new file mode 100644 index 0000000000..753c5e41ca --- /dev/null +++ b/selfdrive/visiond/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "visiond: this is a release" diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README new file mode 100644 index 0000000000..488343bc1e --- /dev/null +++ b/selfdrive/visiond/README @@ -0,0 +1,3 @@ +visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs and video logs lives here. + +Contact us if you'd like features added or support for your platform. diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond new file mode 100755 index 0000000000..c3d6e8d302 Binary files /dev/null and b/selfdrive/visiond/visiond differ