Merge remote-tracking branch 'upstream/master' into take-steering

pull/26010/head
Shane Smiskol 3 years ago
commit 0bdcc57a36
  1. 2
      cereal
  2. 11
      common/params.cc
  3. 17
      common/tests/test_util.cc
  4. 16
      common/util.cc
  5. 1
      common/util.h
  6. 2
      laika_repo
  7. 13
      selfdrive/car/gm/carstate.py
  8. 16
      selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
  9. 42
      selfdrive/controls/lib/lateral_planner.py
  10. 4
      selfdrive/debug/vw_mqb_config.py
  11. 52
      selfdrive/locationd/laikad.py
  12. 2
      selfdrive/modeld/models/driving.h
  13. 4
      selfdrive/modeld/models/supercombo.onnx
  14. 34
      selfdrive/sensord/rawgps/rawgpsd.py
  15. 41
      selfdrive/sensord/rawgps/structs.py
  16. 2
      selfdrive/sensord/rawgps/test_rawgps.py
  17. 2
      selfdrive/test/process_replay/model_replay_ref_commit
  18. 2
      selfdrive/test/process_replay/ref_commit
  19. 43
      selfdrive/tombstoned.py
  20. 2
      system/hardware/tici/hardware.py
  21. 2
      tinygrad_repo
  22. 0
      tools/cabana/README.md
  23. 46
      tools/cabana/videowidget.cc
  24. 5
      tools/cabana/videowidget.h

@ -1 +1 @@
Subproject commit 5ba96b6ded57bcd91e60140ce0036f61370f8512
Subproject commit b29717c4c328d5cf34d46f682f25267150f82637

