openpilot v0.4.4 release

pull/236/head
Vehicle Researcher 7 years ago
parent 4f7336f0e4
commit 9a9ff839a9
  1. 2
      README.md
  2. 10
      RELEASES.md
  3. BIN
      apk/ai.comma.plus.frame.apk
  4. BIN
      apk/ai.comma.plus.offroad.apk
  5. 3
      cereal/car.capnp
  6. 3
      cereal/log.capnp
  7. 2
      cereal/mapd.capnp
  8. 6
      common/fingerprints.py
  9. 2
      common/params.py
  10. 59
      selfdrive/car/__init__.py
  11. 12
      selfdrive/car/toyota/carcontroller.py
  12. 27
      selfdrive/car/toyota/carstate.py
  13. 5
      selfdrive/car/toyota/toyotacan.py
  14. 4
      selfdrive/common/framebuffer.cc
  15. 2
      selfdrive/common/version.h
  16. 32
      selfdrive/common/visionipc.c
  17. 3
      selfdrive/common/visionipc.h
  18. 2
      selfdrive/controls/lib/alertmanager.py
  19. 10
      selfdrive/controls/lib/longitudinal_mpc/generator.cpp
  20. 4
      selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_common.h
  21. 37
      selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_solver.c
  22. BIN
      selfdrive/loggerd/loggerd
  23. 10
      selfdrive/loggerd/uploader.py
  24. 5
      selfdrive/manager.py
  25. BIN
      selfdrive/sensord/gpsd
  26. BIN
      selfdrive/sensord/sensord
  27. 1
      selfdrive/service_list.yaml
  28. 10
      selfdrive/test/tests/plant/test_longitudinal.py
  29. BIN
      selfdrive/ui/spinner/spinner
  30. 14
      selfdrive/ui/ui.c
  31. 14
      selfdrive/version.py
  32. BIN
      selfdrive/visiond/visiond

