Skip to content

Commit

Permalink
openpilot v0.5.9 release
Browse files Browse the repository at this point in the history
old-commit-hash: 0207a97
  • Loading branch information
Vehicle Researcher committed Feb 20, 2019
1 parent 34c9a47 commit 2cc4edd
Show file tree
Hide file tree
Showing 55 changed files with 1,871 additions and 827 deletions.
10 changes: 6 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ Supported Cars
| ---------------------| -------------------------| ---------------------| --------| ---------------| -----------------| ---------------|-------------------|
| Acura | ILX 2016-17 | AcuraWatch Plus | Yes | Yes | 25mph<sup>1</sup>| 25mph | Nidec |
| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
| Buick<sup>3</sup> | Regal 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Chevrolet<sup>3</sup>| Malibu 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Chevrolet<sup>3</sup>| Volt 2017-18 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Cadillac<sup>3</sup> | ATS 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
Expand All @@ -81,19 +82,20 @@ Supported Cars
| Hyundai | Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
| Hyundai | Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | Custom<sup>6</sup>|
| Hyundai | Genesis 2018 | All | Yes | Stock | 19mph | 34mph | Custom<sup>6</sup>|
| Kia | Optima 2019 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
| Lexus | RX Hybrid 2016-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Camry 2018<sup>4</sup> | All | Yes | Stock | 0mph<sup>5</sup> | 0mph | Toyota |
| Toyota | C-HR 2017-18<sup>4</sup> | All | Yes | Stock | 0mph | 0mph | Toyota |
| Toyota | Corolla 2017-18 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph | Toyota |
| Toyota | Corolla 2017-18 | All | Yes | Yes<sup>2</sup>| 20mph<sup>1</sup>| 0mph | Toyota |
| Toyota | Highlander 2017-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Highlander Hybrid 2018 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Prius 2016 | TSS-P | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Prius 2017-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Prius Prime 2017-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Toyota | Rav4 2016 | TSS-P | Yes | Yes<sup>2</sup>| 20mph | 0mph | Toyota |
| Toyota | Rav4 2017-18 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph | Toyota |
| Toyota | Rav4 2016 | TSS-P | Yes | Yes<sup>2</sup>| 20mph<sup>1</sup>| 0mph | Toyota |
| Toyota | Rav4 2017-18 | All | Yes | Yes<sup>2</sup>| 20mph<sup>1</sup>| 0mph | Toyota |
| Toyota | Rav4 Hybrid 2017-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |

<sup>1</sup>[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)***
Expand Down Expand Up @@ -166,7 +168,7 @@ Directory structure
├── sensord # IMU / GPS interface code
├── test # Car simulator running code through virtual maneuvers
├── ui # The UI
└── visiond # Embedded vision pipeline
└── visiond # Vision pipeline

To understand how the services interact, see `selfdrive/service_list.yaml`

Expand Down
13 changes: 12 additions & 1 deletion RELEASES.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,21 @@
Version 0.5.9 (2019-02-10)
========================
* Improve calibration using a dedicated neural network
* Abstract planner in its own process to remove lags in controls process
* Improve speed limits with country/region defaults by road type
* Reduce mapd data usage with gzip thanks to eFiniLan
* Zip log files in the background to reduce disk usage
* Kia Optima support thanks to emmertex!
* Buick Regal 2018 support thanks to HOYS!
* Comma pedal support for Toyota thanks to wocsor! Note: tuning needed and not maintained by comma

Version 0.5.8 (2019-01-17)
========================
* Open sourced visiond
* Auto-slowdown for upcoming turns
* Chrysler/Jeep/Fiat support thanks to adhintz!
* Honda Civic 2019 support thanks to csouers!
* Improved use of car display in Toyota thanks to arne182!
* Improve use of car display in Toyota thanks to arne182!
* No data upload when connected to Android or iOS hotspots and "Enable Upload Over Cellular" setting is off
* EON stops charging when 12V battery drops below 11.8V

