diff --git a/README.md b/README.md index afa45fe2cb..0e034f068e 100644 --- a/README.md +++ b/README.md @@ -20,7 +20,7 @@ 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 +- Honda Civic 2016 with Honda Sensing - Limitations: Due to limitations in steering firmware, steering is disabled below 18 mph Directory structure diff --git a/RELEASES.md b/RELEASES.md index 81ce6dd355..b4ef4650f4 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,9 @@ +Version 0.2.7 (2017-02-08) +=========================== + * Better performance and pictures at night + * Fix ptr alignment issue in boardd + * Fix brake error light, fix crash if too cold + Version 0.2.6 (2017-01-31) =========================== * Fix bug in visiond model execution diff --git a/cereal/gen/c/log.capnp.c b/cereal/gen/c/log.capnp.c index a62a180aab..1ae7c2c567 100644 --- a/cereal/gen/c/log.capnp.c +++ b/cereal/gen/c/log.capnp.c @@ -280,12 +280,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, 24, 0); + p.p = capn_new_struct(s, 24, 1); return p; } cereal_ThermalData_list cereal_new_ThermalData_list(struct capn_segment *s, int len) { cereal_ThermalData_list p; - p.p = capn_new_list(s, len, 24, 0); + p.p = capn_new_list(s, len, 24, 1); return p; } void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { @@ -299,6 +299,7 @@ void cereal_read_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_pt s->bat = capn_read32(p.p, 12); s->freeSpace = capn_to_f32(capn_read32(p.p, 16)); s->batteryPercent = (int16_t) ((int16_t)capn_read16(p.p, 20)); + s->batteryStatus = capn_get_text(p.p, 0, capn_val0); } void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_ThermalData_ptr p) { capn_resolve(&p.p); @@ -311,6 +312,7 @@ void cereal_write_ThermalData(const struct cereal_ThermalData *s, cereal_Thermal capn_write32(p.p, 12, s->bat); capn_write32(p.p, 16, capn_from_f32(s->freeSpace)); capn_write16(p.p, 20, (uint16_t) (s->batteryPercent)); + capn_set_text(p.p, 0, s->batteryStatus); } void cereal_get_ThermalData(struct cereal_ThermalData *s, cereal_ThermalData_list l, int i) { cereal_ThermalData_ptr p; @@ -1018,7 +1020,8 @@ void cereal_read_Event(struct cereal_Event *s, cereal_Event_ptr p) { case cereal_Event_androidLogEntry: case cereal_Event_gpsLocation: case cereal_Event_carState: - s->carState.p = capn_getp(p.p, 0, 0); + case cereal_Event_carControl: + s->carControl.p = capn_getp(p.p, 0, 0); break; default: break; @@ -1053,7 +1056,8 @@ void cereal_write_Event(const struct cereal_Event *s, cereal_Event_ptr p) { case cereal_Event_androidLogEntry: case cereal_Event_gpsLocation: case cereal_Event_carState: - capn_setp(p.p, 0, s->carState.p); + case cereal_Event_carControl: + capn_setp(p.p, 0, s->carControl.p); break; default: break; diff --git a/cereal/gen/c/log.capnp.h b/cereal/gen/c/log.capnp.h index 24ad3e1ebe..9b365fdde1 100644 --- a/cereal/gen/c/log.capnp.h +++ b/cereal/gen/c/log.capnp.h @@ -224,13 +224,14 @@ struct cereal_ThermalData { uint32_t bat; float freeSpace; int16_t batteryPercent; + capn_text batteryStatus; }; static const size_t cereal_ThermalData_word_count = 3; -static const size_t cereal_ThermalData_pointer_count = 0; +static const size_t cereal_ThermalData_pointer_count = 1; -static const size_t cereal_ThermalData_struct_bytes_count = 24; +static const size_t cereal_ThermalData_struct_bytes_count = 32; struct cereal_HealthData { uint32_t voltage; @@ -509,7 +510,8 @@ enum cereal_Event_which { cereal_Event_liveCalibration = 18, cereal_Event_androidLogEntry = 19, cereal_Event_gpsLocation = 20, - cereal_Event_carState = 21 + cereal_Event_carState = 21, + cereal_Event_carControl = 22 }; struct cereal_Event { @@ -538,6 +540,7 @@ struct cereal_Event { cereal_AndroidLogEntry_ptr androidLogEntry; cereal_GpsLocationData_ptr gpsLocation; cereal_CarState_ptr carState; + cereal_CarControl_ptr carControl; }; }; diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ index 99178add84..20949cefaa 100644 --- a/cereal/gen/cpp/log.capnp.c++ +++ b/cereal/gen/cpp/log.capnp.c++ @@ -862,87 +862,94 @@ 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<154> b_8d8231a40b7fe6e0 = { +static const ::capnp::_::AlignedData<170> b_8d8231a40b7fe6e0 = { { 0, 0, 0, 0, 5, 0, 6, 0, 224, 230, 127, 11, 164, 49, 130, 141, 10, 0, 0, 0, 1, 0, 3, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 0, 0, 7, 0, 0, 0, 0, 0, + 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, 255, 1, 0, 0, + 25, 0, 0, 0, 55, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, 112, 58, 84, 104, 101, 114, 109, 97, 108, 68, 97, 116, 97, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 36, 0, 0, 0, 3, 0, 4, 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, - 237, 0, 0, 0, 42, 0, 0, 0, + 9, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 232, 0, 0, 0, 3, 0, 1, 0, - 244, 0, 0, 0, 2, 0, 1, 0, + 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, - 241, 0, 0, 0, 42, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 0, 0, 0, 3, 0, 1, 0, - 248, 0, 0, 0, 2, 0, 1, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 0, 0, 0, 42, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 0, 0, 0, 3, 0, 1, 0, - 252, 0, 0, 0, 2, 0, 1, 0, + 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, - 249, 0, 0, 0, 42, 0, 0, 0, + 21, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 0, 0, 0, 3, 0, 1, 0, - 0, 1, 0, 0, 2, 0, 1, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 0, 0, 0, 34, 0, 0, 0, + 25, 1, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 0, 0, 0, 3, 0, 1, 0, - 4, 1, 0, 0, 2, 0, 1, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 1, 0, 0, 34, 0, 0, 0, + 29, 1, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 0, 0, 0, 3, 0, 1, 0, - 8, 1, 0, 0, 2, 0, 1, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 1, 0, 0, 34, 0, 0, 0, + 33, 1, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 1, 0, 0, 3, 0, 1, 0, - 12, 1, 0, 0, 2, 0, 1, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 9, 1, 0, 0, 82, 0, 0, 0, + 37, 1, 0, 0, 82, 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, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 17, 1, 0, 0, 122, 0, 0, 0, + 45, 1, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 16, 1, 0, 0, 3, 0, 1, 0, - 28, 1, 0, 0, 2, 0, 1, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, 99, 112, 117, 48, 0, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -1015,16 +1022,25 @@ static const ::capnp::_::AlignedData<154> b_8d8231a40b7fe6e0 = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_8d8231a40b7fe6e0 = b_8d8231a40b7fe6e0.words; #if !CAPNP_LITE -static const uint16_t m_8d8231a40b7fe6e0[] = {6, 8, 0, 1, 2, 3, 7, 5, 4}; -static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +static const uint16_t m_8d8231a40b7fe6e0[] = {6, 8, 9, 0, 1, 2, 3, 7, 5, 4}; +static const uint16_t i_8d8231a40b7fe6e0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; const ::capnp::_::RawSchema s_8d8231a40b7fe6e0 = { - 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 154, nullptr, m_8d8231a40b7fe6e0, - 0, 9, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } + 0x8d8231a40b7fe6e0, b_8d8231a40b7fe6e0.words, 170, nullptr, m_8d8231a40b7fe6e0, + 0, 10, i_8d8231a40b7fe6e0, nullptr, nullptr, { &s_8d8231a40b7fe6e0, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<112> b_cfa2b0c2c82af1e4 = { @@ -3339,184 +3355,191 @@ const ::capnp::_::RawSchema s_9811e1f38f62f2d1 = { 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<398> b_d314cfd957229c11 = { +static const ::capnp::_::AlignedData<414> b_d314cfd957229c11 = { { 0, 0, 0, 0, 5, 0, 6, 0, 17, 156, 34, 87, 217, 207, 20, 211, 10, 0, 0, 0, 1, 0, 2, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 1, 0, 7, 0, 0, 0, 22, 0, + 1, 0, 7, 0, 0, 0, 23, 0, 4, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 130, 0, 0, 0, 25, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 15, 5, 0, 0, + 21, 0, 0, 0, 71, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, 112, 58, 69, 118, 101, 110, 116, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 92, 0, 0, 0, 3, 0, 4, 0, + 96, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 2, 0, 0, 98, 0, 0, 0, + 145, 2, 0, 0, 98, 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, + 144, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, 1, 0, 255, 255, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 2, 0, 0, 74, 0, 0, 0, + 153, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 124, 2, 0, 0, 3, 0, 1, 0, - 136, 2, 0, 0, 2, 0, 1, 0, + 152, 2, 0, 0, 3, 0, 1, 0, + 164, 2, 0, 0, 2, 0, 1, 0, 2, 0, 254, 255, 0, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 133, 2, 0, 0, 50, 0, 0, 0, + 161, 2, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 2, 0, 0, 3, 0, 1, 0, - 140, 2, 0, 0, 2, 0, 1, 0, + 156, 2, 0, 0, 3, 0, 1, 0, + 168, 2, 0, 0, 2, 0, 1, 0, 3, 0, 253, 255, 0, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 2, 0, 0, 66, 0, 0, 0, + 165, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 132, 2, 0, 0, 3, 0, 1, 0, - 144, 2, 0, 0, 2, 0, 1, 0, + 160, 2, 0, 0, 3, 0, 1, 0, + 172, 2, 0, 0, 2, 0, 1, 0, 4, 0, 252, 255, 0, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 2, 0, 0, 178, 0, 0, 0, + 169, 2, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 2, 0, 0, 3, 0, 1, 0, - 156, 2, 0, 0, 2, 0, 1, 0, + 172, 2, 0, 0, 3, 0, 1, 0, + 184, 2, 0, 0, 2, 0, 1, 0, 5, 0, 251, 255, 0, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 2, 0, 0, 34, 0, 0, 0, + 181, 2, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 2, 0, 0, 3, 0, 1, 0, - 176, 2, 0, 0, 2, 0, 1, 0, + 176, 2, 0, 0, 3, 0, 1, 0, + 204, 2, 0, 0, 2, 0, 1, 0, 6, 0, 250, 255, 0, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 2, 0, 0, 66, 0, 0, 0, + 201, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 2, 0, 0, 3, 0, 1, 0, - 180, 2, 0, 0, 2, 0, 1, 0, + 196, 2, 0, 0, 3, 0, 1, 0, + 208, 2, 0, 0, 2, 0, 1, 0, 7, 0, 249, 255, 0, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 2, 0, 0, 66, 0, 0, 0, + 205, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 2, 0, 0, 3, 0, 1, 0, - 184, 2, 0, 0, 2, 0, 1, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, 8, 0, 248, 255, 0, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 2, 0, 0, 162, 0, 0, 0, + 209, 2, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 2, 0, 0, 3, 0, 1, 0, - 212, 2, 0, 0, 2, 0, 1, 0, + 212, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, 9, 0, 247, 255, 0, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 209, 2, 0, 0, 50, 0, 0, 0, + 237, 2, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 2, 0, 0, 3, 0, 1, 0, - 216, 2, 0, 0, 2, 0, 1, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, 10, 0, 246, 255, 0, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 2, 0, 0, 74, 0, 0, 0, + 241, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 2, 0, 0, 3, 0, 1, 0, - 224, 2, 0, 0, 2, 0, 1, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, 11, 0, 245, 255, 0, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 2, 0, 0, 106, 0, 0, 0, + 249, 2, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 2, 0, 0, 3, 0, 1, 0, - 248, 2, 0, 0, 2, 0, 1, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, 12, 0, 244, 255, 0, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 2, 0, 0, 58, 0, 0, 0, + 17, 3, 0, 0, 58, 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, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, 13, 0, 243, 255, 0, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 2, 0, 0, 58, 0, 0, 0, + 21, 3, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 2, 0, 0, 3, 0, 1, 0, - 0, 3, 0, 0, 2, 0, 1, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, 14, 0, 242, 255, 0, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 2, 0, 0, 138, 0, 0, 0, + 25, 3, 0, 0, 138, 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, + 28, 3, 0, 0, 3, 0, 1, 0, + 40, 3, 0, 0, 2, 0, 1, 0, 15, 0, 241, 255, 0, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 9, 3, 0, 0, 82, 0, 0, 0, + 37, 3, 0, 0, 82, 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, + 36, 3, 0, 0, 3, 0, 1, 0, + 48, 3, 0, 0, 2, 0, 1, 0, 16, 0, 240, 255, 0, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 17, 3, 0, 0, 90, 0, 0, 0, + 45, 3, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 16, 3, 0, 0, 3, 0, 1, 0, - 44, 3, 0, 0, 2, 0, 1, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, 17, 0, 239, 255, 0, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 41, 3, 0, 0, 66, 0, 0, 0, + 69, 3, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 36, 3, 0, 0, 3, 0, 1, 0, - 64, 3, 0, 0, 2, 0, 1, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 92, 3, 0, 0, 2, 0, 1, 0, 18, 0, 238, 255, 0, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 3, 0, 0, 90, 0, 0, 0, + 89, 3, 0, 0, 90, 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, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, 19, 0, 237, 255, 0, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 3, 0, 0, 130, 0, 0, 0, + 97, 3, 0, 0, 130, 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, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, 20, 0, 236, 255, 0, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 3, 0, 0, 130, 0, 0, 0, + 105, 3, 0, 0, 130, 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, + 104, 3, 0, 0, 3, 0, 1, 0, + 116, 3, 0, 0, 2, 0, 1, 0, 21, 0, 235, 255, 0, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 3, 0, 0, 98, 0, 0, 0, + 113, 3, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 84, 3, 0, 0, 3, 0, 1, 0, - 96, 3, 0, 0, 2, 0, 1, 0, + 112, 3, 0, 0, 3, 0, 1, 0, + 124, 3, 0, 0, 2, 0, 1, 0, 22, 0, 234, 255, 0, 0, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 3, 0, 0, 74, 0, 0, 0, + 121, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 3, 0, 0, 3, 0, 1, 0, + 132, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 233, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 3, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 3, 0, 0, 3, 0, 1, 0, - 104, 3, 0, 0, 2, 0, 1, 0, + 128, 3, 0, 0, 3, 0, 1, 0, + 140, 3, 0, 0, 2, 0, 1, 0, 108, 111, 103, 77, 111, 110, 111, 84, 105, 109, 101, 0, 0, 0, 0, 0, 9, 0, 0, 0, 0, 0, 0, 0, @@ -3735,6 +3758,15 @@ static const ::capnp::_::AlignedData<398> b_d314cfd957229c11 = { 60, 144, 82, 224, 9, 250, 164, 157, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 67, 111, 110, 116, 114, + 111, 108, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } @@ -3761,12 +3793,13 @@ static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { &s_e946524859add50e, &s_ea0245f695ae0a33, &s_ea095da1894f7d85, + &s_f78829049ab814af, }; -static const uint16_t m_d314cfd957229c11[] = {20, 5, 22, 15, 10, 2, 21, 3, 12, 1, 7, 13, 19, 8, 16, 14, 18, 0, 9, 17, 4, 11, 6}; -static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 0}; +static const uint16_t m_d314cfd957229c11[] = {20, 5, 23, 22, 15, 10, 2, 21, 3, 12, 1, 7, 13, 19, 8, 16, 14, 18, 0, 9, 17, 4, 11, 6}; +static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 0}; const ::capnp::_::RawSchema s_d314cfd957229c11 = { - 0xd314cfd957229c11, b_d314cfd957229c11.words, 398, d_d314cfd957229c11, m_d314cfd957229c11, - 19, 23, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } + 0xd314cfd957229c11, b_d314cfd957229c11.words, 414, d_d314cfd957229c11, m_d314cfd957229c11, + 20, 24, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE } // namespace schemas diff --git a/cereal/gen/cpp/log.capnp.h b/cereal/gen/cpp/log.capnp.h index 084d36aaed..ff33d05a04 100644 --- a/cereal/gen/cpp/log.capnp.h +++ b/cereal/gen/cpp/log.capnp.h @@ -185,7 +185,7 @@ struct ThermalData { class Pipeline; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 3, 0) + CAPNP_DECLARE_STRUCT_HEADER(8d8231a40b7fe6e0, 3, 1) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand = &schema->defaultBrand; #endif // !CAPNP_LITE @@ -467,6 +467,7 @@ struct Event { ANDROID_LOG_ENTRY, GPS_LOCATION, CAR_STATE, + CAR_CONTROL, }; struct _capnpPrivate { @@ -1258,6 +1259,9 @@ public: inline ::int16_t getBatteryPercent() const; + inline bool hasBatteryStatus() const; + inline ::capnp::Text::Reader getBatteryStatus() const; + private: ::capnp::_::StructReader _reader; template @@ -1313,6 +1317,13 @@ public: inline ::int16_t getBatteryPercent(); inline void setBatteryPercent( ::int16_t value); + inline bool hasBatteryStatus(); + inline ::capnp::Text::Builder getBatteryStatus(); + inline void setBatteryStatus( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initBatteryStatus(unsigned int size); + inline void adoptBatteryStatus(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownBatteryStatus(); + private: ::capnp::_::StructBuilder _builder; template @@ -3285,6 +3296,10 @@ public: inline bool hasCarState() const; inline ::cereal::CarState::Reader getCarState() const; + inline bool isCarControl() const; + inline bool hasCarControl() const; + inline ::cereal::CarControl::Reader getCarControl() const; + private: ::capnp::_::StructReader _reader; template @@ -3493,6 +3508,14 @@ public: inline void adoptCarState(::capnp::Orphan< ::cereal::CarState>&& value); inline ::capnp::Orphan< ::cereal::CarState> disownCarState(); + inline bool isCarControl(); + inline bool hasCarControl(); + inline ::cereal::CarControl::Builder getCarControl(); + inline void setCarControl( ::cereal::CarControl::Reader value); + inline ::cereal::CarControl::Builder initCarControl(); + inline void adoptCarControl(::capnp::Orphan< ::cereal::CarControl>&& value); + inline ::capnp::Orphan< ::cereal::CarControl> disownCarControl(); + private: ::capnp::_::StructBuilder _builder; template @@ -4444,6 +4467,38 @@ inline void ThermalData::Builder::setBatteryPercent( ::int16_t value) { 10 * ::capnp::ELEMENTS, value); } +inline bool ThermalData::Reader::hasBatteryStatus() const { + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool ThermalData::Builder::hasBatteryStatus() { + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader ThermalData::Reader::getBatteryStatus() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder ThermalData::Builder::getBatteryStatus() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void ThermalData::Builder::setBatteryStatus( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder ThermalData::Builder::initBatteryStatus(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init( + _builder.getPointerField(0 * ::capnp::POINTERS), size); +} +inline void ThermalData::Builder::adoptBatteryStatus( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> ThermalData::Builder::disownBatteryStatus() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + inline ::uint32_t HealthData::Reader::getVoltage() const { return _reader.getDataField< ::uint32_t>( 0 * ::capnp::ELEMENTS); @@ -7702,6 +7757,58 @@ inline ::capnp::Orphan< ::cereal::CarState> Event::Builder::disownCarState() { _builder.getPointerField(0 * ::capnp::POINTERS)); } +inline bool Event::Reader::isCarControl() const { + return which() == Event::CAR_CONTROL; +} +inline bool Event::Builder::isCarControl() { + return which() == Event::CAR_CONTROL; +} +inline bool Event::Reader::hasCarControl() const { + if (which() != Event::CAR_CONTROL) return false; + return !_reader.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline bool Event::Builder::hasCarControl() { + if (which() != Event::CAR_CONTROL) return false; + return !_builder.getPointerField(0 * ::capnp::POINTERS).isNull(); +} +inline ::cereal::CarControl::Reader Event::Reader::getCarControl() const { + KJ_IREQUIRE(which() == Event::CAR_CONTROL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CarControl>::get( + _reader.getPointerField(0 * ::capnp::POINTERS)); +} +inline ::cereal::CarControl::Builder Event::Builder::getCarControl() { + KJ_IREQUIRE(which() == Event::CAR_CONTROL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CarControl>::get( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::setCarControl( ::cereal::CarControl::Reader value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); + ::capnp::_::PointerHelpers< ::cereal::CarControl>::set( + _builder.getPointerField(0 * ::capnp::POINTERS), value); +} +inline ::cereal::CarControl::Builder Event::Builder::initCarControl() { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); + return ::capnp::_::PointerHelpers< ::cereal::CarControl>::init( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} +inline void Event::Builder::adoptCarControl( + ::capnp::Orphan< ::cereal::CarControl>&& value) { + _builder.setDataField( + 4 * ::capnp::ELEMENTS, Event::CAR_CONTROL); + ::capnp::_::PointerHelpers< ::cereal::CarControl>::adopt( + _builder.getPointerField(0 * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::cereal::CarControl> Event::Builder::disownCarControl() { + KJ_IREQUIRE(which() == Event::CAR_CONTROL, + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::cereal::CarControl>::disown( + _builder.getPointerField(0 * ::capnp::POINTERS)); +} + } // namespace #endif // CAPNP_INCLUDED_f3b1f17e25a4285b_ diff --git a/cereal/log.capnp b/cereal/log.capnp index 17a879e6d8..34637c6f42 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -103,6 +103,7 @@ struct ThermalData { # not thermal freeSpace @7 :Float32; batteryPercent @8 :Int16; + batteryStatus @9: Text; } struct HealthData { @@ -313,5 +314,6 @@ struct Event { androidLogEntry @20 :AndroidLogEntry; gpsLocation @21 :GpsLocationData; carState @22 :Car.CarState; + carControl @23 :Car.CarControl; } } diff --git a/common/realtime.py b/common/realtime.py index 48c96c93a8..7a6a072218 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -96,7 +96,7 @@ class Ratekeeper(object): 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("%s lagging by %.2f ms" % (self._process_name, -remaining * 1000)) lagged = True self._frame += 1 self._remaining = remaining diff --git a/common/services.py b/common/services.py index 9e9c6e11a1..1c85cd82ed 100644 --- a/common/services.py +++ b/common/services.py @@ -34,6 +34,8 @@ service_list = { "liveCalibration": Service(8019, True), "androidLog": Service(8020, True), "carState": Service(8021, True), + # 8022 is reserved for sshd + "carControl": Service(8023, True), } # manager -- base process to manage starting and stopping of all others @@ -57,7 +59,7 @@ service_list = { # controlsd -- actually drives the car # subscribes: can, thermal, model, live20 -# publishes: carState, sendcan, live100 +# publishes: carState, carControl, sendcan, live100 # radard -- processes the radar data # subscribes: can, live100, model diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 117fee611b..15cea0b4f0 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -177,8 +177,10 @@ void can_send(void *s) { 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)); + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + capnp::FlatArrayMessageReader cmsg(amsg); cereal::Event::Reader event = cmsg.getRoot(); int msg_count = event.getCan().size(); diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 47770039aa..f7d7b72311 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -90,7 +90,7 @@ class CarController(object): #print chime, alert_id, hud_alert fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) - hud = HUDData(int(pcm_accel), int(hud_v_cruise), 0x41, hud_car, + hud = HUDData(int(pcm_accel), int(hud_v_cruise), 0x01, hud_car, 0xc1, 0x41, hud_lanes + steer_required, int(snd_beep), 0x48, (snd_chime << 5) + fcw_display, acc_alert) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index d3f002f874..a0b9e0f04b 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -const char *openpilot_version = "0.2.6"; +const char *openpilot_version = "0.2.7"; diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 51f52d1c56..02566a8696 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -39,6 +39,7 @@ def controlsd_thread(gctx, rate=100): #rate in Hz context = zmq.Context() live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) + carcontrol = messaging.pub_sock(context, service_list['carControl'].port) thermal = messaging.sub_sock(context, service_list['thermal'].port) live20 = messaging.sub_sock(context, service_list['live20'].port) @@ -297,6 +298,12 @@ def controlsd_thread(gctx, rate=100): #rate in Hz if not CI.apply(CC): AM.add("controlsFailed", enabled) + # broadcast carControl + cc_send = messaging.new_message() + cc_send.init('carControl') + cc_send.carControl = CC # copy? + carcontrol.send(cc_send.to_bytes()) + prof.checkpoint("CarControl") # ***** publish state to logger ***** diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index d30f46592d..57246c54c8 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -1,4 +1,5 @@ from cereal import car +from selfdrive.swaglog import cloudlog class ET: ENABLE = 0 @@ -24,7 +25,7 @@ class alert(object): tst = car.CarControl.new_message() tst.hudControl.visualAlert = self.visual_alert tst.hudControl.audibleAlert = self.audible_alert - + def __str__(self): return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_type) + " " + str(self.visual_alert) + " " + str(self.audible_alert) @@ -74,7 +75,8 @@ class AlertManager(object): return len(self.activealerts) > 0 and self.activealerts[0].alert_type >= ET.IMMEDIATE_DISABLE def add(self, alert_type, enabled = True): - this_alert = self.alerts[str(alert_type)] + alert_type = str(alert_type) + this_alert = self.alerts[alert_type] # downgrade the alert if we aren't enabled if not enabled and this_alert.alert_type > ET.NO_ENTRY: @@ -84,6 +86,12 @@ class AlertManager(object): if enabled and this_alert.alert_type < ET.WARNING: return + # if new alert is different, log it + if self.current_alert is None or self.current_alert.alert_text_2 != this_alert.alert_text_2: + cloudlog.event('alert_add', + alert_type=alert_type, + enabled=enabled) + self.activealerts.append(this_alert) self.activealerts.sort() @@ -110,6 +118,10 @@ class AlertManager(object): alert_text_1 = self.current_alert.alert_text_1 alert_text_2 = self.current_alert.alert_text_2 + # disable current alert + if self.alert_start_time + max(self.current_alert.duration_sound, self.current_alert.duration_hud_alert, self.current_alert.duration_text) < cur_time: + self.current_alert = None + # reset self.activealerts = [] diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 2bcb729ac8..997168679f 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -211,6 +211,8 @@ def manager_thread(): msg.thermal.freeSpace = avail with open("/sys/class/power_supply/battery/capacity") as f: msg.thermal.batteryPercent = int(f.read()) + with open("/sys/class/power_supply/battery/status") as f: + msg.thermal.batteryStatus = f.read().strip() thermal_sock.send(msg.to_bytes()) print msg @@ -242,6 +244,10 @@ def manager_thread(): for p in car_started_processes: kill_managed_process(p) + # shutdown if the battery gets lower than 10%, we aren't running, and we are discharging + if msg.thermal.batteryPercent < 5 and msg.thermal.batteryStatus == "Discharging": + os.system('LD_LIBRARY_PATH="" svc power shutdown') + # check the status of all processes, did any of them die? for p in running: cloudlog.debug(" running %s %s" % (p, running[p])) diff --git a/selfdrive/thermal.py b/selfdrive/thermal.py index f89f358d48..24e4d6c52f 100644 --- a/selfdrive/thermal.py +++ b/selfdrive/thermal.py @@ -3,7 +3,7 @@ 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()) + ret = max(0, int(f.read())) return ret def read_thermal(): diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 1d7e68672a..ac6b4155d7 100755 Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