@ -12,7 +12,7 @@ Here are [some](https://www.youtube.com/watch?v=9OwTJFuDI7g) [videos](https://ww
Hardware Hardware
------ ------
Right now openpilot supports the [NEO research platform](http://github.com/commaai/neo) and the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit). We'd like to support other platforms as well. Right now openpilot supports the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit). We'd like to support other platforms as well.
Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup. Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup.

@ -1,3 +1,13 @@
Version 0.4.4 (2018-04-13)
==========================
* EON are flipped! Flip your EON's mount!
* Alpha Honda Ridgeline support thanks to energee!
* Support optional front camera recording
* Upload over cellular toggle now applies to all files, not just video
* Increase acceleration when closing lead gap
* User now prompted for future updates
* NEO no longer supported :(
Version 0.4.3.2 (2018-03-29) Version 0.4.3.2 (2018-03-29)
============================ ============================
* Improve autofocus * Improve autofocus

Binary file not shown.

Binary file not shown.

@ -55,6 +55,8 @@ struct CarEvent @0x9b1657f34caf3ad3 {
manualRestart @30; manualRestart @30;
lowSpeedLockout @31; lowSpeedLockout @31;
plannerError @32; plannerError @32;
ipasOverride @33;
debugAlert @34;
} }
} }
@ -192,6 +194,7 @@ struct RadarState {
struct CarControl { struct CarControl {
# must be true for any actuator commands to work # must be true for any actuator commands to work
enabled @0 :Bool; enabled @0 :Bool;
active @7 :Bool;
gasDEPRECATED @1 :Float32; gasDEPRECATED @1 :Float32;
brakeDEPRECATED @2 :Float32; brakeDEPRECATED @2 :Float32;

@ -485,6 +485,7 @@ struct EncodeIndex {
bigBoxHEVC @2; # bcamera.hevc bigBoxHEVC @2; # bcamera.hevc
chffrAndroidH264 @3; # acamera chffrAndroidH264 @3; # acamera
fullLosslessClip @4; # prcamera.mkv fullLosslessClip @4; # prcamera.mkv
front @5; # dcamera.hevc
} }
} }
@ -542,6 +543,7 @@ struct Plan {
cruise @0; cruise @0;
mpc1 @1; mpc1 @1;
mpc2 @2; mpc2 @2;
mpc3 @3;
} }
} }
@ -1376,6 +1378,7 @@ struct GPSPlannerPlan {
acceleration @4 :Float32; acceleration @4 :Float32;
pointsDEPRECATED @5 :List(ECEFPointDEPRECATED); pointsDEPRECATED @5 :List(ECEFPointDEPRECATED);
points @6 :List(ECEFPoint); points @6 :List(ECEFPoint);
xLookahead @7 :Float32;
} }
struct TrafficEvent @0xacfa74a094e62626 { struct TrafficEvent @0xacfa74a094e62626 {

@ -3,7 +3,7 @@ $Cxx.namespace("cereal");
using Java = import "java.capnp"; using Java = import "java.capnp";
$Java.package("ai.comma.openpilot.cereal"); $Java.package("ai.comma.openpilot.cereal");
$Java.outerClassname("Log"); $Java.outerClassname("Map");
using Log = import "log.capnp"; using Log = import "log.capnp";

@ -15,6 +15,9 @@ class TOYOTA:
COROLLA = "TOYOTA COROLLA 2017" COROLLA = "TOYOTA COROLLA 2017"
LEXUS_RXH = "LEXUS RX HYBRID 2017" LEXUS_RXH = "LEXUS RX HYBRID 2017"
class GM:
VOLT = "CHEVROLET VOLT PREMIER 2017"
_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes _DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes
_FINGERPRINTS = { _FINGERPRINTS = {
@ -76,6 +79,9 @@ _FINGERPRINTS = {
TOYOTA.LEXUS_RXH: [{ TOYOTA.LEXUS_RXH: [{
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8
}], }],
GM.VOLT: [{
170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8
}],
} }
# support additional internal only fingerprints # support additional internal only fingerprints

@ -74,6 +74,8 @@ keys = {
"DoUninstall": TxType.CLEAR_ON_MANAGER_START, "DoUninstall": TxType.CLEAR_ON_MANAGER_START,
"ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START, "ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START,
"IsUpdateAvailable": TxType.PERSISTANT, "IsUpdateAvailable": TxType.PERSISTANT,
"RecordFront": TxType.PERSISTANT,
} }
def fsync_dir(path): def fsync_dir(path):

@ -5,41 +5,26 @@ from common.fingerprints import eliminate_incompatible_cars, all_known_cars
from selfdrive.swaglog import cloudlog from selfdrive.swaglog import cloudlog
import selfdrive.messaging as messaging import selfdrive.messaging as messaging
from selfdrive.car.honda.interface import CarInterface as HondaInterface from common.fingerprints import HONDA, TOYOTA, GM
from selfdrive.car.toyota.interface import CarInterface as ToyotaInterface
from selfdrive.car.mock.interface import CarInterface as MockInterface def load_interfaces(x):
from common.fingerprints import HONDA, TOYOTA ret = {}
for interface in x:
try: try:
from .simulator.interface import CarInterface as SimInterface imp = __import__('selfdrive.car.%s.interface' % interface, fromlist=['CarInterface']).CarInterface
except ImportError: except ImportError:
SimInterface = None imp = None
for car in x[interface]:
try: ret[car] = imp
from .simulator2.interface import CarInterface as Sim2Interface return ret
except ImportError:
Sim2Interface = None # imports from directory selfdrive/car/<name>/
interfaces = load_interfaces({
'honda': [HONDA.CIVIC, HONDA.ACURA_ILX, HONDA.CRV, HONDA.ODYSSEY, HONDA.ACURA_RDX, HONDA.PILOT, HONDA.RIDGELINE],
interfaces = { 'toyota': [TOYOTA.PRIUS, TOYOTA.RAV4, TOYOTA.RAV4H, TOYOTA.COROLLA, TOYOTA.LEXUS_RXH],
HONDA.CIVIC: HondaInterface, 'gm': [GM.VOLT],
HONDA.ACURA_ILX: HondaInterface, 'simulator2': ['simulator2'],
HONDA.CRV: HondaInterface, 'mock': ['mock']})
HONDA.ODYSSEY: HondaInterface,
HONDA.ACURA_RDX: HondaInterface,
HONDA.PILOT: HondaInterface,
HONDA.RIDGELINE: HondaInterface,
TOYOTA.PRIUS: ToyotaInterface,
TOYOTA.RAV4: ToyotaInterface,
TOYOTA.RAV4H: ToyotaInterface,
TOYOTA.COROLLA: ToyotaInterface,
TOYOTA.LEXUS_RXH: ToyotaInterface,
"simulator2": Sim2Interface,
"mock": MockInterface
}
# **** for use live only **** # **** for use live only ****
def fingerprint(logcan, timeout): def fingerprint(logcan, timeout):
@ -92,6 +77,10 @@ def get_car(logcan, sendcan=None, passive=True):
return None, None return None, None
interface_cls = interfaces[candidate] interface_cls = interfaces[candidate]
if interface_cls is None:
cloudlog.warning("car matched %s, but interface wasn't available" % candidate)
return None, None
params = interface_cls.get_params(candidate, fingerprints) params = interface_cls.get_params(candidate, fingerprints)
return interface_cls(params, sendcan), params return interface_cls(params, sendcan), params

@ -157,9 +157,9 @@ class CarController(object):
# windup slower # windup slower
if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle): if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle):
angle_rate_lim = interp(CS.v_ego, ANGLE_MAX_BP, ANGLE_DELTA_V) angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_V)
else: else:
angle_rate_lim = interp(CS.v_ego, ANGLE_MAX_BP, ANGLE_DELTA_VU) angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_VU)
apply_angle = clip(apply_angle, self.last_angle - angle_rate_lim, self.last_angle + angle_rate_lim) apply_angle = clip(apply_angle, self.last_angle - angle_rate_lim, self.last_angle + angle_rate_lim)
else: else:
@ -195,11 +195,11 @@ class CarController(object):
else: else:
can_sends.append(create_steer_command(self.packer, apply_steer, frame)) can_sends.append(create_steer_command(self.packer, apply_steer, frame))
if ECU.APGS in self.fake_ecus:
if self.angle_control: if self.angle_control:
can_sends.append(create_ipas_steer_command(self.packer, apply_angle, self.steer_angle_enabled)) can_sends.append(create_ipas_steer_command(self.packer, apply_angle, self.steer_angle_enabled,
else: ECU.APGS in self.fake_ecus))
can_sends.append(create_ipas_steer_command(self.packer, 0, 0)) elif ECU.APGS in self.fake_ecus:
can_sends.append(create_ipas_steer_command(self.packer, 0, 0, True))
# accel cmd comes from DSU, but we can spam can to cancel the system even if we are using lat only control # accel cmd comes from DSU, but we can spam can to cancel the system even if we are using lat only control
if (frame % 3 == 0 and ECU.DSU in self.fake_ecus) or (pcm_cancel_cmd and ECU.CAM in self.fake_ecus): if (frame % 3 == 0 and ECU.DSU in self.fake_ecus) or (pcm_cancel_cmd and ECU.CAM in self.fake_ecus):