Expand Down
4 changes: 2 additions & 2 deletions apk/ai.comma.plus.frame.apk
Git LFS file not shown
4 changes: 2 additions & 2 deletions apk/ai.comma.plus.offroad.apk
Git LFS file not shown
49 changes: 43 additions & 6 deletions cereal/log.capnp
Original file line number Diff line number Diff line change
Expand Up @@ -374,6 +374,7 @@ struct Live100Data {
l20MonoTimeDEPRECATED @17 :UInt64;
mdMonoTimeDEPRECATED @18 :UInt64;
planMonoTime @28 :UInt64;
pathPlanMonoTime @50 :UInt64;

state @31 :ControlState;
vEgo @0 :Float32;
Expand Down Expand Up @@ -401,6 +402,7 @@ struct Live100Data {
cumLagMs @15 :Float32;
startMonoTime @48 :UInt64;
mapValid @49 :Bool;
forceDecel @51 :Bool;

enabled @19 :Bool;
active @36 :Bool;
Expand Down Expand Up @@ -546,12 +548,12 @@ struct Plan {
events @13 :List(Car.CarEvent);

# lateral, 3rd order polynomial
lateralValid @0 :Bool;
dPoly @1 :List(Float32);
laneWidth @11 :Float32;
lateralValidDEPRECATED @0 :Bool;
dPolyDEPRECATED @1 :List(Float32);
laneWidthDEPRECATED @11 :Float32;

# longitudinal
longitudinalValid @2 :Bool;
longitudinalValidDEPRECATED @2 :Bool;
vCruise @16 :Float32;
aCruise @17 :Float32;
vTarget @3 :Float32;
Expand All @@ -560,10 +562,14 @@ struct Plan {
aTargetMinDEPRECATED @4 :Float32;
aTargetMaxDEPRECATED @5 :Float32;
aTarget @18 :Float32;

vStart @26 :Float32;
aStart @27 :Float32;

jerkFactor @6 :Float32;
hasLead @7 :Bool;
hasLeftLane @23 :Bool;
hasRightLane @24 :Bool;
hasLeftLaneDEPRECATED @23 :Bool;
hasRightLaneDEPRECATED @24 :Bool;
fcw @8 :Bool;
longitudinalPlanSource @15 :LongitudinalPlanSource;

Expand All @@ -577,6 +583,7 @@ struct Plan {
decelForTurn @22 :Bool;
mapValid @25 :Bool;


struct GpsTrajectory {
x @0 :List(Float32);
y @1 :List(Float32);
Expand All @@ -590,6 +597,21 @@ struct Plan {
}
}

struct PathPlan {
laneWidth @0 :Float32;

dPoly @1 :List(Float32);
cPoly @2 :List(Float32);
cProb @3 :Float32;
lPoly @4 :List(Float32);
lProb @5 :Float32;
rPoly @6 :List(Float32);
rProb @7 :Float32;

angleSteers @8 :Float32;
valid @9 :Bool;
}

struct LiveLocationData {
status @0 :UInt8;

Expand Down Expand Up @@ -1276,6 +1298,7 @@ struct UbloxGnss {
carrierPhaseStdev @10 :Float32;
# doppler standard deviation in Hz
dopplerStdev @11 :Float32;
sigId @12 :UInt8;

struct TrackingStatus {
# pseudorange valid
Expand Down Expand Up @@ -1584,6 +1607,11 @@ struct LiveParametersData {
struct LiveMapData {
speedLimitValid @0 :Bool;
speedLimit @1 :Float32;
speedAdvisoryValid @12 :Bool;
speedAdvisory @13 :Float32;
speedLimitAheadValid @14 :Bool;
speedLimitAhead @15 :Float32;
speedLimitAheadDistance @16 :Float32;
curvatureValid @2 :Bool;
curvature @3 :Float32;
wayId @4 :UInt64;
Expand All @@ -1603,6 +1631,13 @@ struct CameraOdometry {
rotStd @3 :List(Float32); # std rad/s in device frame
}

struct KalmanOdometry {
trans @0 :List(Float32); # m/s in device frame
rot @1 :List(Float32); # rad/s in device frame
transStd @2 :List(Float32); # std m/s in device frame
rotStd @3 :List(Float32); # std rad/s in device frame
}

struct Event {
# in nanoseconds?
logMonoTime @0 :UInt64;
Expand Down Expand Up @@ -1671,5 +1706,7 @@ struct Event {
liveParameters @61 :LiveParametersData;
liveMapData @62 :LiveMapData;
cameraOdometry @63 :CameraOdometry;
pathPlan @64 :PathPlan;
kalmanOdometry @65 :KalmanOdometry;
}
}
1 change: 1 addition & 0 deletions common/params.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ class UnknownKeyName(Exception):
# written: visiond
# read: visiond, controlsd
"CalibrationParams": TxType.PERSISTENT,
"ControlsParams": TxType.PERSISTENT,
# written: controlsd
# read: radard
"CarParams": TxType.CLEAR_ON_CAR_START,
Expand Down
10 changes: 1 addition & 9 deletions common/transformations/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,21 +29,13 @@
def get_calib_from_vp(vp):
vp_norm = normalize(vp)
yaw_calib = np.arctan(vp_norm[0])
pitch_calib = np.arctan(vp_norm[1]*np.cos(yaw_calib))
# TODO should be, this but written
# to be compatible with meshcalib and
# get_view_frame_from_road_fram
#pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib))
pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib))
roll_calib = 0
return roll_calib, pitch_calib, yaw_calib

# aka 'extrinsic_matrix'
# road : x->forward, y -> left, z->up
def get_view_frame_from_road_frame(roll, pitch, yaw, height):
# TODO
# calibration pitch is currently defined
# opposite to pitch in device frame
pitch = -pitch
device_from_road = orient.rot_from_euler([roll, pitch, yaw]).dot(np.diag([1, -1, -1]))
view_from_road = view_frame_from_device_frame.dot(device_from_road)
return np.hstack((view_from_road, [[0], [height], [0]]))
Expand Down
3 changes: 3 additions & 0 deletions models/posenet.dlc
Git LFS file not shown
4 changes: 2 additions & 2 deletions requirements_openpilot.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ cffi==1.11.5
contextlib2==0.5.4
crc16==0.1.1
crcmod==1.7
cryptography==1.4
cryptography==2.1.4
cycler==0.10.0
decorator==4.0.10
docopt==0.6.2
Expand All @@ -31,7 +31,7 @@ nose==1.3.7
numpy==1.11.1
pause==0.1.2
py==1.4.31
pyOpenSSL==16.0.0
pyOpenSSL==17.5.0
pyasn1-modules==0.0.8
pyasn1==0.1.9
pycapnp==0.6.3
Expand Down
4 changes: 2 additions & 2 deletions selfdrive/car/chrysler/interface.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python
from common.realtime import sec_since_boot
from cereal import car, log
from cereal import car
from selfdrive.config import Conversions as CV
from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event
from selfdrive.controls.lib.vehicle_model import VehicleModel
Expand Down Expand Up @@ -256,7 +256,7 @@ def update(self, c):

# pass in a car.CarControl
# to be called @ 100hz
def apply(self, c, perception_state=log.Live20Data.new_message()):
def apply(self, c):

if (self.CS.frame == -1):
return False # if we haven't seen a frame 220, then do not update.
Expand Down
4 changes: 2 additions & 2 deletions selfdrive/car/ford/interface.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python
from common.realtime import sec_since_boot
from cereal import car, log
from cereal import car
from selfdrive.swaglog import cloudlog
from selfdrive.config import Conversions as CV
from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event
Expand Down Expand Up @@ -210,7 +210,7 @@ def update(self, c):

# pass in a car.CarControl
# to be called @ 100hz
def apply(self, c, perception_state=log.Live20Data.new_message()):
def apply(self, c):

self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators,
c.hudControl.visualAlert, c.cruiseControl.cancel)
Expand Down
50 changes: 26 additions & 24 deletions selfdrive/car/gm/carcontroller.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,24 @@
from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car import apply_std_steer_torque_limits
from selfdrive.car.gm import gmcan
from selfdrive.car.gm.values import CAR, DBC
from selfdrive.car.gm.values import DBC, SUPERCRUISE_CARS
from selfdrive.can.packer import CANPacker


class CarControllerParams():
def __init__(self, car_fingerprint):
if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
self.STEER_MAX = 300
self.STEER_STEP = 2 # how often we update the steer cmd
self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s)
self.STEER_DELTA_DOWN = 17 # ~0.3s from peak torque to zero
elif car_fingerprint == CAR.CADILLAC_CT6:
if car_fingerprint in SUPERCRUISE_CARS:
self.STEER_MAX = 150
self.STEER_STEP = 1 # how often we update the steer cmd
self.STEER_DELTA_UP = 2 # 0.75s time to peak torque
self.STEER_DELTA_DOWN = 5 # 0.3s from peak torque to zero
self.MIN_STEER_SPEED = -1. # can steer down to zero
else:
self.STEER_MAX = 300
self.STEER_STEP = 2 # how often we update the steer cmd
self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s)
self.STEER_DELTA_DOWN = 17 # ~0.3s from peak torque to zero
self.MIN_STEER_SPEED = 3.

self.STEER_DRIVER_ALLOWANCE = 50 # allowed driver torque before start limiting
self.STEER_DRIVER_MULTIPLIER = 4 # weight driver torque heavily
Expand Down Expand Up @@ -94,7 +96,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, \
### STEER ###

if (frame % P.STEER_STEP) == 0:
lkas_enabled = enabled and not CS.steer_not_allowed and CS.v_ego > 3.
lkas_enabled = enabled and not CS.steer_not_allowed and CS.v_ego > P.MIN_STEER_SPEED
if lkas_enabled:
apply_steer = actuators.steer * P.STEER_MAX
apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, P)
Expand All @@ -104,16 +106,16 @@ def update(self, sendcan, enabled, CS, frame, actuators, \
self.apply_steer_last = apply_steer
idx = (frame / P.STEER_STEP) % 4

if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
can_sends.append(gmcan.create_steering_control(self.packer_pt,
canbus.powertrain, apply_steer, idx, lkas_enabled))
if self.car_fingerprint == CAR.CADILLAC_CT6:
if self.car_fingerprint in SUPERCRUISE_CARS:
can_sends += gmcan.create_steering_control_ct6(self.packer_pt,
canbus, apply_steer, CS.v_ego, idx, lkas_enabled)
else:
can_sends.append(gmcan.create_steering_control(self.packer_pt,
canbus.powertrain, apply_steer, idx, lkas_enabled))

### GAS/BRAKE ###

if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
if self.car_fingerprint not in SUPERCRUISE_CARS:
# no output if not enabled, but keep sending keepalive messages
# treat pedals as one
final_pedal = actuators.gas - actuators.brake
Expand Down Expand Up @@ -164,17 +166,17 @@ def update(self, sendcan, enabled, CS, frame, actuators, \
if frame % P.ADAS_KEEPALIVE_STEP == 0:
can_sends += gmcan.create_adas_keepalive(canbus.powertrain)

# Show green icon when LKA torque is applied, and
# alarming orange icon when approaching torque limit.
# If not sent again, LKA icon disappears in about 5 seconds.
# Conveniently, sending camera message periodically also works as a keepalive.
lka_active = CS.lkas_status == 1
lka_critical = lka_active and abs(actuators.steer) > 0.9
lka_icon_status = (lka_active, lka_critical)
if frame % P.CAMERA_KEEPALIVE_STEP == 0 \
or lka_icon_status != self.lka_icon_status_last:
can_sends.append(gmcan.create_lka_icon_command(canbus.sw_gmlan, lka_active, lka_critical))
self.lka_icon_status_last = lka_icon_status
# Show green icon when LKA torque is applied, and
# alarming orange icon when approaching torque limit.
# If not sent again, LKA icon disappears in about 5 seconds.
# Conveniently, sending camera message periodically also works as a keepalive.
lka_active = CS.lkas_status == 1
lka_critical = lka_active and abs(actuators.steer) > 0.9
lka_icon_status = (lka_active, lka_critical)
if frame % P.CAMERA_KEEPALIVE_STEP == 0 \
or lka_icon_status != self.lka_icon_status_last:
can_sends.append(gmcan.create_lka_icon_command(canbus.sw_gmlan, lka_active, lka_critical))
self.lka_icon_status_last = lka_icon_status

# Send chimes
if self.chime != chime:
Expand Down
Loading

0 comments on commit 2cc4edd

Please sign in to comment.