Skip to content

Commit 83dfc3c

Browse files
author
Vehicle Researcher
committed
openpilot v0.5.11 release
old-commit-hash: 2f92d57
1 parent 1abde66 commit 83dfc3c

File tree

99 files changed

+2763
-1629
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

99 files changed

+2763
-1629
lines changed

README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,7 @@ Supported Cars
7979
| Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
8080
| Honda | CR-V Hybrid 2019 | All | Yes | Stock | 0mph | 12mph | Bosch |
8181
| Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 0mph | Inverted Nidec |
82+
| Honda | Passport 2019 | All | Yes | Yes | 25mph<sup>1</sup>| 12mph | Inverted Nidec |
8283
| Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
8384
| Honda | Pilot 2019 | All | Yes | Yes | 25mph<sup>1</sup>| 12mph | Inverted Nidec |
8485
| Honda | Ridgeline 2017-19 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph | Nidec |
@@ -90,7 +91,8 @@ Supported Cars
9091
| Kia | Optima 2019 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
9192
| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
9293
| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom<sup>6</sup>|
93-
| Lexus | RX Hybrid 2016-18 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
94+
| Lexus | RX Hybrid 2016-19 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph | Toyota |
95+
| Subaru | Impreza 2019 | EyeSight | Yes | Stock | 0mph | 0mph | Subaru |
9496
| Toyota | Camry 2018<sup>4</sup> | All | Yes | Stock | 0mph<sup>5</sup> | 0mph | Toyota |
9597
| Toyota | C-HR 2017-18<sup>4</sup> | All | Yes | Stock | 0mph | 0mph | Toyota |
9698
| Toyota | Corolla 2017-18 | All | Yes | Yes<sup>2</sup>| 20mph<sup>1</sup>| 0mph | Toyota |

RELEASES.md

Lines changed: 15 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,25 @@
1+
Version 0.5.11 (2019-04-17)
2+
========================
3+
* Add support for Subaru
4+
* Reduce panda power consumption by 60% when car is off
5+
* Fix controlsd lag every 6 minutes. This would sometimes cause disengagements
6+
* Fix bug in controls with new angle-offset learner in MPC
7+
* Reduce cpu consumption of ubloxd by rewriting it in C++
8+
* Improve driver monitoring model and face detection
9+
* Improve performance of visiond and ui
10+
* Honda Passport 2019 support
11+
* Lexus RX Hybrid 2019 support thanks to schomems!
12+
113
Version 0.5.10 (2019-03-19)
214
========================
3-
* Self-tuning vehicle parameters: steering offset, tires stiffness and steering ratio
15+
* Self-tuning vehicle parameters: steering offset, tire stiffness and steering ratio
416
* Improve longitudinal control at low speed when lead vehicle harshly decelerates
517
* Fix panda bug going unexpectedly in DCP mode when EON is connected
618
* Reduce white panda power consumption by 500mW when EON is disconnected by turning off WIFI
719
* New Driver Monitoring Model
820
* Support QR codes for login using comma connect
9-
* Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required.
10-
Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal.
21+
* Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required.
22+
Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal.
1123
* Additional speed limit rules for Germany thanks to arne182
1224
* Allow negative speed limit offsets
1325

SAFETY.md

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,19 @@ Chrysler/Jeep/Fiat (Lateral only)
133133
units above the actual EPS generated motor torque to ensure limited differences between
134134
commanded and actual torques.
135135

136+
Subaru (Lateral only)
137+
------
138+
139+
- While the system is engaged, steer commands are subject to the same limits used by
140+
the stock system.
141+
142+
- Steering torque is controlled through the 0x122 CAN message and it's limited by the panda firmware and by
143+
openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will fault for
144+
commands outside the values of -2047 and 2047. A steering torque rate limit is enforced by the panda firmware and by
145+
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
146+
0.41s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's
147+
torque exceeds 60 units in the opposite dicrection to ensure limited applied torque against the
148+
driver's will.
136149

137150
**Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or
138151
not fully meeting the above requirements.

apk/ai.comma.plus.offroad.apk

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
version https://git-lfs.github.com/spec/v1
2-
oid sha256:e03ff9d6482c19f14ce565d64aab24433847208106e5a5e31947f5307e510ee5
3-
size 18376966
2+
oid sha256:1c82f4ea28008aad9a25cd434e5f817c84d621423739e7bca814f4dcff2b9714
3+
size 18376958