@ -36,17 +36,6 @@ def parse_gear_shifter(can_gear, car_fingerprint):
def get_can_parser(CP): def get_can_parser(CP):
# this function generates lists for signal, messages and initial values
if CP.carFingerprint == CAR.PRIUS:
dbc_f = 'toyota_prius_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.RAV4H:
dbc_f = 'toyota_rav4_hybrid_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.RAV4:
dbc_f = 'toyota_rav4_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.COROLLA:
dbc_f = 'toyota_corolla_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.LEXUS_RXH:
dbc_f = 'lexus_rx_hybrid_2017_pt_generated.dbc'
signals = [ signals = [
# sig_name, sig_address, default # sig_name, sig_address, default
@ -91,6 +80,19 @@ def get_can_parser(CP):
("EPS_STATUS", 25), ("EPS_STATUS", 25),
] ]
# this function generates lists for signal, messages and initial values
if CP.carFingerprint == CAR.PRIUS:
dbc_f = 'toyota_prius_2017_pt_generated.dbc'
signals += [("STATE", "AUTOPARK_STATUS", 0)]
elif CP.carFingerprint == CAR.RAV4H:
dbc_f = 'toyota_rav4_hybrid_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.RAV4:
dbc_f = 'toyota_rav4_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.COROLLA:
dbc_f = 'toyota_corolla_2017_pt_generated.dbc'
elif CP.carFingerprint == CAR.LEXUS_RXH:
dbc_f = 'lexus_rx_hybrid_2017_pt_generated.dbc'
return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0)
@ -172,4 +174,7 @@ class CarState(object):
self.gas_pressed = not cp.vl["PCM_CRUISE"]['GAS_RELEASED'] self.gas_pressed = not cp.vl["PCM_CRUISE"]['GAS_RELEASED']
self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2 self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2
self.brake_lights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) self.brake_lights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or self.brake_pressed)
if self.CP.carFingerprint == CAR.PRIUS:
self.generic_toggle = cp.vl["AUTOPARK_STATUS"]['STATE'] != 0
else:
self.generic_toggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM']) self.generic_toggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM'])