@ -299,10 +299,13 @@ std::map<std::string, std::string> Params::readAll() {
void Params::clearAll(ParamKeyType key_type) {
FileLock file_lock(params_path + "/.lock");
std::string path;
for (auto &[key, type] : keys) {
if (type & key_type) {
unlink(getParamPath(key).c_str());
if (key_type == ALL) {
util::remove_files_in_dir(getParamPath());
} else {
for (auto &[key, type] : keys) {
if (type & key_type) {
unlink(getParamPath(key).c_str());
}
}
}

@ -143,3 +143,20 @@ TEST_CASE("util::create_directories") {
REQUIRE(util::create_directories("", 0755) == false);
}
}
TEST_CASE("util::remove_files_in_dir") {
std::string tmp_dir = "/tmp/test_remove_all_in_dir";
system("rm /tmp/test_remove_all_in_dir -rf");
REQUIRE(util::create_directories(tmp_dir, 0755));
const int tmp_file_cnt = 10;
for (int i = 0; i < tmp_file_cnt; ++i) {
std::string tmp_file = tmp_dir + "/test_XXXXXX";
int fd = mkstemp((char*)tmp_file.c_str());
close(fd);
REQUIRE(util::file_exists(tmp_file.c_str()));
}
REQUIRE(util::read_files_in_dir(tmp_dir).size() == tmp_file_cnt);
util::remove_files_in_dir(tmp_dir);
REQUIRE(util::read_files_in_dir(tmp_dir).empty());
}

@ -97,6 +97,22 @@ std::map<std::string, std::string> read_files_in_dir(const std::string &path) {
return ret;
}
void remove_files_in_dir(const std::string &path) {
DIR *d = opendir(path.c_str());
if (!d) return;
std::string fn;
struct dirent *de = NULL;
while ((de = readdir(d))) {
if (de->d_type != DT_DIR) {
fn = path + "/" + de->d_name;
unlink(fn.c_str());
}
}
closedir(d);
}
int write_file(const char* path, const void* data, size_t size, int flags, mode_t mode) {
int fd = HANDLE_EINTR(open(path, flags, mode));
if (fd == -1) {

@ -80,6 +80,7 @@ std::string dir_name(std::string const& path);
// **** file fhelpers *****
std::string read_file(const std::string& fn);
std::map<std::string, std::string> read_files_in_dir(const std::string& path);
void remove_files_in_dir(const std::string& path);
int write_file(const char* path, const void* data, size_t size, int flags = O_WRONLY, mode_t mode = 0664);
FILE* safe_fopen(const char* filename, const char* mode);

@ -1 +1 @@
Subproject commit c8bc1fa01be9f22592efb991ee52d3d965d21968
Subproject commit e1049cde0a68f7d4a70b1ebd76befdc0e163ad55

@ -41,9 +41,12 @@ class CarState(CarStateBase):
else:
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None))
# Brake pedal's potentiometer returns near-zero reading even when pedal is not pressed.
ret.brake = pt_cp.vl["EBCMBrakePedalPosition"]["BrakePedalPosition"] / 0xd0
ret.brakePressed = pt_cp.vl["EBCMBrakePedalPosition"]["BrakePedalPosition"] >= 10
# Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe
# that the brake is being intermittently pressed without user interaction.
# To avoid a cruise fault we need to match the ECM's brake pressed signal and threshold
# https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf
ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] / 0xd0
ret.brakePressed = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] >= 8
# Regen braking is braking
if self.CP.transmissionType == TransmissionType.direct:
@ -102,7 +105,7 @@ class CarState(CarStateBase):
def get_can_parser(CP):
signals = [
# sig_name, sig_address
("BrakePedalPosition", "EBCMBrakePedalPosition"),
("BrakePedalPos", "ECMAcceleratorPos"),
("FrontLeftDoor", "BCMDoorBeltStatus"),
("FrontRightDoor", "BCMDoorBeltStatus"),
("RearLeftDoor", "BCMDoorBeltStatus"),
@ -148,7 +151,7 @@ class CarState(CarStateBase):
("ASCMSteeringButton", 33),
("ECMEngineStatus", 100),
("PSCMSteeringAngle", 100),
("EBCMBrakePedalPosition", 100),
("ECMAcceleratorPos", 80),
]
if CP.transmissionType == TransmissionType.direct:

@ -20,6 +20,7 @@ P_DIM = 2
N = 16
COST_E_DIM = 3
COST_DIM = COST_E_DIM + 1
SPEED_OFFSET = 10.0
MODEL_NAME = 'lat'
ACADOS_SOLVER_TYPE = 'SQP_RTI'
@ -88,14 +89,13 @@ def gen_lat_ocp():
ocp.cost.yref = np.zeros((COST_DIM, ))
ocp.cost.yref_e = np.zeros((COST_E_DIM, ))
# TODO hacky weights to keep behavior the same
ocp.model.cost_y_expr = vertcat(y_ego,
((v_ego + 5.0) * psi_ego),
((v_ego + 5.0) * psi_rate_ego),
((v_ego + 5.0) * psi_rate_ego_dot))
((v_ego + SPEED_OFFSET) * psi_ego),
((v_ego + SPEED_OFFSET) * psi_rate_ego),
((v_ego + SPEED_OFFSET) * psi_rate_ego_dot))
ocp.model.cost_y_expr_e = vertcat(y_ego,
((v_ego + 5.0) * psi_ego),
((v_ego + 5.0) * psi_rate_ego))
((v_ego + SPEED_OFFSET) * psi_ego),
((v_ego + SPEED_OFFSET) * psi_rate_ego))
# set constraints
ocp.constraints.constr_type = 'BGH'
@ -158,8 +158,8 @@ class LateralMpc():
self.yref[:,0] = y_pts
v_ego = p_cp[0]
# rotation_radius = p_cp[1]
self.yref[:,1] = heading_pts * (v_ego+5.0)
self.yref[:,2] = yaw_rate_pts * (v_ego+5.0)
self.yref[:,1] = heading_pts * (v_ego + SPEED_OFFSET)
self.yref[:,2] = yaw_rate_pts * (v_ego + SPEED_OFFSET)
for i in range(N):
self.solver.cost_set(i, "yref", self.yref[i])
self.solver.set(i, "p", p_cp)

