Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pull in changes from OP 0.5.11 #12

Merged
merged 20 commits into from
Apr 26, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
585 changes: 585 additions & 0 deletions .pylintrc

Large diffs are not rendered by default.

8 changes: 6 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,12 @@ install:
- docker build -t tmppilot -f Dockerfile.openpilot .

script:
- docker run
tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py'
- docker run
tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pyflakes $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda")'
- docker run
tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pylint $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda"); exit $(($? & 3))'
- docker run
-v "$(pwd)"/selfdrive/test/tests/plant/out:/tmp/openpilot/selfdrive/test/tests/plant/out
tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/tests/plant && OPTEST=1 ./test_longitudinal.py'
- docker run
tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py'
2 changes: 2 additions & 0 deletions Dockerfile.openpilot
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,14 @@ RUN pip install -r /tmp/requirements_openpilot.txt

ENV PYTHONPATH /tmp/openpilot:$PYTHONPATH

COPY ./.pylintrc /tmp/openpilot/.pylintrc
COPY ./common /tmp/openpilot/common
COPY ./cereal /tmp/openpilot/cereal
COPY ./opendbc /tmp/openpilot/opendbc
COPY ./selfdrive /tmp/openpilot/selfdrive
COPY ./phonelibs /tmp/openpilot/phonelibs
COPY ./pyextra /tmp/openpilot/pyextra
COPY ./panda /tmp/openpilot/panda

RUN mkdir -p /tmp/openpilot/selfdrive/test/out
RUN make -C /tmp/openpilot/selfdrive/controls/lib/longitudinal_mpc clean
Expand Down
9 changes: 7 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ Supported Cars
| Cadillac<sup>3</sup> | ATS 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Chrysler | Pacifica 2018 | Adaptive Cruise | Yes | Stock | 0mph | 9mph | FCA |
| Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Yes | Stock | 0mph | 9mph | FCA |
| Chrysler | Pacifica Hybrid 2019 | Adaptive Cruise | Yes | Stock | 0mph | 39mph | FCA |
| GMC<sup>3</sup> | Acadia Denali 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Holden<sup>3</sup> | Astra 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom<sup>7</sup>|
| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | Bosch |
Expand All @@ -76,18 +77,22 @@ Supported Cars
| Honda | Civic Hatchback 2017-19 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
| Honda | CR-V 2015-16 | Touring | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
| Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
| Honda | CR-V Hybrid 2019 | All | Yes | Stock | 0mph | 12mph | Bosch |
| Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 0mph | Inverted Nidec |
| Honda | Passport 2019 | All | Yes | Yes | 25mph<sup>1</sup>| 12mph | Inverted Nidec |
| Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
| Honda | Pilot 2019 | All | Yes | Yes | 25mph<sup>1</sup>| 12mph | Inverted Nidec |
| Honda | Ridgeline 2017-19 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
| 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>|
| Jeep | Grand Cherokee 2017-19 | Adaptive Cruise | Yes | Stock | 0mph | 9mph | FCA |
| Jeep | Grand Cherokee 2017-18 | Adaptive Cruise | Yes | Stock | 0mph | 9mph | FCA |
| Jeep | Grand Cherokee 2019 | Adaptive Cruise | Yes | Stock | 0mph | 39mph | FCA |
| 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 |
| Lexus | RX Hybrid 2016-19 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
| Subaru | Impreza 2019 | EyeSight | Yes | Stock | 0mph | 0mph | Subaru |
| 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<sup>1</sup>| 0mph | Toyota |
Expand Down
19 changes: 16 additions & 3 deletions RELEASES.md
Original file line number Diff line number Diff line change
@@ -1,14 +1,27 @@
Version 0.5.11 (2019-04-17)
========================
* Add support for Subaru
* Reduce panda power consumption by 60% when car is off
* Fix controlsd lag every 6 minutes. This would sometimes cause disengagements
* Fix bug in controls with new angle-offset learner in MPC
* Reduce cpu consumption of ubloxd by rewriting it in C++
* Improve driver monitoring model and face detection
* Improve performance of visiond and ui
* Honda Passport 2019 support
* Lexus RX Hybrid 2019 support thanks to schomems!