@ -28,7 +28,7 @@ def create_video_target(frame, addr):
return make_can_msg(addr, msg, 1, True) return make_can_msg(addr, msg, 1, True)
def create_ipas_steer_command(packer, steer, enabled): def create_ipas_steer_command(packer, steer, enabled, apgs_enabled):
"""Creates a CAN message for the Toyota Steer Command.""" """Creates a CAN message for the Toyota Steer Command."""
if steer < 0: if steer < 0:
direction = 3 direction = 3
@ -46,7 +46,10 @@ def create_ipas_steer_command(packer, steer, enabled):
"SET_ME_X10": 0x10, "SET_ME_X10": 0x10,
"SET_ME_X40": 0x40 "SET_ME_X40": 0x40
} }
if apgs_enabled:
return packer.make_can_msg("STEERING_IPAS", 0, values) return packer.make_can_msg("STEERING_IPAS", 0, values)
else:
return packer.make_can_msg("STEERING_IPAS_COMMA", 0, values)
def create_steer_command(packer, steer, raw_cnt): def create_steer_command(packer, steer, raw_cnt):

@ -56,8 +56,8 @@ extern "C" FramebufferState* framebuffer_init(
status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo); status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo);
assert(status == 0); assert(status == 0);
int orientation = 3; // rotate framebuffer 270 degrees //int orientation = 3; // rotate framebuffer 270 degrees
//int orientation = 1; // rotate framebuffer 90 degrees int orientation = 1; // rotate framebuffer 90 degrees
if(orientation == 1 || orientation == 3) { if(orientation == 1 || orientation == 3) {
int temp = s->dinfo.h; int temp = s->dinfo.h;
s->dinfo.h = s->dinfo.w; s->dinfo.h = s->dinfo.w;

@ -1 +1 @@
#define COMMA_VERSION "0.4.3.2-release" #define COMMA_VERSION "0.4.4-release"

@ -193,6 +193,21 @@ int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, Visi
return 0; return 0;
} }
void visionstream_release(VisionStream *s) {
int err;
if (s->last_idx >= 0) {
VisionPacket rep = {
.type = VIPC_STREAM_RELEASE,
.d = { .stream_rel = {
.type = s->last_type,
.idx = s->last_idx,
}}
};
err = vipc_send(s->ipc_fd, &rep);
s->last_idx = -1;
}
}
VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) {
int err; int err;
@ -207,7 +222,7 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) {
VisionPacket rep = { VisionPacket rep = {
.type = VIPC_STREAM_RELEASE, .type = VIPC_STREAM_RELEASE,
.d = { .stream_rel = { .d = { .stream_rel = {
.type = rp.d.stream_acq.type, .type = s->last_type,
.idx = s->last_idx, .idx = s->last_idx,
}} }}
}; };
@ -217,6 +232,7 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) {
} }
} }
s->last_type = rp.d.stream_acq.type;
s->last_idx = rp.d.stream_acq.idx; s->last_idx = rp.d.stream_acq.idx;
assert(s->last_idx < s->num_bufs); assert(s->last_idx < s->num_bufs);
@ -228,6 +244,20 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) {
} }
void visionstream_destroy(VisionStream *s) { void visionstream_destroy(VisionStream *s) {
int err;
if (s->last_idx >= 0) {
VisionPacket rep = {
.type = VIPC_STREAM_RELEASE,
.d = { .stream_rel = {
.type = s->last_type,
.idx = s->last_idx,
}}
};
err = vipc_send(s->ipc_fd, &rep);
s->last_idx = -1;
}
for (int i=0; i<s->num_bufs; i++) { for (int i=0; i<s->num_bufs; i++) {
if (s->bufs[i].addr) { if (s->bufs[i].addr) {
munmap(s->bufs[i].addr, s->bufs[i].len); munmap(s->bufs[i].addr, s->bufs[i].len);

@ -24,6 +24,7 @@ typedef enum VisionStreamType {
VISION_STREAM_UI_BACK, VISION_STREAM_UI_BACK,
VISION_STREAM_UI_FRONT, VISION_STREAM_UI_FRONT,
VISION_STREAM_YUV, VISION_STREAM_YUV,
VISION_STREAM_YUV_FRONT,
VISION_STREAM_MAX, VISION_STREAM_MAX,
} VisionStreamType; } VisionStreamType;
@ -94,12 +95,14 @@ void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs,
typedef struct VisionStream { typedef struct VisionStream {
int ipc_fd; int ipc_fd;
int last_idx; int last_idx;
int last_type;
int num_bufs; int num_bufs;
VisionStreamBufs bufs_info; VisionStreamBufs bufs_info;
VIPCBuf *bufs; VIPCBuf *bufs;
} VisionStream; } VisionStream;
int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info);
void visionstream_release(VisionStream *s);
VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra);
void visionstream_destroy(VisionStream *s); void visionstream_destroy(VisionStream *s);

@ -101,8 +101,8 @@ class AlertManager(object):
Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1),
"startup": Alert( "startup": Alert(
"Always keep hands on wheel",
"Be ready to take over at any time", "Be ready to take over at any time",
"Always keep hands on wheel and eyes on road",
AlertStatus.normal, AlertSize.mid, AlertStatus.normal, AlertSize.mid,
Priority.LOWEST, None, None, 0., 0., 15.), Priority.LOWEST, None, None, 0., 0., 15.),

@ -39,9 +39,9 @@ int main( )
// Running cost // Running cost
Function h; Function h;
h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired));
h << (d_l - desired) / (0.1 * v_ego + 0.5); h << (d_l - desired) / (0.05 * v_ego + 0.5);
h << a_ego * (1.0 + v_ego / 10.0); h << a_ego * (0.1 * v_ego + 1.0);
h << j_ego * (1.0 + v_ego / 10.0); h << j_ego * (0.1 * v_ego + 1.0);
// Weights are defined in mpc. // Weights are defined in mpc.
BMatrix Q(4,4); Q.setAll(true); BMatrix Q(4,4); Q.setAll(true);
@ -49,8 +49,8 @@ int main( )
// Terminal cost // Terminal cost
Function hN; Function hN;
hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired));
hN << (d_l - desired) / (0.1 * v_ego + 0.5); hN << (d_l - desired) / (0.05 * v_ego + 0.5);
hN << a_ego * (1.0 + v_ego / 10.0); hN << a_ego * (0.1 * v_ego + 1.0);
// Weights are defined in mpc. // Weights are defined in mpc.
BMatrix QN(3,3); QN.setAll(true); BMatrix QN(3,3); QN.setAll(true);

