mirror of
https://github.com/sunnypilot/sunnypilot.git
synced 2026-02-19 01:53:57 +08:00
getting ready for Python 3 (#619)
* tabs to spaces python 2 to 3: https://portingguide.readthedocs.io/en/latest/syntax.html#tabs-and-spaces * use the new except syntax python 2 to 3: https://portingguide.readthedocs.io/en/latest/exceptions.html#the-new-except-syntax * make relative imports absolute python 2 to 3: https://portingguide.readthedocs.io/en/latest/imports.html#absolute-imports * Queue renamed to queue in python 3 Use the six compatibility library to support both python 2 and 3: https://portingguide.readthedocs.io/en/latest/stdlib-reorg.html#renamed-modules * replace dict.has_key() with in python 2 to 3: https://portingguide.readthedocs.io/en/latest/dicts.html#removed-dict-has-key * make dict views compatible with python 3 python 2 to 3: https://portingguide.readthedocs.io/en/latest/dicts.html#dict-views-and-iterators Where needed, wrapping things that will be a view in python 3 with a list(). For example, if it's accessed with [] Python 3 has no iter*() methods, so just using the values() instead of itervalues() as long as it's not too performance intensive. Note that any minor performance hit of using a list instead of a view will go away when switching to python 3. If it is intensive, we could use the six version. * Explicitly use truncating division python 2 to 3: https://portingguide.readthedocs.io/en/latest/numbers.html#division python 3 treats / as float division. When we want the result to be an integer, use // * replace map() with list comprehension where a list result is needed. In python 3, map() returns an iterator. python 2 to 3: https://portingguide.readthedocs.io/en/latest/iterators.html#new-behavior-of-map-and-filter * replace filter() with list comprehension In python 3, filter() returns an interatoooooooooooor. python 2 to 3: https://portingguide.readthedocs.io/en/latest/iterators.html#new-behavior-of-map-and-filter * wrap zip() in list() where we need the result to be a list python 2 to 3: https://portingguide.readthedocs.io/en/latest/iterators.html#new-behavior-of-zip * clean out some lint Removes these pylint warnings: ************* Module selfdrive.car.chrysler.chryslercan W: 15, 0: Unnecessary semicolon (unnecessary-semicolon) W: 16, 0: Unnecessary semicolon (unnecessary-semicolon) W: 25, 0: Unnecessary semicolon (unnecessary-semicolon) ************* Module common.dbc W:101, 0: Anomalous backslash in string: '\?'. String constant might be missing an r prefix. (anomalous-backslash-in-string) ************* Module selfdrive.car.gm.interface R:102, 6: Redefinition of ret.minEnableSpeed type from float to int (redefined-variable-type) R:103, 6: Redefinition of ret.mass type from int to float (redefined-variable-type) ************* Module selfdrive.updated R: 20, 6: Redefinition of r type from int to str (redefined-variable-type)
This commit is contained in:
@@ -98,7 +98,7 @@ class dbc(object):
|
||||
sgname = dat.group(2)
|
||||
defvals = dat.group(3)
|
||||
|
||||
defvals = defvals.replace("?","\?") #escape sequence in C++
|
||||
defvals = defvals.replace("?",r"\?") #escape sequence in C++
|
||||
defvals = defvals.split('"')[:-1]
|
||||
|
||||
defs = defvals[1::2]
|
||||
@@ -112,7 +112,7 @@ class dbc(object):
|
||||
|
||||
self.def_vals[ids].append((sgname, defvals))
|
||||
|
||||
for msg in self.msgs.viewvalues():
|
||||
for msg in self.msgs.values():
|
||||
msg[1].sort(key=lambda x: x.start_bit)
|
||||
|
||||
self.msg_name_to_address = {}
|
||||
|
||||
@@ -61,4 +61,4 @@ def eliminate_incompatible_cars(msg, candidate_cars):
|
||||
|
||||
def all_known_cars():
|
||||
"""Returns a list of all known car strings."""
|
||||
return _FINGERPRINTS.keys()
|
||||
return list(_FINGERPRINTS.keys())
|
||||
|
||||
@@ -75,7 +75,7 @@ def sympy_into_c(sympy_functions):
|
||||
routines.append(r)
|
||||
|
||||
[(c_name, c_code), (h_name, c_header)] = codegen.get_code_generator('C', 'ekf', 'C99').write(routines, "ekf")
|
||||
c_code = '\n'.join(filter(lambda x: len(x) > 0 and x[0] != '#', c_code.split("\n")))
|
||||
c_header = '\n'.join(filter(lambda x: len(x) > 0 and x[0] != '#', c_header.split("\n")))
|
||||
c_code = '\n'.join(x for x in c_code.split("\n") if len(x) > 0 and x[0] != '#')
|
||||
c_header = '\n'.join(x for x in c_header.split("\n") if len(x) > 0 and x[0] != '#')
|
||||
|
||||
return c_header, c_code
|
||||
|
||||
@@ -15,13 +15,13 @@ eon_intrinsics = np.array([
|
||||
|
||||
|
||||
leon_dcam_intrinsics = np.array([
|
||||
[650, 0, 816/2],
|
||||
[ 0, 650, 612/2],
|
||||
[650, 0, 816//2],
|
||||
[ 0, 650, 612//2],
|
||||
[ 0, 0, 1]])
|
||||
|
||||
eon_dcam_intrinsics = np.array([
|
||||
[860, 0, 1152/2],
|
||||
[ 0, 860, 864/2],
|
||||
[860, 0, 1152//2],
|
||||
[ 0, 860, 864//2],
|
||||
[ 0, 0, 1]])
|
||||
|
||||
# aka 'K_inv' aka view_frame_from_camera_frame
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
|
||||
from common.transformations.camera import eon_focal_length, \
|
||||
vp_from_ke, \
|
||||
get_view_frame_from_road_frame, \
|
||||
FULL_FRAME_SIZE
|
||||
vp_from_ke, \
|
||||
get_view_frame_from_road_frame, \
|
||||
FULL_FRAME_SIZE
|
||||
|
||||
# segnet
|
||||
|
||||
|
||||
@@ -6,7 +6,7 @@ import time
|
||||
import threading
|
||||
import traceback
|
||||
import zmq
|
||||
import Queue
|
||||
import six.moves.queue
|
||||
from jsonrpc import JSONRPCResponseManager, dispatcher
|
||||
from websocket import create_connection, WebSocketTimeoutException
|
||||
|
||||
@@ -21,8 +21,8 @@ ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai')
|
||||
HANDLER_THREADS = os.getenv('HANDLER_THREADS', 4)
|
||||
|
||||
dispatcher["echo"] = lambda s: s
|
||||
payload_queue = Queue.Queue()
|
||||
response_queue = Queue.Queue()
|
||||
payload_queue = six.moves.queue.Queue()
|
||||
response_queue = six.moves.queue.Queue()
|
||||
|
||||
def handle_long_poll(ws):
|
||||
end_event = threading.Event()
|
||||
@@ -52,7 +52,7 @@ def jsonrpc_handler(end_event):
|
||||
data = payload_queue.get(timeout=1)
|
||||
response = JSONRPCResponseManager.handle(data, dispatcher)
|
||||
response_queue.put_nowait(response)
|
||||
except Queue.Empty:
|
||||
except six.moves.queue.Empty:
|
||||
pass
|
||||
except Exception as e:
|
||||
cloudlog.exception("athena jsonrpc handler failed")
|
||||
@@ -87,7 +87,7 @@ def ws_send(ws, end_event):
|
||||
try:
|
||||
response = response_queue.get(timeout=1)
|
||||
ws.send(response.json)
|
||||
except Queue.Empty:
|
||||
except six.moves.queue.Empty:
|
||||
pass
|
||||
except Exception:
|
||||
traceback.print_exc()
|
||||
|
||||
@@ -127,16 +127,13 @@ def boardd_mock_loop():
|
||||
|
||||
while 1:
|
||||
tsc = messaging.drain_sock(logcan, wait_for_one=True)
|
||||
snds = map(lambda x: can_capnp_to_can_list(x.can), tsc)
|
||||
snd = []
|
||||
for s in snds:
|
||||
snd += s
|
||||
snd = filter(lambda x: x[-1] <= 1, snd)
|
||||
can_send_many(snd)
|
||||
snds = [can_capnp_to_can_list(x.can) for x in tsc]
|
||||
snds = [x for x in snds if x[-1] <= 1]
|
||||
can_send_many(snds)
|
||||
|
||||
# recv @ 100hz
|
||||
can_msgs = can_recv()
|
||||
print("sent %d got %d" % (len(snd), len(can_msgs)))
|
||||
print("sent %d got %d" % (len(snds), len(can_msgs)))
|
||||
m = can_list_to_can_capnp(can_msgs)
|
||||
sendcan.send(m.to_bytes())
|
||||
|
||||
|
||||
@@ -20,7 +20,7 @@ class CANPacker(object):
|
||||
|
||||
def pack(self, addr, values, counter):
|
||||
values_thing = []
|
||||
for name, value in values.iteritems():
|
||||
for name, value in values.items():
|
||||
if name not in self.sig_names:
|
||||
self.sig_names[name] = ffi.new("char[]", name)
|
||||
|
||||
|
||||
@@ -58,7 +58,7 @@ class CANParser(object):
|
||||
{
|
||||
'address': msg_address,
|
||||
'check_frequency': freq,
|
||||
} for msg_address, freq in message_options.iteritems()])
|
||||
} for msg_address, freq in message_options.items()])
|
||||
|
||||
self.can = libdbc.can_init(bus, dbc_name, len(message_options_c), message_options_c,
|
||||
len(signal_options_c), signal_options_c, sendcan, tcp_addr)
|
||||
|
||||
@@ -39,10 +39,10 @@ def main():
|
||||
continue #skip output is newer than template and dbc
|
||||
|
||||
msgs = [(address, msg_name, msg_size, sorted(msg_sigs, key=lambda s: s.name not in ("COUNTER", "CHECKSUM"))) # process counter and checksums first
|
||||
for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.iteritems()) if msg_sigs]
|
||||
for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.items()) if msg_sigs]
|
||||
|
||||
def_vals = {a: set(b) for a,b in can_dbc.def_vals.items()} #remove duplicates
|
||||
def_vals = [(address, sig) for address, sig in sorted(def_vals.iteritems())]
|
||||
def_vals = [(address, sig) for address, sig in sorted(def_vals.items())]
|
||||
|
||||
if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"):
|
||||
checksum_type = "honda"
|
||||
|
||||
@@ -12,8 +12,8 @@ def calc_checksum(data):
|
||||
end_index = len(data)
|
||||
index = 0
|
||||
checksum = 0xFF
|
||||
temp_chk = 0;
|
||||
bit_sum = 0;
|
||||
temp_chk = 0
|
||||
bit_sum = 0
|
||||
if(end_index <= index):
|
||||
return False
|
||||
for index in range(0, end_index):
|
||||
@@ -22,7 +22,7 @@ def calc_checksum(data):
|
||||
iterate = 8
|
||||
while(iterate > 0):
|
||||
iterate -= 1
|
||||
bit_sum = curr & shift;
|
||||
bit_sum = curr & shift
|
||||
temp_chk = checksum & 0x80
|
||||
if (bit_sum != 0):
|
||||
bit_sum = 0x1C
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
import chryslercan
|
||||
from selfdrive.car.chrysler import chryslercan
|
||||
from selfdrive.can.packer import CANPacker
|
||||
|
||||
from cereal import car
|
||||
|
||||
@@ -25,29 +25,29 @@ def _create_radard_can_parser():
|
||||
|
||||
# The factor and offset are applied by the dbc parsing library, so the
|
||||
# default values should be after the factor/offset are applied.
|
||||
signals = zip(['LONG_DIST'] * msg_n +
|
||||
signals = list(zip(['LONG_DIST'] * msg_n +
|
||||
['LAT_DIST'] * msg_n +
|
||||
['REL_SPEED'] * msg_n,
|
||||
RADAR_MSGS_C * 2 + # LONG_DIST, LAT_DIST
|
||||
RADAR_MSGS_D, # REL_SPEED
|
||||
[0] * msg_n + # LONG_DIST
|
||||
[-1000] * msg_n + # LAT_DIST
|
||||
[-146.278] * msg_n) # REL_SPEED set to 0, factor/offset to this
|
||||
[-146.278] * msg_n)) # REL_SPEED set to 0, factor/offset to this
|
||||
# TODO what are the checks actually used for?
|
||||
# honda only checks the last message,
|
||||
# toyota checks all the messages. Which do we want?
|
||||
checks = zip(RADAR_MSGS_C +
|
||||
checks = list(zip(RADAR_MSGS_C +
|
||||
RADAR_MSGS_D,
|
||||
[20]*msg_n + # 20Hz (0.05s)
|
||||
[20]*msg_n) # 20Hz (0.05s)
|
||||
[20]*msg_n)) # 20Hz (0.05s)
|
||||
|
||||
return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1)
|
||||
|
||||
def _address_to_track(address):
|
||||
if address in RADAR_MSGS_C:
|
||||
return (address - RADAR_MSGS_C[0]) / 2
|
||||
return (address - RADAR_MSGS_C[0]) // 2
|
||||
if address in RADAR_MSGS_D:
|
||||
return (address - RADAR_MSGS_D[0]) / 2
|
||||
return (address - RADAR_MSGS_D[0]) // 2
|
||||
raise ValueError("radar received unexpected address %d" % address)
|
||||
|
||||
class RadarInterface(object):
|
||||
|
||||
@@ -14,10 +14,10 @@ RADAR_MSGS = range(0x500, 0x540)
|
||||
def _create_radard_can_parser():
|
||||
dbc_f = 'ford_fusion_2018_adas.dbc'
|
||||
msg_n = len(RADAR_MSGS)
|
||||
signals = zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n,
|
||||
RADAR_MSGS * 3,
|
||||
[0] * msg_n + [0] * msg_n + [0] * msg_n)
|
||||
checks = zip(RADAR_MSGS, [20]*msg_n)
|
||||
signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n,
|
||||
RADAR_MSGS * 3,
|
||||
[0] * msg_n + [0] * msg_n + [0] * msg_n))
|
||||
checks = list(zip(RADAR_MSGS, [20]*msg_n))
|
||||
|
||||
return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1)
|
||||
|
||||
|
||||
@@ -104,7 +104,7 @@ class CarController(object):
|
||||
apply_steer = 0
|
||||
|
||||
self.apply_steer_last = apply_steer
|
||||
idx = (frame / P.STEER_STEP) % 4
|
||||
idx = (frame // P.STEER_STEP) % 4
|
||||
|
||||
if self.car_fingerprint in SUPERCRUISE_CARS:
|
||||
can_sends += gmcan.create_steering_control_ct6(self.packer_pt,
|
||||
@@ -134,7 +134,7 @@ class CarController(object):
|
||||
|
||||
# Gas/regen and brakes - all at 25Hz
|
||||
if (frame % 4) == 0:
|
||||
idx = (frame / 4) % 4
|
||||
idx = (frame // 4) % 4
|
||||
|
||||
at_full_stop = enabled and CS.standstill
|
||||
near_stop = enabled and (CS.v_ego < P.NEAR_STOP_BRAKE_PHASE)
|
||||
@@ -153,13 +153,13 @@ class CarController(object):
|
||||
tt = sec_since_boot()
|
||||
|
||||
if frame % time_and_headlights_step == 0:
|
||||
idx = (frame / time_and_headlights_step) % 4
|
||||
idx = (frame // time_and_headlights_step) % 4
|
||||
can_sends.append(gmcan.create_adas_time_status(canbus.obstacle, int((tt - self.start_time) * 60), idx))
|
||||
can_sends.append(gmcan.create_adas_headlights_status(canbus.obstacle))
|
||||
|
||||
speed_and_accelerometer_step = 2
|
||||
if frame % speed_and_accelerometer_step == 0:
|
||||
idx = (frame / speed_and_accelerometer_step) % 4
|
||||
idx = (frame // speed_and_accelerometer_step) % 4
|
||||
can_sends.append(gmcan.create_adas_steering_status(canbus.obstacle, idx))
|
||||
can_sends.append(gmcan.create_adas_accelerometer_speed_status(canbus.obstacle, CS.v_ego, idx))
|
||||
|
||||
|
||||
@@ -70,7 +70,7 @@ class CarInterface(object):
|
||||
# supports stop and go, but initial engage must be above 18mph (which include conservatism)
|
||||
ret.minEnableSpeed = 18 * CV.MPH_TO_MS
|
||||
# kg of standard extra cargo to count for driver, gas, etc...
|
||||
ret.mass = 1607 + std_cargo
|
||||
ret.mass = 1607. + std_cargo
|
||||
ret.safetyModel = car.CarParams.SafetyModels.gm
|
||||
ret.wheelbase = 2.69
|
||||
ret.steerRatio = 15.7
|
||||
@@ -80,7 +80,7 @@ class CarInterface(object):
|
||||
elif candidate == CAR.MALIBU:
|
||||
# supports stop and go, but initial engage must be above 18mph (which include conservatism)
|
||||
ret.minEnableSpeed = 18 * CV.MPH_TO_MS
|
||||
ret.mass = 1496 + std_cargo
|
||||
ret.mass = 1496. + std_cargo
|
||||
ret.safetyModel = car.CarParams.SafetyModels.gm
|
||||
ret.wheelbase = 2.83
|
||||
ret.steerRatio = 15.8
|
||||
@@ -89,7 +89,7 @@ class CarInterface(object):
|
||||
|
||||
elif candidate == CAR.HOLDEN_ASTRA:
|
||||
# kg of standard extra cargo to count for driver, gas, etc...
|
||||
ret.mass = 1363 + std_cargo
|
||||
ret.mass = 1363. + std_cargo
|
||||
ret.wheelbase = 2.662
|
||||
# Remaining parameters copied from Volt for now
|
||||
ret.centerToFront = ret.wheelbase * 0.4
|
||||
@@ -99,7 +99,7 @@ class CarInterface(object):
|
||||
ret.steerRatioRear = 0.
|
||||
|
||||
elif candidate == CAR.ACADIA:
|
||||
ret.minEnableSpeed = -1 # engage speed is decided by pcm
|
||||
ret.minEnableSpeed = -1. # engage speed is decided by pcm
|
||||
ret.mass = 4353. * CV.LB_TO_KG + std_cargo
|
||||
ret.safetyModel = car.CarParams.SafetyModels.gm
|
||||
ret.wheelbase = 2.86
|
||||
@@ -118,7 +118,7 @@ class CarInterface(object):
|
||||
|
||||
elif candidate == CAR.CADILLAC_ATS:
|
||||
ret.minEnableSpeed = 18 * CV.MPH_TO_MS
|
||||
ret.mass = 1601 + std_cargo
|
||||
ret.mass = 1601. + std_cargo
|
||||
ret.safetyModel = car.CarParams.SafetyModels.gm
|
||||
ret.wheelbase = 2.78
|
||||
ret.steerRatio = 15.3
|
||||
@@ -127,7 +127,7 @@ class CarInterface(object):
|
||||
|
||||
elif candidate == CAR.CADILLAC_CT6:
|
||||
# engage speed is decided by pcm
|
||||
ret.minEnableSpeed = -1
|
||||
ret.minEnableSpeed = -1.
|
||||
# kg of standard extra cargo to count for driver, gas, etc...
|
||||
ret.mass = 4016. * CV.LB_TO_KG + std_cargo
|
||||
ret.safetyModel = car.CarParams.SafetyModels.cadillac
|
||||
@@ -218,7 +218,7 @@ class CarInterface(object):
|
||||
ret.gasPressed = self.CS.user_gas_pressed
|
||||
|
||||
# brake pedal
|
||||
ret.brake = self.CS.user_brake / 0xd0
|
||||
ret.brake = self.CS.user_brake // 0xd0
|
||||
ret.brakePressed = self.CS.brake_pressed
|
||||
|
||||
# steering wheel
|
||||
|
||||
@@ -25,7 +25,7 @@ def create_radard_can_parser(canbus, car_fingerprint):
|
||||
if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
|
||||
# C1A-ARS3-A by Continental
|
||||
radar_targets = range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)
|
||||
signals = zip(['FLRRNumValidTargets',
|
||||
signals = list(zip(['FLRRNumValidTargets',
|
||||
'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt',
|
||||
'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt',
|
||||
'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] +
|
||||
@@ -36,7 +36,7 @@ def create_radard_can_parser(canbus, car_fingerprint):
|
||||
[0] * 7 +
|
||||
[0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS +
|
||||
[0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS +
|
||||
[0.0] * NUM_SLOTS + [0] * NUM_SLOTS)
|
||||
[0.0] * NUM_SLOTS + [0] * NUM_SLOTS))
|
||||
|
||||
checks = []
|
||||
|
||||
|
||||
@@ -133,7 +133,7 @@ class CarController(object):
|
||||
# **** process the car messages ****
|
||||
|
||||
# *** compute control surfaces ***
|
||||
BRAKE_MAX = 1024/4
|
||||
BRAKE_MAX = 1024//4
|
||||
if CS.CP.carFingerprint in (CAR.ACURA_ILX):
|
||||
STEER_MAX = 0xF00
|
||||
elif CS.CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX):
|
||||
@@ -160,7 +160,7 @@ class CarController(object):
|
||||
|
||||
# Send dashboard UI commands.
|
||||
if (frame % 10) == 0:
|
||||
idx = (frame/10) % 4
|
||||
idx = (frame//10) % 4
|
||||
can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, idx))
|
||||
|
||||
if CS.CP.radarOffCan:
|
||||
@@ -173,7 +173,7 @@ class CarController(object):
|
||||
else:
|
||||
# Send gas and brake commands.
|
||||
if (frame % 2) == 0:
|
||||
idx = frame / 2
|
||||
idx = frame // 2
|
||||
pump_on, self.last_pump_ts = brake_pump_hysteresys(apply_brake, self.apply_brake_last, self.last_pump_ts)
|
||||
can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on,
|
||||
pcm_override, pcm_cancel_cmd, hud.chime, hud.fcw, idx))
|
||||
|
||||
@@ -12,12 +12,12 @@ import selfdrive.messaging as messaging
|
||||
def _create_nidec_can_parser():
|
||||
dbc_f = 'acura_ilx_2016_nidec.dbc'
|
||||
radar_messages = [0x400] + range(0x430, 0x43A) + range(0x440, 0x446)
|
||||
signals = zip(['RADAR_STATE'] +
|
||||
signals = list(zip(['RADAR_STATE'] +
|
||||
['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 +
|
||||
['REL_SPEED'] * 16,
|
||||
[0x400] + radar_messages[1:] * 4,
|
||||
[0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16)
|
||||
checks = zip([0x445], [20])
|
||||
[0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16))
|
||||
checks = list(zip([0x445], [20]))
|
||||
|
||||
return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1)
|
||||
|
||||
|
||||
@@ -13,7 +13,7 @@ def create_steering_control(packer, car_fingerprint, apply_steer, frame, steer_s
|
||||
|
||||
if car_fingerprint == CAR.IMPREZA:
|
||||
#counts from 0 to 15 then back to 0 + 16 for enable bit
|
||||
idx = ((frame / steer_step) % 16)
|
||||
idx = ((frame // steer_step) % 16)
|
||||
|
||||
values = {
|
||||
"Counter": idx,
|
||||
|
||||
@@ -226,11 +226,11 @@ class CarController(object):
|
||||
if (frame % 2 == 0) and (CS.CP.enableGasInterceptor):
|
||||
# send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas.
|
||||
# This prevents unexpected pedal range rescaling
|
||||
can_sends.append(create_gas_command(self.packer, apply_gas, frame/2))
|
||||
can_sends.append(create_gas_command(self.packer, apply_gas, frame//2))
|
||||
|
||||
if frame % 10 == 0 and ECU.CAM in self.fake_ecus and not forwarding_camera:
|
||||
for addr in TARGET_IDS:
|
||||
can_sends.append(create_video_target(frame/10, addr))
|
||||
can_sends.append(create_video_target(frame//10, addr))
|
||||
|
||||
# ui mesg is at 100Hz but we send asap if:
|
||||
# - there is something to display
|
||||
@@ -257,11 +257,11 @@ class CarController(object):
|
||||
if frame % fr_step == 0 and ecu in self.fake_ecus and self.car_fingerprint in cars and not (ecu == ECU.CAM and forwarding_camera):
|
||||
# special cases
|
||||
if fr_step == 5 and ecu == ECU.CAM and bus == 1:
|
||||
cnt = (((frame / 5) % 7) + 1) << 5
|
||||
cnt = (((frame // 5) % 7) + 1) << 5
|
||||
vl = chr(cnt) + vl
|
||||
elif addr in (0x489, 0x48a) and bus == 0:
|
||||
# add counter for those 2 messages (last 4 bits)
|
||||
cnt = ((frame/100)%0xf) + 1
|
||||
cnt = ((frame // 100) % 0xf) + 1
|
||||
if addr == 0x48a:
|
||||
# 0x48a has a 8 preceding the counter
|
||||
cnt += 1 << 7
|
||||
|
||||
@@ -19,12 +19,13 @@ def _create_radard_can_parser():
|
||||
msg_a_n = len(RADAR_A_MSGS)
|
||||
msg_b_n = len(RADAR_B_MSGS)
|
||||
|
||||
signals = zip(['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n +
|
||||
['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n,
|
||||
RADAR_A_MSGS * 5 + RADAR_B_MSGS,
|
||||
[255] * msg_a_n + [1] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_b_n)
|
||||
signals = list(zip(
|
||||
['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n +
|
||||
['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n,
|
||||
RADAR_A_MSGS * 5 + RADAR_B_MSGS,
|
||||
[255] * msg_a_n + [1] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_b_n))
|
||||
|
||||
checks = zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n))
|
||||
checks = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n)))
|
||||
|
||||
return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1)
|
||||
|
||||
|
||||
@@ -59,7 +59,7 @@ def compute_path_pinv(l=50):
|
||||
|
||||
|
||||
def model_polyfit(points, path_pinv):
|
||||
return np.dot(path_pinv, map(float, points))
|
||||
return np.dot(path_pinv, [float(x) for x in points])
|
||||
|
||||
|
||||
def calc_desired_path(l_poly,
|
||||
|
||||
@@ -106,12 +106,12 @@ class PathPlanner(object):
|
||||
plan_send = messaging.new_message()
|
||||
plan_send.init('pathPlan')
|
||||
plan_send.pathPlan.laneWidth = float(self.MP.lane_width)
|
||||
plan_send.pathPlan.dPoly = map(float, self.MP.d_poly)
|
||||
plan_send.pathPlan.cPoly = map(float, self.MP.c_poly)
|
||||
plan_send.pathPlan.dPoly = [float(x) for x in self.MP.d_poly]
|
||||
plan_send.pathPlan.cPoly = [float(x) for x in self.MP.c_poly]
|
||||
plan_send.pathPlan.cProb = float(self.MP.c_prob)
|
||||
plan_send.pathPlan.lPoly = map(float, l_poly)
|
||||
plan_send.pathPlan.lPoly = [float(x) for x in l_poly]
|
||||
plan_send.pathPlan.lProb = float(self.MP.l_prob)
|
||||
plan_send.pathPlan.rPoly = map(float, r_poly)
|
||||
plan_send.pathPlan.rPoly = [float(x) for x in r_poly]
|
||||
plan_send.pathPlan.rProb = float(self.MP.r_prob)
|
||||
plan_send.pathPlan.angleSteers = float(self.angle_steers_des_mpc)
|
||||
plan_send.pathPlan.rateSteers = float(rate_desired)
|
||||
|
||||
@@ -152,7 +152,7 @@ class Planner(object):
|
||||
|
||||
# Calculate speed for normal cruise control
|
||||
if enabled:
|
||||
accel_limits = map(float, calc_cruise_accel_limits(v_ego, following))
|
||||
accel_limits = [float(x) for x in calc_cruise_accel_limits(v_ego, following)]
|
||||
jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])] # TODO: make a separate lookup for jerk tuning
|
||||
accel_limits = limit_accel_in_turns(v_ego, CS.carState.steeringAngle, accel_limits, self.CP)
|
||||
|
||||
|
||||
@@ -226,7 +226,7 @@ def radard_thread(gctx=None):
|
||||
if VISION_POINT in ar_pts:
|
||||
print("vision", ar_pts[VISION_POINT])
|
||||
|
||||
idens = tracks.keys()
|
||||
idens = list(tracks.keys())
|
||||
track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens])
|
||||
|
||||
# If we have multiple points, cluster them
|
||||
|
||||
@@ -23,7 +23,7 @@ VP_INIT = np.array([W/2., H/2.])
|
||||
|
||||
# These validity corners were chosen by looking at 1000
|
||||
# and taking most extreme cases with some margin.
|
||||
VP_VALIDITY_CORNERS = np.array([[W/2 - 150, 280], [W/2 + 150, 540]])
|
||||
VP_VALIDITY_CORNERS = np.array([[W//2 - 150, 280], [W//2 + 150, 540]])
|
||||
DEBUG = os.getenv("DEBUG") is not None
|
||||
|
||||
|
||||
@@ -90,10 +90,10 @@ class Calibrator(object):
|
||||
cal_send = messaging.new_message()
|
||||
cal_send.init('liveCalibration')
|
||||
cal_send.liveCalibration.calStatus = self.cal_status
|
||||
cal_send.liveCalibration.calPerc = min(len(self.vps) * 100 / INPUTS_NEEDED, 100)
|
||||
cal_send.liveCalibration.warpMatrix2 = map(float, warp_matrix.flatten())
|
||||
cal_send.liveCalibration.warpMatrixBig = map(float, warp_matrix_big.flatten())
|
||||
cal_send.liveCalibration.extrinsicMatrix = map(float, extrinsic_matrix.flatten())
|
||||
cal_send.liveCalibration.calPerc = min(len(self.vps) * 100 // INPUTS_NEEDED, 100)
|
||||
cal_send.liveCalibration.warpMatrix2 = [float(x) for x in warp_matrix.flatten()]
|
||||
cal_send.liveCalibration.warpMatrixBig = [float(x) for x in warp_matrix_big.flatten()]
|
||||
cal_send.liveCalibration.extrinsicMatrix = [float(x) for x in extrinsic_matrix.flatten()]
|
||||
|
||||
livecalibration.send(cal_send.to_bytes())
|
||||
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
#!/usr/bin/env python
|
||||
import numpy as np
|
||||
import loc_local_model
|
||||
from selfdrive.locationd.kalman import loc_local_model
|
||||
|
||||
from kalman_helpers import ObservationKind
|
||||
from ekf_sym import EKF_sym
|
||||
from selfdrive.locationd.kalman.kalman_helpers import ObservationKind
|
||||
from selfdrive.locationd.kalman.ekf_sym import EKF_sym
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -2,8 +2,8 @@ import numpy as np
|
||||
import sympy as sp
|
||||
import os
|
||||
|
||||
from kalman_helpers import ObservationKind
|
||||
from ekf_sym import gen_code
|
||||
from selfdrive.locationd.kalman.kalman_helpers import ObservationKind
|
||||
from selfdrive.locationd.kalman.ekf_sym import gen_code
|
||||
|
||||
|
||||
def gen_model(name, dim_state):
|
||||
|
||||
@@ -5,8 +5,8 @@ import sys
|
||||
import argparse
|
||||
import tempfile
|
||||
|
||||
from ubloxd_py_test import parser_test
|
||||
from ubloxd_regression_test import compare_results
|
||||
from selfdrive.locationd.test.ubloxd_py_test import parser_test
|
||||
from selfdrive.locationd.test.ubloxd_regression_test import compare_results
|
||||
|
||||
|
||||
def mkdirs_exists_ok(path):
|
||||
|
||||
@@ -184,7 +184,7 @@ class UBloxAttrDict(dict):
|
||||
raise AttributeError(name)
|
||||
|
||||
def __setattr__(self, name, value):
|
||||
if self.__dict__.has_key(name):
|
||||
if name in self.__dict__:
|
||||
# allow set on normal attributes
|
||||
dict.__setattr__(self, name, value)
|
||||
else:
|
||||
@@ -256,7 +256,7 @@ class UBloxDescriptor:
|
||||
break
|
||||
|
||||
if self.count_field == '_remaining':
|
||||
count = len(buf) / struct.calcsize(self.format2)
|
||||
count = len(buf) // struct.calcsize(self.format2)
|
||||
|
||||
if count == 0:
|
||||
msg._unpacked = True
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python
|
||||
import os
|
||||
import serial
|
||||
import ublox
|
||||
from selfdrive.locationd.test import ublox
|
||||
import time
|
||||
import datetime
|
||||
import struct
|
||||
@@ -11,7 +11,7 @@ from common import realtime
|
||||
import zmq
|
||||
import selfdrive.messaging as messaging
|
||||
from selfdrive.services import service_list
|
||||
from ephemeris import EphemerisData, GET_FIELD_U
|
||||
from selfdrive.locationd.test.ephemeris import EphemerisData, GET_FIELD_U
|
||||
|
||||
panda = os.getenv("PANDA") is not None # panda directly connected
|
||||
grey = not (os.getenv("EVAL") is not None) # panda through boardd
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
#!/usr/bin/env python
|
||||
import os
|
||||
import ublox
|
||||
from selfdrive.locationd.test import ublox
|
||||
from common import realtime
|
||||
from ubloxd import gen_raw, gen_solution
|
||||
from selfdrive.locationd.test.ubloxd import gen_raw, gen_solution
|
||||
import zmq
|
||||
import selfdrive.messaging as messaging
|
||||
from selfdrive.services import service_list
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
import sys
|
||||
import os
|
||||
|
||||
from ublox import UBloxMessage
|
||||
from ubloxd import gen_solution, gen_raw, gen_nav_data
|
||||
from selfdrive.locationd.test.ublox import UBloxMessage
|
||||
from selfdrive.locationd.test.ubloxd import gen_solution, gen_raw, gen_nav_data
|
||||
from common import realtime
|
||||
|
||||
|
||||
|
||||
@@ -391,7 +391,7 @@ def update_apks():
|
||||
|
||||
cloudlog.info("installed apks %s" % (str(installed), ))
|
||||
|
||||
for app in installed.iterkeys():
|
||||
for app in installed.keys():
|
||||
|
||||
apk_path = os.path.join(BASEDIR, "apk/"+app+".apk")
|
||||
if not os.path.exists(apk_path):
|
||||
|
||||
@@ -205,7 +205,7 @@ class Country(Region):
|
||||
def jsonify(self):
|
||||
ret_dict = {}
|
||||
ret_dict[self.name] = {}
|
||||
for r_name, region in self.regions.iteritems():
|
||||
for r_name, region in self.regions.items():
|
||||
ret_dict[self.name].update(region.jsonify())
|
||||
ret_dict[self.name]['Default'] = self.rules
|
||||
return ret_dict
|
||||
|
||||
@@ -17,7 +17,7 @@ except ImportError as e:
|
||||
os.execv(sys.executable, args)
|
||||
|
||||
DEFAULT_SPEEDS_BY_REGION_JSON_FILE = BASEDIR + "/selfdrive/mapd/default_speeds_by_region.json"
|
||||
import default_speeds_generator
|
||||
from selfdrive.mapd import default_speeds_generator
|
||||
default_speeds_generator.main(DEFAULT_SPEEDS_BY_REGION_JSON_FILE)
|
||||
|
||||
import os
|
||||
@@ -33,7 +33,7 @@ from common.params import Params
|
||||
from common.transformations.coordinates import geodetic2ecef
|
||||
from selfdrive.services import service_list
|
||||
import selfdrive.messaging as messaging
|
||||
from mapd_helpers import MAPS_LOOKAHEAD_DISTANCE, Way, circle_through_points
|
||||
from selfdrive.mapd.mapd_helpers import MAPS_LOOKAHEAD_DISTANCE, Way, circle_through_points
|
||||
import selfdrive.crash as crash
|
||||
from selfdrive.version import version, dirty
|
||||
|
||||
@@ -176,7 +176,7 @@ def mapsd_thread():
|
||||
|
||||
xs = pnts[:, 0]
|
||||
ys = pnts[:, 1]
|
||||
road_points = map(float, xs), map(float, ys)
|
||||
road_points = [float(x) for x in xs], [float(y) for y in ys]
|
||||
|
||||
if speed < 10:
|
||||
curvature_valid = False
|
||||
@@ -266,8 +266,8 @@ def mapsd_thread():
|
||||
if road_points is not None:
|
||||
dat.liveMapData.roadX, dat.liveMapData.roadY = road_points
|
||||
if curvature is not None:
|
||||
dat.liveMapData.roadCurvatureX = map(float, dists)
|
||||
dat.liveMapData.roadCurvature = map(float, curvature)
|
||||
dat.liveMapData.roadCurvatureX = [float(x) for x in dists]
|
||||
dat.liveMapData.roadCurvature = [float(x) for x in curvature]
|
||||
|
||||
dat.liveMapData.mapValid = map_valid
|
||||
|
||||
|
||||
@@ -91,7 +91,7 @@ def geocode_maxspeed(tags, location_info):
|
||||
rule_valid = all(
|
||||
tag_name in tags
|
||||
and tags[tag_name] == value
|
||||
for tag_name, value in rule['tags'].iteritems()
|
||||
for tag_name, value in rule['tags'].items()
|
||||
)
|
||||
if rule_valid:
|
||||
max_speed = rule['speed']
|
||||
@@ -102,7 +102,7 @@ def geocode_maxspeed(tags, location_info):
|
||||
rule_valid = all(
|
||||
tag_name in tags
|
||||
and tags[tag_name] == value
|
||||
for tag_name, value in rule['tags'].iteritems()
|
||||
for tag_name, value in rule['tags'].items()
|
||||
)
|
||||
if rule_valid:
|
||||
max_speed = rule['speed']
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
from maneuverplots import ManeuverPlot
|
||||
from plant import Plant
|
||||
from selfdrive.test.plant.maneuverplots import ManeuverPlot
|
||||
from selfdrive.test.plant.plant import Plant
|
||||
import numpy as np
|
||||
|
||||
|
||||
|
||||
@@ -207,7 +207,7 @@ class Plant(object):
|
||||
lateral_pos_rel = 0.
|
||||
|
||||
# print at 5hz
|
||||
if (self.rk.frame%(self.rate/5)) == 0:
|
||||
if (self.rk.frame % (self.rate//5)) == 0:
|
||||
print("%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel))
|
||||
|
||||
# ******** publish the car ********
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
#!/usr/bin/env python
|
||||
import pygame # pylint: disable=import-error
|
||||
from plant import Plant
|
||||
from selfdrive.test.plant.plant import Plant
|
||||
from selfdrive.car.honda.values import CruiseButtons
|
||||
import numpy as np
|
||||
import selfdrive.messaging as messaging
|
||||
@@ -41,7 +41,7 @@ if __name__ == "__main__":
|
||||
plant = Plant(100, distance_lead = 40.0)
|
||||
|
||||
control_offset = 2.0
|
||||
control_pts = zip(np.arange(0, 100.0, 10.0), [50.0 + control_offset]*10)
|
||||
control_pts = list(zip(np.arange(0, 100.0, 10.0), [50.0 + control_offset]*10))
|
||||
|
||||
def pt_to_car(pt):
|
||||
x,y = pt
|
||||
@@ -73,7 +73,7 @@ if __name__ == "__main__":
|
||||
x.prob = 0.0
|
||||
x.std = 1.0
|
||||
|
||||
car_pts = map(pt_to_car, control_pts)
|
||||
car_pts = [pt_to_car(pt) for pt in control_pts]
|
||||
|
||||
print(car_pts)
|
||||
|
||||
|
||||
@@ -10,15 +10,15 @@ NICE_LOW_PRIORITY = ["nice", "-n", "19"]
|
||||
def main(gctx=None):
|
||||
while True:
|
||||
# try network
|
||||
r = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"])
|
||||
if r:
|
||||
ping_failed = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"])
|
||||
if ping_failed:
|
||||
time.sleep(60)
|
||||
continue
|
||||
|
||||
# download application update
|
||||
try:
|
||||
r = subprocess.check_output(NICE_LOW_PRIORITY + ["git", "fetch"], stderr=subprocess.STDOUT)
|
||||
except subprocess.CalledProcessError, e:
|
||||
except subprocess.CalledProcessError as e:
|
||||
cloudlog.event("git fetch failed",
|
||||
cmd=e.cmd,
|
||||
output=e.output,
|
||||
|
||||
Reference in New Issue
Block a user