openpilot v0.2.2 release

pull/43/head v0.2.2
Vehicle Researcher 2017-01-09 20:59:00 -08:00
parent 0138eca61d
commit a64b9aa9b8
28 changed files with 655 additions and 400 deletions

21
.gitignore vendored 100644
View File

@ -0,0 +1,21 @@
.DS_Store
.tags
*.pyc
.*.swp
.*.swo
.*.un~
*.o
*.d
*.so
*.a
*.clb
config.json
clcache
board/obj/
selfdrive/boardd/boardd
selfdrive/logcatd/logcatd
selfdrive/sensord/sensord
selfdrive/ui/ui

View File

@ -1,3 +1,9 @@
Version 0.2.2 (2017-01-10)
===========================
* Board triggers started signal on CAN messages
* Improved autoexposure
* Handle out of space, improve upload status
Version 0.2.1 (2016-12-14)
===========================
* Performance improvements, removal of more numpy

View File

@ -25,7 +25,12 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS;
// debug safety check: is controls allowed?
int controls_allowed = 0;
int started = 0;
int can_live = 0, pending_can_live = 0;
// optional features
int gas_interceptor_detected = 0;
int started_signal_detected = 0;
// ********************* instantiate queues *********************
@ -147,6 +152,9 @@ void CAN2_TX_IRQHandler() {
// CAN receive handlers
void can_rx(CAN_TypeDef *CAN, int can_number) {
while (CAN->RF0R & CAN_RF0R_FMP0) {
// can is live
pending_can_live = 1;
// add to my fifo
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sFIFOMailBox[0].RIR;
@ -256,6 +264,7 @@ int get_health_pkt(void *dat) {
uint8_t started;
uint8_t controls_allowed;
uint8_t gas_interceptor_detected;
uint8_t started_signal_detected;
} *health = dat;
health->voltage = adc_get(ADCCHAN_VOLTAGE);
#ifdef ENABLE_CURRENT_SENSOR
@ -263,9 +272,12 @@ int get_health_pkt(void *dat) {
#else
health->current = 0;
#endif
health->started = (GPIOC->IDR & (1 << 13)) != 0;
health->started = started;
health->controls_allowed = controls_allowed;
health->gas_interceptor_detected = gas_interceptor_detected;
health->started_signal_detected = started_signal_detected;
return sizeof(*health);
}
@ -468,6 +480,9 @@ int main() {
// LED should keep on blinking all the time
while (1) {
can_live = pending_can_live;
pending_can_live = 0;
#ifdef DEBUG
puts("** blink ");
puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" ");
@ -489,14 +504,21 @@ int main() {
GPIOB->ODR &= ~(1 << 10);
delay(1000000);
if (GPIOC->IDR & (1 << 13)) {
// started logic
int started_signal = (GPIOC->IDR & (1 << 13)) != 0;
if (started_signal) { started_signal_detected = 1; }
if (started_signal || (!started_signal_detected && can_live)) {
started = 1;
// turn on fan at half speed
set_fan_speed(32768);
} else {
started = 0;
// turn off fan
set_fan_speed(0);
}
}
return 0;

View File

@ -235,12 +235,12 @@ void cereal_set_CanData(const struct cereal_CanData *s, cereal_CanData_list l, i
cereal_ThermalData_ptr cereal_new_ThermalData(struct capn_segment *s) {
cereal_ThermalData_ptr p;
p.p = capn_new_struct(s, 16, 0);
p.p = capn_new_struct(s, 24, 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);
p.p = capn_new_list(s, len, 24, 0);
return p;
}
void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_ptr p) {
@ -252,6 +252,7 @@ void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_pt
s->mem = capn_read16(p.p, 8);
s->gpu = capn_read16(p.p, 10);
s->bat = capn_read32(p.p, 12);
s->freeSpace = capn_to_f32(capn_read32(p.p, 16));
}
void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) {
capn_resolve(&p.p);
@ -262,6 +263,7 @@ void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_Thermal
capn_write16(p.p, 8, s->mem);
capn_write16(p.p, 10, s->gpu);
capn_write32(p.p, 12, s->bat);
capn_write32(p.p, 16, capn_from_f32(s->freeSpace));
}
void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) {
cereal_ThermalData_ptr p;
@ -291,6 +293,7 @@ void cereal_read_HealthData(struct cereal_HealthData *s, cereal_HealthData_ptr p
s->started = (capn_read8(p.p, 8) & 1) != 0;
s->controlsAllowed = (capn_read8(p.p, 8) & 2) != 0;
s->gasInterceptorDetected = (capn_read8(p.p, 8) & 4) != 0;
s->startedSignalDetected = (capn_read8(p.p, 8) & 8) != 0;
}
void cereal_write_HealthData(const struct cereal_HealthData *s, cereal_HealthData_ptr p) {
capn_resolve(&p.p);
@ -299,6 +302,7 @@ void cereal_write_HealthData(const struct cereal_HealthData *s, cereal_HealthDat
capn_write1(p.p, 64, s->started != 0);
capn_write1(p.p, 65, s->controlsAllowed != 0);
capn_write1(p.p, 66, s->gasInterceptorDetected != 0);
capn_write1(p.p, 67, s->startedSignalDetected != 0);
}
void cereal_get_HealthData(struct cereal_HealthData *s, cereal_HealthData_list l, int i) {
cereal_HealthData_ptr p;
@ -361,11 +365,11 @@ void cereal_read_Live20Data(struct cereal_Live20Data *s, cereal_Live20Data_ptr 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->warpMatrixDEPRECATED.p = capn_getp(p.p, 0, 0);
s->angleOffsetDEPRECATED = capn_to_f32(capn_read32(p.p, 0));
s->calStatusDEPRECATED = (int8_t) ((int8_t)capn_read8(p.p, 4));
s->calCycleDEPRECATED = (int32_t) ((int32_t)capn_read32(p.p, 12));
s->calPercDEPRECATED = (int8_t) ((int8_t)capn_read8(p.p, 5));
s->leadOne.p = capn_getp(p.p, 1, 0);
s->leadTwo.p = capn_getp(p.p, 2, 0);
s->cumLagMs = capn_to_f32(capn_read32(p.p, 8));
@ -375,11 +379,11 @@ void cereal_write_Live20Data(const struct cereal_Live20Data *s, cereal_Live20Dat
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, 0, s->warpMatrixDEPRECATED.p);
capn_write32(p.p, 0, capn_from_f32(s->angleOffsetDEPRECATED));
capn_write8(p.p, 4, (uint8_t) (s->calStatusDEPRECATED));
capn_write32(p.p, 12, (uint32_t) (s->calCycleDEPRECATED));
capn_write8(p.p, 5, (uint8_t) (s->calPercDEPRECATED));
capn_setp(p.p, 1, s->leadOne.p);
capn_setp(p.p, 2, s->leadTwo.p);
capn_write32(p.p, 8, capn_from_f32(s->cumLagMs));
@ -545,7 +549,7 @@ void cereal_read_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_pt
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->aEgoDEPRECATED = capn_to_f32(capn_read32(p.p, 4));
s->vPid = capn_to_f32(capn_read32(p.p, 8));
s->vTargetLead = capn_to_f32(capn_read32(p.p, 12));
s->upAccelCmd = capn_to_f32(capn_read32(p.p, 16));
@ -558,7 +562,7 @@ void cereal_read_Live100Data(struct cereal_Live100Data *s, cereal_Live100Data_pt
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->hudLeadDEPRECATED = (int32_t) ((int32_t)capn_read32(p.p, 56));
s->cumLagMs = capn_to_f32(capn_read32(p.p, 60));
s->enabled = (capn_read8(p.p, 88) & 1) != 0;
s->steerOverride = (capn_read8(p.p, 88) & 2) != 0;
@ -575,7 +579,7 @@ void cereal_write_Live100Data(const struct cereal_Live100Data *s, cereal_Live100
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, 4, capn_from_f32(s->aEgoDEPRECATED));
capn_write32(p.p, 8, capn_from_f32(s->vPid));
capn_write32(p.p, 12, capn_from_f32(s->vTargetLead));
capn_write32(p.p, 16, capn_from_f32(s->upAccelCmd));
@ -588,7 +592,7 @@ void cereal_write_Live100Data(const struct cereal_Live100Data *s, cereal_Live100
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, 56, (uint32_t) (s->hudLeadDEPRECATED));
capn_write32(p.p, 60, capn_from_f32(s->cumLagMs));
capn_write1(p.p, 704, s->enabled != 0);
capn_write1(p.p, 705, s->steerOverride != 0);

View File

@ -193,13 +193,14 @@ struct cereal_ThermalData {
uint16_t mem;
uint16_t gpu;
uint32_t bat;
float freeSpace;
};
static const size_t cereal_ThermalData_word_count = 2;
static const size_t cereal_ThermalData_word_count = 3;
static const size_t cereal_ThermalData_pointer_count = 0;
static const size_t cereal_ThermalData_struct_bytes_count = 16;
static const size_t cereal_ThermalData_struct_bytes_count = 24;
struct cereal_HealthData {
uint32_t voltage;
@ -207,6 +208,7 @@ struct cereal_HealthData {
unsigned started : 1;
unsigned controlsAllowed : 1;
unsigned gasInterceptorDetected : 1;
unsigned startedSignalDetected : 1;
};
static const size_t cereal_HealthData_word_count = 2;
@ -232,11 +234,11 @@ 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;
capn_list32 warpMatrixDEPRECATED;
float angleOffsetDEPRECATED;
int8_t calStatusDEPRECATED;
int32_t calCycleDEPRECATED;
int8_t calPercDEPRECATED;
cereal_Live20Data_LeadData_ptr leadOne;
cereal_Live20Data_LeadData_ptr leadTwo;
float cumLagMs;
@ -307,7 +309,7 @@ struct cereal_Live100Data {
uint64_t l20MonoTime;
uint64_t mdMonoTime;
float vEgo;
float aEgo;
float aEgoDEPRECATED;
float vPid;
float vTargetLead;
float upAccelCmd;
@ -320,7 +322,7 @@ struct cereal_Live100Data {
float aTargetMax;
float jerkFactor;
float angleSteers;
int32_t hudLead;
int32_t hudLeadDEPRECATED;
float cumLagMs;
unsigned enabled : 1;
unsigned steerOverride : 1;

View File

@ -641,73 +641,80 @@ const ::capnp::_::RawSchema s_8785009a964c7c59 = {
0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<122> b_8d8231a40b7fe6e0 = {
static const ::capnp::_::AlignedData<138> 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,
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, 7, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
25, 0, 0, 0, 143, 1, 0, 0,
25, 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, 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,
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,
181, 0, 0, 0, 42, 0, 0, 0,
209, 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,
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,
185, 0, 0, 0, 42, 0, 0, 0,
213, 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,
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,
189, 0, 0, 0, 42, 0, 0, 0,
217, 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,
212, 0, 0, 0, 3, 0, 1, 0,
224, 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,
221, 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,
216, 0, 0, 0, 3, 0, 1, 0,
228, 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,
225, 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,
220, 0, 0, 0, 3, 0, 1, 0,
232, 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,
229, 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,
224, 0, 0, 0, 3, 0, 1, 0,
236, 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,
233, 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,
228, 0, 0, 0, 3, 0, 1, 0,
240, 0, 0, 0, 2, 0, 1, 0,
7, 0, 0, 0, 4, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
237, 0, 0, 0, 82, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
236, 0, 0, 0, 3, 0, 1, 0,
248, 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,
@ -762,19 +769,28 @@ static const ::capnp::_::AlignedData<122> b_8d8231a40b7fe6e0 = {
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
8, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
102, 114, 101, 101, 83, 112, 97, 99,
101, 0, 0, 0, 0, 0, 0, 0,
10, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
10, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, }
};
::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};
static const uint16_t m_8d8231a40b7fe6e0[] = {6, 0, 1, 2, 3, 7, 5, 4};
static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7};
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 }
0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 138, nullptr, m_8d8231a40b7fe6e0,
0, 8, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = {
static const ::capnp::_::AlignedData<112> b_cfa2b0c2c82af1e4 = {
{ 0, 0, 0, 0, 5, 0, 6, 0,
228, 241, 42, 200, 194, 176, 162, 207,
10, 0, 0, 0, 1, 0, 2, 0,
@ -784,49 +800,56 @@ static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = {
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,
25, 0, 0, 0, 87, 1, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
108, 111, 103, 46, 99, 97, 112, 110,
112, 58, 72, 101, 97, 108, 116, 104,
68, 97, 116, 97, 0, 0, 0, 0,
0, 0, 0, 0, 1, 0, 1, 0,
20, 0, 0, 0, 3, 0, 4, 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,
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,
153, 0, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
148, 0, 0, 0, 3, 0, 1, 0,
160, 0, 0, 0, 2, 0, 1, 0,
1, 0, 0, 0, 1, 0, 0, 0,
0, 0, 1, 0, 1, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
157, 0, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
152, 0, 0, 0, 3, 0, 1, 0,
164, 0, 0, 0, 2, 0, 1, 0,
2, 0, 0, 0, 64, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
161, 0, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
156, 0, 0, 0, 3, 0, 1, 0,
168, 0, 0, 0, 2, 0, 1, 0,
3, 0, 0, 0, 65, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
165, 0, 0, 0, 130, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
164, 0, 0, 0, 3, 0, 1, 0,
176, 0, 0, 0, 2, 0, 1, 0,
4, 0, 0, 0, 66, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
173, 0, 0, 0, 186, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
176, 0, 0, 0, 3, 0, 1, 0,
188, 0, 0, 0, 2, 0, 1, 0,
5, 0, 0, 0, 67, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
185, 0, 0, 0, 178, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
188, 0, 0, 0, 3, 0, 1, 0,
200, 0, 0, 0, 2, 0, 1, 0,
118, 111, 108, 116, 97, 103, 101, 0,
8, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -863,6 +886,16 @@ static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = {
103, 97, 115, 73, 110, 116, 101, 114,
99, 101, 112, 116, 111, 114, 68, 101,
116, 101, 99, 116, 101, 100, 0, 0,
1, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
1, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
115, 116, 97, 114, 116, 101, 100, 83,
105, 103, 110, 97, 108, 68, 101, 116,
101, 99, 116, 101, 100, 0, 0, 0,
1, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -873,11 +906,11 @@ static const ::capnp::_::AlignedData<95> b_cfa2b0c2c82af1e4 = {
};
::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};
static const uint16_t m_cfa2b0c2c82af1e4[] = {3, 1, 4, 2, 5, 0};
static const uint16_t i_cfa2b0c2c82af1e4[] = {0, 1, 2, 3, 4, 5};
const ::capnp::_::RawSchema s_cfa2b0c2c82af1e4 = {
0xcfa2b0c2c82af1e4, b_cfa2b0c2c82af1e4.words, 95, nullptr, m_cfa2b0c2c82af1e4,
0, 5, i_cfa2b0c2c82af1e4, nullptr, nullptr, { &s_cfa2b0c2c82af1e4, nullptr, nullptr, 0, 0, nullptr }
0xcfa2b0c2c82af1e4, b_cfa2b0c2c82af1e4.words, 112, nullptr, m_cfa2b0c2c82af1e4,
0, 6, i_cfa2b0c2c82af1e4, nullptr, nullptr, { &s_cfa2b0c2c82af1e4, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<81> b_c08240f996aefced = {
@ -972,7 +1005,7 @@ const ::capnp::_::RawSchema s_c08240f996aefced = {
0, 4, i_c08240f996aefced, nullptr, nullptr, { &s_c08240f996aefced, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
static const ::capnp::_::AlignedData<208> b_9a185389d6fdd05f = {
{ 0, 0, 0, 0, 5, 0, 6, 0,
95, 208, 253, 214, 137, 83, 24, 154,
10, 0, 0, 0, 1, 0, 4, 0,
@ -997,82 +1030,83 @@ static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
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,
37, 1, 0, 0, 170, 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,
40, 1, 0, 0, 3, 0, 1, 0,
68, 1, 0, 0, 2, 0, 1, 0,
4, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1, 0, 1, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
65, 1, 0, 0, 178, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
68, 1, 0, 0, 3, 0, 1, 0,
80, 1, 0, 0, 2, 0, 1, 0,
5, 0, 0, 0, 4, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
77, 1, 0, 0, 162, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
80, 1, 0, 0, 3, 0, 1, 0,
92, 1, 0, 0, 2, 0, 1, 0,
8, 0, 0, 0, 1, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
89, 1, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
84, 1, 0, 0, 3, 0, 1, 0,
96, 1, 0, 0, 2, 0, 1, 0,
9, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
93, 1, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
88, 1, 0, 0, 3, 0, 1, 0,
100, 1, 0, 0, 2, 0, 1, 0,
10, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
97, 1, 0, 0, 74, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
96, 1, 0, 0, 3, 0, 1, 0,
108, 1, 0, 0, 2, 0, 1, 0,
1, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 6, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
93, 1, 0, 0, 90, 0, 0, 0,
105, 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,
104, 1, 0, 0, 3, 0, 1, 0,
116, 1, 0, 0, 2, 0, 1, 0,
2, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
113, 1, 0, 0, 90, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
112, 1, 0, 0, 3, 0, 1, 0,
124, 1, 0, 0, 2, 0, 1, 0,
6, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 8, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
121, 1, 0, 0, 154, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
124, 1, 0, 0, 3, 0, 1, 0,
136, 1, 0, 0, 2, 0, 1, 0,
7, 0, 0, 0, 5, 0, 0, 0,
0, 0, 1, 0, 9, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
133, 1, 0, 0, 146, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
136, 1, 0, 0, 3, 0, 1, 0,
148, 1, 0, 0, 2, 0, 1, 0,
0, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 10, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
121, 1, 0, 0, 106, 0, 0, 0,
145, 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,
144, 1, 0, 0, 3, 0, 1, 0,
172, 1, 0, 0, 2, 0, 1, 0,
119, 97, 114, 112, 77, 97, 116, 114,
105, 120, 0, 0, 0, 0, 0, 0,
105, 120, 68, 69, 80, 82, 69, 67,
65, 84, 69, 68, 0, 0, 0, 0,
14, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1085,7 +1119,8 @@ static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
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,
115, 101, 116, 68, 69, 80, 82, 69,
67, 65, 84, 69, 68, 0, 0, 0,
10, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1094,7 +1129,8 @@ static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
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,
115, 68, 69, 80, 82, 69, 67, 65,
84, 69, 68, 0, 0, 0, 0, 0,
2, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1146,7 +1182,8 @@ static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
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,
68, 69, 80, 82, 69, 67, 65, 84,
69, 68, 0, 0, 0, 0, 0, 0,
4, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1154,7 +1191,9 @@ static const ::capnp::_::AlignedData<202> b_9a185389d6fdd05f = {
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,
99, 97, 108, 80, 101, 114, 99, 68,
69, 80, 82, 69, 67, 65, 84, 69,
68, 0, 0, 0, 0, 0, 0, 0,
2, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1184,7 +1223,7 @@ static const ::capnp::_::RawSchema* const d_9a185389d6fdd05f[] = {
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,
0x9a185389d6fdd05f, b_9a185389d6fdd05f.words, 208, d_9a185389d6fdd05f, m_9a185389d6fdd05f,
1, 11, i_9a185389d6fdd05f, nullptr, nullptr, { &s_9a185389d6fdd05f, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
@ -1675,7 +1714,7 @@ const ::capnp::_::RawSchema s_8faa644732dec251 = {
0, 10, i_8faa644732dec251, nullptr, nullptr, { &s_8faa644732dec251, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE
static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = {
static const ::capnp::_::AlignedData<446> b_97ff69c53601abf1 = {
{ 0, 0, 0, 0, 5, 0, 6, 0,
241, 171, 1, 54, 197, 105, 255, 151,
10, 0, 0, 0, 1, 0, 13, 0,
@ -1703,185 +1742,185 @@ static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = {
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,
233, 2, 0, 0, 122, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
232, 2, 0, 0, 3, 0, 1, 0,
244, 2, 0, 0, 2, 0, 1, 0,
6, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 2, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
241, 2, 0, 0, 42, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
236, 2, 0, 0, 3, 0, 1, 0,
248, 2, 0, 0, 2, 0, 1, 0,
7, 0, 0, 0, 3, 0, 0, 0,
0, 0, 1, 0, 3, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
241, 2, 0, 0, 98, 0, 0, 0,
245, 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,
244, 2, 0, 0, 3, 0, 1, 0,
0, 3, 0, 0, 2, 0, 1, 0,
8, 0, 0, 0, 4, 0, 0, 0,
0, 0, 1, 0, 4, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
249, 2, 0, 0, 90, 0, 0, 0,
253, 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,
252, 2, 0, 0, 3, 0, 1, 0,
8, 3, 0, 0, 2, 0, 1, 0,
9, 0, 0, 0, 5, 0, 0, 0,
0, 0, 1, 0, 5, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
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,
11, 0, 0, 0, 7, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0,
10, 0, 0, 0, 6, 0, 0, 0,
0, 0, 1, 0, 6, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
13, 3, 0, 0, 42, 0, 0, 0,
13, 3, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
8, 3, 0, 0, 3, 0, 1, 0,
20, 3, 0, 0, 2, 0, 1, 0,
12, 0, 0, 0, 8, 0, 0, 0,
0, 0, 1, 0, 8, 0, 0, 0,
11, 0, 0, 0, 7, 0, 0, 0,
0, 0, 1, 0, 7, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
17, 3, 0, 0, 66, 0, 0, 0,
17, 3, 0, 0, 42, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
12, 3, 0, 0, 3, 0, 1, 0,
24, 3, 0, 0, 2, 0, 1, 0,
13, 0, 0, 0, 9, 0, 0, 0,
0, 0, 1, 0, 9, 0, 0, 0,
12, 0, 0, 0, 8, 0, 0, 0,
0, 0, 1, 0, 8, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
21, 3, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
16, 3, 0, 0, 3, 0, 1, 0,
28, 3, 0, 0, 2, 0, 1, 0,
13, 0, 0, 0, 9, 0, 0, 0,
0, 0, 1, 0, 9, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
25, 3, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
20, 3, 0, 0, 3, 0, 1, 0,
32, 3, 0, 0, 2, 0, 1, 0,
14, 0, 0, 0, 10, 0, 0, 0,
0, 0, 1, 0, 10, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
25, 3, 0, 0, 90, 0, 0, 0,
29, 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,
28, 3, 0, 0, 3, 0, 1, 0,
40, 3, 0, 0, 2, 0, 1, 0,
15, 0, 0, 0, 11, 0, 0, 0,
0, 0, 1, 0, 11, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
33, 3, 0, 0, 90, 0, 0, 0,
37, 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,
36, 3, 0, 0, 3, 0, 1, 0,
48, 3, 0, 0, 2, 0, 1, 0,
16, 0, 0, 0, 12, 0, 0, 0,
0, 0, 1, 0, 12, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
41, 3, 0, 0, 90, 0, 0, 0,
45, 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,
44, 3, 0, 0, 3, 0, 1, 0,
56, 3, 0, 0, 2, 0, 1, 0,
17, 0, 0, 0, 13, 0, 0, 0,
0, 0, 1, 0, 13, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
53, 3, 0, 0, 98, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
52, 3, 0, 0, 3, 0, 1, 0,
64, 3, 0, 0, 2, 0, 1, 0,
18, 0, 0, 0, 14, 0, 0, 0,
0, 0, 1, 0, 14, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
61, 3, 0, 0, 146, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
64, 3, 0, 0, 3, 0, 1, 0,
76, 3, 0, 0, 2, 0, 1, 0,
19, 0, 0, 0, 15, 0, 0, 0,
0, 0, 1, 0, 15, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
61, 3, 0, 0, 74, 0, 0, 0,
73, 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,
72, 3, 0, 0, 3, 0, 1, 0,
84, 3, 0, 0, 2, 0, 1, 0,
0, 0, 0, 0, 8, 0, 0, 0,
0, 0, 1, 0, 16, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
69, 3, 0, 0, 98, 0, 0, 0,
81, 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,
80, 3, 0, 0, 3, 0, 1, 0,
92, 3, 0, 0, 2, 0, 1, 0,
2, 0, 0, 0, 9, 0, 0, 0,
0, 0, 1, 0, 17, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
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,
89, 3, 0, 0, 98, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
88, 3, 0, 0, 3, 0, 1, 0,
100, 3, 0, 0, 2, 0, 1, 0,
21, 0, 0, 0, 193, 2, 0, 0,
0, 0, 1, 0, 20, 0, 0, 0,
3, 0, 0, 0, 10, 0, 0, 0,
0, 0, 1, 0, 18, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
97, 3, 0, 0, 114, 0, 0, 0,
97, 3, 0, 0, 90, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
96, 3, 0, 0, 3, 0, 1, 0,
108, 3, 0, 0, 2, 0, 1, 0,
20, 0, 0, 0, 192, 2, 0, 0,
0, 0, 1, 0, 19, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
105, 3, 0, 0, 66, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
100, 3, 0, 0, 3, 0, 1, 0,
112, 3, 0, 0, 2, 0, 1, 0,
21, 0, 0, 0, 193, 2, 0, 0,
0, 0, 1, 0, 20, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
109, 3, 0, 0, 114, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
108, 3, 0, 0, 3, 0, 1, 0,
120, 3, 0, 0, 2, 0, 1, 0,
1, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1, 0, 21, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
105, 3, 0, 0, 106, 0, 0, 0,
117, 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,
116, 3, 0, 0, 3, 0, 1, 0,
144, 3, 0, 0, 2, 0, 1, 0,
22, 0, 0, 0, 23, 0, 0, 0,
0, 0, 1, 0, 22, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
129, 3, 0, 0, 66, 0, 0, 0,
141, 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,
136, 3, 0, 0, 3, 0, 1, 0,
148, 3, 0, 0, 2, 0, 1, 0,
23, 0, 0, 0, 194, 2, 0, 0,
0, 0, 1, 0, 23, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
133, 3, 0, 0, 98, 0, 0, 0,
145, 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,
144, 3, 0, 0, 3, 0, 1, 0,
156, 3, 0, 0, 2, 0, 1, 0,
24, 0, 0, 0, 1, 0, 0, 0,
0, 0, 1, 0, 24, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
141, 3, 0, 0, 90, 0, 0, 0,
153, 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,
152, 3, 0, 0, 3, 0, 1, 0,
164, 3, 0, 0, 2, 0, 1, 0,
25, 0, 0, 0, 2, 0, 0, 0,
0, 0, 1, 0, 25, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
149, 3, 0, 0, 90, 0, 0, 0,
161, 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,
160, 3, 0, 0, 3, 0, 1, 0,
172, 3, 0, 0, 2, 0, 1, 0,
26, 0, 0, 0, 24, 0, 0, 0,
0, 0, 1, 0, 26, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
157, 3, 0, 0, 130, 0, 0, 0,
169, 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,
168, 3, 0, 0, 3, 0, 1, 0,
180, 3, 0, 0, 2, 0, 1, 0,
118, 69, 103, 111, 0, 0, 0, 0,
10, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -1890,7 +1929,8 @@ static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = {
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,
97, 69, 103, 111, 68, 69, 80, 82,
69, 67, 65, 84, 69, 68, 0, 0,
10, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -2001,7 +2041,9 @@ static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = {
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,
104, 117, 100, 76, 101, 97, 100, 68,
69, 80, 82, 69, 67, 65, 84, 69,
68, 0, 0, 0, 0, 0, 0, 0,
4, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0,
@ -2125,7 +2167,7 @@ static const ::capnp::_::AlignedData<443> b_97ff69c53601abf1 = {
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,
0x97ff69c53601abf1, b_97ff69c53601abf1.words, 446, nullptr, m_97ff69c53601abf1,
0, 27, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr }
};
#endif // !CAPNP_LITE

View File

@ -158,7 +158,7 @@ struct ThermalData {
class Pipeline;
struct _capnpPrivate {
CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 2, 0)
CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 3, 0)
#if !CAPNP_LITE
static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand;
#endif // !CAPNP_LITE
@ -1109,6 +1109,8 @@ public:
inline ::uint32_t getBat() const;
inline float getFreeSpace() const;
private:
::capnp::_::StructReader _reader;
template <typename, ::capnp::Kind>
@ -1158,6 +1160,9 @@ public:
inline ::uint32_t getBat();
inline void setBat( ::uint32_t value);
inline float getFreeSpace();
inline void setFreeSpace(float value);
private:
::capnp::_::StructBuilder _builder;
template <typename, ::capnp::Kind>
@ -1211,6 +1216,8 @@ public:
inline bool getGasInterceptorDetected() const;
inline bool getStartedSignalDetected() const;
private:
::capnp::_::StructReader _reader;
template <typename, ::capnp::Kind>
@ -1254,6 +1261,9 @@ public:
inline bool getGasInterceptorDetected();
inline void setGasInterceptorDetected(bool value);
inline bool getStartedSignalDetected();
inline void setStartedSignalDetected(bool value);
private:
::capnp::_::StructBuilder _builder;
template <typename, ::capnp::Kind>
@ -1398,12 +1408,12 @@ public:
}
#endif // !CAPNP_LITE
inline bool hasWarpMatrix() const;
inline ::capnp::List<float>::Reader getWarpMatrix() const;
inline bool hasWarpMatrixDEPRECATED() const;
inline ::capnp::List<float>::Reader getWarpMatrixDEPRECATED() const;
inline float getAngleOffset() const;
inline float getAngleOffsetDEPRECATED() const;
inline ::int8_t getCalStatus() const;
inline ::int8_t getCalStatusDEPRECATED() const;
inline bool hasLeadOne() const;
inline ::cereal::Live20Data::LeadData::Reader getLeadOne() const;
@ -1417,9 +1427,9 @@ public:
inline ::uint64_t getFtMonoTime() const;
inline ::int32_t getCalCycle() const;
inline ::int32_t getCalCycleDEPRECATED() const;
inline ::int8_t getCalPerc() const;
inline ::int8_t getCalPercDEPRECATED() const;
inline bool hasCanMonoTimes() const;
inline ::capnp::List< ::uint64_t>::Reader getCanMonoTimes() const;
@ -1452,19 +1462,19 @@ public:
inline ::kj::StringTree toString() const { return asReader().toString(); }
#endif // !CAPNP_LITE
inline bool hasWarpMatrix();
inline ::capnp::List<float>::Builder getWarpMatrix();
inline void setWarpMatrix( ::capnp::List<float>::Reader value);
inline void setWarpMatrix(::kj::ArrayPtr<const float> value);
inline ::capnp::List<float>::Builder initWarpMatrix(unsigned int size);
inline void adoptWarpMatrix(::capnp::Orphan< ::capnp::List<float>>&& value);
inline ::capnp::Orphan< ::capnp::List<float>> disownWarpMatrix();
inline bool hasWarpMatrixDEPRECATED();
inline ::capnp::List<float>::Builder getWarpMatrixDEPRECATED();
inline void setWarpMatrixDEPRECATED( ::capnp::List<float>::Reader value);
inline void setWarpMatrixDEPRECATED(::kj::ArrayPtr<const float> value);
inline ::capnp::List<float>::Builder initWarpMatrixDEPRECATED(unsigned int size);
inline void adoptWarpMatrixDEPRECATED(::capnp::Orphan< ::capnp::List<float>>&& value);
inline ::capnp::Orphan< ::capnp::List<float>> disownWarpMatrixDEPRECATED();
inline float getAngleOffset();
inline void setAngleOffset(float value);
inline float getAngleOffsetDEPRECATED();
inline void setAngleOffsetDEPRECATED(float value);
inline ::int8_t getCalStatus();
inline void setCalStatus( ::int8_t value);
inline ::int8_t getCalStatusDEPRECATED();
inline void setCalStatusDEPRECATED( ::int8_t value);
inline bool hasLeadOne();
inline ::cereal::Live20Data::LeadData::Builder getLeadOne();
@ -1489,11 +1499,11 @@ public:
inline ::uint64_t getFtMonoTime();
inline void setFtMonoTime( ::uint64_t value);
inline ::int32_t getCalCycle();
inline void setCalCycle( ::int32_t value);
inline ::int32_t getCalCycleDEPRECATED();
inline void setCalCycleDEPRECATED( ::int32_t value);
inline ::int8_t getCalPerc();
inline void setCalPerc( ::int8_t value);
inline ::int8_t getCalPercDEPRECATED();
inline void setCalPercDEPRECATED( ::int8_t value);
inline bool hasCanMonoTimes();
inline ::capnp::List< ::uint64_t>::Builder getCanMonoTimes();
@ -1899,7 +1909,7 @@ public:
inline float getVEgo() const;
inline float getAEgo() const;
inline float getAEgoDEPRECATED() const;
inline float getVPid() const;
@ -1925,7 +1935,7 @@ public:
inline float getAngleSteers() const;
inline ::int32_t getHudLead() const;
inline ::int32_t getHudLeadDEPRECATED() const;
inline float getCumLagMs() const;
@ -1985,8 +1995,8 @@ public:
inline float getVEgo();
inline void setVEgo(float value);
inline float getAEgo();
inline void setAEgo(float value);
inline float getAEgoDEPRECATED();
inline void setAEgoDEPRECATED(float value);
inline float getVPid();
inline void setVPid(float value);
@ -2024,8 +2034,8 @@ public:
inline float getAngleSteers();
inline void setAngleSteers(float value);
inline ::int32_t getHudLead();
inline void setHudLead( ::int32_t value);
inline ::int32_t getHudLeadDEPRECATED();
inline void setHudLeadDEPRECATED( ::int32_t value);
inline float getCumLagMs();
inline void setCumLagMs(float value);
@ -4106,6 +4116,20 @@ inline void ThermalData::Builder::setBat( ::uint32_t value) {
3 * ::capnp::ELEMENTS, value);
}
inline float ThermalData::Reader::getFreeSpace() const {
return _reader.getDataField<float>(
4 * ::capnp::ELEMENTS);
}
inline float ThermalData::Builder::getFreeSpace() {
return _builder.getDataField<float>(
4 * ::capnp::ELEMENTS);
}
inline void ThermalData::Builder::setFreeSpace(float value) {
_builder.setDataField<float>(
4 * ::capnp::ELEMENTS, value);
}
inline ::uint32_t HealthData::Reader::getVoltage() const {
return _reader.getDataField< ::uint32_t>(
0 * ::capnp::ELEMENTS);
@ -4176,6 +4200,20 @@ inline void HealthData::Builder::setGasInterceptorDetected(bool value) {
66 * ::capnp::ELEMENTS, value);
}
inline bool HealthData::Reader::getStartedSignalDetected() const {
return _reader.getDataField<bool>(
67 * ::capnp::ELEMENTS);
}
inline bool HealthData::Builder::getStartedSignalDetected() {
return _builder.getDataField<bool>(
67 * ::capnp::ELEMENTS);
}
inline void HealthData::Builder::setStartedSignalDetected(bool value) {
_builder.setDataField<bool>(
67 * ::capnp::ELEMENTS, value);
}
inline bool LiveUI::Reader::getRearViewCam() const {
return _reader.getDataField<bool>(
0 * ::capnp::ELEMENTS);
@ -4268,66 +4306,66 @@ inline void LiveUI::Builder::setAwarenessStatus(float value) {
1 * ::capnp::ELEMENTS, value);
}
inline bool Live20Data::Reader::hasWarpMatrix() const {
inline bool Live20Data::Reader::hasWarpMatrixDEPRECATED() const {
return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull();
}
inline bool Live20Data::Builder::hasWarpMatrix() {
inline bool Live20Data::Builder::hasWarpMatrixDEPRECATED() {
return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull();
}
inline ::capnp::List<float>::Reader Live20Data::Reader::getWarpMatrix() const {
inline ::capnp::List<float>::Reader Live20Data::Reader::getWarpMatrixDEPRECATED() const {
return ::capnp::_::PointerHelpers< ::capnp::List<float>>::get(
_reader.getPointerField(0 * ::capnp::POINTERS));
}
inline ::capnp::List<float>::Builder Live20Data::Builder::getWarpMatrix() {
inline ::capnp::List<float>::Builder Live20Data::Builder::getWarpMatrixDEPRECATED() {
return ::capnp::_::PointerHelpers< ::capnp::List<float>>::get(
_builder.getPointerField(0 * ::capnp::POINTERS));
}
inline void Live20Data::Builder::setWarpMatrix( ::capnp::List<float>::Reader value) {
inline void Live20Data::Builder::setWarpMatrixDEPRECATED( ::capnp::List<float>::Reader value) {
::capnp::_::PointerHelpers< ::capnp::List<float>>::set(
_builder.getPointerField(0 * ::capnp::POINTERS), value);
}
inline void Live20Data::Builder::setWarpMatrix(::kj::ArrayPtr<const float> value) {
inline void Live20Data::Builder::setWarpMatrixDEPRECATED(::kj::ArrayPtr<const float> value) {
::capnp::_::PointerHelpers< ::capnp::List<float>>::set(
_builder.getPointerField(0 * ::capnp::POINTERS), value);
}
inline ::capnp::List<float>::Builder Live20Data::Builder::initWarpMatrix(unsigned int size) {
inline ::capnp::List<float>::Builder Live20Data::Builder::initWarpMatrixDEPRECATED(unsigned int size) {
return ::capnp::_::PointerHelpers< ::capnp::List<float>>::init(
_builder.getPointerField(0 * ::capnp::POINTERS), size);
}
inline void Live20Data::Builder::adoptWarpMatrix(
inline void Live20Data::Builder::adoptWarpMatrixDEPRECATED(
::capnp::Orphan< ::capnp::List<float>>&& value) {
::capnp::_::PointerHelpers< ::capnp::List<float>>::adopt(
_builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value));
}
inline ::capnp::Orphan< ::capnp::List<float>> Live20Data::Builder::disownWarpMatrix() {
inline ::capnp::Orphan< ::capnp::List<float>> Live20Data::Builder::disownWarpMatrixDEPRECATED() {
return ::capnp::_::PointerHelpers< ::capnp::List<float>>::disown(
_builder.getPointerField(0 * ::capnp::POINTERS));
}
inline float Live20Data::Reader::getAngleOffset() const {
inline float Live20Data::Reader::getAngleOffsetDEPRECATED() const {
return _reader.getDataField<float>(
0 * ::capnp::ELEMENTS);
}
inline float Live20Data::Builder::getAngleOffset() {
inline float Live20Data::Builder::getAngleOffsetDEPRECATED() {
return _builder.getDataField<float>(
0 * ::capnp::ELEMENTS);
}
inline void Live20Data::Builder::setAngleOffset(float value) {
inline void Live20Data::Builder::setAngleOffsetDEPRECATED(float value) {
_builder.setDataField<float>(
0 * ::capnp::ELEMENTS, value);
}
inline ::int8_t Live20Data::Reader::getCalStatus() const {
inline ::int8_t Live20Data::Reader::getCalStatusDEPRECATED() const {
return _reader.getDataField< ::int8_t>(
4 * ::capnp::ELEMENTS);
}
inline ::int8_t Live20Data::Builder::getCalStatus() {
inline ::int8_t Live20Data::Builder::getCalStatusDEPRECATED() {
return _builder.getDataField< ::int8_t>(
4 * ::capnp::ELEMENTS);
}
inline void Live20Data::Builder::setCalStatus( ::int8_t value) {
inline void Live20Data::Builder::setCalStatusDEPRECATED( ::int8_t value) {
_builder.setDataField< ::int8_t>(
4 * ::capnp::ELEMENTS, value);
}
@ -4448,30 +4486,30 @@ inline void Live20Data::Builder::setFtMonoTime( ::uint64_t value) {
3 * ::capnp::ELEMENTS, value);
}
inline ::int32_t Live20Data::Reader::getCalCycle() const {
inline ::int32_t Live20Data::Reader::getCalCycleDEPRECATED() const {
return _reader.getDataField< ::int32_t>(
3 * ::capnp::ELEMENTS);
}
inline ::int32_t Live20Data::Builder::getCalCycle() {
inline ::int32_t Live20Data::Builder::getCalCycleDEPRECATED() {
return _builder.getDataField< ::int32_t>(
3 * ::capnp::ELEMENTS);
}
inline void Live20Data::Builder::setCalCycle( ::int32_t value) {
inline void Live20Data::Builder::setCalCycleDEPRECATED( ::int32_t value) {
_builder.setDataField< ::int32_t>(
3 * ::capnp::ELEMENTS, value);
}
inline ::int8_t Live20Data::Reader::getCalPerc() const {
inline ::int8_t Live20Data::Reader::getCalPercDEPRECATED() const {
return _reader.getDataField< ::int8_t>(
5 * ::capnp::ELEMENTS);
}
inline ::int8_t Live20Data::Builder::getCalPerc() {
inline ::int8_t Live20Data::Builder::getCalPercDEPRECATED() {
return _builder.getDataField< ::int8_t>(
5 * ::capnp::ELEMENTS);
}
inline void Live20Data::Builder::setCalPerc( ::int8_t value) {
inline void Live20Data::Builder::setCalPercDEPRECATED( ::int8_t value) {
_builder.setDataField< ::int8_t>(
5 * ::capnp::ELEMENTS, value);
}
@ -4912,16 +4950,16 @@ inline void Live100Data::Builder::setVEgo(float value) {
0 * ::capnp::ELEMENTS, value);
}
inline float Live100Data::Reader::getAEgo() const {
inline float Live100Data::Reader::getAEgoDEPRECATED() const {
return _reader.getDataField<float>(
1 * ::capnp::ELEMENTS);
}
inline float Live100Data::Builder::getAEgo() {
inline float Live100Data::Builder::getAEgoDEPRECATED() {
return _builder.getDataField<float>(
1 * ::capnp::ELEMENTS);
}
inline void Live100Data::Builder::setAEgo(float value) {
inline void Live100Data::Builder::setAEgoDEPRECATED(float value) {
_builder.setDataField<float>(
1 * ::capnp::ELEMENTS, value);
}
@ -5094,16 +5132,16 @@ inline void Live100Data::Builder::setAngleSteers(float value) {
13 * ::capnp::ELEMENTS, value);
}
inline ::int32_t Live100Data::Reader::getHudLead() const {
inline ::int32_t Live100Data::Reader::getHudLeadDEPRECATED() const {
return _reader.getDataField< ::int32_t>(
14 * ::capnp::ELEMENTS);
}
inline ::int32_t Live100Data::Builder::getHudLead() {
inline ::int32_t Live100Data::Builder::getHudLeadDEPRECATED() {
return _builder.getDataField< ::int32_t>(
14 * ::capnp::ELEMENTS);
}
inline void Live100Data::Builder::setHudLead( ::int32_t value) {
inline void Live100Data::Builder::setHudLeadDEPRECATED( ::int32_t value) {
_builder.setDataField< ::int32_t>(
14 * ::capnp::ELEMENTS, value);
}

View File

@ -61,6 +61,9 @@ struct ThermalData {
mem @4 :UInt16;
gpu @5 :UInt16;
bat @6 :UInt32;
# not thermal
freeSpace @7 :Float32;
}
struct HealthData {
@ -70,6 +73,7 @@ struct HealthData {
started @2 :Bool;
controlsAllowed @3 :Bool;
gasInterceptorDetected @4 :Bool;
startedSignalDetected @5 :Bool;
}
struct LiveUI {

26
common/profiler.py 100644
View File

@ -0,0 +1,26 @@
from common.realtime import sec_since_boot
class Profiler(object):
def __init__(self, enabled=False):
self.enabled = enabled
self.cp = []
self.start_time = sec_since_boot()
self.last_time = self.start_time
def checkpoint(self, name):
if not self.enabled:
return
tt = sec_since_boot()
self.cp.append((name, tt - self.last_time))
self.last_time = tt
def display(self):
if not self.enabled:
return
print "******* Profiling *******"
tot = 0.0
for n, ms in self.cp:
print "%30s: %7.2f" % (n, ms*1000.0)
tot += ms
print " TOTAL: %7.2f" % (tot*1000.0)

View File

@ -28,7 +28,7 @@ if libc is not None:
libc.clock_gettime.argtypes = [ctypes.c_int, ctypes.POINTER(timespec)]
def clock_gettime(clk_id):
if platform.system() == "darwin":
if platform.system().lower() == "darwin":
# TODO: fix this
return time.time()
else:
@ -47,7 +47,7 @@ def sec_since_boot():
def set_realtime_priority(level):
if os.getuid() != 0:
print "not setting priority, not root"
print("not setting priority, not root")
return
if platform.machine() == "x86_64":
NR_gettid = 186
@ -80,15 +80,19 @@ class Ratekeeper(object):
# Maintain loop rate by calling this at the end of each loop
def keep_time(self):
self.monitor_time()
lagged = self.monitor_time()
if self._remaining > 0:
time.sleep(self._remaining)
return lagged
# this only monitor the cumulative lag, but does not enforce a rate
def monitor_time(self):
lagged = False
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"
print(self._process_name, "lagging by", round(-remaining * 1000, 2), "ms")
lagged = True
self._frame += 1
self._remaining = remaining
return lagged

View File

@ -3,21 +3,18 @@
# 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
if [ ! -d /data/openpilot ]; then
cd /tmp
git clone git@github.com:commaai/openpilot.git -b release
git clone https://github.com/commaai/openpilot.git -b release
mv /tmp/openpilot /data/openpilot
fi
# enter openpilot directory
cd /data/openpilot
# removed automatic update from openpilot
#git pull
# automatic update
git pull
# start manager
cd selfdrive

View File

@ -1,27 +0,0 @@
-----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-----

View File

@ -1,10 +1,6 @@
#!/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/

View File

@ -1,7 +1,6 @@
Cython==0.24.1
bitstring==3.1.5
fastcluster==1.1.21
h5py==2.6.0
libusb1==1.5.0
pycapnp==0.5.9
pyzmq==15.4.0

View File

@ -36,7 +36,7 @@ bool spoofing_started = false;
#define DEBUG_BOARDD
#ifdef DEBUG_BOARDD
#define DPRINTF(fmt, ...) printf("boardd: " fmt, ## __VA_ARGS__)
#define DPRINTF(fmt, ...) printf("boardd(%lu): " fmt, time(NULL), ## __VA_ARGS__)
#else
#define DPRINTF(fmt, ...)
#endif
@ -129,6 +129,7 @@ void can_health(void *s) {
uint8_t started;
uint8_t controls_allowed;
uint8_t gas_interceptor_detected;
uint8_t started_signal_detected;
} health;
// recv from board
@ -157,6 +158,7 @@ void can_health(void *s) {
}
healthData.setControlsAllowed(health.controls_allowed);
healthData.setGasInterceptorDetected(health.gas_interceptor_detected);
healthData.setStartedSignalDetected(health.started_signal_detected);
// send to health
auto words = capnp::messageToFlatArray(msg);
@ -274,16 +276,16 @@ int set_realtime_priority(int level) {
struct sched_param sa;
memset(&sa, 0, sizeof(sa));
sa.sched_priority = level;
return sched_setscheduler(gettid(), SCHED_FIFO, &sa);
return sched_setscheduler(getpid(), SCHED_FIFO, &sa);
}
int main() {
int err;
printf("boardd: starting boardd\n");
DPRINTF("starting boardd\n");
// set process priority
err = set_realtime_priority(4);
printf("boardd: setpriority returns %d\n", err);
DPRINTF("setpriority returns %d\n", err);
// check the environment
if (getenv("STARTED")) {

View File

@ -109,7 +109,7 @@ def boardd_mock_loop():
while 1:
tsc = messaging.drain_sock(logcan, wait_for_one=True)
snds = map(can_capnp_to_can_list, tsc)
snds = map(lambda x: can_capnp_to_can_list(x.can), tsc)
snd = []
for s in snds:
snd += s
@ -162,7 +162,7 @@ def boardd_loop(rate=200):
# 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))
can_send_many(can_capnp_to_can_list(tsc.sendcan))
rk.keep_time()

View File

@ -74,7 +74,7 @@ class CANParser(object):
msg_vl = fix(ck_portion, msg)
# compare recalculated vs received checksum
if msg_vl != cdat:
print hex(msg), "CHECKSUM FAIL"
print "CHECKSUM FAIL: " + hex(msg)
self.ck[msg] = False
self.ok[msg] = False
# counter check
@ -89,6 +89,7 @@ class CANParser(object):
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:
print "COUNTER WRONG: " + hex(msg)
self.ok[msg] = False
# update msg time stamps and counter value

View File

@ -0,0 +1 @@
const char *openpilot_version = "0.2.2";

View File

@ -11,6 +11,7 @@ from common.numpy_fast import clip
from selfdrive.config import Conversions as CV
from common.services import service_list
from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper
from common.profiler import Profiler
from selfdrive.controls.lib.drive_helpers import learn_angle_offset
@ -72,16 +73,23 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
soft_disable_timer = None
# Is cpu temp too high to enable?
overtemp = False
free_space = 1.0
# start the loop
set_realtime_priority(2)
rk = Ratekeeper(rate, print_delay_threshold=2./1000)
while 1:
prof = Profiler()
cur_time = sec_since_boot()
# read CAN
CS = CI.update()
prof.checkpoint("CarInterface")
# did it request to enable?
enable_request, enable_condition = False, False
@ -120,12 +128,14 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX)
if not enabled and b.type in ["accelCruise", "decelCruise"] and not b.pressed:
enable_request = True
enable_request = True
# do disable on button down
if b.type == "cancel" and b.pressed:
AM.add("disable", enabled)
prof.checkpoint("Buttons")
# *** health checking logic ***
hh = messaging.recv_sock(health)
if hh is not None:
@ -138,11 +148,15 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
# thermal data, checked every second
td = messaging.recv_sock(thermal)
if td is not None:
cpu_temps = [td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2,
td.thermal.cpu3, td.thermal.mem, td.thermal.gpu]
# check overtemp
if any(t > 950 for t in cpu_temps):
AM.add("overheat", enabled)
# Check temperature.
overtemp = any(
t > 950
for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2,
td.thermal.cpu3, td.thermal.mem, td.thermal.gpu))
# under 15% of space free
free_space = td.thermal.freeSpace
prof.checkpoint("Health")
# *** getting model logic ***
PP.update(cur_time, CS.vEgo)
@ -165,6 +179,11 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
print "enabled pressed at", cur_time
last_enable_request = cur_time
# don't engage with less than 15% free
if free_space < 0.15:
AM.add("outOfSpace", enabled)
enable_request = False
if VP.brake_only:
enable_condition = ((cur_time - last_enable_request) < 0.2) and CS.cruiseState.enabled
else:
@ -181,6 +200,11 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
if PP.dead:
AM.add("modelCommIssue", enabled)
if overtemp:
AM.add("overheat", enabled)
prof.checkpoint("Model")
if enable_condition and not enabled and not AM.alertPresent():
print "*** enabling controls"
@ -207,12 +231,16 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
# *** put the adaptive in adaptive cruise control ***
AC.update(cur_time, CS.vEgo, CS.steeringAngle, LoC.v_pid, awareness_status, VP)
prof.checkpoint("AdaptiveCruise")
# *** gas/brake PID loop ***
final_gas, final_brake = LoC.update(enabled, CS.vEgo, v_cruise_kph, AC.v_target_lead, AC.a_target, AC.jerk_factor, VP)
# *** steering PID loop ***
final_steer, sat_flag = LaC.update(enabled, CS.vEgo, CS.steeringAngle, CS.steeringPressed, PP.d_poly, angle_offset, VP)
prof.checkpoint("PID")
# ***** handle alerts ****
# send a "steering required alert" if saturation count has reached the limit
if sat_flag:
@ -232,7 +260,6 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
soft_disable_timer -= 1
else:
soft_disable_timer = None
# *** push the alerts to current ***
alert_text_1, alert_text_2, visual_alert, audible_alert = AM.process_alerts(cur_time)
@ -263,6 +290,8 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
if not CI.apply(CC):
AM.add("controlsFailed", enabled)
prof.checkpoint("CarControl")
# ***** publish state to logger *****
# publish controls state at 100Hz
@ -311,12 +340,14 @@ def controlsd_thread(gctx, rate=100): #rate in Hz
live100.send(dat.to_bytes())
prof.checkpoint("Live100")
# *** run loop at fixed rate ***
rk.keep_time()
if rk.keep_time():
prof.display()
def main(gctx=None):
controlsd_thread(gctx, 100)
if __name__ == "__main__":
main()

View File

@ -54,7 +54,9 @@ class AlertManager(object):
"doorOpen": alert("Take Control Immediately","Door Open", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.),
"seatbeltNotLatched": alert("Take Control Immediately","Seatbelt Unlatched", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.),
"espDisabled": alert("Take Control Immediately","ESP Off", ET.SOFT_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.),
"wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, None, .4, 0., 3.),
"wrongCarMode": alert("Comma Unavailable","Main Switch Off", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.),
"outOfSpace": alert("Comma Unavailable","Out of Space", ET.NO_ENTRY, None, "chimeDouble", .4, 0., 3.),
"ethicalDilemma": alert("Take Control Immediately","Ethical Dilemma Detected", ET.IMMEDIATE_DISABLE, "steerRequired", "chimeRepeated", 1., 3., 3.),
}
def __init__(self):
self.activealerts = []

View File

@ -3,10 +3,17 @@ import numpy as np
from common.numpy_fast import interp
import selfdrive.messaging as messaging
X_PATH = np.arange(0.0, 50.0)
def model_polyfit(points):
return np.polyfit(X_PATH, map(float, points), 3)
def compute_path_pinv():
deg = 3
x = np.arange(50.0)
X = np.vstack(tuple(x**n for n in range(deg, -1, -1))).T
pinv = np.linalg.pinv(X)
return pinv
def model_polyfit(points, path_pinv):
return np.dot(path_pinv, map(float, points))
# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm
_LANE_WIDTH_V = [3., 3.8]
@ -40,24 +47,26 @@ class PathPlanner(object):
self.last_model = 0.
self.logMonoTime = 0
self.lead_dist, self.lead_prob, self.lead_var = 0, 0, 1
self._path_pinv = compute_path_pinv()
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
p_poly = model_polyfit(md.model.path.points, self._path_pinv) # predicted path
l_poly = model_polyfit(md.model.leftLane.points, self._path_pinv) # left line
r_poly = model_polyfit(md.model.rightLane.points, self._path_pinv) # right line
p_prob = 1. # model does not tell this probability yet, so set to 1 for now
l_prob = md.model.leftLane.prob # left line prob
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 ***
# 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

View File

@ -0,0 +1,31 @@
#!/usr/bin/env python
import sys
import argparse
import zmq
from hexdump import hexdump
import selfdrive.messaging as messaging
from common.services import service_list
if __name__ == "__main__":
context = zmq.Context()
poller = zmq.Poller()
parser = argparse.ArgumentParser(description='Sniff a communcation socket')
parser.add_argument('--raw', action='store_true')
parser.add_argument("socket", type=str,
help="socket name")
args = parser.parse_args()
messaging.sub_sock(context, service_list[args.socket].port, poller)
while 1:
polld = poller.poll(timeout=1000)
for sock, mode in polld:
if mode != zmq.POLLIN:
continue
if args.raw:
hexdump(sock.recv())
else:
print messaging.recv_sock(sock)

View File

@ -1,8 +1,8 @@
import os
# fetch from environment
DONGLE_ID = os.getenv("DONGLE_ID")
DONGLE_SECRET = os.getenv("DONGLE_SECRET")
def get_dongle_id_and_secret():
return os.getenv("DONGLE_ID"), os.getenv("DONGLE_SECRET")
ROOT = '/sdcard/realdata/'

View File

@ -75,10 +75,17 @@ def main(gctx=None):
rotate_msg = messaging.log.LogRotate.new_message()
rotate_msg.segmentNum = cur_part
rotate_msg.path = cur_dir
vision_control_sock.send(rotate_msg.to_bytes())
finally:
cloudlog.info("loggerd exiting...")
# tell visiond to stop logging
rotate_msg = messaging.log.LogRotate.new_message()
rotate_msg.segmentNum = -1
rotate_msg.path = "/dev/null"
vision_control_sock.send(rotate_msg.to_bytes())
# stop logging
logger.stop()
if __name__ == "__main__":

View File

@ -10,7 +10,7 @@ import traceback
import threading
from selfdrive.swaglog import cloudlog
from selfdrive.loggerd.config import DONGLE_ID, DONGLE_SECRET, ROOT
from selfdrive.loggerd.config import get_dongle_id_and_secret, ROOT
from common.api import api_get
@ -205,7 +205,13 @@ class Uploader(object):
def uploader_fn(exit_event):
cloudlog.info("uploader_fn")
uploader = Uploader(DONGLE_ID, DONGLE_SECRET, ROOT)
dongle_id, dongle_secret = get_dongle_id_and_secret()
if dongle_id is None or dongle_secret is None:
cloudlog.info("uploader MISSING DONGLE_ID or DONGLE_SECRET")
raise Exception("uploader can't start without dongle id and secret")
uploader = Uploader(dongle_id, dongle_secret, ROOT)
while True:
backoff = 0.1

View File

@ -21,6 +21,8 @@ from selfdrive.registration import register
import common.crash
from selfdrive.loggerd.config import ROOT
# comment out anything you don't want to run
managed_processes = {
"uploader": "selfdrive.loggerd.uploader",
@ -49,10 +51,6 @@ car_started_processes = ['controlsd', 'loggerd', 'sensord', 'radard', 'calibrati
# ****************** 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)
@ -61,6 +59,8 @@ def launcher(proc, gctx):
# exec the process
mod.main(gctx)
except KeyboardInterrupt:
cloudlog.info("child %s got ctrl-c" % proc)
except Exception:
# can't install the crash handler becuase sys.excepthook doesn't play nice
# with threads, so catch it here.
@ -156,10 +156,6 @@ def manager_init():
}
}
# 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()
@ -188,6 +184,8 @@ def manager_thread():
for p in car_started_processes:
start_managed_process(p)
logger_dead = False
while 1:
# get health of board, log this in "thermal"
td = messaging.recv_sock(health_sock, wait=True)
@ -195,6 +193,13 @@ def manager_thread():
# replace thermald
msg = read_thermal()
# loggerd is gated based on free space
statvfs = os.statvfs(ROOT)
avail = (statvfs.f_bavail * 1.0)/statvfs.f_blocks
# thermal message now also includes free space
msg.thermal.freeSpace = avail
thermal_sock.send(msg.to_bytes())
print msg
@ -209,18 +214,26 @@ def manager_thread():
elif max_temp < 70.0:
start_managed_process("uploader")
if avail < 0.05:
logger_dead = True
# start constellation of processes when the car starts
if not os.getenv("STARTALL"):
if td.health.started:
# with 2% left, we killall, otherwise the phone is bricked
if td.health.started and avail > 0.02:
for p in car_started_processes:
start_managed_process(p)
if p == "loggerd" and logger_dead:
kill_managed_process(p)
else:
start_managed_process(p)
else:
logger_dead = False
for p in car_started_processes:
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]))
cloudlog.debug(" running %s %s" % (p, running[p]))
# optional, build the c++ binaries and preimport the python for speed

View File

@ -25,6 +25,8 @@
#include "common/visionipc.h"
#include "common/modeldata.h"
#include "common/version.h"
#include "cereal/gen/c/log.capnp.h"
#include "touch.h"
@ -95,7 +97,6 @@ typedef struct UIState {
// base ui
uint64_t last_base_update;
uint64_t last_rx_bytes;
uint64_t last_tx_bytes;
char serial[4096];
const char* dongle_id;
@ -861,6 +862,11 @@ static void ui_draw_vision(UIState *s) {
}
}
static void ui_draw_blank(UIState *s) {
glClearColor(0.1, 0.1, 0.1, 1.0);
glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
}
static void ui_draw_base(UIState *s) {
glClearColor(0.1, 0.1, 0.1, 1.0);
glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
@ -910,8 +916,10 @@ static void ui_draw(UIState *s) {
if (s->vision_connected) {
ui_draw_vision(s);
} else {
} else if (s->awake) {
ui_draw_base(s);
} else {
ui_draw_blank(s);
}
eglSwapBuffers(s->display, s->surface);
@ -987,9 +995,20 @@ static int pending_uploads() {
int cnt = 0;
struct dirent *entry = NULL;
while ((entry = readdir(dirp))) {
if (entry->d_name[0] != '.') {
if (entry->d_name[0] == '.') continue;
char subdirn[255];
snprintf(subdirn, 255, "/sdcard/realdata/%s", entry->d_name);
DIR *subdirp = opendir(subdirn);
if (!subdirp) continue;
struct dirent *subentry = NULL;
while ((subentry = readdir(subdirp))) {
if (subentry->d_name[0] == '.') continue;
//snprintf(subdirn, 255, "/sdcard/realdata/%s/%s", entry->d_name, subentry->d_name);
cnt++;
}
closedir(subdirp);
}
closedir(dirp);
return cnt;
@ -1206,20 +1225,19 @@ static void ui_update(UIState *s) {
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 = 0;
char *tx_bytes;
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);
// cellular bytes
tx_bytes = read_file("/sys/class/net/rmnet_data0/statistics/tx_bytes");
if (tx_bytes) { tx_bytes_n += atoll(tx_bytes); free(tx_bytes); }
// wifi bytes
tx_bytes = read_file("/sys/class/net/wlan0/statistics/tx_bytes");
if (tx_bytes) { tx_bytes_n += atoll(tx_bytes); free(tx_bytes); }
tx_rate = tx_bytes_n - s->last_tx_bytes;
s->last_tx_bytes = tx_bytes_n;
// TODO: do this properly
system("git rev-parse --abbrev-ref HEAD > /tmp/git_branch");
@ -1240,10 +1258,10 @@ static void ui_update(UIState *s) {
s->board_connected = !system("lsusb | grep bbaa > /dev/null");
snprintf(s->base_text, sizeof(s->base_text),
"version: %s (%s)\nserial: %s\n dongle id: %s\n battery: %s %s\npending: %d\nrx %.1fkiB/s tx %.1fkiB/s\nboard: %s",
git_commit, git_branch,
"version: v%s %s (%s)\nserial: %s\n dongle id: %s\n battery: %s %s\npending: %d -> %.1f kb/s\nboard: %s",
openpilot_version, git_commit, git_branch,
s->serial, s->dongle_id, bat_cap ? bat_cap : "(null)", bat_stat ? bat_stat : "(null)",
pending, rx_rate / 1024.0, tx_rate / 1024.0, s->board_connected ? "found" : "NOT FOUND");
pending, tx_rate / 1024.0, s->board_connected ? "found" : "NOT FOUND");
if (bat_cap) free(bat_cap);
if (bat_stat) free(bat_stat);

Binary file not shown.