Version 0.5.10 (2019-03-19)
========================
* Self-tuning vehicle parameters: steering offset, tires stiffness and steering ratio
* Self-tuning vehicle parameters: steering offset, tire stiffness and steering ratio
* Improve longitudinal control at low speed when lead vehicle harshly decelerates
* Fix panda bug going unexpectedly in DCP mode when EON is connected
* Reduce white panda power consumption by 500mW when EON is disconnected by turning off WIFI
* New Driver Monitoring Model
* Support QR codes for login using comma connect
* Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required.
Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal.
* Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required.
Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal.
* Additional speed limit rules for Germany thanks to arne182
* Allow negative speed limit offsets

Version 0.5.9 (2019-02-10)
========================
Expand Down
13 changes: 13 additions & 0 deletions SAFETY.md
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,19 @@ Chrysler/Jeep/Fiat (Lateral only)
units above the actual EPS generated motor torque to ensure limited differences between
commanded and actual torques.

Subaru (Lateral only)
------

- While the system is engaged, steer commands are subject to the same limits used by
the stock system.

- Steering torque is controlled through the 0x122 CAN message and it's limited by the panda firmware and by
openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will fault for
commands outside the values of -2047 and 2047. A steering torque rate limit is enforced by the panda firmware and by
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
0.41s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's
torque exceeds 60 units in the opposite dicrection to ensure limited applied torque against the
driver's will.

**Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or
not fully meeting the above requirements.
Binary file modified apk/ai.comma.plus.offroad.apk
Binary file not shown.
21 changes: 12 additions & 9 deletions common/dbc.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@

def int_or_float(s):
# return number, trying to maintain int format
try:
return int(s)
except ValueError:
if s.isdigit():
return int(s, 10)
else:
return float(s)

DBCSignal = namedtuple(
Expand All @@ -21,7 +21,7 @@ class dbc(object):
def __init__(self, fn):
self.name, _ = os.path.splitext(os.path.basename(fn))
with open(fn) as f:
self.txt = f.read().split("\n")
self.txt = f.readlines()
self._warned_addresses = set()

# regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py
Expand Down Expand Up @@ -51,7 +51,8 @@ def __init__(self, fn):
dat = bo_regexp.match(l)

if dat is None:
print "bad BO", l
print("bad BO {0}".format(l))

name = dat.group(2)
size = int(dat.group(3))
ids = int(dat.group(1), 0) # could be hex
Expand All @@ -67,8 +68,9 @@ def __init__(self, fn):
if dat is None:
dat = sgm_regexp.match(l)
go = 1

if dat is None:
print "bad SG", l
print("bad SG {0}".format(l))

sgname = dat.group(1)
start_bit = int(dat.group(go+2))
Expand All @@ -90,7 +92,8 @@ def __init__(self, fn):
dat = val_regexp.match(l)

if dat is None:
print "bad VAL", l
print("bad VAL {0}".format(l))

ids = int(dat.group(1), 0) # could be hex
sgname = dat.group(2)
defvals = dat.group(3)
Expand Down Expand Up @@ -208,7 +211,7 @@ def decode(self, x, arr=None, debug=False):

name = msg[0][0]
if debug:
print name
print(name)

st = x[2].ljust(8, '\x00')
le, be = None, None
Expand Down Expand Up @@ -252,7 +255,7 @@ def decode(self, x, arr=None, debug=False):
tmp = tmp * factor + offset

# if debug:
# print "%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1])
# print("%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1]))

if arr is None:
out[s[0]] = tmp
Expand Down
6 changes: 2 additions & 4 deletions common/ffi_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,8 @@
import hashlib
from cffi import FFI

TMPDIR = "/tmp/ccache"


def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None):
def ffi_wrap(name, c_code, c_header, tmpdir="/tmp/ccache", cflags="", libraries=None):
if libraries is None:
libraries = []