common/dbc.py

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,9 @@
77

88
def int_or_float(s):
99
# return number, trying to maintain int format
10-
try:
11-
return int(s)
12-
except ValueError:
10+
if s.isdigit():
11+
return int(s, 10)
12+
else:
1313
return float(s)
1414

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

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

5353
if dat is None:
54-
print "bad BO", l
54+
print("bad BO {0}".format(l))
55+
5556
name = dat.group(2)
5657
size = int(dat.group(3))
5758
ids = int(dat.group(1), 0) # could be hex
@@ -67,8 +68,9 @@ def __init__(self, fn):
6768
if dat is None:
6869
dat = sgm_regexp.match(l)
6970
go = 1
71+
7072
if dat is None:
71-
print "bad SG", l
73+
print("bad SG {0}".format(l))
7274

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

9294
if dat is None:
93-
print "bad VAL", l
95+
print("bad VAL {0}".format(l))
96+
9497
ids = int(dat.group(1), 0) # could be hex
9598
sgname = dat.group(2)
9699
defvals = dat.group(3)
@@ -208,7 +211,7 @@ def decode(self, x, arr=None, debug=False):
208211

209212
name = msg[0][0]
210213
if debug:
211-
print name
214+
print(name)
212215

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

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

257260
if arr is None:
258261
out[s[0]] = tmp

common/ffi_wrapper.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,8 @@
44
import hashlib
55
from cffi import FFI
66

7-
TMPDIR = "/tmp/ccache"
87

9-
10-
def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None):
8+
def ffi_wrap(name, c_code, c_header, tmpdir="/tmp/ccache", cflags="", libraries=None):
119
if libraries is None:
1210
libraries = []
1311

@@ -24,7 +22,7 @@ def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None):
2422
try:
2523
mod = __import__(cache)
2624
except Exception:
27-
print "cache miss", cache
25+
print("cache miss {0}".format(cache))
2826
compile_code(cache, c_code, c_header, tmpdir, cflags, libraries)
2927
mod = __import__(cache)
3028
finally:

common/transformations/camera.py

Lines changed: 48 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
import numpy as np
22
import common.transformations.orientation as orient
33
import cv2
4+
import math
45

56
FULL_FRAME_SIZE = (1164, 874)
67
W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1]
@@ -12,6 +13,17 @@
1213
[ 0., FOCAL, H/2.],
1314
[ 0., 0., 1.]])
1415

16+
17+
leon_dcam_intrinsics = np.array([
18+
[650, 0, 816/2],
19+
[ 0, 650, 612/2],
20+
[ 0, 0, 1]])
21+
22+
eon_dcam_intrinsics = np.array([
23+
[860, 0, 1152/2],
24+
[ 0, 860, 864/2],
25+
[ 0, 0, 1]])
26+
1527
# aka 'K_inv' aka view_frame_from_camera_frame
1628
eon_intrinsics_inv = np.linalg.inv(eon_intrinsics)
1729