@ -12,6 +12,15 @@ from cereal import log
TRAJECTORY_SIZE = 33
CAMERA_OFFSET = 0.04
PATH_COST = 1.0
LATERAL_MOTION_COST = 0.11
LATERAL_ACCEL_COST = 0.0
LATERAL_JERK_COST = 0.05
MIN_SPEED = 1.5
class LateralPlanner:
def __init__(self, CP):
self.DH = DesireHelper()
@ -36,7 +45,8 @@ class LateralPlanner:
self.lat_mpc.reset(x0=self.x0)
def update(self, sm):
v_ego = sm['carState'].vEgo
# clip speed , lateral planning is not possible at 0 speed
self.v_ego = max(MIN_SPEED, sm['carState'].vEgo)
measured_curvature = sm['controlsState'].curvature
# Parse model predictions
@ -56,29 +66,28 @@ class LateralPlanner:
self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob)
d_path_xyz = self.path_xyz
# Heading cost is useful at low speed, otherwise end of plan can be off-heading
heading_cost = interp(v_ego, [5.0, 10.0], [1.0, 0.15])
self.lat_mpc.set_weights(1.0, heading_cost, 0.0, .075)
self.lat_mpc.set_weights(PATH_COST, LATERAL_MOTION_COST,
LATERAL_ACCEL_COST, LATERAL_JERK_COST)
y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1])
heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw)
yaw_rate_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw_rate)
y_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1])
heading_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw)
yaw_rate_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw_rate)
self.y_pts = y_pts
assert len(y_pts) == LAT_MPC_N + 1
assert len(heading_pts) == LAT_MPC_N + 1
assert len(yaw_rate_pts) == LAT_MPC_N + 1
lateral_factor = max(0, self.factor1 - (self.factor2 * v_ego**2))
p = np.array([v_ego, lateral_factor])
lateral_factor = max(0, self.factor1 - (self.factor2 * self.v_ego**2))
p = np.array([self.v_ego, lateral_factor])
self.lat_mpc.run(self.x0,
p,
y_pts,
heading_pts,
yaw_rate_pts)
# init state for next
# mpc.u_sol is the desired curvature rate given x0 curv state.
# with x0[3] = measured_curvature, this would be the actual desired rate.
# instead, interpolate x_sol so that x0[3] is the desired curvature for lat_control.
# init state for next iteration
# mpc.u_sol is the desired second derivative of psi given x0 curv state.
# with x0[3] = measured_yaw_rate, this would be the actual desired yaw rate.
# instead, interpolate x_sol so that x0[3] is the desired yaw rate for lat_control.
self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3])
# Check for infeasible MPC solution
@ -86,7 +95,7 @@ class LateralPlanner:
t = sec_since_boot()
if mpc_nans or self.lat_mpc.solution_status != 0:
self.reset_mpc()
self.x0[3] = measured_curvature
self.x0[3] = measured_curvature * self.v_ego
if t > self.last_cloudlog_t + 5.0:
self.last_cloudlog_t = t
cloudlog.warning("Lateral mpc - nan: True")
@ -105,8 +114,9 @@ class LateralPlanner:
lateralPlan.modelMonoTime = sm.logMonoTime['modelV2']
lateralPlan.dPathPoints = self.y_pts.tolist()
lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist()
lateralPlan.curvatures = (self.lat_mpc.x_sol[0:CONTROL_N, 3]/sm['carState'].vEgo).tolist()
lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0]
lateralPlan.curvatures = (self.lat_mpc.x_sol[0:CONTROL_N, 3]/self.v_ego).tolist()
lateralPlan.curvatureRates = [float(x/self.v_ego) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0]
lateralPlan.mpcSolutionValid = bool(plan_solution_valid)
lateralPlan.solverExecutionTime = self.lat_mpc.solve_time

@ -70,8 +70,8 @@ if __name__ == "__main__":
coding_variant, current_coding_array, coding_byte, coding_bit = None, None, 0, 0
coding_length = len(current_coding)
# EV_SteerAssisMQB covers the majority of MQB racks (EPS_MQB_ZFLS)
if odx_file == "EV_SteerAssisMQB\x00":
# EV_SteerAssisMQB/MNB cover the majority of MQB racks (EPS_MQB_ZFLS)
if odx_file in ("EV_SteerAssisMQB\x00", "EV_SteerAssisMNB\x00"):
coding_variant = "ZF"
coding_byte = 0
coding_bit = 4