Expand All @@ -24,7 +22,7 @@ def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None):
try:
mod = __import__(cache)
except Exception:
print "cache miss", cache
print("cache miss {0}".format(cache))
compile_code(cache, c_code, c_header, tmpdir, cflags, libraries)
mod = __import__(cache)
finally:
Expand Down
72 changes: 50 additions & 22 deletions common/transformations/camera.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import numpy as np
import common.transformations.orientation as orient
import cv2
import math

FULL_FRAME_SIZE = (1164, 874)
W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1]
Expand All @@ -12,6 +13,17 @@
[ 0., FOCAL, H/2.],
[ 0., 0., 1.]])


leon_dcam_intrinsics = np.array([
[650, 0, 816/2],
[ 0, 650, 612/2],
[ 0, 0, 1]])

eon_dcam_intrinsics = np.array([
[860, 0, 1152/2],
[ 0, 860, 864/2],
[ 0, 0, 1]])

# aka 'K_inv' aka view_frame_from_camera_frame
eon_intrinsics_inv = np.linalg.inv(eon_intrinsics)

Expand Down Expand Up @@ -64,7 +76,7 @@ def normalize(img_pts, intrinsics=eon_intrinsics):
input_shape = img_pts.shape
img_pts = np.atleast_2d(img_pts)
img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1))))
img_pts_normalized = intrinsics_inv.dot(img_pts.T).T
img_pts_normalized = img_pts.dot(intrinsics_inv.T)
img_pts_normalized[(img_pts < 0).any(axis=1)] = np.nan
return img_pts_normalized[:,:2].reshape(input_shape)

Expand All @@ -76,7 +88,7 @@ def denormalize(img_pts, intrinsics=eon_intrinsics):
input_shape = img_pts.shape
img_pts = np.atleast_2d(img_pts)
img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1))))
img_pts_denormalized = intrinsics.dot(img_pts.T).T
img_pts_denormalized = img_pts.dot(intrinsics.T)
img_pts_denormalized[img_pts_denormalized[:,0] > W] = np.nan
img_pts_denormalized[img_pts_denormalized[:,0] < 0] = np.nan
img_pts_denormalized[img_pts_denormalized[:,1] > H] = np.nan
Expand Down Expand Up @@ -147,28 +159,44 @@ def transform_img(base_img,
from_intr=eon_intrinsics,
to_intr=eon_intrinsics,
calib_rot_view=None,
output_size=None):
cy = from_intr[1,2]
output_size=None,
pretransform=None,
top_hacks=True):
size = base_img.shape[:2]
if not output_size:
output_size = size[::-1]
h = 1.22
quadrangle = np.array([[0, cy + 20],
[size[1]-1, cy + 20],
[0, size[0]-1],
[size[1]-1, size[0]-1]], dtype=np.float32)
quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1))))
quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1],
h*np.ones(4),
h/quadrangle_norm[:,1]))
rot = orient.rot_from_euler(augment_eulers)
if calib_rot_view is not None:
rot = calib_rot_view.dot(rot)
to_extrinsics = np.hstack((rot.T, -augment_trans[:,None]))
to_KE = to_intr.dot(to_extrinsics)
warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1)))))
warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2],
warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32)
M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32))

cy = from_intr[1,2]
def get_M(h=1.22):
quadrangle = np.array([[0, cy + 20],
[size[1]-1, cy + 20],
[0, size[0]-1],
[size[1]-1, size[0]-1]], dtype=np.float32)
quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1))))
quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1],
h*np.ones(4),
h/quadrangle_norm[:,1]))
rot = orient.rot_from_euler(augment_eulers)
if calib_rot_view is not None:
rot = calib_rot_view.dot(rot)
to_extrinsics = np.hstack((rot.T, -augment_trans[:,None]))
to_KE = to_intr.dot(to_extrinsics)
warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1)))))
warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2],
warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32)
M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32))
return M

M = get_M()
if pretransform is not None:
M = M.dot(pretransform)
augmented_rgb = cv2.warpPerspective(base_img, M, output_size, borderMode=cv2.BORDER_REPLICATE)