@ -181,8 +181,8 @@ real_t evGx[ 720 ];
/** Column vector of size: 120 */ /** Column vector of size: 120 */
real_t evGu[ 120 ]; real_t evGu[ 120 ];
/** Column vector of size: 32 */ /** Column vector of size: 30 */
real_t objAuxVar[ 32 ]; real_t objAuxVar[ 30 ];
/** Row vector of size: 8 */ /** Row vector of size: 8 */
real_t objValueIn[ 8 ]; real_t objValueIn[ 8 ];

@ -107,7 +107,7 @@ void acado_evaluateLSQ(const real_t* in, real_t* out)
{ {
const real_t* xd = in; const real_t* xd = in;
const real_t* u = in + 6; const real_t* u = in + 6;
/* Vector of auxiliary variables; number of elements: 32. */ /* Vector of auxiliary variables; number of elements: 30. */
real_t* a = acadoWorkspace.objAuxVar; real_t* a = acadoWorkspace.objAuxVar;
/* Compute intermediate quantities: */ /* Compute intermediate quantities: */
@ -137,18 +137,16 @@ a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-(
a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]);
a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[28] = (a[26]*a[26]); a[28] = (a[26]*a[26]);
a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[30] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01));
a[31] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01));
/* Compute outputs: */ /* Compute outputs: */
out[0] = (a[1]-a[3]); out[0] = (a[1]-a[3]);
out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
out[2] = (xd[2]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)));
out[3] = (u[0]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); out[3] = (u[0]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)));
out[4] = a[6]; out[4] = a[6];
out[5] = (a[11]-a[19]); out[5] = (a[11]-a[19]);
out[6] = (real_t)(0.0000000000000000e+00); out[6] = (real_t)(0.0000000000000000e+00);
@ -156,19 +154,19 @@ out[7] = a[20];
out[8] = (a[22]-a[25]); out[8] = (a[22]-a[25]);
out[9] = (real_t)(0.0000000000000000e+00); out[9] = (real_t)(0.0000000000000000e+00);
out[10] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); out[10] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]);
out[11] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(1.0000000000000001e-01))*a[28])); out[11] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28]));
out[12] = (real_t)(0.0000000000000000e+00); out[12] = (real_t)(0.0000000000000000e+00);
out[13] = a[26]; out[13] = a[26];
out[14] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]); out[14] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]);
out[15] = (real_t)(0.0000000000000000e+00); out[15] = (real_t)(0.0000000000000000e+00);
out[16] = (real_t)(0.0000000000000000e+00); out[16] = (real_t)(0.0000000000000000e+00);
out[17] = (xd[2]*a[30]); out[17] = (xd[2]*(real_t)(1.0000000000000001e-01));
out[18] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); out[18] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00));
out[19] = (real_t)(0.0000000000000000e+00); out[19] = (real_t)(0.0000000000000000e+00);
out[20] = (real_t)(0.0000000000000000e+00); out[20] = (real_t)(0.0000000000000000e+00);
out[21] = (real_t)(0.0000000000000000e+00); out[21] = (real_t)(0.0000000000000000e+00);
out[22] = (real_t)(0.0000000000000000e+00); out[22] = (real_t)(0.0000000000000000e+00);
out[23] = (u[0]*a[31]); out[23] = (u[0]*(real_t)(1.0000000000000001e-01));
out[24] = (real_t)(0.0000000000000000e+00); out[24] = (real_t)(0.0000000000000000e+00);
out[25] = (real_t)(0.0000000000000000e+00); out[25] = (real_t)(0.0000000000000000e+00);
out[26] = (real_t)(0.0000000000000000e+00); out[26] = (real_t)(0.0000000000000000e+00);
@ -176,13 +174,13 @@ out[27] = (real_t)(0.0000000000000000e+00);
out[28] = (real_t)(0.0000000000000000e+00); out[28] = (real_t)(0.0000000000000000e+00);
out[29] = (real_t)(0.0000000000000000e+00); out[29] = (real_t)(0.0000000000000000e+00);
out[30] = (real_t)(0.0000000000000000e+00); out[30] = (real_t)(0.0000000000000000e+00);
out[31] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); out[31] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00));
} }
void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) void acado_evaluateLSQEndTerm(const real_t* in, real_t* out)
{ {
const real_t* xd = in; const real_t* xd = in;
/* Vector of auxiliary variables; number of elements: 31. */ /* Vector of auxiliary variables; number of elements: 30. */
real_t* a = acadoWorkspace.objAuxVar; real_t* a = acadoWorkspace.objAuxVar;
/* Compute intermediate quantities: */ /* Compute intermediate quantities: */
@ -212,16 +210,15 @@ a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-(
a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]);
a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[28] = (a[26]*a[26]); a[28] = (a[26]*a[26]);
a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
a[30] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01));
/* Compute outputs: */ /* Compute outputs: */
out[0] = (a[1]-a[3]); out[0] = (a[1]-a[3]);
out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
out[2] = (xd[2]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)));
out[3] = a[6]; out[3] = a[6];
out[4] = (a[11]-a[19]); out[4] = (a[11]-a[19]);
out[5] = (real_t)(0.0000000000000000e+00); out[5] = (real_t)(0.0000000000000000e+00);
@ -229,14 +226,14 @@ out[6] = a[20];
out[7] = (a[22]-a[25]); out[7] = (a[22]-a[25]);
out[8] = (real_t)(0.0000000000000000e+00); out[8] = (real_t)(0.0000000000000000e+00);
out[9] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); out[9] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]);
out[10] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(1.0000000000000001e-01))*a[28])); out[10] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28]));
out[11] = (real_t)(0.0000000000000000e+00); out[11] = (real_t)(0.0000000000000000e+00);
out[12] = a[26]; out[12] = a[26];
out[13] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]); out[13] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]);
out[14] = (real_t)(0.0000000000000000e+00); out[14] = (real_t)(0.0000000000000000e+00);
out[15] = (real_t)(0.0000000000000000e+00); out[15] = (real_t)(0.0000000000000000e+00);
out[16] = (xd[2]*a[30]); out[16] = (xd[2]*(real_t)(1.0000000000000001e-01));
out[17] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); out[17] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00));
out[18] = (real_t)(0.0000000000000000e+00); out[18] = (real_t)(0.0000000000000000e+00);
out[19] = (real_t)(0.0000000000000000e+00); out[19] = (real_t)(0.0000000000000000e+00);
out[20] = (real_t)(0.0000000000000000e+00); out[20] = (real_t)(0.0000000000000000e+00);