@ -16,7 +16,7 @@ from common.params import Params, put_nonblocking
from laika import AstroDog
from laika.constants import SECS_IN_HR, SECS_IN_MIN
from laika.downloader import DownloadFailed
from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem
from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem, parse_qcom_ephem
from laika.gps_time import GPSTime
from laika.helpers import ConstellationId
from laika.raw_gnss import GNSSMeasurement, correct_measurements, process_measurements, read_raw_ublox, read_raw_qcom
@ -61,6 +61,7 @@ class Laikad:
self.last_pos_fix = []
self.last_pos_residual = []
self.last_pos_fix_t = None
self.gps_week = None
self.use_qcom = use_qcom
def load_cache(self):
@ -107,11 +108,11 @@ class Laikad:
return self.last_pos_fix
def is_good_report(self, gnss_msg):
if gnss_msg.which == 'drMeasurementReport' and self.use_qcom:
if gnss_msg.which() == 'drMeasurementReport' and self.use_qcom:
constellation_id = ConstellationId.from_qcom_source(gnss_msg.drMeasurementReport.source)
# TODO support GLONASS
return constellation_id in [ConstellationId.GPS, ConstellationId.SBAS]
elif gnss_msg.which == 'measurementReport' and not self.use_qcom:
elif gnss_msg.which() == 'measurementReport' and not self.use_qcom:
return True
else:
return False
@ -129,9 +130,28 @@ class Laikad:
new_meas = read_raw_ublox(report)
return week, tow, new_meas
def is_ephemeris(self, gnss_msg):
if self.use_qcom:
return gnss_msg.which() == 'drSvPoly'
else:
return gnss_msg.which() == 'ephemeris'
def read_ephemeris(self, gnss_msg):
# TODO this only works on GLONASS
if self.use_qcom:
# TODO this is not robust to gps week rollover
if self.gps_week is None:
return
ephem = parse_qcom_ephem(gnss_msg.drSvPoly, self.gps_week)
else:
ephem = convert_ublox_ephem(gnss_msg.ephemeris)
self.astro_dog.add_navs({ephem.prn: [ephem]})
self.cache_ephemeris(t=ephem.epoch)
def process_gnss_msg(self, gnss_msg, gnss_mono_time: int, block=False):
if self.is_good_report(gnss_msg):
week, tow, new_meas = self.read_report(gnss_msg)
self.gps_week = week
t = gnss_mono_time * 1e-9
if week > 0:
@ -172,12 +192,10 @@ class Laikad:
"correctedMeasurements": meas_msgs
}
return dat
# TODO this only works on GLONASS, qcom needs live ephemeris parsing too
elif gnss_msg.which == 'ephemeris':
ephem = convert_ublox_ephem(gnss_msg.ephemeris)
self.astro_dog.add_navs({ephem.prn: [ephem]})
self.cache_ephemeris(t=ephem.epoch)
#elif gnss_msg.which == 'ionoData':
elif self.is_ephemeris(gnss_msg):
self.read_ephemeris(gnss_msg)
#elif gnss_msg.which() == 'ionoData':
# todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them.
def update_localizer(self, est_pos, t: float, measurements: List[GNSSMeasurement]):
@ -265,9 +283,11 @@ def create_measurement_msg(meas: GNSSMeasurement):
c.satVel = meas.sat_vel.tolist()
ephem = meas.sat_ephemeris
assert ephem is not None
week, time_of_week = -1, -1
if ephem.eph_type == EphemerisType.NAV:
source_type = EphemerisSourceType.nav
week, time_of_week = -1, -1
elif ephem.eph_type == EphemerisType.QCOM_POLY:
source_type = EphemerisSourceType.qcom
else:
assert ephem.file_epoch is not None
week = ephem.file_epoch.week
@ -325,6 +345,7 @@ class EphemerisSourceType(IntEnum):
nav = 0
nasaUltraRapid = 1
glonassIacUltraRapid = 2
qcom = 3
def main(sm=None, pm=None):
@ -348,6 +369,17 @@ def main(sm=None, pm=None):
if sm.updated[raw_gnss_socket]:
gnss_msg = sm[raw_gnss_socket]
# TODO: Understand and use remaining unknown constellations
if gnss_msg.which() == "drMeasurementReport":
if getattr(gnss_msg, gnss_msg.which()).source not in ['glonass', 'gps', 'beidou', 'sbas']:
continue
if getattr(gnss_msg, gnss_msg.which()).gpsWeek > np.iinfo(np.int16).max:
# gpsWeek 65535 is received rarely from quectel, this cannot be
# passed to GnssMeasurements's gpsWeek (Int16)
continue
msg = laikad.process_gnss_msg(gnss_msg, sm.logMonoTime[raw_gnss_socket], block=replay)
if msg is not None:
pm.send('gnssMeasurements', msg)