if top_hacks:
cyy = int(math.ceil(to_intr[1,2]))
M = get_M(1000)
if pretransform is not None:
M = M.dot(pretransform)
augmented_rgb[:cyy] = cv2.warpPerspective(base_img, M, (output_size[0], cyy), borderMode=cv2.BORDER_REPLICATE)

return augmented_rgb
2 changes: 1 addition & 1 deletion common/transformations/model.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@


# MED model
MEDMODEL_INPUT_SIZE = (640, 240)
MEDMODEL_INPUT_SIZE = (512, 256)
MEDMODEL_YUV_SIZE = (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1] * 3 // 2)
MEDMODEL_CY = 47.6

Expand Down
2 changes: 2 additions & 0 deletions launch_chffrplus.sh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@ function launch {
echo 0-3 > /dev/cpuset/foreground/cpus
echo 0-3 > /dev/cpuset/android/cpus

# handle pythonpath
ln -s /data/openpilot /data/pythonpath
export PYTHONPATH="$PWD"

# start manager
Expand Down
Binary file modified models/monitoring_model.dlc
Binary file not shown.
2 changes: 2 additions & 0 deletions opendbc/ford_cgea1_2_bodycan_2011.dbc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ NS_ :
BU_BO_REL_
SG_MUL_VAL_

BS_:

BU_: XXX


Expand Down
2 changes: 2 additions & 0 deletions opendbc/ford_cgea1_2_ptcan_2011.dbc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ NS_ :
BU_BO_REL_
SG_MUL_VAL_

BS_:

BU_: XXX


Expand Down
2 changes: 2 additions & 0 deletions opendbc/ford_fusion_2018_adas.dbc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ NS_ :
BU_BO_REL_
SG_MUL_VAL_

BS_:

BU_: XXX

BO_ 1280 Object_00: 8 XXX
Expand Down
5 changes: 4 additions & 1 deletion opendbc/ford_fusion_2018_pt.dbc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ NS_ :
BU_BO_REL_
SG_MUL_VAL_

BS_:

BU_: XXX

BO_ 130 EPAS_INFO: 8 XXX
Expand Down Expand Up @@ -128,9 +130,10 @@ BO_ 984 Lane_Keep_Assist_Ui: 8 XXX
SG_ Hands_Warning : 49|1@0+ (1,0) [0|1] "" XXX
SG_ Set_Me_X30 : 63|8@0+ (1,0) [0|255] "" XXX

CM_ SG_ 970 Lkas_Action "only vals 4, 5, 8, 9 seem to work. 4 and 5 are a bit smoother" ;

VAL_ 357 Cruise_State 4 "active" 3 "standby" 0 "off" ;
VAL_ 970 Lkas_Action 15 "off" 9 "abrupt" 8 "abrupt2" 5 "smooth" 4 "smooth2" ;
VAL_ 970 Lkas_Alert 15 "no_alert" 3 "high_intensity" 2 "mid_intensity" 1 "low_intensity" ;
VAL_ 972 LaActAvail_D_Actl 3 "available" 2 "tbd" 1 "not_available" 0 "fault" ;
VAL_ 984 Lines_Hud 15 "none" 11 "grey_yellow" 8 "green_red" 7 "yellow_grey" 6 "grey_grey" 4 "red_green" 3 "green_green" ;
CM_ SG_ 970 Lkas_Action "only vals 4, 5, 8, 9 seem to work. 4 and 5 are a bit smoother" ;
4 changes: 4 additions & 0 deletions opendbc/generator/honda/honda_civic_touring_2016_can.dbc
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,9 @@ BO_ 450 EPB_STATUS: 8 EPB
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON

BO_ 493 HUD_SETTING: 8 XXX
SG_ SPEED_UNIT : 5|1@0+ (1,0) [0|1] "" EON

BO_ 487 BRAKE_PRESSURE: 4 VSA
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
Expand Down Expand Up @@ -125,6 +128,7 @@ VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_spe
VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ;
VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ;
VAL_ 493 SPEED_UNIT 1 "mph" 0 "kph" ;
VAL_ 545 ECON_ON_2 0 "off" 3 "on" ;
VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
Expand Down
Loading