pre-commit: add codespell (#25571)

old-commit-hash: 6590fb2b93
taco
Adeeb Shihadeh 3 years ago committed by GitHub
parent 8f468a01fa
commit 35ff65121e
  1. 2
      .github/PULL_REQUEST_TEMPLATE/car_bugfix.md
  2. 9
      .pre-commit-config.yaml
  3. 2
      README.md
  4. 6
      RELEASES.md
  5. 2
      SConstruct
  6. 2
      cereal
  7. 2
      common/tests/test_util.cc
  8. 2
      opendbc
  9. 2
      panda
  10. 4
      selfdrive/boardd/boardd.cc
  11. 2
      selfdrive/car/car_helpers.py
  12. 2
      selfdrive/car/tests/test_fingerprints.py
  13. 2
      selfdrive/car/tests/test_models.py
  14. 2
      selfdrive/controls/lib/tests/test_vehicle_model.py
  15. 2
      selfdrive/controls/tests/test_alerts.py
  16. 2
      selfdrive/debug/README.md
  17. 4
      selfdrive/debug/cpu_usage_stat.py
  18. 2
      selfdrive/debug/hyundai_enable_radar_points.py
  19. 2
      selfdrive/debug/internal/power_monitor.py
  20. 2
      selfdrive/debug/test_fw_query_on_routes.py
  21. 6
      selfdrive/locationd/locationd.cc
  22. 2
      selfdrive/locationd/models/loc_kf.py
  23. 2
      selfdrive/locationd/test/ubloxd.py
  24. 2
      selfdrive/loggerd/logger.cc
  25. 2
      selfdrive/loggerd/tests/test_logger.cc
  26. 2
      selfdrive/loggerd/tests/test_loggerd.py
  27. 2
      selfdrive/manager/helpers.py
  28. 2
      selfdrive/modeld/transforms/transform.cc
  29. 8
      selfdrive/navd/navd.py
  30. 2
      selfdrive/sensord/sensors/lsm6ds3_accel.cc
  31. 2
      selfdrive/test/process_replay/model_replay.py
  32. 2
      selfdrive/ui/SConscript
  33. 2
      selfdrive/ui/installer/installer.cc
  34. 8
      system/camerad/cameras/camera_qcom2.cc
  35. 4
      system/hardware/tici/agnos.py
  36. 2
      system/hardware/tici/hardware.py
  37. 2
      system/proclogd/proclog.cc
  38. 4
      tools/README.md
  39. 2
      tools/camerastream/compressed_vipc.py
  40. 4
      tools/latencylogger/latency_logger.py
  41. 2
      tools/lib/README.md
  42. 4
      tools/lib/tests/test_readers.py
  43. 4
      tools/plotjuggler/juggle.py
  44. 4
      tools/plotjuggler/layouts/max-torque-debug.xml
  45. 2
      tools/replay/framereader.cc
  46. 2
      tools/replay/replay.cc
  47. 2
      tools/replay/replay.h
  48. 2
      tools/sim/bridge.py

@ -1,6 +1,6 @@
---
name: Car Bug fix
about: For vehicle/brand specifc bug fixes
about: For vehicle/brand specific bug fixes
title: ''
labels: 'car bug fix'
assignees: ''

@ -15,6 +15,15 @@ repos:
- id: check-symlinks
- id: check-added-large-files
args: ['--maxkb=100']
- repo: https://github.com/codespell-project/codespell
rev: v2.2.1
hooks:
- id: codespell
exclude: '^(pyextra/)|(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(include/)|(selfdrive/ui/translations/.*.ts)|(selfdrive/controls/lib/cluster)'
args:
# if you've got a short variable name that's getting flagged, add it here
- -L bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup
- --builtins clear,rare,informal,usage,code,names,en-GB_to_en-US
- repo: https://github.com/pre-commit/mirrors-mypy
rev: v0.931
hooks:

@ -119,7 +119,7 @@ Directory Structure
├── debug # Tools to help you debug and do car ports
├── locationd # Precise localization and vehicle parameter estimation
├── loggerd # Logger and uploader of car data
├── manager # Deamon that starts/stops all other daemons as needed
├── manager # Daemon that starts/stops all other daemons as needed
├── modeld # Driving and monitoring model runners
├── monitoring # Daemon to determine driver attention
├── navd # Turn-by-turn navigation

@ -78,7 +78,7 @@ Version 0.8.14 (2022-06-01)
Version 0.8.13 (2022-02-18)
========================
* Improved driver monitoring
* Retuned driver pose learner for relaxed driving positions
* Re-tuned driver pose learner for relaxed driving positions
* Added reliance on driving model to be more scene adaptive
* Matched strictness between comma two and comma three
* Improved performance in turns by compensating for the road bank angle
@ -224,7 +224,7 @@ Version 0.8.4 (2021-05-17)
* Delay controls start until system is ready
* Fuzzy car identification, enabled with Community Features toggle
* Localizer optimized for increased precision and less CPU usage
* Retuned lateral control to be more aggressive when model is confident
* Re-tuned lateral control to be more aggressive when model is confident
* Toyota Mirai 2021 support
* Lexus NX 300 2020 support thanks to goesreallyfast!
* Volkswagen Atlas 2018-19 support thanks to jyoung8607!
@ -389,7 +389,7 @@ Version 0.7 (2019-12-13)
* Improve GM longitudinal control: proper computations for 15Hz radar
* Move GM port, Toyota with DSU removed, comma pedal in community features; toggle switch required
* Remove upload over cellular toggle: only upload qlog and qcamera files if not on wifi
* Refactor Panda code towards ISO26262 and SIL2 compliancy
* Refactor Panda code towards ISO26262 and SIL2 compliance
* Forward stock FCW for Honda Nidec
* Volkswagen port now standard: comma Harness intercepts stock camera

@ -254,7 +254,7 @@ def abspath(x):
# rpath works elsewhere
return x[0].path.rsplit("/", 1)[1][:-3]
# Cython build enviroment
# Cython build environment
py_include = sysconfig.get_paths()['include']
envCython = env.Clone()
envCython["CPPPATH"] += [py_include, np.get_include()]

@ -1 +1 @@
Subproject commit 589ef049a7b0bac31f4c8987c0fc539839fae489
Subproject commit c4cc38c4689b5e06be1cbfbb26c0463c377c0a6d

@ -136,7 +136,7 @@ TEST_CASE("util::create_directories") {
REQUIRE(util::create_directories(dir + "/file", 0755) == false);
REQUIRE(util::create_directories(dir + "/file/1/2/3", 0755) == false);
}
SECTION("end with slashs") {
SECTION("end with slashes") {
REQUIRE(util::create_directories(dir + "/", 0755));
}
SECTION("empty") {

@ -1 +1 @@
Subproject commit 778894f128f9acd83b983688542c3d4e9f47307f
Subproject commit 8c634615c5b6eb05ebdecc097bdc72f5403a3afa

@ -1 +1 @@
Subproject commit 9d6496ece8465dfe30997b31dfb352e1e51dde6c
Subproject commit 1776165a3d902d6320965b6b6b1715bb9a25915b

@ -34,7 +34,7 @@
// - The internal panda will always be the first panda
// - Consecutive pandas will be sorted based on panda type, and then serial number
// Connecting:
// - If a panda connection is dropped, boardd wil reconnect to all pandas
// - If a panda connection is dropped, boardd will reconnect to all pandas
// - If a panda is added, we will only reconnect when we are offroad
// CAN buses:
// - Each panda will have it's block of 4 buses. E.g.: the second panda will use
@ -44,7 +44,7 @@
// Safety:
// - SafetyConfig is a list, which is mapped to the connected pandas
// - If there are more pandas connected than there are SafetyConfigs,
// the excess pandas will remain in "silent" ot "noOutput" mode
// the excess pandas will remain in "silent" or "noOutput" mode
// Ignition:
// - If any of the ignition sources in any panda is high, ignition is high

@ -82,7 +82,7 @@ def fingerprint(logcan, sendcan):
ecu_rx_addrs = set()
if not fixed_fingerprint and not skip_fw_query:
# Vin query only reliably works thorugh OBDII
# Vin query only reliably works through OBDII
bus = 1
cached_params = Params().get("CarParamsCache")

@ -94,4 +94,4 @@ if __name__ == "__main__":
print("TEST FAILED")
sys.exit(1)
else:
print("TEST SUCESSFUL")
print("TEST SUCCESSFUL")

@ -137,7 +137,7 @@ class TestCarModelBase(unittest.TestCase):
elif tuning == 'indi':
self.assertTrue(len(self.CP.lateralTuning.indi.outerLoopGainV))
else:
raise Exception("unkown tuning")
raise Exception("unknown tuning")
def test_car_interface(self):
# TODO: also check for checksum violations from can parser

@ -41,7 +41,7 @@ class TestVehicleModel(unittest.TestCase):
self.assertAlmostEqual(float(yr1), yr2)
def test_syn_ss_sol_simulate(self):
"""Verifies that dyn_ss_sol mathes a simulation"""
"""Verifies that dyn_ss_sol matches a simulation"""
for roll in np.linspace(math.radians(-20), math.radians(20), num=11):
for u in np.linspace(1, 30, num=10):

@ -52,7 +52,7 @@ class TestAlerts(unittest.TestCase):
bold_font_path = os.path.join(font_path, "Inter-Bold.ttf")
semibold_font_path = os.path.join(font_path, "Inter-SemiBold.ttf")
max_text_width = 2160 - 300 # full screen width is useable, minus sidebar
max_text_width = 2160 - 300 # full screen width is usable, minus sidebar
draw = ImageDraw.Draw(Image.new('RGB', (0, 0)))
fonts = {

@ -19,7 +19,7 @@ optional arguments:
```
usage: dump.py [-h] [--pipe] [--raw] [--json] [--dump-json] [--no-print] [--addr ADDR] [--values VALUES] [socket [socket ...]]
Dump communcation sockets. See cereal/services.py for a complete list of available sockets.
Dump communication sockets. See cereal/services.py for a complete list of available sockets.
positional arguments:
socket socket names to dump. defaults to all services defined in cereal

@ -5,8 +5,8 @@ System tools like top/htop can only show current cpu usage values, so I write th
Features:
Use psutil library to sample cpu usage(avergage for all cores) of openpilot processes, at a rate of 5 samples/sec.
Do cpu usage statistics periodically, 5 seconds as a cycle.
Caculate the average cpu usage within this cycle.
Caculate minumium/maximium/accumulated_average cpu usage as long term inspections.
Calculate the average cpu usage within this cycle.
Calculate minumium/maximum/accumulated_average cpu usage as long term inspections.
Monitor multiple processes simuteneously.
Sample usage:
root@localhost:/data/openpilot$ python selfdrive/debug/cpu_usage_stat.py boardd,ubloxd

@ -6,7 +6,7 @@ firmware versions. If you want to try on a new radar make sure to note the defau
in case it's different from the other radars and you need to revert the changes.
After changing the config the car should not show any faults when openpilot is not running.
These config changes are persistent accross car reboots. You need to run this script again
These config changes are persistent across car reboots. You need to run this script again
to go back to the default values.
USE AT YOUR OWN RISK! Safety features, like AEB and FCW, might be affected by these changes."""

@ -59,6 +59,6 @@ if __name__ == '__main__':
print(f" {(stop_time - start_time).total_seconds():.2f} Seconds {voltage_average[1]} samples")
print("----------------------------------------------------------------")
# reenable charging
# re-enable charging
os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled')
print("charging enabled\n")

@ -168,7 +168,7 @@ if __name__ == "__main__":
break
print()
# Print FW versions that need to be added seperated out by car and address
# Print FW versions that need to be added separated out by car and address
for car, m in sorted(mismatches.items()):
print(car)
addrs = defaultdict(list)

@ -476,9 +476,9 @@ bool Localizer::isGpsOK() {
}
void Localizer::determine_gps_mode(double current_time) {
// 1. If the pos_std is greater than what's not acceptible and localizer is in gps-mode, reset to no-gps-mode
// 2. If the pos_std is greater than what's not acceptible and localizer is in no-gps-mode, fake obs
// 3. If the pos_std is smaller than what's not acceptible, let gps-mode be whatever it is
// 1. If the pos_std is greater than what's not acceptable and localizer is in gps-mode, reset to no-gps-mode
// 2. If the pos_std is greater than what's not acceptable and localizer is in no-gps-mode, fake obs
// 3. If the pos_std is smaller than what's not acceptable, let gps-mode be whatever it is
VectorXd current_pos_std = this->kf->get_P().block<STATE_ECEF_POS_ERR_LEN, STATE_ECEF_POS_ERR_LEN>(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal().array().sqrt();
if (current_pos_std.norm() > SANE_GPS_UNCERTAINTY){
if (this->gps_mode){

@ -33,7 +33,7 @@ class States():
ACCELEROMETER_BIAS = slice(30, 33) # bias of mems accelerometer
# TODO the offset is likely a translation of the sensor, not a rotation of the camera
WIDE_FROM_DEVICE_EULER = slice(33, 36) # wide camera offset angles in radians (tici only)
# We curently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_FROM_DEVICE_EULER).
# We currently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_FROM_DEVICE_EULER).
# From experiments we see that ACCELEROMETER_BIAS is more correct than ACCELEROMETER_SCALE
# Error-state has different slices because it is an ESKF

@ -65,7 +65,7 @@ def configure_ublox(dev):
print("backup restore polling message (implement custom response handler!):")
dev.configure_poll(0x09, 0x14)
print("if succesfull, send this to clear the flash:")
print("if successful, send this to clear the flash:")
dev.send_message(0x09, 0x14, b"\x01\x00\x00\x00")
print("send on stop:")

@ -182,7 +182,7 @@ int logger_next(LoggerState *s, const char* root_path,
pthread_mutex_unlock(&s->lock);
// write beggining of log metadata
// write beginning of log metadata
log_init_data(s);
lh_log_sentinel(s->cur_handle, is_start_of_route ? SentinelType::START_OF_ROUTE : SentinelType::START_OF_SEGMENT);
return 0;

@ -47,7 +47,7 @@ void verify_segment(const std::string &route_path, int segment, int max_segment,
}
++i;
} catch (const kj::Exception &ex) {
INFO("failed parse " << i << " excpetion :" << ex.getDescription());
INFO("failed parse " << i << " exception :" << ex.getDescription());
REQUIRE(0);
break;
}

@ -186,7 +186,7 @@ class TestLoggerd(unittest.TestCase):
pm = messaging.PubMaster(services)
# sleep enough for the first poll to time out
# TOOD: fix loggerd bug dropping the msgs from the first poll
# TODO: fix loggerd bug dropping the msgs from the first poll
managed_processes["loggerd"].start()
for s in services:
while not pm.all_readers_updated(s):

@ -33,6 +33,6 @@ def unblock_stdout() -> None:
pass
# os.wait() returns a tuple with the pid and a 16 bit value
# whose low byte is the signal number and whose high byte is the exit satus
# whose low byte is the signal number and whose high byte is the exit status
exit_status = os.wait()[1] >> 8
os._exit(exit_status)

@ -32,7 +32,7 @@ void transform_queue(Transform* s,
const int zero = 0;
// sampled using pixel center origin
// (because thats how fastcv and opencv does it)
// (because that's how fastcv and opencv does it)
mat3 projection_y = projection;

@ -194,10 +194,10 @@ class RouteEngine:
parse_banner_instructions(msg.navInstruction, step['bannerInstructions'], distance_to_maneuver_along_geometry)
# Compute total remaining time and distance
remaning = 1.0 - along_geometry / max(step['distance'], 1)
total_distance = step['distance'] * remaning
total_time = step['duration'] * remaning
total_time_typical = step['duration_typical'] * remaning
remaining = 1.0 - along_geometry / max(step['distance'], 1)
total_distance = step['distance'] * remaining
total_time = step['duration'] * remaining
total_time_typical = step['duration_typical'] * remaining
# Add up totals for future steps
for i in range(self.step_idx + 1, len(self.route)):

@ -27,7 +27,7 @@ int LSM6DS3_Accel::init() {
source = cereal::SensorEventData::SensorSource::LSM6DS3TRC;
}
// TODO: set scale and bandwith. Default is +- 2G, 50 Hz
// TODO: set scale and bandwidth. Default is +- 2G, 50 Hz
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ);
if (ret < 0) {
goto fail;

@ -173,7 +173,7 @@ if __name__ == "__main__":
'driverStateV2.modelExecutionTime',
'driverStateV2.dspExecutionTime'
]
# TODO this tolerence is absurdly large
# TODO this tolerance is absurdly large
tolerance = 5e-1 if PC else None
results: Any = {TEST_ROUTE: {}}
log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}}

@ -78,7 +78,7 @@ if GetOption('extras'):
if GetOption('extras'):
# buidl updater UI
# build updater UI
qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs)
# build mui

@ -107,7 +107,7 @@ void Installer::doInstall() {
qDebug() << "Waiting for valid time";
}
// cleanup previous install attemps
// cleanup previous install attempts
run("rm -rf " TMP_INSTALL_PATH " " INSTALL_PATH);
// do the install

@ -949,7 +949,7 @@ std::map<uint16_t, std::pair<int, int>> CameraState::ar0231_build_register_lut(u
//
// 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address.
// Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional
// for contigous ranges. See page 27-29 of the AR0231 Developer guide for more information.
// for contiguous ranges. See page 27-29 of the AR0231 Developer guide for more information.
int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3};
auto get_next_idx = [](int cur_idx) {
@ -1077,7 +1077,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
// It takes 3 frames for the commanded exposure settings to take effect. The first frame is already started by the time
// we reach this function, the other 2 are due to the register buffering in the sensor.
// Therefore we use the target EV from 3 frames ago, the grey fraction that was just measured was the result of that control action.
// TODO: Lower latency to 2 frames, by using the histogram outputed by the sensor we can do AE before the debayering is complete
// TODO: Lower latency to 2 frames, by using the histogram outputted by the sensor we can do AE before the debayering is complete
const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3];
@ -1110,7 +1110,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
// Compute optimal time for given gain
int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX);
// Only go below recomended gain when absolutely necessary to not overexpose
// Only go below recommended gain when absolutely necessary to not overexpose
if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < gain_idx) {
continue;
}
@ -1118,7 +1118,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
// Compute error to desired ev
float score = std::abs(desired_ev - (t * gain)) * 10;
// Going below recomended gain needs lower penalty to not overexpose
// Going below recommended gain needs lower penalty to not overexpose
float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1;
score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m;

@ -241,7 +241,7 @@ def flash_partition(target_slot_number: int, partition: dict, cloudlog, standalo
else:
extract_compressed_image(target_slot_number, partition, cloudlog)
# Write hash after successfull flash
# Write hash after successful flash
if not full_check:
with open(path, 'wb+') as out:
out.seek(partition['size'])
@ -257,7 +257,7 @@ def swap(manifest_path: str, target_slot_number: int, cloudlog) -> None:
while True:
out = subprocess.check_output(f"abctl --set_active {target_slot_number}", shell=True, stderr=subprocess.STDOUT, encoding='utf8')
if ("No such file or directory" not in out) and ("lun as boot lun" in out):
cloudlog.info(f"Swap successfull {out}")
cloudlog.info(f"Swap successful {out}")
break
else:
cloudlog.error(f"Swap failed {out}")

@ -287,7 +287,7 @@ class Tici(HardwareBase):
]
upload = [
# Create root Hierarchy Token Bucket that sends all trafic to 1:20
# Create root Hierarchy Token Bucket that sends all traffic to 1:20
(True, tc + ["qdisc", "add", "dev", adapter, "root", "handle", "1:", "htb", "default", "20"]),
# Create class 1:20 with specified rate limit

@ -72,7 +72,7 @@ std::optional<ProcStat> procStat(std::string stat) {
}
std::string name = stat.substr(open_paren + 1, close_paren - open_paren - 1);
// repace space in name with _
// replace space in name with _
std::replace(&stat[open_paren], &stat[close_paren], ' ', '_');
std::istringstream iss(stat);
std::vector<std::string> v{std::istream_iterator<std::string>(iss),

@ -2,7 +2,7 @@
## System Requirements
openpilot is developed and tested on **Ubuntu 20.04**, which is the primary development target aside from the [supported embdedded hardware](https://github.com/commaai/openpilot#running-on-pc). We also have a CI test to verify that openpilot builds on macOS, but the tools are untested. For the best experience, stick to Ubuntu 20.04, otherwise openpilot and the tools should work with minimal to no modifications on macOS and other Linux systems.
openpilot is developed and tested on **Ubuntu 20.04**, which is the primary development target aside from the [supported embedded hardware](https://github.com/commaai/openpilot#running-on-pc). We also have a CI test to verify that openpilot builds on macOS, but the tools are untested. For the best experience, stick to Ubuntu 20.04, otherwise openpilot and the tools should work with minimal to no modifications on macOS and other Linux systems.
## Setup your PC
@ -39,7 +39,7 @@ scons -u -j$(nproc)
### Windows
Neither openpilot nor any of the tools are developed or tested on Windows, but the [Windows Subsystem for Linux (WSL)](https://docs.microsoft.com/en-us/windows/wsl/about) should get Windows users a similiar experience to Ubuntu. [WSL 2](https://docs.microsoft.com/en-us/windows/wsl/compare-versions) specifically has been reported by several users to be a seamless experience.
Neither openpilot nor any of the tools are developed or tested on Windows, but the [Windows Subsystem for Linux (WSL)](https://docs.microsoft.com/en-us/windows/wsl/about) should get Windows users a similar experience to Ubuntu. [WSL 2](https://docs.microsoft.com/en-us/windows/wsl/compare-versions) specifically has been reported by several users to be a seamless experience.
Follow [these instructions](https://docs.microsoft.com/en-us/windows/wsl/install) to setup the WSL and install the `Ubuntu-20.04` distribution. Once your Ubuntu WSL environment is setup, follow the Linux setup instructions to finish setting up your environment.

@ -86,7 +86,7 @@ def decoder(addr, sock_name, vipc_server, vst, nvidia):
print("%2d %4d %.3f %.3f roll %6.2f ms latency %6.2f ms + %6.2f ms + %6.2f ms = %6.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, frame_latency, process_latency, network_latency, pc_latency, process_latency+network_latency+pc_latency ), len(evta.data), sock_name)
if __name__ == "__main__":
parser = argparse.ArgumentParser(description="Decode video streams and broacast on VisionIPC")
parser = argparse.ArgumentParser(description="Decode video streams and broadcast on VisionIPC")
parser.add_argument("addr", help="Address of comma three")
parser.add_argument("--nvidia", action="store_true", help="Use nvidia instead of ffmpeg")
parser.add_argument("--cams", default="0,1,2", help="Cameras to decode")

@ -13,7 +13,7 @@ from tools.lib.logreader import logreader_from_route_or_segment
DEMO_ROUTE = "9f583b1d93915c31|2022-05-18--10-49-51--0"
SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd']
# Retrive controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored
# Retrieve controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored
MONOTIME_KEYS = ['modelMonoTime', 'lateralPlanMonoTime']
MSGQ_TO_SERVICE = {
'roadCameraState': 'camerad',
@ -79,7 +79,7 @@ def read_logs(lr):
if not data['start'][frame_id][service]:
data['start'][frame_id][service] = msg_obj.timestampSof
elif msg.which() == 'controlsState':
# Sendcan is published before controlsState, but the frameId is retrived in CS
# Sendcan is published before controlsState, but the frameId is retrieved in CS
data['timestamp'][frame_id][service].append(("sendcan published", latest_sendcan_monotime))
elif msg.which() == 'modelV2':
if msg_obj.frameIdExtra != frame_id:

@ -1,6 +1,6 @@
## LogReader
Route is a class for conviently accessing all the [logs](/selfdrive/loggerd/) from your routes. The LogReader class reads the non-video logs, i.e. rlog.bz2 and qlog.bz2. There's also a matching FrameReader class for reading the videos.
Route is a class for conveniently accessing all the [logs](/selfdrive/loggerd/) from your routes. The LogReader class reads the non-video logs, i.e. rlog.bz2 and qlog.bz2. There's also a matching FrameReader class for reading the videos.
```python
from tools.lib.route import Route

@ -10,7 +10,7 @@ from tools.lib.logreader import LogReader
class TestReaders(unittest.TestCase):
@unittest.skip("skip for bandwith reasons")
@unittest.skip("skip for bandwidth reasons")
def test_logreader(self):
def _check_data(lr):
hist = defaultdict(int)
@ -31,7 +31,7 @@ class TestReaders(unittest.TestCase):
lr_url = LogReader("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true")
_check_data(lr_url)
@unittest.skip("skip for bandwith reasons")
@unittest.skip("skip for bandwidth reasons")
def test_framereader(self):
def _check_data(f):
self.assertEqual(f.frame_count, 1200)

@ -110,8 +110,8 @@ def juggle_route(route_or_segment_name, segment_count, qlog, can, layout, dbc=No
logs = logs[segment_start:segment_end]
if None in logs:
ans = input(f"{logs.count(None)}/{len(logs)} of the rlogs in this segment are missing, would you like to fall back to the qlogs? (y/n) ")
if ans == 'y':
resp = input(f"{logs.count(None)}/{len(logs)} of the rlogs in this segment are missing, would you like to fall back to the qlogs? (y/n) ")
if resp == 'y':
logs = r.qlog_paths()[segment_start:segment_end]
else:
print("Please try a different route or segment")

@ -16,7 +16,7 @@
<plot flip_y="false" style="Lines" flip_x="false" mode="TimeSeries">
<range left="0.000450" top="5.384416" right="2483.624998" bottom="-7.503945"/>
<limitY/>
<curve color="#1ac938" name="roll compenstated lateral acceleration"/>
<curve color="#1ac938" name="roll compensated lateral acceleration"/>
</plot>
</DockArea>
<DockArea name="...">
@ -53,7 +53,7 @@
<!-- - - - - - - - - - - - - - - -->
<!-- - - - - - - - - - - - - - - -->
<customMathEquations>
<snippet name="roll compenstated lateral acceleration">
<snippet name="roll compensated lateral acceleration">
<global></global>
<function>if (v3 == 0 and v4 == 1) then
return (value * v1 ^ 2) - (v2 * 9.81)

@ -133,7 +133,7 @@ bool FrameReader::load(const std::byte *data, size_t size, bool no_hw_decoder, s
break;
}
packets.push_back(pkt);
// some stream seems to contian no keyframes
// some stream seems to contain no keyframes
key_frames_count_ += pkt->flags & AV_PKT_FLAG_KEY;
}
valid_ = valid_ && !packets.empty();

@ -81,7 +81,7 @@ void Replay::start(int seconds) {
}
void Replay::updateEvents(const std::function<bool()> &lambda) {
// set updating_events to true to force stream thread relase the lock and wait for evnets_udpated.
// set updating_events to true to force stream thread release the lock and wait for evnets_udpated.
updating_events_ = true;
{
std::unique_lock lk(stream_lock_);

@ -61,7 +61,7 @@ signals:
void streamStarted();
protected slots:
void segmentLoadFinished(bool sucess);
void segmentLoadFinished(bool success);
protected:
typedef std::map<int, std::unique_ptr<Segment>> SegmentMap;

@ -346,7 +346,7 @@ class CarlaBridge:
vehicle_state = VehicleState()
# reenable IMU
# re-enable IMU
imu_bp = blueprint_library.find('sensor.other.imu')
imu = world.spawn_actor(imu_bp, transform, attach_to=vehicle)
imu.listen(lambda imu: imu_callback(imu, vehicle_state))

Loading…
Cancel
Save