@ -16,7 +16,7 @@
#include "selfdrive/modeld/models/commonmodel.h"
#include "selfdrive/modeld/runners/run.h"
constexpr int FEATURE_LEN = 2048;
constexpr int FEATURE_LEN = 128;
constexpr int HISTORY_BUFFER_LEN = 99;
constexpr int DESIRE_LEN = 8;
constexpr int DESIRE_PRED_LEN = 4;

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:30f30bc1251c03db135564ecbf7dc0bc96cbb07be0ebd3691edd8d555dc087fa
size 58539693
oid sha256:c4d37af666344af6bb218e0b939b1152ad3784c15ac79e37bcf0124643c8286a
size 58539563

@ -14,12 +14,13 @@ import cereal.messaging as messaging
from laika.gps_time import GPSTime
from system.swaglog import cloudlog
from selfdrive.sensord.rawgps.modemdiag import ModemDiag, DIAG_LOG_F, setup_logs, send_recv
from selfdrive.sensord.rawgps.structs import (dict_unpacker, position_report,
from selfdrive.sensord.rawgps.structs import (dict_unpacker, position_report, relist,
gps_measurement_report, gps_measurement_report_sv,
glonass_measurement_report, glonass_measurement_report_sv,
oemdre_measurement_report, oemdre_measurement_report_sv,
oemdre_measurement_report, oemdre_measurement_report_sv, oemdre_svpoly_report,
LOG_GNSS_GPS_MEASUREMENT_REPORT, LOG_GNSS_GLONASS_MEASUREMENT_REPORT,
LOG_GNSS_POSITION_REPORT, LOG_GNSS_OEMDRE_MEASUREMENT_REPORT)
LOG_GNSS_POSITION_REPORT, LOG_GNSS_OEMDRE_MEASUREMENT_REPORT,
LOG_GNSS_OEMDRE_SVPOLY_REPORT)
DEBUG = int(os.getenv("DEBUG", "0"))==1
@ -28,6 +29,7 @@ LOG_TYPES = [
LOG_GNSS_GLONASS_MEASUREMENT_REPORT,
LOG_GNSS_OEMDRE_MEASUREMENT_REPORT,
LOG_GNSS_POSITION_REPORT,
LOG_GNSS_OEMDRE_SVPOLY_REPORT,
]
@ -88,7 +90,7 @@ def try_setup_logs(diag, log_types):
def mmcli(cmd: str) -> None:
for _ in range(5):
try:
subprocess.check_call(f"mmcli -m 0 {cmd}", shell=True)
subprocess.check_call(f"mmcli -m any --timeout 30 {cmd}", shell=True)
break
except subprocess.CalledProcessError:
cloudlog.exception("rawgps.mmcli_command_failed")
@ -146,12 +148,15 @@ def main() -> NoReturn:
unpack_oemdre_meas, size_oemdre_meas = dict_unpacker(oemdre_measurement_report, True)
unpack_oemdre_meas_sv, size_oemdre_meas_sv = dict_unpacker(oemdre_measurement_report_sv, True)
unpack_svpoly, _ = dict_unpacker(oemdre_svpoly_report, True)
unpack_position, _ = dict_unpacker(position_report)
unpack_position, _ = dict_unpacker(position_report)
# wait for ModemManager to come up
cloudlog.warning("waiting for modem to come up")
while True:
ret = subprocess.call("mmcli -m 0 --location-status", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True)
ret = subprocess.call("mmcli -m any --timeout 10 --location-status", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True)
if ret == 0:
break
time.sleep(0.1)
@ -258,7 +263,24 @@ def main() -> NoReturn:
pm.send('gpsLocation', msg)
if log_type in [LOG_GNSS_GPS_MEASUREMENT_REPORT, LOG_GNSS_GLONASS_MEASUREMENT_REPORT]:
elif log_type == LOG_GNSS_OEMDRE_SVPOLY_REPORT:
msg = messaging.new_message('qcomGnss')
dat = unpack_svpoly(log_payload)
dat = relist(dat)
gnss = msg.qcomGnss
gnss.logTs = log_time
gnss.init('drSvPoly')
poly = gnss.drSvPoly
for k,v in dat.items():
if k == "version":
assert v == 2
elif k == "flags":
pass
else:
setattr(poly, k, v)
pm.send('qcomGnss', msg)
elif log_type in [LOG_GNSS_GPS_MEASUREMENT_REPORT, LOG_GNSS_GLONASS_MEASUREMENT_REPORT]:
msg = messaging.new_message('qcomGnss')
gnss = msg.qcomGnss