Binary file not shown.

@ -155,7 +155,7 @@ class Uploader(object):
self.last_resp = FakeResponse() self.last_resp = FakeResponse()
else: else:
with open(fn, "rb") as f: with open(fn, "rb") as f:
self.last_resp = requests.put(url, data=f, headers=headers) self.last_resp = requests.put(url, data=f, headers=headers, timeout=10)
except Exception as e: except Exception as e:
self.last_exc = (e, traceback.format_exc()) self.last_exc = (e, traceback.format_exc())
raise raise
@ -251,12 +251,16 @@ def uploader_fn(exit_event):
backoff = 0.1 backoff = 0.1
while True: while True:
upload_video = (params.get("IsUploadVideoOverCellularEnabled") != "0") or is_on_wifi() should_upload = (params.get("IsUploadVideoOverCellularEnabled") != "0") or is_on_wifi()
if exit_event.is_set(): if exit_event.is_set():
return return
d = uploader.next_file_to_upload(upload_video) if not should_upload:
time.sleep(5)
continue
d = uploader.next_file_to_upload(with_video=True)
if d is None: if d is None:
time.sleep(5) time.sleep(5)
continue continue

@ -609,6 +609,9 @@ def uninstall():
os.system("service call power 16 i32 0 s16 recovery i32 1") os.system("service call power 16 i32 0 s16 recovery i32 1")
def main(): def main():
# the flippening!
os.system('LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1')
if os.getenv("NOLOG") is not None: if os.getenv("NOLOG") is not None:
del managed_processes['loggerd'] del managed_processes['loggerd']
del managed_processes['tombstoned'] del managed_processes['tombstoned']
@ -640,6 +643,8 @@ def main():
# set unset params # set unset params
if params.get("IsMetric") is None: if params.get("IsMetric") is None:
params.put("IsMetric", "0") params.put("IsMetric", "0")
if params.get("RecordFront") is None:
params.put("RecordFront", "0")
if params.get("IsRearViewMirror") is None: if params.get("IsRearViewMirror") is None:
params.put("IsRearViewMirror", "0") params.put("IsRearViewMirror", "0")
if params.get("IsFcwEnabled") is None: if params.get("IsFcwEnabled") is None:

Binary file not shown.

Binary file not shown.

@ -67,6 +67,7 @@ orbOdometry: [8057, true]
orbFeatures: [8058, true] orbFeatures: [8058, true]
orbKeyFrame: [8059, true] orbKeyFrame: [8059, true]
uiLayoutState: [8060, true] uiLayoutState: [8060, true]
frontEncodeIdx: [8061, true]
testModel: [8040, false] testModel: [8040, false]
testLiveLocation: [8045, false] testLiveLocation: [8045, false]

@ -94,6 +94,16 @@ maneuvers = [
speed_lead_breakpoints = [0., 15., 25.0], speed_lead_breakpoints = [0., 15., 25.0],
cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)]
), ),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2',
duration=50.,
initial_speed = 20.,
lead_relevancy=True,
initial_distance_lead=35.,
speed_lead_values = [20., 20., 0.],
speed_lead_breakpoints = [0., 15., 21.66],
cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)]
),
Maneuver( Maneuver(
'starting at 0mph, approaching a stopped car 100m away', 'starting at 0mph, approaching a stopped car 100m away',
duration=30., duration=30.,

Binary file not shown.

@ -762,7 +762,7 @@ static void ui_draw_track(UIState *s, bool is_mpc) {
if (!started) { if (!started) {
nvgMoveTo(s->vg, x, y); nvgMoveTo(s->vg, x, y);
track_start_x = x; track_start_x = x;
track_start_y = y; track_start_y = vwp_h;
started = true; started = true;
} else { } else {
nvgLineTo(s->vg, x, y); nvgLineTo(s->vg, x, y);
@ -770,7 +770,7 @@ static void ui_draw_track(UIState *s, bool is_mpc) {
} }
// right side down // right side down
for (int i=path_height; i>0; i--) { for (int i=path_height-1; i>0; i--) {
float px, py; float px, py;
if (is_mpc) { if (is_mpc) {
px = mpc_x_coords[i]; px = mpc_x_coords[i];
@ -790,7 +790,7 @@ static void ui_draw_track(UIState *s, bool is_mpc) {
if (!started) { if (!started) {
nvgMoveTo(s->vg, x, y); nvgMoveTo(s->vg, x, y);
track_end_y = y; track_end_y = vwp_h;
track_end_x = x; track_end_x = x;
started = true; started = true;
} else { } else {
@ -833,10 +833,10 @@ static void draw_frame(UIState *s) {
if (s->scene.frontview) { if (s->scene.frontview) {
out_mat = device_transform; // full 16/9 out_mat = device_transform; // full 16/9
// flip horizontally so it looks like a mirror // flip horizontally so it looks like a mirror
x2 = (float)scene->front_box_x / s->rgb_front_width; x1 = (float)scene->front_box_x / s->rgb_front_width;
x1 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width; x2 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width;
y1 = (float)scene->front_box_y / s->rgb_front_height; y2 = (float)scene->front_box_y / s->rgb_front_height;
y2 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height; y1 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height;
} else { } else {
out_mat = matmul(device_transform, frame_transform); out_mat = matmul(device_transform, frame_transform);
x1 = 1.0; x1 = 1.0;

@ -5,14 +5,14 @@ with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "ve
try: try:
origin = subprocess.check_output(["git", "config", "--get", "remote.origin.url"]) origin = subprocess.check_output(["git", "config", "--get", "remote.origin.url"])
if "-private" in origin: if origin.startswith('git@github.com:commaai'):
upstream = "origin/master" if origin.endswith('/one.git'):
dirty = True
else: else:
if 'chffrplus' in origin: branch = subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]).rstrip()
upstream = "origin/release" branch = 'origin/' + branch
dirty = subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0
else: else:
upstream = "origin/release2" dirty = True
dirty = subprocess.call(["git", "diff-index", "--quiet", upstream, "--"]) != 0
except subprocess.CalledProcessError: except subprocess.CalledProcessError:
dirty = True dirty = True

Binary file not shown.
Loading…
Cancel
Save