@@ -147,28 +159,44 @@ def transform_img(base_img,
147159
from_intr=eon_intrinsics,
148160
to_intr=eon_intrinsics,
149161
calib_rot_view=None,
150-
output_size=None):
151-
cy = from_intr[1,2]
162+
output_size=None,
163+
pretransform=None,
164+
top_hacks=True):
152165
size = base_img.shape[:2]
153166
if not output_size:
154167
output_size = size[::-1]
155-
h = 1.22
156-
quadrangle = np.array([[0, cy + 20],
157-
[size[1]-1, cy + 20],
158-
[0, size[0]-1],
159-
[size[1]-1, size[0]-1]], dtype=np.float32)
160-
quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1))))
161-
quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1],
162-
h*np.ones(4),
163-
h/quadrangle_norm[:,1]))
164-
rot = orient.rot_from_euler(augment_eulers)
165-
if calib_rot_view is not None:
166-
rot = calib_rot_view.dot(rot)
167-
to_extrinsics = np.hstack((rot.T, -augment_trans[:,None]))
168-
to_KE = to_intr.dot(to_extrinsics)
169-
warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1)))))
170-
warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2],
171-
warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32)
172-
M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32))
168+
169+
cy = from_intr[1,2]
170+
def get_M(h=1.22):
171+
quadrangle = np.array([[0, cy + 20],
172+
[size[1]-1, cy + 20],
173+
[0, size[0]-1],
174+
[size[1]-1, size[0]-1]], dtype=np.float32)
175+
quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1))))
176+
quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1],
177+
h*np.ones(4),
178+
h/quadrangle_norm[:,1]))
179+
rot = orient.rot_from_euler(augment_eulers)
180+
if calib_rot_view is not None:
181+
rot = calib_rot_view.dot(rot)
182+
to_extrinsics = np.hstack((rot.T, -augment_trans[:,None]))
183+
to_KE = to_intr.dot(to_extrinsics)
184+
warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1)))))
185+
warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2],
186+
warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32)
187+
M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32))
188+
return M
189+
190+
M = get_M()
191+
if pretransform is not None:
192+
M = M.dot(pretransform)
173193
augmented_rgb = cv2.warpPerspective(base_img, M, output_size, borderMode=cv2.BORDER_REPLICATE)
194+
195+
if top_hacks:
196+
cyy = int(math.ceil(to_intr[1,2]))
197+
M = get_M(1000)
198+
if pretransform is not None:
199+
M = M.dot(pretransform)
200+
augmented_rgb[:cyy] = cv2.warpPerspective(base_img, M, (output_size[0], cyy), borderMode=cv2.BORDER_REPLICATE)
201+
174202
return augmented_rgb

common/transformations/model.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232

3333

3434
# MED model
35-
MEDMODEL_INPUT_SIZE = (640, 240)
35+
MEDMODEL_INPUT_SIZE = (512, 256)
3636
MEDMODEL_YUV_SIZE = (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1] * 3 // 2)
3737
MEDMODEL_CY = 47.6
3838

launch_chffrplus.sh

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@ function launch {
1919
echo 0-3 > /dev/cpuset/foreground/cpus
2020
echo 0-3 > /dev/cpuset/android/cpus
2121

22+
# handle pythonpath
23+
ln -s /data/openpilot /data/pythonpath
2224
export PYTHONPATH="$PWD"
2325

2426
# start manager

models/monitoring_model.dlc

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
version https://git-lfs.github.com/spec/v1
2-
oid sha256:0e880365b63e8d48bf8bee797dc96b483682a6b0b14e968e937c9109377b926e
3-
size 427951
2+
oid sha256:f681047cee0e546c1438aecc99f3039456b4044f50e74745171a6aa0fab6503e
3+
size 428211

requirements_openpilot.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ enum34==1.1.6
2323
evdev==0.6.1
2424
fastcluster==1.1.20
2525
filterpy==1.2.4
26-
hexdump
26+
hexdump==3.3
2727
ipaddress==1.0.16
2828
json-rpc==1.12.1
2929
libusb1==1.5.0
@@ -33,6 +33,7 @@ nose==1.3.7
3333
numpy==1.11.1
3434
opencv-python==3.4.0.12
3535
pause==0.1.2
36+
psutil==3.4.2
3637
py==1.4.31
3738
pyOpenSSL==16.0.0
3839
pyasn1-modules==0.0.8

selfdrive/boardd/boardd.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -220,7 +220,7 @@ def boardd_proxy_loop(rate=200, address="192.168.2.251"):
220220
# recv @ 100hz
221221
can_msgs = can_recv()
222222
#for m in can_msgs:
223-
# print "R:",hex(m[0]), str(m[2]).encode("hex")
223+
# print("R: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex")))
224224

225225
# publish to logger
226226
# TODO: refactor for speed
@@ -233,7 +233,7 @@ def boardd_proxy_loop(rate=200, address="192.168.2.251"):
233233
if tsc is not None:
234234
cl = can_capnp_to_can_list(tsc.can)
235235
#for m in cl:
236-
# print "S:",hex(m[0]), str(m[2]).encode("hex")
236+
# print("S: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex")))
237237
can_send_many(cl)
238238

239239
rk.keep_time()

0 commit comments

Comments
 (0)