@ -56,6 +56,29 @@ oemdre_measurement_report = """
uint8_t source;
"""
oemdre_svpoly_report = """
uint8_t version;
uint16_t sv_id;
int8_t frequency_index;
uint8_t flags;
uint16_t iode;
double t0;
double xyz0[3];
double xyzN[9];
float other[4];
float position_uncertainty;
float iono_delay;
float iono_dot;
float sbas_iono_delay;
float sbas_iono_dot;
float tropo_delay;
float elevation;
float elevation_dot;
float elevation_uncertainty;
double velocity_coeff[12];
"""
oemdre_measurement_report_sv = """
uint8_t sv_id;
uint8_t unkn;
@ -311,3 +334,21 @@ def dict_unpacker(ss, camelcase = False):
nams = [name_to_camelcase(x) for x in nams]
sz = calcsize(st)
return lambda x: dict(zip(nams, unpack_from(st, x))), sz
def relist(dat):
list_keys = set()
for key in dat.keys():
if '[' in key:
list_keys.add(key.split('[')[0])
list_dict = {}
for list_key in list_keys:
list_dict[list_key] = []
i = 0
while True:
key = list_key + f'[{i}]'
if key not in dat:
break
list_dict[list_key].append(dat[key])
del dat[key]
i += 1
return {**dat, **list_dict}

@ -40,7 +40,7 @@ class TestRawgpsd(unittest.TestCase):
time.sleep(s)
managed_processes['rawgpsd'].stop()
ls = subprocess.check_output("mmcli -m 0 --location-status --output-json", shell=True, encoding='utf-8')
ls = subprocess.check_output("mmcli -m any --location-status --output-json", shell=True, encoding='utf-8')
loc_status = json.loads(ls)
assert set(loc_status['modem']['location']['enabled']) <= {'3gpp-lac-ci'}

@ -1 +1 @@
008c0a622b7471c6234690d668f76bcb5dc8d999
c171250d2cc013b3eca1cda4fb62f3d0dda28d4d

@ -1 +1 @@
e0ffcae8def2fd9c82c547d1f257d4f06a48a3c3
f636c68e2b4ed88d3731930cf15b6dee984eb6dd

@ -62,47 +62,6 @@ def get_tombstones():
return files
def report_tombstone_android(fn):
f_size = os.path.getsize(fn)
if f_size > MAX_SIZE:
cloudlog.error(f"Tombstone {fn} too big, {f_size}. Skipping...")
return
with open(fn, encoding='ISO-8859-1') as f:
contents = f.read()
message = " ".join(contents.split('\n')[5:7])
# Cut off pid/tid, since that varies per run
name_idx = message.find('name')
if name_idx >= 0:
message = message[name_idx:]
executable = ""
start_exe_idx = message.find('>>> ')
end_exe_idx = message.find(' <<<')
if start_exe_idx >= 0 and end_exe_idx >= 0:
executable = message[start_exe_idx + 4:end_exe_idx]
# Cut off fault addr
fault_idx = message.find(', fault addr')
if fault_idx >= 0:
message = message[:fault_idx]
sentry.report_tombstone(fn, message, contents)
# Copy crashlog to upload folder
clean_path = executable.replace('./', '').replace('/', '_')
date = datetime.datetime.now().strftime("%Y-%m-%d--%H-%M-%S")
new_fn = f"{date}_{get_commit(default='nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN]
crashlog_dir = os.path.join(ROOT, "crash")
mkdirs_exists_ok(crashlog_dir)
shutil.copy(fn, os.path.join(crashlog_dir, new_fn))
def report_tombstone_apport(fn):
f_size = os.path.getsize(fn)
if f_size > MAX_SIZE:
@ -199,7 +158,7 @@ def main() -> NoReturn:
if fn.endswith(".crash"):
report_tombstone_apport(fn)
else:
report_tombstone_android(fn)
cloudlog.error(f"unknown crash type: {fn}")
except Exception:
cloudlog.exception(f"Error reporting tombstone {fn}")

@ -480,7 +480,7 @@ class Tici(HardwareBase):
# blue prime config
if sim_id.startswith('8901410'):
os.system('mmcli -m 0 --3gpp-set-initial-eps-bearer-settings="apn=Broadband"')
os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn=Broadband"')
def get_networks(self):
r = {}

@ -1 +1 @@
Subproject commit 2993dfe9219089bd1464741757f0c2ad67fe6a2e
Subproject commit 46f6db75228cb7744a3a0a87616bfffeffa93658

@ -4,7 +4,9 @@
#include <QDateTime>
#include <QHBoxLayout>
#include <QMouseEvent>
#include <QPainter>
#include <QPushButton>
#include <QTimer>
#include <QVBoxLayout>
#include "tools/cabana/parser.h"
@ -98,8 +100,50 @@ void VideoWidget::updateState() {
}
// Slider
// TODO: show timeline bar like what replay did.
Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) {
QTimer *timer = new QTimer(this);
timer->setInterval(2000);
timer->callOnTimeout([this]() { timeline = parser->replay->getTimeline(); });
timer->start();
}
void Slider::paintEvent(QPaintEvent *ev) {
auto getPaintRange = [this](double begin, double end) -> std::pair<double, double> {
double total_sec = maximum() - minimum();
int start_pos = ((std::max((double)minimum(), (double)begin) - minimum()) / total_sec) * width();
int end_pos = ((std::min((double)maximum(), (double)end) - minimum()) / total_sec) * width();
return {start_pos, end_pos};
};
QPainter p(this);
const int v_margin = 2;
p.fillRect(rect().adjusted(0, v_margin, 0, -v_margin), QColor(0, 0, 128));
for (auto [begin, end, type] : timeline) {
if (begin > maximum() || end < minimum()) continue;
if (type == TimelineType::Engaged) {
auto [start_pos, end_pos] = getPaintRange(begin, end);
p.fillRect(QRect(start_pos, v_margin, end_pos - start_pos, height() - v_margin * 2), QColor(0, 135, 0));
}
}
for (auto [begin, end, type] : timeline) {
if (type == TimelineType::Engaged || begin > maximum() || end < minimum()) continue;
auto [start_pos, end_pos] = getPaintRange(begin, end);
if (type == TimelineType::UserFlag) {
p.fillRect(QRect(start_pos, height() - v_margin - 3, end_pos - start_pos, 3), Qt::white);
} else {
QColor color(Qt::green);
if (type != TimelineType::AlertInfo)
color = type == TimelineType::AlertWarning ? Qt::yellow : Qt::red;
p.fillRect(QRect(start_pos, height() - v_margin - 3, end_pos - start_pos, 3), color);
}
}
p.setPen(QPen(Qt::black, 2));
qreal x = width() * ((value() - minimum()) / double(maximum() - minimum()));
p.drawLine(QPointF{x, 0.}, QPointF{x, (qreal)height()});
}
void Slider::mousePressEvent(QMouseEvent *e) {

@ -5,6 +5,7 @@
#include <QWidget>
#include "selfdrive/ui/qt/widgets/cameraview.h"
#include "tools/replay/replay.h"
class Slider : public QSlider {
Q_OBJECT
@ -15,6 +16,10 @@ public:
signals:
void setPosition(int value);
private:
void paintEvent(QPaintEvent *ev) override;
std::vector<std::tuple<int, int, TimelineType>> timeline;
};
class VideoWidget : public QWidget {

Loading…
Cancel
Save