Merge branch 'master' into mqb-long

mqb-long
Jason Young 3 years ago
commit 3a13793c8e
  1. 10
      .github/workflows/setup/action.yaml
  2. 3
      SConstruct
  3. 2
      cereal
  4. 39
      common/gpio.cc
  5. 12
      common/gpio.h
  6. 6
      docs/CARS.md
  7. 1
      release/files_common
  8. 2
      release/files_tici
  9. 7
      selfdrive/boardd/boardd.cc
  10. 15
      selfdrive/car/body/values.py
  11. 49
      selfdrive/car/chrysler/values.py
  12. 70
      selfdrive/car/ford/carcontroller.py
  13. 49
      selfdrive/car/ford/carstate.py
  14. 88
      selfdrive/car/ford/fordcan.py
  15. 40
      selfdrive/car/ford/interface.py
  16. 72
      selfdrive/car/ford/values.py
  17. 66
      selfdrive/car/fw_query_definitions.py
  18. 275
      selfdrive/car/fw_versions.py
  19. 9
      selfdrive/car/honda/values.py
  20. 2
      selfdrive/car/hyundai/interface.py
  21. 25
      selfdrive/car/hyundai/values.py
  22. 14
      selfdrive/car/mazda/values.py
  23. 32
      selfdrive/car/nissan/values.py
  24. 20
      selfdrive/car/subaru/values.py
  25. 2
      selfdrive/car/tesla/values.py
  26. 3
      selfdrive/car/tests/routes.py
  27. 19
      selfdrive/car/tests/test_fw_fingerprint.py
  28. 5
      selfdrive/car/tests/test_models.py
  29. 1
      selfdrive/car/torque_data/override.yaml
  30. 5
      selfdrive/car/toyota/interface.py
  31. 7
      selfdrive/car/toyota/tunes.py
  32. 33
      selfdrive/car/toyota/values.py
  33. 11
      selfdrive/car/vin.py
  34. 13
      selfdrive/car/volkswagen/carcontroller.py
  35. 4
      selfdrive/car/volkswagen/mqbcan.py
  36. 4
      selfdrive/car/volkswagen/pqcan.py
  37. 31
      selfdrive/car/volkswagen/values.py
  38. 2
      selfdrive/controls/controlsd.py
  39. 2
      selfdrive/controls/lib/longcontrol.py
  40. 121
      selfdrive/debug/sensor_data_to_hist.py
  41. 32
      selfdrive/debug/vw_mqb_config.py
  42. 6
      selfdrive/loggerd/encoderd.cc
  43. 2
      selfdrive/sensord/SConscript
  44. 3
      selfdrive/sensord/sensors/bmx055_accel.cc
  45. 3
      selfdrive/sensord/sensors/bmx055_accel.h
  46. 4
      selfdrive/sensord/sensors/bmx055_gyro.cc
  47. 3
      selfdrive/sensord/sensors/bmx055_gyro.h
  48. 7
      selfdrive/sensord/sensors/bmx055_magn.cc
  49. 3
      selfdrive/sensord/sensors/bmx055_magn.h
  50. 3
      selfdrive/sensord/sensors/bmx055_temp.cc
  51. 3
      selfdrive/sensord/sensors/bmx055_temp.h
  52. 4
      selfdrive/sensord/sensors/file_sensor.cc
  53. 3
      selfdrive/sensord/sensors/file_sensor.h
  54. 23
      selfdrive/sensord/sensors/i2c_sensor.cc
  55. 14
      selfdrive/sensord/sensors/i2c_sensor.h
  56. 4
      selfdrive/sensord/sensors/light_sensor.cc
  57. 3
      selfdrive/sensord/sensors/light_sensor.h
  58. 58
      selfdrive/sensord/sensors/lsm6ds3_accel.cc
  59. 11
      selfdrive/sensord/sensors/lsm6ds3_accel.h
  60. 59
      selfdrive/sensord/sensors/lsm6ds3_gyro.cc
  61. 11
      selfdrive/sensord/sensors/lsm6ds3_gyro.h
  62. 3
      selfdrive/sensord/sensors/lsm6ds3_temp.cc
  63. 3
      selfdrive/sensord/sensors/lsm6ds3_temp.h
  64. 3
      selfdrive/sensord/sensors/mmc5603nj_magn.cc
  65. 3
      selfdrive/sensord/sensors/mmc5603nj_magn.h
  66. 5
      selfdrive/sensord/sensors/sensor.h
  67. 95
      selfdrive/sensord/sensors_qcom2.cc
  68. 236
      selfdrive/sensord/tests/test_sensord.py
  69. 2
      selfdrive/test/process_replay/ref_commit
  70. 4
      selfdrive/ui/qt/home.cc
  71. 4
      selfdrive/ui/qt/maps/map.cc
  72. 52
      selfdrive/ui/qt/maps/map_helpers.cc
  73. 6
      selfdrive/ui/qt/maps/map_helpers.h
  74. 16
      selfdrive/ui/qt/maps/map_settings.cc
  75. 2
      selfdrive/ui/qt/maps/map_settings.h
  76. 3
      selfdrive/ui/qt/offroad/settings.cc
  77. 2
      selfdrive/ui/qt/widgets/controls.h
  78. 11
      selfdrive/ui/qt/widgets/prime.cc
  79. 2
      selfdrive/ui/qt/widgets/prime.h
  80. 14
      selfdrive/ui/translations/main_ja.ts
  81. 38
      selfdrive/ui/translations/main_ko.ts
  82. 4
      selfdrive/ui/translations/main_pt-BR.ts
  83. 4
      selfdrive/ui/translations/main_zh-CHS.ts
  84. 4
      selfdrive/ui/translations/main_zh-CHT.ts
  85. 1
      selfdrive/ui/ui.cc
  86. 1
      selfdrive/ui/ui.h
  87. 7
      selfdrive/updated.py
  88. 19
      system/camerad/SConscript
  89. 10
      system/camerad/cameras/camera_common.cc
  90. 2
      system/camerad/cameras/camera_common.h
  91. 371
      system/camerad/cameras/camera_qcom2.cc
  92. 37
      system/camerad/cameras/camera_qcom2.h
  93. 135
      system/camerad/cameras/camera_util.cc
  94. 30
      system/camerad/cameras/camera_util.h
  95. 35
      system/camerad/cameras/real_debayer.cl
  96. 772
      system/camerad/cameras/sensor2_i2c.h
  97. 7
      system/camerad/main.cc
  98. 25
      system/camerad/test/camera_test.h
  99. 11
      system/hardware/tici/hardware.py
  100. 6
      system/hardware/tici/pins.py
  101. Some files were not shown because too many files have changed in this diff Show More

@ -1,13 +1,5 @@
name: 'openpilot env setup' name: 'openpilot env setup'
env:
BASE_IMAGE: openpilot-base
DOCKER_REGISTRY: ghcr.io/commaai
BUILD: |
docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true
docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true
docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base .
inputs: inputs:
save-cache: save-cache:
default: false default: false
@ -42,4 +34,4 @@ runs:
# build our docker image # build our docker image
- shell: bash - shell: bash
run: eval "$BUILD" run: eval ${{ env.BUILD }}

@ -99,9 +99,6 @@ if arch == "larch64":
"#third_party/libyuv/larch64/lib", "#third_party/libyuv/larch64/lib",
"/usr/lib/aarch64-linux-gnu" "/usr/lib/aarch64-linux-gnu"
] ]
cpppath += [
"#system/camerad/include",
]
cflags = ["-DQCOM2", "-mcpu=cortex-a57"] cflags = ["-DQCOM2", "-mcpu=cortex-a57"]
cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"]
rpath += ["/usr/local/lib"] rpath += ["/usr/local/lib"]

@ -1 +1 @@
Subproject commit cea51afd67b5c56f7a18207ef91c5e45d6345526 Subproject commit 2335f98bbe628ec6fde92c8d929ecaf373b125af

@ -4,11 +4,11 @@
#include <unistd.h> #include <unistd.h>
#include <cstring> #include <cstring>
#include <linux/gpio.h>
#include <sys/ioctl.h>
#include "common/util.h" #include "common/util.h"
#include "common/swaglog.h"
// We assume that all pins have already been exported on boot,
// and that we have permission to write to them.
int gpio_init(int pin_nr, bool output) { int gpio_init(int pin_nr, bool output) {
char pin_dir_path[50]; char pin_dir_path[50];
@ -30,3 +30,36 @@ int gpio_set(int pin_nr, bool high) {
} }
return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1); return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1);
} }
int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr) {
// Assumed that all interrupt pins are unexported and rights are given to
// read from gpiochip0.
std::string gpiochip_path = "/dev/gpiochip" + std::to_string(gpiochiop_id);
int fd = open(gpiochip_path.c_str(), O_RDONLY);
if (fd < 0) {
LOGE("Error opening gpiochip0 fd")
return -1;
}
// Setup event
struct gpioevent_request rq;
rq.lineoffset = pin_nr;
rq.handleflags = GPIOHANDLE_REQUEST_INPUT;
/* Requesting both edges as the data ready pulse from the lsm6ds sensor is
very short(75us) and is mostly detected as falling edge instead of rising.
So if it is detected as rising the following falling edge is skipped. */
rq.eventflags = GPIOEVENT_REQUEST_BOTH_EDGES;
strncpy(rq.consumer_label, consumer_label, std::size(rq.consumer_label) - 1);
int ret = ioctl(fd, GPIO_GET_LINEEVENT_IOCTL, &rq);
if (ret == -1) {
LOGE("Unable to get line event from ioctl : %s", strerror(errno));
close(fd);
return -1;
}
close(fd);
return rq.fd;
}

@ -8,6 +8,11 @@
#define GPIO_UBLOX_PWR_EN 34 #define GPIO_UBLOX_PWR_EN 34
#define GPIO_STM_RST_N 124 #define GPIO_STM_RST_N 124
#define GPIO_STM_BOOT0 134 #define GPIO_STM_BOOT0 134
#define GPIO_BMX_ACCEL_INT 21
#define GPIO_BMX_GYRO_INT 23
#define GPIO_BMX_MAGN_INT 87
#define GPIO_LSM_INT 84
#define GPIOCHIP_INT 0
#else #else
#define GPIO_HUB_RST_N 0 #define GPIO_HUB_RST_N 0
#define GPIO_UBLOX_RST_N 0 #define GPIO_UBLOX_RST_N 0
@ -15,7 +20,14 @@
#define GPIO_UBLOX_PWR_EN 0 #define GPIO_UBLOX_PWR_EN 0
#define GPIO_STM_RST_N 0 #define GPIO_STM_RST_N 0
#define GPIO_STM_BOOT0 0 #define GPIO_STM_BOOT0 0
#define GPIO_BMX_ACCEL_INT 0
#define GPIO_BMX_GYRO_INT 0
#define GPIO_BMX_MAGN_INT 0
#define GPIO_LSM_INT 0
#define GPIOCHIP_INT 0
#endif #endif
int gpio_init(int pin_nr, bool output); int gpio_init(int pin_nr, bool output);
int gpio_set(int pin_nr, bool high); int gpio_set(int pin_nr, bool high);
int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr);

@ -57,7 +57,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J|
|Hyundai|Ioniq 5 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| |Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q|
|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
|Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
@ -78,12 +78,12 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|
|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Hyundai|Tucson Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA|
|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA|
|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Kia|EV6 2022|Highway Driving Assist II|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| |Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P|
|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B|
|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G|
|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|

@ -101,6 +101,7 @@ selfdrive/car/interfaces.py
selfdrive/car/vin.py selfdrive/car/vin.py
selfdrive/car/disable_ecu.py selfdrive/car/disable_ecu.py
selfdrive/car/fw_versions.py selfdrive/car/fw_versions.py
selfdrive/car/fw_query_definitions.py
selfdrive/car/ecu_addrs.py selfdrive/car/ecu_addrs.py
selfdrive/car/isotp_parallel_query.py selfdrive/car/isotp_parallel_query.py
selfdrive/car/tests/__init__.py selfdrive/car/tests/__init__.py

@ -9,6 +9,8 @@ selfdrive/assets/training_wide/*
system/camerad/cameras/camera_qcom2.cc system/camerad/cameras/camera_qcom2.cc
system/camerad/cameras/camera_qcom2.h system/camerad/cameras/camera_qcom2.h
system/camerad/cameras/camera_util.cc
system/camerad/cameras/camera_util.h
system/camerad/cameras/real_debayer.cl system/camerad/cameras/real_debayer.cl
selfdrive/sensord/rawgps/* selfdrive/sensord/rawgps/*

@ -468,7 +468,7 @@ void panda_state_thread(PubMaster *pm, std::vector<Panda *> pandas, bool spoofin
} }
void peripheral_control_thread(Panda *panda) { void peripheral_control_thread(Panda *panda, bool no_fan_control) {
util::set_thread_name("boardd_peripheral_control"); util::set_thread_name("boardd_peripheral_control");
SubMaster sm({"deviceState", "driverCameraState"}); SubMaster sm({"deviceState", "driverCameraState"});
@ -488,7 +488,7 @@ void peripheral_control_thread(Panda *panda) {
// Other pandas don't have fan/IR to control // Other pandas don't have fan/IR to control
if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue; if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue;
if (sm.updated("deviceState")) { if (sm.updated("deviceState") && !no_fan_control) {
// Fan speed // Fan speed
uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired();
if (fan_speed != prev_fan_speed || cnt % 100 == 0) { if (fan_speed != prev_fan_speed || cnt % 100 == 0) {
@ -496,6 +496,7 @@ void peripheral_control_thread(Panda *panda) {
prev_fan_speed = fan_speed; prev_fan_speed = fan_speed;
} }
} }
if (sm.updated("driverCameraState")) { if (sm.updated("driverCameraState")) {
auto event = sm["driverCameraState"]; auto event = sm["driverCameraState"];
int cur_integ_lines = event.getDriverCameraState().getIntegLines(); int cur_integ_lines = event.getDriverCameraState().getIntegLines();
@ -568,7 +569,7 @@ void boardd_main_thread(std::vector<std::string> serials) {
std::vector<std::thread> threads; std::vector<std::thread> threads;
threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr); threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr);
threads.emplace_back(peripheral_control_thread, peripheral_panda); threads.emplace_back(peripheral_control_thread, peripheral_panda, getenv("NO_FAN_CONTROL") != nullptr);
threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr); threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr);
threads.emplace_back(can_recv_thread, pandas); threads.emplace_back(can_recv_thread, pandas);

@ -3,10 +3,13 @@ from typing import Dict
from cereal import car from cereal import car
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo from selfdrive.car.docs_definitions import CarInfo
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
SPEED_FROM_RPM = 0.008587 SPEED_FROM_RPM = 0.008587
class CarControllerParams: class CarControllerParams:
ANGLE_DELTA_BP = [0., 5., 15.] ANGLE_DELTA_BP = [0., 5., 15.]
ANGLE_DELTA_V = [5., .8, .15] # windup limit ANGLE_DELTA_V = [5., .8, .15] # windup limit
@ -14,13 +17,25 @@ class CarControllerParams:
LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower
STEER_THRESHOLD = 1.0 STEER_THRESHOLD = 1.0
class CAR: class CAR:
BODY = "COMMA BODY" BODY = "COMMA BODY"
CAR_INFO: Dict[str, CarInfo] = { CAR_INFO: Dict[str, CarInfo] = {
CAR.BODY: CarInfo("comma body", package="All"), CAR.BODY: CarInfo("comma body", package="All"),
} }
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST],
[StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE],
bus=0,
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.BODY: { CAR.BODY: {
(Ecu.engine, 0x720, None): [ (Ecu.engine, 0x720, None): [

@ -3,8 +3,11 @@ from enum import Enum
from typing import Dict, List, Optional, Union from typing import Dict, List, Optional, Union
from cereal import car from cereal import car
from panda.python import uds
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness from selfdrive.car.docs_definitions import CarInfo, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -129,6 +132,42 @@ FINGERPRINTS = {
}], }],
} }
CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(0xf132)
CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(0xf132)
CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER)
CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER)
CHRYSLER_RX_OFFSET = -0x280
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[CHRYSLER_VERSION_REQUEST],
[CHRYSLER_VERSION_RESPONSE],
whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter],
rx_offset=CHRYSLER_RX_OFFSET,
bus=0,
),
Request(
[CHRYSLER_VERSION_REQUEST],
[CHRYSLER_VERSION_RESPONSE],
whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission],
bus=0,
),
Request(
[CHRYSLER_SOFTWARE_VERSION_REQUEST],
[CHRYSLER_SOFTWARE_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine, Ecu.transmission],
bus=0,
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.PACIFICA_2019_HYBRID: { CAR.PACIFICA_2019_HYBRID: {
(Ecu.hcp, 0x7e2, None): [], (Ecu.hcp, 0x7e2, None): [],
@ -187,12 +226,6 @@ FW_VERSIONS = {
b'68540431AB', b'68540431AB',
b'68484467AC', b'68484467AC',
], ],
(Ecu.gateway, 0x18DACBF1, None): [
b'68402660AB',
b'68445283AB',
b'68533631AB',
b'68500483AB',
],
}, },
CAR.RAM_HD: { CAR.RAM_HD: {
@ -224,10 +257,6 @@ FW_VERSIONS = {
b'M2370131MB', b'M2370131MB',
b'M2421132MB', b'M2421132MB',
], ],
(Ecu.gateway, 0x18DACBF1, None): [
b'68488419AB',
b'68535476AB',
],
}, },
} }

@ -1,3 +1,4 @@
import math
from cereal import car from cereal import car
from common.numpy_fast import clip, interp from common.numpy_fast import clip, interp
from opendbc.can.packer import CANPacker from opendbc.can.packer import CANPacker
@ -7,14 +8,19 @@ from selfdrive.car.ford.values import CarControllerParams
VisualAlert = car.CarControl.HUDControl.VisualAlert VisualAlert = car.CarControl.HUDControl.VisualAlert
def apply_ford_steer_angle_limits(apply_steer, apply_steer_last, vEgo): def apply_ford_steer_angle_limits(apply_angle, apply_angle_last, vEgo):
# rate limit # rate limit
steer_up = apply_steer * apply_steer_last > 0. and abs(apply_steer) > abs(apply_steer_last) steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last)
rate_limit = CarControllerParams.STEER_RATE_LIMIT_UP if steer_up else CarControllerParams.STEER_RATE_LIMIT_DOWN rate_limit = CarControllerParams.RATE_LIMIT_UP if steer_up else CarControllerParams.RATE_LIMIT_DOWN
max_angle_diff = interp(vEgo, rate_limit.speed_points, rate_limit.max_angle_diff_points) max_angle_diff = interp(vEgo, rate_limit.speed_points, rate_limit.max_angle_diff_points)
apply_steer = clip(apply_steer, (apply_steer_last - max_angle_diff), (apply_steer_last + max_angle_diff)) apply_angle = clip(apply_angle, (apply_angle_last - max_angle_diff), (apply_angle_last + max_angle_diff))
return apply_steer # absolute limit (LatCtlPath_An_Actl)
apply_path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO
apply_path_angle = clip(apply_path_angle, -0.4995, 0.5240)
apply_angle = math.degrees(apply_path_angle) * CarControllerParams.STEER_RATIO
return apply_angle
class CarController: class CarController:
@ -24,7 +30,7 @@ class CarController:
self.packer = CANPacker(dbc_name) self.packer = CANPacker(dbc_name)
self.frame = 0 self.frame = 0
self.apply_steer_last = 0 self.apply_angle_last = 0
self.main_on_last = False self.main_on_last = False
self.lkas_enabled_last = False self.lkas_enabled_last = False
self.steer_alert_last = False self.steer_alert_last = False
@ -38,52 +44,62 @@ class CarController:
main_on = CS.out.cruiseState.available main_on = CS.out.cruiseState.available
steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)
### acc buttons ###
if CC.cruiseControl.cancel: if CC.cruiseControl.cancel:
# cancel stock ACC can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True))
can_sends.append(fordcan.spam_cancel_button(self.packer)) elif CC.cruiseControl.resume:
can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True))
# if stock lane centering is active or in standby, toggle it off
# the stock system checks for steering pressed, and eventually disengages cruise control
if (self.frame % 200) == 0 and CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0:
can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, tja_toggle=True))
# apply rate limits ### lateral control ###
new_steer = actuators.steeringAngleDeg if CC.latActive:
apply_steer = apply_ford_steer_angle_limits(new_steer, self.apply_steer_last, CS.out.vEgo) apply_angle = apply_ford_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo)
else:
apply_angle = CS.out.steeringAngleDeg
# send steering commands at 20Hz # send steering commands at 20Hz
if (self.frame % CarControllerParams.LKAS_STEER_STEP) == 0: if (self.frame % CarControllerParams.LKAS_STEER_STEP) == 0:
lca_rq = 1 if CC.latActive else 0 lca_rq = 1 if CC.latActive else 0
# use LatCtlPath_An_Actl to actuate steering for now until curvature control is implemented # use LatCtlPath_An_Actl to actuate steering
path_angle = apply_steer # path angle is the car wheel angle, not the steering wheel angle
path_angle = math.radians(apply_angle) / CarControllerParams.STEER_RATIO
# convert steer angle to curvature # ramp rate: 0=Slow, 1=Medium, 2=Fast, 3=Immediately
curvature = self.VM.calc_curvature(apply_steer, CS.out.vEgo, 0.0) # TODO: try slower ramp speed when driver torque detected
ramp_type = 3
precision = 1 # 0=Comfortable, 1=Precise (the stock system always uses comfortable)
# TODO: get other actuators offset_roll_compensation_curvature = clip(self.VM.calc_curvature(0, CS.out.vEgo, -CS.yaw_data["VehYaw_W_Actl"]), -0.02, 0.02094)
curvature_rate = 0
path_offset = 0
ramp_type = 3 # 0=Slow, 1=Medium, 2=Fast, 3=Immediately self.apply_angle_last = apply_angle
precision = 0 # 0=Comfortable, 1=Precise can_sends.append(fordcan.create_lka_command(self.packer, apply_angle, 0))
self.apply_steer_last = apply_steer
can_sends.append(fordcan.create_lkas_command(self.packer, apply_steer, curvature))
can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision, can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision,
path_offset, path_angle, curvature_rate, curvature)) 0, path_angle, 0, offset_roll_compensation_curvature))
### ui ###
send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert)
# send lkas ui command at 1Hz or if ui state changes # send lkas ui command at 1Hz or if ui state changes
if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui:
can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, CS.lkas_status_stock_values)) can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values))
# send acc ui command at 20Hz or if ui state changes # send acc ui command at 20Hz or if ui state changes
if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui:
can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, CS.acc_tja_status_stock_values)) can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, hud_control, CS.acc_tja_status_stock_values))
self.main_on_last = main_on self.main_on_last = main_on
self.lkas_enabled_last = CC.latActive self.lkas_enabled_last = CC.latActive
self.steer_alert_last = steer_alert self.steer_alert_last = steer_alert
new_actuators = actuators.copy() new_actuators = actuators.copy()
new_actuators.steeringAngleDeg = apply_steer new_actuators.steeringAngleDeg = apply_angle
self.frame += 1 self.frame += 1
return new_actuators, can_sends return new_actuators, can_sends

@ -3,7 +3,7 @@ from common.conversions import Conversions as CV
from opendbc.can.can_define import CANDefine from opendbc.can.can_define import CANDefine
from opendbc.can.parser import CANParser from opendbc.can.parser import CANParser
from selfdrive.car.interfaces import CarStateBase from selfdrive.car.interfaces import CarStateBase
from selfdrive.car.ford.values import CANBUS, DBC from selfdrive.car.ford.values import CANBUS, DBC, CarControllerParams
GearShifter = car.CarState.GearShifter GearShifter = car.CarState.GearShifter
TransmissionType = car.CarParams.TransmissionType TransmissionType = car.CarParams.TransmissionType
@ -22,7 +22,7 @@ class CarState(CarStateBase):
# car speed # car speed
ret.vEgoRaw = cp.vl["EngVehicleSpThrottle2"]["Veh_V_ActlEng"] * CV.KPH_TO_MS ret.vEgoRaw = cp.vl["EngVehicleSpThrottle2"]["Veh_V_ActlEng"] * CV.KPH_TO_MS
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] * CV.RAD_TO_DEG ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"]
ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1
# gas pedal # gas pedal
@ -37,7 +37,7 @@ class CarState(CarStateBase):
# steering wheel # steering wheel
ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"]
ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"]
ret.steeringPressed = cp.vl["Lane_Assist_Data3_FD1"]["LaHandsOff_B_Actl"] == 0 ret.steeringPressed = abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE
ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1
ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3)
# ret.espDisabled = False # TODO: find traction control signal # ret.espDisabled = False # TODO: find traction control signal
@ -46,6 +46,8 @@ class CarState(CarStateBase):
ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * CV.MPH_TO_MS ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * CV.MPH_TO_MS
ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5)
ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5)
ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0
ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3
# gear # gear
if self.CP.transmissionType == TransmissionType.automatic: if self.CP.transmissionType == TransmissionType.automatic:
@ -65,6 +67,7 @@ class CarState(CarStateBase):
# button presses # button presses
ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1
ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2
# TODO: block this going to the camera otherwise it will enable stock TJA
ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"])
# lock info # lock info
@ -77,9 +80,13 @@ class CarState(CarStateBase):
ret.leftBlindspot = cp.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 ret.leftBlindspot = cp.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0
ret.rightBlindspot = cp.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 ret.rightBlindspot = cp.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0
# Stock steering buttons so that we can passthru blinkers etc.
self.buttons_stock_values = cp.vl["Steering_Data_FD1"]
# Stock values from IPMA so that we can retain some stock functionality # Stock values from IPMA so that we can retain some stock functionality
self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"]
self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"]
# Use stock sensor values
self.yaw_data = cp.vl["Yaw_Data_FD1"]
return ret return ret
@ -97,6 +104,8 @@ class CarState(CarStateBase):
("Veh_V_DsplyCcSet", "EngBrakeData"), # PCM ACC set speed (mph) ("Veh_V_DsplyCcSet", "EngBrakeData"), # PCM ACC set speed (mph)
# The units might change with IPC settings? # The units might change with IPC settings?
("CcStat_D_Actl", "EngBrakeData"), # PCM ACC status ("CcStat_D_Actl", "EngBrakeData"), # PCM ACC status
("AccStopMde_D_Rq", "EngBrakeData"), # PCM ACC standstill
("AccEnbl_B_RqDrv", "Cluster_Info1_FD1"), # PCM ACC enable
("StePinComp_An_Est", "SteeringPinion_Data"), # PSCM estimated steering angle (deg) ("StePinComp_An_Est", "SteeringPinion_Data"), # PSCM estimated steering angle (deg)
# Calculates steering angle (and offset) from pinion # Calculates steering angle (and offset) from pinion
# angle and driving measurements. # angle and driving measurements.
@ -104,7 +113,6 @@ class CarState(CarStateBase):
# to zero at the beginning of the drive. # to zero at the beginning of the drive.
("SteeringColumnTorque", "EPAS_INFO"), # PSCM steering column torque (Nm) ("SteeringColumnTorque", "EPAS_INFO"), # PSCM steering column torque (Nm)
("EPAS_Failure", "EPAS_INFO"), # PSCM EPAS status ("EPAS_Failure", "EPAS_INFO"), # PSCM EPAS status
("LaHandsOff_B_Actl", "Lane_Assist_Data3_FD1"), # PSCM LKAS hands off wheel
("TurnLghtSwtch_D_Stat", "Steering_Data_FD1"), # SCCM Turn signal switch ("TurnLghtSwtch_D_Stat", "Steering_Data_FD1"), # SCCM Turn signal switch
("TjaButtnOnOffPress", "Steering_Data_FD1"), # SCCM ACC button, lane-centering/traffic jam assist toggle ("TjaButtnOnOffPress", "Steering_Data_FD1"), # SCCM ACC button, lane-centering/traffic jam assist toggle
("DrStatDrv_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, driver ("DrStatDrv_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, driver
@ -112,6 +120,38 @@ class CarState(CarStateBase):
("DrStatRl_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear left ("DrStatRl_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear left
("DrStatRr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear right ("DrStatRr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear right
("FirstRowBuckleDriver", "RCMStatusMessage2_FD1"), # RCM Seatbelt status, driver ("FirstRowBuckleDriver", "RCMStatusMessage2_FD1"), # RCM Seatbelt status, driver
("HeadLghtHiFlash_D_Stat", "Steering_Data_FD1"), # SCCM Passthru the remaining buttons
("WiprFront_D_Stat", "Steering_Data_FD1"),
("LghtAmb_D_Sns", "Steering_Data_FD1"),
("AccButtnGapDecPress", "Steering_Data_FD1"),
("AccButtnGapIncPress", "Steering_Data_FD1"),
("AslButtnOnOffCnclPress", "Steering_Data_FD1"),
("AslButtnOnOffPress", "Steering_Data_FD1"),
("CcAslButtnCnclPress", "Steering_Data_FD1"),
("LaSwtchPos_D_Stat", "Steering_Data_FD1"),
("CcAslButtnCnclResPress", "Steering_Data_FD1"),
("CcAslButtnDeny_B_Actl", "Steering_Data_FD1"),
("CcAslButtnIndxDecPress", "Steering_Data_FD1"),
("CcAslButtnIndxIncPress", "Steering_Data_FD1"),
("CcAslButtnOffCnclPress", "Steering_Data_FD1"),
("CcAslButtnOnOffCncl", "Steering_Data_FD1"),
("CcAslButtnOnPress", "Steering_Data_FD1"),
("CcAslButtnResDecPress", "Steering_Data_FD1"),
("CcAslButtnResIncPress", "Steering_Data_FD1"),
("CcAslButtnSetDecPress", "Steering_Data_FD1"),
("CcAslButtnSetIncPress", "Steering_Data_FD1"),
("CcAslButtnSetPress", "Steering_Data_FD1"),
("CcAsllButtnResPress", "Steering_Data_FD1"),
("CcButtnOffPress", "Steering_Data_FD1"),
("CcButtnOnOffCnclPress", "Steering_Data_FD1"),
("CcButtnOnOffPress", "Steering_Data_FD1"),
("CcButtnOnPress", "Steering_Data_FD1"),
("HeadLghtHiFlash_D_Actl", "Steering_Data_FD1"),
("HeadLghtHiOn_B_StatAhb", "Steering_Data_FD1"),
("AhbStat_B_Dsply", "Steering_Data_FD1"),
("AccButtnGapTogglePress", "Steering_Data_FD1"),
("WiprFrontSwtch_D_Stat", "Steering_Data_FD1"),
("HeadLghtHiCtrl_D_RqAhb", "Steering_Data_FD1"),
] ]
checks = [ checks = [
@ -122,6 +162,7 @@ class CarState(CarStateBase):
("EngVehicleSpThrottle", 100), ("EngVehicleSpThrottle", 100),
("BrakeSnData_4", 50), ("BrakeSnData_4", 50),
("EngBrakeData", 10), ("EngBrakeData", 10),
("Cluster_Info1_FD1", 10),
("SteeringPinion_Data", 100), ("SteeringPinion_Data", 100),
("EPAS_INFO", 50), ("EPAS_INFO", 50),
("Lane_Assist_Data3_FD1", 33), ("Lane_Assist_Data3_FD1", 33),

@ -1,7 +1,10 @@
from common.numpy_fast import clip from cereal import car
from selfdrive.car.ford.values import CANBUS
HUDControl = car.CarControl.HUDControl
def create_lkas_command(packer, angle_deg: float, curvature: float):
def create_lka_command(packer, angle_deg: float, curvature: float):
""" """
Creates a CAN message for the Ford LKAS Command. Creates a CAN message for the Ford LKAS Command.
@ -20,7 +23,7 @@ def create_lkas_command(packer, angle_deg: float, curvature: float):
"LdwActvStats_D_Req": 0, # LDW status [0|7] "LdwActvStats_D_Req": 0, # LDW status [0|7]
"LdwActvIntns_D_Req": 0, # LDW intensity [0|3], shake alert strength "LdwActvIntns_D_Req": 0, # LDW intensity [0|3], shake alert strength
} }
return packer.make_can_msg("Lane_Assist_Data1", 0, values) return packer.make_can_msg("Lane_Assist_Data1", CANBUS.main, values)
def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path_offset: float, path_angle: float, curvature_rate: float, curvature: float): def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path_offset: float, path_angle: float, curvature_rate: float, curvature: float):
@ -43,15 +46,15 @@ def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path
"LatCtl_D_Rq": lca_rq, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, 3=InterventionRight, 4-7=NotUsed [0|7] "LatCtl_D_Rq": lca_rq, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, 3=InterventionRight, 4-7=NotUsed [0|7]
"LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] "LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3]
"LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] "LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3]
"LatCtlPathOffst_L_Actl": clip(path_offset, -5.12, 5.11), # Path offset [-5.12|5.11] meter "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter
"LatCtlPath_An_Actl": clip(path_angle, -0.5, 0.5235), # Path angle [-0.5|0.5235] radians "LatCtlPath_An_Actl": path_angle, # Path angle [-0.4995|0.5240] radians
"LatCtlCurv_NoRate_Actl": clip(curvature_rate, -0.001024, 0.00102375), # Curvature rate [-0.001024|0.00102375] 1/meter^2 "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2
"LatCtlCurv_No_Actl": clip(curvature, -0.02, 0.02094), # Curvature [-0.02|0.02094] 1/meter "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter
} }
return packer.make_can_msg("LateralMotionControl", 0, values) return packer.make_can_msg("LateralMotionControl", CANBUS.main, values)
def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, stock_values: dict): def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, hud_control, stock_values: dict):
""" """
Creates a CAN message for the Ford IPC IPMA/LKAS status. Creates a CAN message for the Ford IPC IPMA/LKAS status.
@ -63,23 +66,47 @@ def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bo
""" """
# LaActvStats_D_Dsply # LaActvStats_D_Dsply
# TODO: get LDW state from OP # R Intvn Warn Supprs Avail No
# L
# Intvn 24 19 14 9 4
# Warn 23 18 13 8 3
# Supprs 22 17 12 7 2
# Avail 21 16 11 6 1
# No 20 15 10 5 0
#
# TODO: test suppress state
if enabled: if enabled:
lines = 6 lines = 0 # NoLeft_NoRight
if hud_control.leftLaneDepart:
lines += 4
elif hud_control.leftLaneVisible:
lines += 1
if hud_control.rightLaneDepart:
lines += 20
elif hud_control.rightLaneVisible:
lines += 5
elif main_on: elif main_on:
lines = 0 lines = 0
else: else:
lines = 30 if hud_control.leftLaneDepart:
lines = 3 # WarnLeft_NoRight
elif hud_control.rightLaneDepart:
lines = 15 # NoLeft_WarnRight
else:
lines = 30 # LA_Off
# TODO: use level 1 for no sound when less severe?
hands_on_wheel_dsply = 2 if steer_alert else 0
values = { values = {
**stock_values, **stock_values,
"LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31]
"LaHandsOff_D_Dsply": 2 if steer_alert else 0, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed
} }
return packer.make_can_msg("IPMA_Data", 0, values) return packer.make_can_msg("IPMA_Data", CANBUS.main, values)
def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values: dict): def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, stock_values: dict):
""" """
Creates a CAN message for the Ford IPC adaptive cruise, forward collision Creates a CAN message for the Ford IPC adaptive cruise, forward collision
warning and traffic jam assist status. warning and traffic jam assist status.
@ -89,14 +116,32 @@ def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values: di
Frequency is 20Hz. Frequency is 20Hz.
""" """
# Tja_D_Stat
if enabled:
if hud_control.leftLaneDepart:
status = 3 # ActiveInterventionLeft
elif hud_control.rightLaneDepart:
status = 4 # ActiveInterventionRight
else:
status = 2 # Active
elif main_on:
if hud_control.leftLaneDepart:
status = 5 # ActiveWarningLeft
elif hud_control.rightLaneDepart:
status = 6 # ActiveWarningRight
else:
status = 1 # Standby
else:
status = 0 # Off
values = { values = {
**stock_values, **stock_values,
"Tja_D_Stat": 2 if enabled else (1 if main_on else 0), # TJA status: 0=Off, 1=Standby, 2=Active, 3=InterventionLeft, 4=InterventionRight, 5=WarningLeft, 6=WarningRight, 7=NotUsed [0|7] "Tja_D_Stat": status,
} }
return packer.make_can_msg("ACCDATA_3", 0, values) return packer.make_can_msg("ACCDATA_3", CANBUS.main, values)
def spam_cancel_button(packer, cancel=1): def create_button_command(packer, stock_values: dict, cancel = False, resume = False, tja_toggle = False, bus = CANBUS.camera):
""" """
Creates a CAN message for the Ford SCCM buttons/switches. Creates a CAN message for the Ford SCCM buttons/switches.
@ -104,6 +149,9 @@ def spam_cancel_button(packer, cancel=1):
""" """
values = { values = {
"CcAslButtnCnclPress": cancel, # CC cancel button **stock_values,
"CcAslButtnCnclPress": 1 if cancel else 0, # CC cancel button
"CcAsllButtnResPress": 1 if resume else 0, # CC resume button
"TjaButtnOnOffPress": 1 if tja_toggle else 0, # TJA toggle button
} }
return packer.make_can_msg("Steering_Data_FD1", 0, values) return packer.make_can_msg("Steering_Data_FD1", bus, values)

@ -1,8 +1,8 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
from cereal import car from cereal import car
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config
from selfdrive.car.ford.values import CAR, TransmissionType, GearShifter from selfdrive.car.ford.values import CAR, Ecu, TransmissionType, GearShifter
from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.interfaces import CarInterfaceBase
@ -12,59 +12,59 @@ EventName = car.CarEvent.EventName
class CarInterface(CarInterfaceBase): class CarInterface(CarInterfaceBase):
@staticmethod @staticmethod
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False): def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False):
if car_fw is None:
car_fw = []
ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
ret.carName = "ford" ret.carName = "ford"
#ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)]
ret.dashcamOnly = True ret.dashcamOnly = True
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)]
# Angle-based steering # Angle-based steering
# TODO: use curvature control when ready
ret.steerControlType = car.CarParams.SteerControlType.angle ret.steerControlType = car.CarParams.SteerControlType.angle
ret.steerActuatorDelay = 0.1 ret.steerActuatorDelay = 0.4
ret.steerLimitTimer = 1.0 ret.steerLimitTimer = 1.0
tire_stiffness_factor = 1.0
# TODO: detect stop-and-go vehicles
stop_and_go = False
if candidate == CAR.ESCAPE_MK4: if candidate == CAR.ESCAPE_MK4:
ret.wheelbase = 2.71 ret.wheelbase = 2.71
ret.steerRatio = 14.3 # Copied from Focus ret.steerRatio = 14.3 # Copied from Focus
tire_stiffness_factor = 0.5328 # Copied from Focus
ret.mass = 1750 + STD_CARGO_KG ret.mass = 1750 + STD_CARGO_KG
elif candidate == CAR.EXPLORER_MK6:
ret.wheelbase = 3.025
ret.steerRatio = 16.8 # learned
ret.mass = 2050 + STD_CARGO_KG
elif candidate == CAR.FOCUS_MK4: elif candidate == CAR.FOCUS_MK4:
ret.wheelbase = 2.7 ret.wheelbase = 2.7
ret.steerRatio = 14.3 ret.steerRatio = 13.8 # learned
tire_stiffness_factor = 0.5328
ret.mass = 1350 + STD_CARGO_KG ret.mass = 1350 + STD_CARGO_KG
else: else:
raise ValueError(f"Unsupported car: ${candidate}") raise ValueError(f"Unsupported car: ${candidate}")
# Auto Transmission: Gear_Shift_by_Wire_FD1 # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1
# TODO: detect transmission in car_fw? found_ecus = [fw.ecu for fw in car_fw]
if 0x5A in fingerprint[0]: if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[0]:
ret.transmissionType = TransmissionType.automatic ret.transmissionType = TransmissionType.automatic
else: else:
ret.transmissionType = TransmissionType.manual ret.transmissionType = TransmissionType.manual
ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS
# BSM: Side_Detect_L_Stat, Side_Detect_R_Stat # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat
# TODO: detect bsm in car_fw? # TODO: detect bsm in car_fw?
ret.enableBsm = 0x3A6 in fingerprint[0] and 0x3A7 in fingerprint[0] ret.enableBsm = 0x3A6 in fingerprint[0] and 0x3A7 in fingerprint[0]
# min speed to enable ACC. if car can do stop and go, then set enabling speed
# to a negative value, so it won't matter.
ret.minEnableSpeed = -1. if (stop_and_go) else 20. * CV.MPH_TO_MS
# LCA can steer down to zero # LCA can steer down to zero
ret.minSteerSpeed = 0. ret.minSteerSpeed = 0.
ret.centerToFront = ret.wheelbase * 0.44 ret.autoResumeSng = ret.minEnableSpeed == -1.
ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase)
ret.centerToFront = ret.wheelbase * 0.44
ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront,
tire_stiffness_factor=tire_stiffness_factor) tire_stiffness_factor=tire_stiffness_factor)
return ret return ret
def _update(self, c): def _update(self, c):

@ -1,9 +1,12 @@
from collections import namedtuple from collections import namedtuple
from dataclasses import dataclass
from enum import Enum
from typing import Dict, List, Union from typing import Dict, List, Union
from cereal import car from cereal import car
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo from selfdrive.car.docs_definitions import CarInfo, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
TransmissionType = car.CarParams.TransmissionType TransmissionType = car.CarParams.TransmissionType
@ -20,8 +23,11 @@ class CarControllerParams:
# Message: ACCDATA_3 # Message: ACCDATA_3
ACC_UI_STEP = 5 ACC_UI_STEP = 5
STEER_RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15]) STEER_RATIO = 2.75
STEER_RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) STEER_DRIVER_ALLOWANCE = 0.8
RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15])
RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4])
class RADAR: class RADAR:
@ -37,14 +43,40 @@ class CANBUS:
class CAR: class CAR:
ESCAPE_MK4 = "FORD ESCAPE 4TH GEN" ESCAPE_MK4 = "FORD ESCAPE 4TH GEN"
EXPLORER_MK6 = "FORD EXPLORER 6TH GEN"
FOCUS_MK4 = "FORD FOCUS 4TH GEN" FOCUS_MK4 = "FORD FOCUS 4TH GEN"
@dataclass
class FordCarInfo(CarInfo):
package: str = "Co-Pilot360 Assist+"
harness: Enum = Harness.ford_q3
CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = {
CAR.ESCAPE_MK4: CarInfo("Ford Escape", "NA"), CAR.ESCAPE_MK4: [
CAR.FOCUS_MK4: CarInfo("Ford Focus", "NA"), FordCarInfo("Ford Escape 2020"),
FordCarInfo("Ford Kuga EU", "Driver Assistance Pack"),
],
CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-21"),
CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"),
} }
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST],
[StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine],
),
Request(
[StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST],
[StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE],
bus=0,
whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.ESCAPE_MK4: { CAR.ESCAPE_MK4: {
@ -63,6 +95,33 @@ FW_VERSIONS = {
(Ecu.engine, 0x7E0, None): [ (Ecu.engine, 0x7E0, None): [
b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00',
], ],
(Ecu.shiftByWire, 0x732, None): [
],
},
CAR.EXPLORER_MK6: {
(Ecu.eps, 0x730, None): [
b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x760, None): [
b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x764, None): [
b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x706, None): [
b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x7E0, None): [
b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.shiftByWire, 0x732, None): [
b'L1MP-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MP-14G395-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
}, },
CAR.FOCUS_MK4: { CAR.FOCUS_MK4: {
(Ecu.eps, 0x730, None): [ (Ecu.eps, 0x730, None): [
@ -80,11 +139,14 @@ FW_VERSIONS = {
(Ecu.engine, 0x7E0, None): [ (Ecu.engine, 0x7E0, None): [
b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00',
], ],
(Ecu.shiftByWire, 0x732, None): [
],
}, },
} }
DBC = { DBC = {
CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR),
CAR.EXPLORER_MK6: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR),
CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR),
} }

@ -0,0 +1,66 @@
#!/usr/bin/env python3
import capnp
from dataclasses import dataclass, field
import struct
from typing import Dict, List
import panda.python.uds as uds
def p16(val):
return struct.pack("!H", val)
class StdQueries:
# FW queries
TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0])
TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0])
SHORT_TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT])
SHORT_TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40])
DEFAULT_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL,
uds.SESSION_TYPE.DEFAULT])
DEFAULT_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40,
uds.SESSION_TYPE.DEFAULT, 0x0, 0x32, 0x1, 0xf4])
EXTENDED_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL,
uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC])
EXTENDED_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40,
uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC, 0x0, 0x32, 0x1, 0xf4])
MANUFACTURER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
MANUFACTURER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION)
UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION)
OBD_VERSION_REQUEST = b'\x09\x04'
OBD_VERSION_RESPONSE = b'\x49\x04'
# VIN queries
OBD_VIN_REQUEST = b'\x09\x02'
OBD_VIN_RESPONSE = b'\x49\x02\x01'
UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN)
UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN)
@dataclass
class Request:
request: List[bytes]
response: List[bytes]
whitelist_ecus: List[int] = field(default_factory=list)
rx_offset: int = 0x8
bus: int = 1
@dataclass
class FwQueryConfig:
requests: List[Request]
# Overrides and removes from essential ecus for specific models and ecus (exact matching)
non_essential_ecus: Dict[capnp.lib.capnp._EnumModule, List[str]] = field(default_factory=dict)

@ -1,9 +1,7 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import struct
import traceback import traceback
from collections import defaultdict from collections import defaultdict
from dataclasses import dataclass, field from typing import Any, Optional, Set, Tuple
from typing import Any, List, Optional, Set, Tuple
from tqdm import tqdm from tqdm import tqdm
import panda.python.uds as uds import panda.python.uds as uds
@ -12,237 +10,16 @@ from selfdrive.car.ecu_addrs import get_ecu_addrs
from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.interfaces import get_interface_attr
from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.fingerprints import FW_VERSIONS
from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery
from selfdrive.car.toyota.values import CAR as TOYOTA
from system.swaglog import cloudlog from system.swaglog import cloudlog
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa]
FW_QUERY_CONFIGS = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True)
VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True)
def p16(val): MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e}
return struct.pack("!H", val) REQUESTS = [(brand, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests]
TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0])
TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0])
SHORT_TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT])
SHORT_TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40])
DEFAULT_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL,
uds.SESSION_TYPE.DEFAULT])
DEFAULT_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40,
uds.SESSION_TYPE.DEFAULT, 0x0, 0x32, 0x1, 0xf4])
EXTENDED_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL,
uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC])
EXTENDED_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40,
uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC, 0x0, 0x32, 0x1, 0xf4])
UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION)
UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION)
HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(0xf100) # Long description
HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \
p16(0xf100)
HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40])
TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01'
TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01'
VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40])
OBD_VERSION_REQUEST = b'\x09\x04'
OBD_VERSION_RESPONSE = b'\x49\x04'
DEFAULT_RX_OFFSET = 0x8
VOLKSWAGEN_RX_OFFSET = 0x6a
MAZDA_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
MAZDA_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xc0])
NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xc0])
NISSAN_VERSION_REQUEST_KWP = b'\x21\x83'
NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83'
NISSAN_VERSION_REQUEST_STANDARD = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
NISSAN_VERSION_RESPONSE_STANDARD = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
NISSAN_RX_OFFSET = 0x20
SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(0xf132)
CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(0xf132)
CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER)
CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER)
CHRYSLER_RX_OFFSET = -0x280
FORD_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
FORD_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
@dataclass
class Request:
brand: str
request: List[bytes]
response: List[bytes]
whitelist_ecus: List[int] = field(default_factory=list)
rx_offset: int = DEFAULT_RX_OFFSET
bus: int = 1
REQUESTS: List[Request] = [
# Subaru
Request(
"subaru",
[TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST],
[TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE],
),
# Hyundai
Request(
"hyundai",
[HYUNDAI_VERSION_REQUEST_LONG],
[HYUNDAI_VERSION_RESPONSE],
),
Request(
"hyundai",
[HYUNDAI_VERSION_REQUEST_MULTI],
[HYUNDAI_VERSION_RESPONSE],
),
# Honda
Request(
"honda",
[UDS_VERSION_REQUEST],
[UDS_VERSION_RESPONSE],
),
# Toyota
Request(
"toyota",
[SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST],
[SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE],
bus=0,
),
Request(
"toyota",
[SHORT_TESTER_PRESENT_REQUEST, OBD_VERSION_REQUEST],
[SHORT_TESTER_PRESENT_RESPONSE, OBD_VERSION_RESPONSE],
bus=0,
),
Request(
"toyota",
[TESTER_PRESENT_REQUEST, DEFAULT_DIAGNOSTIC_REQUEST, EXTENDED_DIAGNOSTIC_REQUEST, UDS_VERSION_REQUEST],
[TESTER_PRESENT_RESPONSE, DEFAULT_DIAGNOSTIC_RESPONSE, EXTENDED_DIAGNOSTIC_RESPONSE, UDS_VERSION_RESPONSE],
bus=0,
),
# Volkswagen
Request(
"volkswagen",
[VOLKSWAGEN_VERSION_REQUEST_MULTI],
[VOLKSWAGEN_VERSION_RESPONSE],
whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar],
rx_offset=VOLKSWAGEN_RX_OFFSET,
),
Request(
"volkswagen",
[VOLKSWAGEN_VERSION_REQUEST_MULTI],
[VOLKSWAGEN_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine, Ecu.transmission],
),
# Mazda
Request(
"mazda",
[MAZDA_VERSION_REQUEST],
[MAZDA_VERSION_RESPONSE],
),
# Nissan
Request(
"nissan",
[NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP],
[NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP],
),
Request(
"nissan",
[NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP],
[NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP],
rx_offset=NISSAN_RX_OFFSET,
),
Request(
"nissan",
[NISSAN_VERSION_REQUEST_STANDARD],
[NISSAN_VERSION_RESPONSE_STANDARD],
rx_offset=NISSAN_RX_OFFSET,
),
# Body
Request(
"body",
[TESTER_PRESENT_REQUEST, UDS_VERSION_REQUEST],
[TESTER_PRESENT_RESPONSE, UDS_VERSION_RESPONSE],
bus=0,
),
# Chrysler / FCA / Stellantis
Request(
"chrysler",
[CHRYSLER_VERSION_REQUEST],
[CHRYSLER_VERSION_RESPONSE],
whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter],
rx_offset=CHRYSLER_RX_OFFSET,
),
Request(
"chrysler",
[CHRYSLER_VERSION_REQUEST],
[CHRYSLER_VERSION_RESPONSE],
whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission],
),
Request(
"chrysler",
[CHRYSLER_SOFTWARE_VERSION_REQUEST],
[CHRYSLER_SOFTWARE_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine, Ecu.transmission],
),
# Ford
Request(
"ford",
[TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST],
[TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine],
),
Request(
"ford",
[TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST],
[TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE],
bus=0,
whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera],
),
]
def chunks(l, n=128): def chunks(l, n=128):
@ -261,9 +38,8 @@ def build_fw_dict(fw_versions, filter_brand=None):
def get_brand_addrs(): def get_brand_addrs():
versions = get_interface_attr('FW_VERSIONS', ignore_none=True)
brand_addrs = defaultdict(set) brand_addrs = defaultdict(set)
for brand, cars in versions.items(): for brand, cars in VERSIONS.items():
for fw in cars.values(): for fw in cars.values():
brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in fw.keys()} brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in fw.keys()}
return brand_addrs return brand_addrs
@ -325,18 +101,18 @@ def match_fw_to_car_exact(fw_versions_dict):
for candidate, fws in candidates.items(): for candidate, fws in candidates.items():
for ecu, expected_versions in fws.items(): for ecu, expected_versions in fws.items():
config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]]
ecu_type = ecu[0] ecu_type = ecu[0]
addr = ecu[1:] addr = ecu[1:]
found_versions = fw_versions_dict.get(addr, set())
if ecu_type == Ecu.abs and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions):
continue
# On some Toyota models, the engine can show on two different addresses found_versions = fw_versions_dict.get(addr, set())
if ecu_type == Ecu.engine and candidate in (TOYOTA.CAMRY, TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS) and not len(found_versions): if not len(found_versions):
# Some models can sometimes miss an ecu, or show on two different addresses
if candidate in config.non_essential_ecus.get(ecu_type, []):
continue continue
# Ignore non essential ecus # Ignore non essential ecus
if ecu_type not in ESSENTIAL_ECUS and not len(found_versions): if ecu_type not in ESSENTIAL_ECUS:
continue continue
# Virtual debug ecu doesn't need to match the database # Virtual debug ecu doesn't need to match the database
@ -358,11 +134,10 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True):
if allow_fuzzy: if allow_fuzzy:
exact_matches.append((False, match_fw_to_car_fuzzy)) exact_matches.append((False, match_fw_to_car_fuzzy))
brands = get_interface_attr('FW_VERSIONS', ignore_none=True).keys()
for exact_match, match_func in exact_matches: for exact_match, match_func in exact_matches:
# For each brand, attempt to fingerprint using all FW returned from its queries # For each brand, attempt to fingerprint using all FW returned from its queries
matches = set() matches = set()
for brand in brands: for brand in VERSIONS.keys():
fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand)
matches |= match_func(fw_versions_dict) matches |= match_func(fw_versions_dict)
@ -376,13 +151,9 @@ def get_present_ecus(logcan, sendcan):
queries = list() queries = list()
parallel_queries = list() parallel_queries = list()
responses = set() responses = set()
versions = get_interface_attr('FW_VERSIONS', ignore_none=True)
for r in REQUESTS:
if r.brand not in versions:
continue
for brand_versions in versions[r.brand].values(): for brand, r in REQUESTS:
for brand_versions in VERSIONS[brand].values():
for ecu_type, addr, sub_addr in brand_versions: for ecu_type, addr, sub_addr in brand_versions:
# Only query ecus in whitelist if whitelist is not empty # Only query ecus in whitelist if whitelist is not empty
if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus:
@ -411,9 +182,9 @@ def get_brand_ecu_matches(ecu_rx_addrs):
"""Returns dictionary of brands and matches with ECUs in their FW versions""" """Returns dictionary of brands and matches with ECUs in their FW versions"""
brand_addrs = get_brand_addrs() brand_addrs = get_brand_addrs()
brand_matches = {r.brand: set() for r in REQUESTS} brand_matches = {brand: set() for brand, _ in REQUESTS}
brand_rx_offsets = set((r.brand, r.rx_offset) for r in REQUESTS) brand_rx_offsets = set((brand, r.rx_offset) for brand, r in REQUESTS)
for addr, sub_addr, _ in ecu_rx_addrs: for addr, sub_addr, _ in ecu_rx_addrs:
# Since we can't know what request an ecu responded to, add matches for all possible rx offsets # Since we can't know what request an ecu responded to, add matches for all possible rx offsets
for brand, rx_offset in brand_rx_offsets: for brand, rx_offset in brand_rx_offsets:
@ -442,7 +213,7 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa
def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False): def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False):
versions = get_interface_attr('FW_VERSIONS', ignore_none=True) versions = VERSIONS.copy()
if query_brand is not None: if query_brand is not None:
versions = {query_brand: versions[query_brand]} versions = {query_brand: versions[query_brand]}
@ -473,12 +244,12 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
# Get versions and build capnp list to put into CarParams # Get versions and build capnp list to put into CarParams
car_fw = [] car_fw = []
requests = [r for r in REQUESTS if query_brand is None or r.brand == query_brand] requests = [(brand, r) for brand, r in REQUESTS if query_brand is None or brand == query_brand]
for addr in tqdm(addrs, disable=not progress): for addr in tqdm(addrs, disable=not progress):
for addr_chunk in chunks(addr): for addr_chunk in chunks(addr):
for r in requests: for brand, r in requests:
try: try:
addrs = [(a, s) for (b, a, s) in addr_chunk if b in (r.brand, 'any') and addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and
(len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)]
if addrs: if addrs:
@ -486,12 +257,12 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
for (addr, rx_addr), version in query.get_data(timeout).items(): for (addr, rx_addr), version in query.get_data(timeout).items():
f = car.CarParams.CarFw.new_message() f = car.CarParams.CarFw.new_message()
f.ecu = ecu_types.get((r.brand, addr[0], addr[1]), Ecu.unknown) f.ecu = ecu_types.get((brand, addr[0], addr[1]), Ecu.unknown)
f.fwVersion = version f.fwVersion = version
f.address = addr[0] f.address = addr[0]
f.responseAddress = rx_addr f.responseAddress = rx_addr
f.request = r.request f.request = r.request
f.brand = r.brand f.brand = brand
f.bus = r.bus f.bus = r.bus
if addr[1] is not None: if addr[1] is not None:

@ -6,6 +6,7 @@ from cereal import car
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
VisualAlert = car.CarControl.HUDControl.VisualAlert VisualAlert = car.CarControl.HUDControl.VisualAlert
@ -142,6 +143,14 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = {
CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
} }
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.UDS_VERSION_REQUEST],
[StdQueries.UDS_VERSION_RESPONSE],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.ACCORD: { CAR.ACCORD: {

@ -28,7 +28,7 @@ class CarInterface(CarInterfaceBase):
ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None
# WARNING: disabling radar also disables AEB (and we show the same warning on the instrument cluster as if you manually disabled AEB) # WARNING: disabling radar also disables AEB (and we show the same warning on the instrument cluster as if you manually disabled AEB)
ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR | CANFD_CAR)
ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable
ret.pcmCruise = not ret.openpilotLongitudinalControl ret.pcmCruise = not ret.openpilotLongitudinalControl

@ -3,9 +3,12 @@ from dataclasses import dataclass
from typing import Dict, List, Optional, Union from typing import Dict, List, Optional, Union
from cereal import car from cereal import car
from panda.python import uds
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness from selfdrive.car.docs_definitions import CarInfo, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -272,6 +275,26 @@ FINGERPRINTS = {
}], }],
} }
HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(0xf100) # Long description
HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \
p16(0xf100)
HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40])
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[HYUNDAI_VERSION_REQUEST_LONG],
[HYUNDAI_VERSION_RESPONSE],
),
Request(
[HYUNDAI_VERSION_REQUEST_MULTI],
[HYUNDAI_VERSION_RESPONSE],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.IONIQ: { CAR.IONIQ: {
@ -1273,6 +1296,7 @@ FW_VERSIONS = {
}, },
CAR.KIA_EV6: { CAR.KIA_EV6: {
(Ecu.abs, 0x7d1, None): [ (Ecu.abs, 0x7d1, None): [
b'\xf1\x00CV IEB \x03 101!\x10\x18 58520-CV100',
b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100',
], ],
(Ecu.eps, 0x7d4, None): [ (Ecu.eps, 0x7d4, None): [
@ -1284,6 +1308,7 @@ FW_VERSIONS = {
], ],
(Ecu.fwdCamera, 0x7c4, None): [ (Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027',
b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027',
], ],
}, },
CAR.IONIQ_5: { CAR.IONIQ_5: {

@ -2,9 +2,11 @@ from dataclasses import dataclass
from enum import Enum from enum import Enum
from typing import Dict, List, Union from typing import Dict, List, Union
from cereal import car
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness from selfdrive.car.docs_definitions import CarInfo, Harness
from cereal import car from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -50,6 +52,7 @@ class LKAS_LIMITS:
DISABLE_SPEED = 45 # kph DISABLE_SPEED = 45 # kph
ENABLE_SPEED = 52 # kph ENABLE_SPEED = 52 # kph
class Buttons: class Buttons:
NONE = 0 NONE = 0
SET_PLUS = 1 SET_PLUS = 1
@ -58,6 +61,15 @@ class Buttons:
CANCEL = 4 CANCEL = 4
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST],
[StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.CX5_2022: { CAR.CX5_2022: {
(Ecu.eps, 0x730, None): [ (Ecu.eps, 0x730, None): [

@ -2,9 +2,12 @@ from dataclasses import dataclass
from typing import Dict, List, Optional, Union from typing import Dict, List, Optional, Union
from enum import Enum from enum import Enum
from cereal import car
from panda.python import uds
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness from selfdrive.car.docs_definitions import CarInfo, Harness
from cereal import car from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -75,6 +78,33 @@ FINGERPRINTS = {
] ]
} }
NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xc0])
NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xc0])
NISSAN_VERSION_REQUEST_KWP = b'\x21\x83'
NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83'
NISSAN_RX_OFFSET = 0x20
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP],
[NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP],
),
Request(
[NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP],
[NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP],
rx_offset=NISSAN_RX_OFFSET,
),
Request(
[StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST],
[StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE],
rx_offset=NISSAN_RX_OFFSET,
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.ALTIMA: { CAR.ALTIMA: {
(Ecu.fwdCamera, 0x707, None): [ (Ecu.fwdCamera, 0x707, None): [

@ -2,9 +2,11 @@ from dataclasses import dataclass
from enum import Enum from enum import Enum
from typing import Dict, List, Union from typing import Dict, List, Union
from cereal import car
from panda.python import uds
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness from selfdrive.car.docs_definitions import CarInfo, Harness
from cereal import car from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -71,6 +73,19 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = {
CAR.OUTBACK_PREGLOBAL_2018: SubaruCarInfo("Subaru Outback 2018-19"), CAR.OUTBACK_PREGLOBAL_2018: SubaruCarInfo("Subaru Outback 2018-19"),
} }
SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST],
[StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.ASCENT: { CAR.ASCENT: {
@ -89,6 +104,7 @@ FW_VERSIONS = {
b'\000\000e~\037@ \'', b'\000\000e~\037@ \'',
b'\x00\x00e@\x1f@ $', b'\x00\x00e@\x1f@ $',
b'\x00\x00d\xb9\x00\x00\x00\x00', b'\x00\x00d\xb9\x00\x00\x00\x00',
b'\x00\x00e@\x00\x00\x00\x00',
], ],
(Ecu.engine, 0x7e0, None): [ (Ecu.engine, 0x7e0, None): [
b'\xbb,\xa0t\a', b'\xbb,\xa0t\a',
@ -96,11 +112,13 @@ FW_VERSIONS = {
b'\xf1\x82\xbb,\xa0t\a', b'\xf1\x82\xbb,\xa0t\a',
b'\xf1\x82\xd9,\xa0@\a', b'\xf1\x82\xd9,\xa0@\a',
b'\xf1\x82\xd1,\xa0q\x07', b'\xf1\x82\xd1,\xa0q\x07',
b'\xd1,\xa0q\x07',
], ],
(Ecu.transmission, 0x7e1, None): [ (Ecu.transmission, 0x7e1, None): [
b'\x00\xfe\xf7\x00\x00', b'\x00\xfe\xf7\x00\x00',
b'\001\xfe\xf9\000\000', b'\001\xfe\xf9\000\000',
b'\x01\xfe\xf7\x00\x00', b'\x01\xfe\xf7\x00\x00',
b'\x01\xfe\xfa\x00\x00',
], ],
}, },
CAR.LEGACY: { CAR.LEGACY: {

@ -22,7 +22,7 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = {
FINGERPRINTS = { FINGERPRINTS = {
CAR.AP2_MODELS: [ CAR.AP2_MODELS: [
{ {
1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 6, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2015: 8, 2043: 5, 2045: 4 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 538: 8, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 576: 3, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 7, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1625: 8, 1665: 8, 1792: 8, 1798: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1825: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1842: 8, 1848: 8, 1864: 8, 1872: 8, 1880: 8, 1888: 8, 1892: 8, 1896: 8, 1912: 8, 1937: 8, 1953: 8, 1960: 8, 1968: 8, 1992: 8, 2001: 8, 2008: 3, 2015: 8, 2016: 8, 2043: 5, 2045: 4
}, },
], ],
CAR.AP1_MODELS: [ CAR.AP1_MODELS: [

@ -41,13 +41,14 @@ routes = [
CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500),
CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6),
CarTestRoute("62241b0c7fea4589|2022-09-01--15-32-49", FORD.EXPLORER_MK6),
#TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION), #TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION),
CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA),
CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL),
CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV),
CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT),
CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV, segment=1),
CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO),
CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G),

@ -6,7 +6,7 @@ from parameterized import parameterized
from cereal import car from cereal import car
from selfdrive.car.car_helpers import get_interface_attr, interfaces from selfdrive.car.car_helpers import get_interface_attr, interfaces
from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.fingerprints import FW_VERSIONS
from selfdrive.car.fw_versions import REQUESTS, match_fw_to_car from selfdrive.car.fw_versions import FW_QUERY_CONFIGS, match_fw_to_car
CarFw = car.CarParams.CarFw CarFw = car.CarParams.CarFw
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
@ -59,14 +59,25 @@ class TestFwFingerprint(unittest.TestCase):
for ecu in ecus.keys(): for ecu in ecus.keys():
self.assertNotEqual(ecu[0], Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})") self.assertNotEqual(ecu[0], Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})")
def test_missing_versions_and_configs(self):
brand_versions = set(VERSIONS.keys())
brand_configs = set(FW_QUERY_CONFIGS.keys())
if len(brand_configs - brand_versions):
with self.subTest():
self.fail(f"Brands do not implement FW_VERSIONS: {brand_configs - brand_versions}")
if len(brand_versions - brand_configs):
with self.subTest():
self.fail(f"Brands do not implement FW_QUERY_CONFIG: {brand_versions - brand_configs}")
def test_fw_request_ecu_whitelist(self): def test_fw_request_ecu_whitelist(self):
for brand in set(r.brand for r in REQUESTS): for brand, config in FW_QUERY_CONFIGS.items():
with self.subTest(brand=brand): with self.subTest(brand=brand):
whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] whitelisted_ecus = set([ecu for r in config.requests for ecu in r.whitelist_ecus])
brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw]) brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw])
# each ecu in brand's fw versions needs to be whitelisted at least once # each ecu in brand's fw versions needs to be whitelisted at least once
ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) ecus_not_whitelisted = brand_ecus - whitelisted_ecus
ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted])
self.assertFalse(len(whitelisted_ecus) and len(ecus_not_whitelisted), self.assertFalse(len(whitelisted_ecus) and len(ecus_not_whitelisted),

@ -234,7 +234,7 @@ class TestCarModelBase(unittest.TestCase):
checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev()
checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available
if self.CP.carName in ("honda", "toyota"): if self.CP.carName not in ("hyundai", "volkswagen", "subaru", "gm", "body"):
# TODO: fix standstill mismatches for other makes # TODO: fix standstill mismatches for other makes
checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving() checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving()
@ -243,7 +243,8 @@ class TestCarModelBase(unittest.TestCase):
if CS.brakePressed and not self.safety.get_brake_pressed_prev(): if CS.brakePressed and not self.safety.get_brake_pressed_prev():
if self.CP.carFingerprint in (HONDA.PILOT, HONDA.PASSPORT, HONDA.RIDGELINE) and CS.brake > 0.05: if self.CP.carFingerprint in (HONDA.PILOT, HONDA.PASSPORT, HONDA.RIDGELINE) and CS.brake > 0.05:
brake_pressed = False brake_pressed = False
checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev() safety_brake_pressed = self.safety.get_brake_pressed_prev() or self.safety.get_regen_braking_prev()
checks['brakePressed'] += brake_pressed != safety_brake_pressed
if self.CP.pcmCruise: if self.CP.pcmCruise:
# On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state. # On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state.

@ -13,6 +13,7 @@ TESLA AP2 MODEL S: [.nan, 2.5, .nan]
# Guess # Guess
FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan] FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan]
FORD EXPLORER 6TH GEN: [.nan, 1.5, .nan]
FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] FORD FOCUS 4TH GEN: [.nan, 1.5, .nan]
### ###

@ -230,10 +230,9 @@ class CarInterface(CarInterfaceBase):
# to a negative value, so it won't matter. # to a negative value, so it won't matter.
ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED
if ret.enableGasInterceptor: if candidate in TSS2_CAR or ret.enableGasInterceptor:
set_long_tune(ret.longitudinalTuning, LongTunes.PEDAL)
elif candidate in TSS2_CAR:
set_long_tune(ret.longitudinalTuning, LongTunes.TSS2) set_long_tune(ret.longitudinalTuning, LongTunes.TSS2)
if candidate in TSS2_CAR:
ret.stoppingDecelRate = 0.3 # reach stopping target smoothly ret.stoppingDecelRate = 0.3 # reach stopping target smoothly
else: else:
set_long_tune(ret.longitudinalTuning, LongTunes.TSS) set_long_tune(ret.longitudinalTuning, LongTunes.TSS)

@ -2,9 +2,8 @@
from enum import Enum from enum import Enum
class LongTunes(Enum): class LongTunes(Enum):
PEDAL = 0 TSS2 = 0
TSS2 = 1 TSS = 1
TSS = 2
class LatTunes(Enum): class LatTunes(Enum):
INDI_PRIUS = 0 INDI_PRIUS = 0
@ -28,7 +27,7 @@ class LatTunes(Enum):
###### LONG ###### ###### LONG ######
def set_long_tune(tune, name): def set_long_tune(tune, name):
# Improved longitudinal tune # Improved longitudinal tune
if name == LongTunes.TSS2 or name == LongTunes.PEDAL: if name == LongTunes.TSS2:
tune.deadzoneBP = [0., 8.05] tune.deadzoneBP = [0., 8.05]
tune.deadzoneV = [.0, .14] tune.deadzoneV = [.0, .14]
tune.kpBP = [0., 5., 20.] tune.kpBP = [0., 5., 20.]

@ -7,6 +7,7 @@ from cereal import car
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
MIN_ACC_SPEED = 19. * CV.MPH_TO_MS MIN_ACC_SPEED = 19. * CV.MPH_TO_MS
@ -198,6 +199,35 @@ STATIC_DSU_MSGS = [
(0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'),
] ]
TOYOTA_VERSION_REQUEST = b'\x1a\x88\x01'
TOYOTA_VERSION_RESPONSE = b'\x5a\x88\x01'
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST],
[StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE],
bus=0,
),
Request(
[StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST],
[StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE],
bus=0,
),
Request(
[StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST],
[StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE],
bus=0,
),
],
non_essential_ecus={
# FIXME: On some models, abs can sometimes be missing
Ecu.abs: [CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_IS],
# On some models, the engine can show on two different addresses
Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.LEXUS_IS],
}
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.AVALON: { CAR.AVALON: {
(Ecu.abs, 0x7b0, None): [ (Ecu.abs, 0x7b0, None): [
@ -511,13 +541,16 @@ FW_VERSIONS = {
CAR.CAMRYH_TSS2: { CAR.CAMRYH_TSS2: {
(Ecu.eps, 0x7a1, None): [ (Ecu.eps, 0x7a1, None): [
b'8965B33630\x00\x00\x00\x00\x00\x00', b'8965B33630\x00\x00\x00\x00\x00\x00',
b'8965B33650\x00\x00\x00\x00\x00\x00',
], ],
(Ecu.abs, 0x7b0, None): [ (Ecu.abs, 0x7b0, None): [
b'F152633D00\x00\x00\x00\x00\x00\x00', b'F152633D00\x00\x00\x00\x00\x00\x00',
b'F152633D60\x00\x00\x00\x00\x00\x00',
], ],
(Ecu.engine, 0x700, None): [ (Ecu.engine, 0x700, None): [
b'\x018966306Q6000\x00\x00\x00\x00', b'\x018966306Q6000\x00\x00\x00\x00',
b'\x018966306Q7000\x00\x00\x00\x00', b'\x018966306Q7000\x00\x00\x00\x00',
b'\x01896633T20000\x00\x00\x00\x00',
], ],
(Ecu.fwdRadar, 0x750, 15): [ (Ecu.fwdRadar, 0x750, 15): [
b'\x018821F6201200\x00\x00\x00\x00', b'\x018821F6201200\x00\x00\x00\x00',

@ -1,19 +1,12 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import re import re
import struct
import traceback import traceback
import cereal.messaging as messaging import cereal.messaging as messaging
import panda.python.uds as uds
from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery
from selfdrive.car.fw_query_definitions import StdQueries
from system.swaglog import cloudlog from system.swaglog import cloudlog
OBD_VIN_REQUEST = b'\x09\x02'
OBD_VIN_RESPONSE = b'\x49\x02\x01'
UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + struct.pack("!H", uds.DATA_IDENTIFIER_TYPE.VIN)
UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + struct.pack("!H", uds.DATA_IDENTIFIER_TYPE.VIN)
VIN_UNKNOWN = "0" * 17 VIN_UNKNOWN = "0" * 17
VIN_RE = "[A-HJ-NPR-Z0-9]{17}" VIN_RE = "[A-HJ-NPR-Z0-9]{17}"
@ -25,7 +18,7 @@ def is_valid_vin(vin: str):
def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False):
addrs = [0x7e0, 0x7e2, 0x18da10f1, 0x18da0ef1] # engine, VMCU, 29-bit engine, PGM-FI addrs = [0x7e0, 0x7e2, 0x18da10f1, 0x18da0ef1] # engine, VMCU, 29-bit engine, PGM-FI
for i in range(retry): for i in range(retry):
for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): for request, response in ((StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE), (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE)):
try: try:
query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, [request, ], [response, ], debug=debug) query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, [request, ], [response, ], debug=debug)
for (addr, rx_addr), vin in query.get_data(timeout).items(): for (addr, rx_addr), vin in query.get_data(timeout).items():

@ -18,6 +18,7 @@ class CarController:
self.packer_pt = CANPacker(dbc_name) self.packer_pt = CANPacker(dbc_name)
self.apply_steer_last = 0 self.apply_steer_last = 0
self.gra_acc_counter_last = None
self.frame = 0 self.frame = 0
self.hcaSameTorqueCount = 0 self.hcaSameTorqueCount = 0
self.hcaEnabledFrameCount = 0 self.hcaEnabledFrameCount = 0
@ -94,15 +95,15 @@ class CarController:
# **** Stock ACC Button Controls **************************************** # # **** Stock ACC Button Controls **************************************** #
if self.CP.pcmCruise and self.frame % self.CCP.GRA_ACC_STEP == 0: gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last
idx = (CS.gra_stock_values["COUNTER"] + 1) % 16 if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume):
if CC.cruiseControl.cancel: counter = (CS.gra_stock_values["COUNTER"] + 1) % 16
can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, idx, cancel=True)) can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, counter,
elif CC.cruiseControl.resume: cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume))
can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, ext_bus, CS.gra_stock_values, idx, resume=True))
new_actuators = actuators.copy() new_actuators = actuators.copy()
new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX
self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"]
self.frame += 1 self.frame += 1
return new_actuators, can_sends return new_actuators, can_sends

@ -26,11 +26,11 @@ def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pres
return packer.make_can_msg("LDW_02", bus, values) return packer.make_can_msg("LDW_02", bus, values)
def create_acc_buttons_control(packer, bus, gra_stock_values, idx, cancel=False, resume=False): def create_acc_buttons_control(packer, bus, gra_stock_values, counter, cancel=False, resume=False):
values = gra_stock_values.copy() values = gra_stock_values.copy()
values.update({ values.update({
"COUNTER": idx, "COUNTER": counter,
"GRA_Abbrechen": cancel, "GRA_Abbrechen": cancel,
"GRA_Tip_Wiederaufnahme": resume, "GRA_Tip_Wiederaufnahme": resume,
}) })

@ -23,11 +23,11 @@ def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pres
return packer.make_can_msg("LDW_Status", bus, values) return packer.make_can_msg("LDW_Status", bus, values)
def create_acc_buttons_control(packer, bus, gra_stock_values, idx, cancel=False, resume=False): def create_acc_buttons_control(packer, bus, gra_stock_values, counter, cancel=False, resume=False):
values = gra_stock_values.copy() values = gra_stock_values.copy()
values.update({ values.update({
"COUNTER": idx, "COUNTER": counter,
"GRA_Abbrechen": cancel, "GRA_Abbrechen": cancel,
"GRA_Recall": resume, "GRA_Recall": resume,
}) })

@ -4,9 +4,11 @@ from enum import Enum
from typing import Dict, List, Union from typing import Dict, List, Union
from cereal import car from cereal import car
from panda.python import uds
from opendbc.can.can_define import CANDefine from opendbc.can.can_define import CANDefine
from selfdrive.car import dbc_dict from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16
Ecu = car.CarParams.Ecu Ecu = car.CarParams.Ecu
NetworkLocation = car.CarParams.NetworkLocation NetworkLocation = car.CarParams.NetworkLocation
@ -17,7 +19,6 @@ Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values'])
class CarControllerParams: class CarControllerParams:
HCA_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz HCA_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz
GRA_ACC_STEP = 3 # GRA_ACC_01/GRA_Neu message frequency 33Hz
ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz
ACCEL_MAX = 2.0 # 2.0 m/s max acceleration ACCEL_MAX = 2.0 # 2.0 m/s max acceleration
@ -244,6 +245,30 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have # ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have
# them repaired by the tuner before including them in openpilot. # them repaired by the tuner before including them in openpilot.
VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \
p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION)
VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40])
VOLKSWAGEN_RX_OFFSET = 0x6a
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
[VOLKSWAGEN_VERSION_REQUEST_MULTI],
[VOLKSWAGEN_VERSION_RESPONSE],
whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar],
rx_offset=VOLKSWAGEN_RX_OFFSET,
),
Request(
[VOLKSWAGEN_VERSION_REQUEST_MULTI],
[VOLKSWAGEN_VERSION_RESPONSE],
whitelist_ecus=[Ecu.engine, Ecu.transmission],
),
],
)
FW_VERSIONS = { FW_VERSIONS = {
CAR.ARTEON_MK1: { CAR.ARTEON_MK1: {
(Ecu.engine, 0x7e0, None): [ (Ecu.engine, 0x7e0, None): [
@ -749,6 +774,7 @@ FW_VERSIONS = {
b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259L \xf1\x890002',
b'\xf1\x875G0906259Q \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002',
b'\xf1\x878V0906259F \xf1\x890002', b'\xf1\x878V0906259F \xf1\x890002',
b'\xf1\x878V0906259J \xf1\x890002',
b'\xf1\x878V0906259K \xf1\x890001', b'\xf1\x878V0906259K \xf1\x890001',
b'\xf1\x878V0906264B \xf1\x890003', b'\xf1\x878V0906264B \xf1\x890003',
b'\xf1\x878V0907115B \xf1\x890007', b'\xf1\x878V0907115B \xf1\x890007',
@ -767,6 +793,7 @@ FW_VERSIONS = {
b'\xf1\x870DD300046F \xf1\x891602', b'\xf1\x870DD300046F \xf1\x891602',
b'\xf1\x870DD300046G \xf1\x891601', b'\xf1\x870DD300046G \xf1\x891601',
b'\xf1\x870DL300012E \xf1\x892012', b'\xf1\x870DL300012E \xf1\x892012',
b'\xf1\x870GC300011 \xf1\x890403',
b'\xf1\x870GC300013M \xf1\x892402', b'\xf1\x870GC300013M \xf1\x892402',
b'\xf1\x870GC300042J \xf1\x891402', b'\xf1\x870GC300042J \xf1\x891402',
], ],
@ -774,6 +801,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\0211111001111111206110412111321139114', b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\0211111001111111206110412111321139114',
b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100',
b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100',
b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100',
b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100',
b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221',
b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221',
@ -784,6 +812,7 @@ FW_VERSIONS = {
], ],
(Ecu.eps, 0x712, None): [ (Ecu.eps, 0x712, None): [
b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566G0HA14A1', b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566G0HA14A1',
b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1',
b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1',
b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1',
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1',

@ -215,7 +215,7 @@ class Controls:
controls_state = log.ControlsState.from_bytes(controls_state) controls_state = log.ControlsState.from_bytes(controls_state)
self.v_cruise_kph = controls_state.vCruise self.v_cruise_kph = controls_state.vCruise
if self.sm['pandaStates'][0].controlsAllowed: if any(ps.controlsAllowed for ps in self.sm['pandaStates']):
self.state = State.enabled self.state = State.enabled
def update_events(self, CS): def update_events(self, CS):

@ -91,6 +91,7 @@ class LongControl:
v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, T_IDXS[:CONTROL_N], speeds) v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, T_IDXS[:CONTROL_N], speeds)
else: else:
v_target = 0.0 v_target = 0.0
v_target_now = 0.0
v_target_1sec = 0.0 v_target_1sec = 0.0
a_target = 0.0 a_target = 0.0
@ -131,7 +132,6 @@ class LongControl:
feedforward=a_target, feedforward=a_target,
freeze_integrator=freeze_integrator) freeze_integrator=freeze_integrator)
self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1])
return self.last_output_accel return self.last_output_accel

@ -0,0 +1,121 @@
#!/usr/bin/env python3
'''
printing the gap between interrupts in a histogram to check if the
frequency is what we expect, the bmx is not interrupt driven for as we
get interrupts in a 2kHz rate.
'''
import argparse
import sys
from collections import defaultdict
from tools.lib.logreader import LogReader
from tools.lib.route import Route
import matplotlib.pyplot as plt
SRC_BMX = "bmx055"
SRC_LSM = "lsm6ds3"
def parseEvents(log_reader):
bmx_data = defaultdict(list)
lsm_data = defaultdict(list)
for m in log_reader:
# only sensorEvents
if m.which() != 'sensorEvents':
continue
for se in m.sensorEvents:
# convert data to dictionary
d = se.to_dict()
if d["timestamp"] == 0:
continue # empty event?
if d["source"] == SRC_BMX and "acceleration" in d:
bmx_data["accel"].append(d["timestamp"] / 1e9)
if d["source"] == SRC_BMX and "gyroUncalibrated" in d:
bmx_data["gyro"].append(d["timestamp"] / 1e9)
if d["source"] == SRC_LSM and "acceleration" in d:
lsm_data["accel"].append(d["timestamp"] / 1e9)
if d["source"] == SRC_LSM and "gyroUncalibrated" in d:
lsm_data["gyro"].append(d["timestamp"] / 1e9)
return bmx_data, lsm_data
def cleanData(data):
if len(data) == 0:
return [], []
data.sort()
prev = data[0]
diffs = []
for v in data[1:]:
diffs.append(v - prev)
prev = v
return data, diffs
def logAvgValues(data, sensor):
if len(data) == 0:
print(f"{sensor}: no data to average")
return
avg = sum(data) / len(data)
hz = 1 / avg
print(f"{sensor}: data_points: {len(data)} avg [ns]: {avg} avg [Hz]: {hz}")
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("route", type=str, help="route name")
parser.add_argument("segment", type=int, help="segment number")
args = parser.parse_args()
r = Route(args.route)
logs = r.log_paths()
if len(logs) == 0:
print("NO data routes")
sys.exit(0)
if args.segment >= len(logs):
print(f"RouteID: {args.segment} out of range, max: {len(logs) -1}")
sys.exit(0)
lr = LogReader(logs[args.segment])
bmx_data, lsm_data = parseEvents(lr)
# sort bmx accel data, and then cal all the diffs, and to a histogram of those
bmx_accel, bmx_accel_diffs = cleanData(bmx_data["accel"])
bmx_gyro, bmx_gyro_diffs = cleanData(bmx_data["gyro"])
lsm_accel, lsm_accel_diffs = cleanData(lsm_data["accel"])
lsm_gyro, lsm_gyro_diffs = cleanData(lsm_data["gyro"])
# get out the averages
logAvgValues(bmx_accel_diffs, "bmx accel")
logAvgValues(bmx_gyro_diffs, "bmx gyro ")
logAvgValues(lsm_accel_diffs, "lsm accel")
logAvgValues(lsm_gyro_diffs, "lsm gyro ")
fig, axs = plt.subplots(1, 2, tight_layout=True)
axs[0].hist(bmx_accel_diffs, bins=50)
axs[0].set_title("bmx_accel")
axs[1].hist(bmx_gyro_diffs, bins=50)
axs[1].set_title("bmx_gyro")
figl, axsl = plt.subplots(1, 2, tight_layout=True)
axsl[0].hist(lsm_accel_diffs, bins=50)
axsl[0].set_title("lsm_accel")
axsl[1].hist(lsm_gyro_diffs, bins=50)
axsl[1].set_title("lsm_gyro")
print("check plot...")
plt.show()

@ -67,20 +67,30 @@ if __name__ == "__main__":
print("Timeout fetching data from EPS") print("Timeout fetching data from EPS")
quit() quit()
coding_variant, current_coding_array = None, None 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) # EV_SteerAssisMQB covers the majority of MQB racks (EPS_MQB_ZFLS)
# APA racks (MQB_PP_APA) have a different coding layout, which should
# be easy to support once we identify the specific config bit
if odx_file == "EV_SteerAssisMQB\x00": if odx_file == "EV_SteerAssisMQB\x00":
coding_variant = "ZF" coding_variant = "ZF"
current_coding_array = struct.unpack("!4B", current_coding) coding_byte = 0
hca_enabled = (current_coding_array[0] & (1 << 4) != 0) coding_bit = 4
hca_text = ("DISABLED", "ENABLED")[hca_enabled]
print(f" Lane Assist: {hca_text}") # APA racks (MQB_PP_APA) have a different coding layout
elif odx_file == "EV_SteerAssisVWBSMQBA\x00\x00\x00\x00":
coding_variant = "APA"
coding_byte = 3
coding_bit = 0
else: else:
print("Configuration changes not yet supported on this EPS!") print("Configuration changes not yet supported on this EPS!")
quit() quit()
current_coding_array = struct.unpack(f"!{coding_length}B", current_coding)
hca_enabled = (current_coding_array[coding_byte] & (1 << coding_bit) != 0)
hca_text = ("DISABLED", "ENABLED")[hca_enabled]
print(f" Lane Assist: {hca_text}")
try: try:
params = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION).decode("utf-8") params = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION).decode("utf-8")
param_version_system_params = params[1:3] param_version_system_params = params[1:3]
@ -101,14 +111,14 @@ if __name__ == "__main__":
if args.action in ["enable", "disable"]: if args.action in ["enable", "disable"]:
print("\nAttempting configuration update") print("\nAttempting configuration update")
assert(coding_variant == "ZF") # revisit when we have the APA rack coding bit assert(coding_variant in ("ZF", "APA"))
# ZF EPS config coding length can be anywhere from 1 to 4 bytes, but the # ZF EPS config coding length can be anywhere from 1 to 4 bytes, but the
# bit we care about is always in the same place in the first byte # bit we care about is always in the same place in the first byte
if args.action == "enable": if args.action == "enable":
new_byte_0 = current_coding_array[0] | (1 << 4) new_byte = current_coding_array[coding_byte] | (1 << coding_bit)
else: else:
new_byte_0 = current_coding_array[0] & ~(1 << 4) new_byte = current_coding_array[coding_byte] & ~(1 << coding_bit)
new_coding = new_byte_0.to_bytes(1, "little") + current_coding[1:] new_coding = current_coding[0:coding_byte] + new_byte.to_bytes(1, "little") + current_coding[coding_byte+1:]
try: try:
seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore

@ -52,6 +52,7 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) {
VisionBuf buf_info = vipc_client.buffers[0]; VisionBuf buf_info = vipc_client.buffers[0];
LOGW("encoder %s init %dx%d", cam_info.filename, buf_info.width, buf_info.height); LOGW("encoder %s init %dx%d", cam_info.filename, buf_info.width, buf_info.height);
if (buf_info.width > 0 && buf_info.height > 0) {
// main encoder // main encoder
encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height,
cam_info.fps, cam_info.bitrate, cam_info.fps, cam_info.bitrate,
@ -64,6 +65,11 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) {
qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264,
qcam_info.frame_width, qcam_info.frame_height, false)); qcam_info.frame_width, qcam_info.frame_height, false));
} }
} else {
LOGE("not initting empty encoder");
s->max_waiting--;
break;
}
} }
for (int i = 0; i < encoders.size(); ++i) { for (int i = 0; i < encoders.size(); ++i) {

@ -13,7 +13,7 @@ sensors = [
'sensors/lsm6ds3_temp.cc', 'sensors/lsm6ds3_temp.cc',
'sensors/mmc5603nj_magn.cc', 'sensors/mmc5603nj_magn.cc',
] ]
libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj'] libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj', 'pthread']
if arch == "larch64": if arch == "larch64":
libs.append('i2c') libs.append('i2c')
env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs) env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs)

@ -43,7 +43,7 @@ fail:
return ret; return ret;
} }
void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) { bool BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[6]; uint8_t buffer[6];
int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer)); int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer));
@ -66,4 +66,5 @@ void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) {
svec.setV(xyz); svec.setV(xyz);
svec.setStatus(true); svec.setStatus(true);
return true;
} }

@ -33,5 +33,6 @@ class BMX055_Accel : public I2CSensor {
public: public:
BMX055_Accel(I2CBus *bus); BMX055_Accel(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -54,7 +54,7 @@ fail:
return ret; return ret;
} }
void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) { bool BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[6]; uint8_t buffer[6];
int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer)); int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer));
@ -76,5 +76,5 @@ void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) {
auto svec = event.initGyroUncalibrated(); auto svec = event.initGyroUncalibrated();
svec.setV(xyz); svec.setV(xyz);
svec.setStatus(true); svec.setStatus(true);
return true;
} }

@ -33,5 +33,6 @@ class BMX055_Gyro : public I2CSensor {
public: public:
BMX055_Gyro(I2CBus *bus); BMX055_Gyro(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -213,7 +213,7 @@ bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *
} }
void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { bool BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[8]; uint8_t buffer[8];
int16_t _x, _y, x, y, z; int16_t _x, _y, x, y, z;
@ -221,7 +221,8 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) {
int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer));
assert(len == sizeof(buffer)); assert(len == sizeof(buffer));
if (parse_xyz(buffer, &_x, &_y, &z)) { bool parsed = parse_xyz(buffer, &_x, &_y, &z);
if (parsed) {
event.setSource(cereal::SensorEventData::SensorSource::BMX055); event.setSource(cereal::SensorEventData::SensorSource::BMX055);
event.setVersion(2); event.setVersion(2);
event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED);
@ -247,4 +248,6 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) {
// at a 100 Hz. When reading the registers we have to check the ready bit // at a 100 Hz. When reading the registers we have to check the ready bit
// To verify the measurement was completed this cycle. // To verify the measurement was completed this cycle.
set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED); set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED);
return parsed;
} }

@ -59,5 +59,6 @@ class BMX055_Magn : public I2CSensor{
public: public:
BMX055_Magn(I2CBus *bus); BMX055_Magn(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -28,7 +28,7 @@ fail:
return ret; return ret;
} }
void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) { bool BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[1]; uint8_t buffer[1];
int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer)); int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer));
@ -41,4 +41,5 @@ void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) {
event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE);
event.setTimestamp(start_time); event.setTimestamp(start_time);
event.setTemperature(temp); event.setTemperature(temp);
return true;
} }

@ -8,5 +8,6 @@ class BMX055_Temp : public I2CSensor {
public: public:
BMX055_Temp(I2CBus *bus); BMX055_Temp(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -12,3 +12,7 @@ int FileSensor::init() {
FileSensor::~FileSensor() { FileSensor::~FileSensor() {
file.close(); file.close();
} }
bool FileSensor::has_interrupt_enabled() {
return false;
}

@ -14,5 +14,6 @@ public:
FileSensor(std::string filename); FileSensor(std::string filename);
~FileSensor(); ~FileSensor();
int init(); int init();
virtual void get_event(cereal::SensorEventData::Builder &event) = 0; bool has_interrupt_enabled();
virtual bool get_event(cereal::SensorEventData::Builder &event) = 0;
}; };

@ -15,8 +15,12 @@ int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0) {
return int32_t(combined) / (1 << 4); return int32_t(combined) / (1 << 4);
} }
I2CSensor::I2CSensor(I2CBus *bus, int gpio_nr, bool shared_gpio) : bus(bus), gpio_nr(gpio_nr), shared_gpio(shared_gpio) {}
I2CSensor::I2CSensor(I2CBus *bus) : bus(bus) { I2CSensor::~I2CSensor() {
if (gpio_fd != -1) {
close(gpio_fd);
}
} }
int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) { int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) {
@ -26,3 +30,20 @@ int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len
int I2CSensor::set_register(uint register_address, uint8_t data) { int I2CSensor::set_register(uint register_address, uint8_t data) {
return bus->set_register(get_device_address(), register_address, data); return bus->set_register(get_device_address(), register_address, data);
} }
int I2CSensor::init_gpio() {
if (shared_gpio || gpio_nr == 0) {
return 0;
}
gpio_fd = gpiochip_get_ro_value_fd("sensord", GPIOCHIP_INT, gpio_nr);
if (gpio_fd < 0) {
return -1;
}
return 0;
}
bool I2CSensor::has_interrupt_enabled() {
return gpio_nr != 0;
}

@ -1,9 +1,13 @@
#pragma once #pragma once
#include <cstdint> #include <cstdint>
#include <unistd.h>
#include "cereal/gen/cpp/log.capnp.h" #include "cereal/gen/cpp/log.capnp.h"
#include "common/i2c.h" #include "common/i2c.h"
#include "common/gpio.h"
#include "selfdrive/sensord/sensors/constants.h" #include "selfdrive/sensord/sensors/constants.h"
#include "selfdrive/sensord/sensors/sensor.h" #include "selfdrive/sensord/sensors/sensor.h"
@ -15,12 +19,18 @@ int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0);
class I2CSensor : public Sensor { class I2CSensor : public Sensor {
private: private:
I2CBus *bus; I2CBus *bus;
int gpio_nr;
bool shared_gpio;
virtual uint8_t get_device_address() = 0; virtual uint8_t get_device_address() = 0;
public: public:
I2CSensor(I2CBus *bus); I2CSensor(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false);
~I2CSensor();
int read_register(uint register_address, uint8_t *buffer, uint8_t len); int read_register(uint register_address, uint8_t *buffer, uint8_t len);
int set_register(uint register_address, uint8_t data); int set_register(uint register_address, uint8_t data);
int init_gpio();
bool has_interrupt_enabled();
virtual int init() = 0; virtual int init() = 0;
virtual void get_event(cereal::SensorEventData::Builder &event) = 0; virtual bool get_event(cereal::SensorEventData::Builder &event) = 0;
virtual int shutdown() = 0;
}; };

@ -5,7 +5,7 @@
#include "common/timing.h" #include "common/timing.h"
#include "selfdrive/sensord/sensors/constants.h" #include "selfdrive/sensord/sensors/constants.h"
void LightSensor::get_event(cereal::SensorEventData::Builder &event) { bool LightSensor::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
file.clear(); file.clear();
file.seekg(0); file.seekg(0);
@ -19,4 +19,6 @@ void LightSensor::get_event(cereal::SensorEventData::Builder &event) {
event.setType(SENSOR_TYPE_LIGHT); event.setType(SENSOR_TYPE_LIGHT);
event.setTimestamp(start_time); event.setTimestamp(start_time);
event.setLight(value); event.setLight(value);
return true;
} }

@ -4,5 +4,6 @@
class LightSensor : public FileSensor { class LightSensor : public FileSensor {
public: public:
LightSensor(std::string filename) : FileSensor(filename){}; LightSensor(std::string filename) : FileSensor(filename){};
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -5,11 +5,12 @@
#include "common/swaglog.h" #include "common/swaglog.h"
#include "common/timing.h" #include "common/timing.h"
LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus) : I2CSensor(bus) {} LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus, int gpio_nr, bool shared_gpio) : I2CSensor(bus, gpio_nr, shared_gpio) {}
int LSM6DS3_Accel::init() { int LSM6DS3_Accel::init() {
int ret = 0; int ret = 0;
uint8_t buffer[1]; uint8_t buffer[1];
uint8_t value = 0;
ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1); ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1);
if(ret < 0) { if(ret < 0) {
@ -27,20 +28,69 @@ int LSM6DS3_Accel::init() {
source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; source = cereal::SensorEventData::SensorSource::LSM6DS3TRC;
} }
ret = init_gpio();
if (ret < 0) {
goto fail;
}
// TODO: set scale and bandwidth. 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); ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ);
if (ret < 0) { if (ret < 0) {
goto fail; goto fail;
} }
ret = set_register(LSM6DS3_ACCEL_I2C_REG_DRDY_CFG, LSM6DS3_ACCEL_DRDY_PULSE_MODE);
if (ret < 0) {
goto fail;
}
// enable data ready interrupt for accel on INT1
// (without resetting existing interrupts)
ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1);
if (ret < 0) {
goto fail;
}
value |= LSM6DS3_ACCEL_INT1_DRDY_XL;
ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value);
fail:
return ret;
}
int LSM6DS3_Accel::shutdown() {
int ret = 0;
// disable data ready interrupt for accel on INT1
uint8_t value = 0;
ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1);
if (ret < 0) {
goto fail;
}
value &= ~(LSM6DS3_ACCEL_INT1_DRDY_XL);
ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value);
if (ret < 0) {
goto fail;
}
return ret;
fail: fail:
LOGE("Could not disable lsm6ds3 acceleration interrupt!")
return ret; return ret;
} }
void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) { bool LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) {
if (has_interrupt_enabled()) {
// INT1 shared with gyro, check STATUS_REG who triggered
uint8_t status_reg = 0;
read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg));
if ((status_reg & LSM6DS3_ACCEL_DRDY_XLDA) == 0) {
return false;
}
}
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6]; uint8_t buffer[6];
int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer)); int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer));
assert(len == sizeof(buffer)); assert(len == sizeof(buffer));
@ -54,11 +104,11 @@ void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) {
event.setVersion(1); event.setVersion(1);
event.setSensor(SENSOR_ACCELEROMETER); event.setSensor(SENSOR_ACCELEROMETER);
event.setType(SENSOR_TYPE_ACCELEROMETER); event.setType(SENSOR_TYPE_ACCELEROMETER);
event.setTimestamp(start_time);
float xyz[] = {y, -x, z}; float xyz[] = {y, -x, z};
auto svec = event.initAcceleration(); auto svec = event.initAcceleration();
svec.setV(xyz); svec.setV(xyz);
svec.setStatus(true); svec.setStatus(true);
return true;
} }

@ -6,21 +6,28 @@
#define LSM6DS3_ACCEL_I2C_ADDR 0x6A #define LSM6DS3_ACCEL_I2C_ADDR 0x6A
// Registers of the chip // Registers of the chip
#define LSM6DS3_ACCEL_I2C_REG_DRDY_CFG 0x0B
#define LSM6DS3_ACCEL_I2C_REG_ID 0x0F #define LSM6DS3_ACCEL_I2C_REG_ID 0x0F
#define LSM6DS3_ACCEL_I2C_REG_INT1_CTRL 0x0D
#define LSM6DS3_ACCEL_I2C_REG_CTRL1_XL 0x10 #define LSM6DS3_ACCEL_I2C_REG_CTRL1_XL 0x10
#define LSM6DS3_ACCEL_I2C_REG_STAT_REG 0x1E
#define LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL 0x28 #define LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL 0x28
// Constants // Constants
#define LSM6DS3_ACCEL_CHIP_ID 0x69 #define LSM6DS3_ACCEL_CHIP_ID 0x69
#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A #define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A
#define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4) #define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4)
#define LSM6DS3_ACCEL_INT1_DRDY_XL 0b1
#define LSM6DS3_ACCEL_DRDY_XLDA 0b1
#define LSM6DS3_ACCEL_DRDY_PULSE_MODE (1 << 7)
class LSM6DS3_Accel : public I2CSensor { class LSM6DS3_Accel : public I2CSensor {
uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;} uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;}
cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3;
public: public:
LSM6DS3_Accel(I2CBus *bus); LSM6DS3_Accel(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown();
}; };

@ -8,12 +8,12 @@
#define DEG2RAD(x) ((x) * M_PI / 180.0) #define DEG2RAD(x) ((x) * M_PI / 180.0)
LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus, int gpio_nr, bool shared_gpio) : I2CSensor(bus, gpio_nr, shared_gpio) {}
LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus) : I2CSensor(bus) {}
int LSM6DS3_Gyro::init() { int LSM6DS3_Gyro::init() {
int ret = 0; int ret = 0;
uint8_t buffer[1]; uint8_t buffer[1];
uint8_t value = 0;
ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1); ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1);
if(ret < 0) { if(ret < 0) {
@ -31,20 +31,69 @@ int LSM6DS3_Gyro::init() {
source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; source = cereal::SensorEventData::SensorSource::LSM6DS3TRC;
} }
ret = init_gpio();
if (ret < 0) {
goto fail;
}
// TODO: set scale. Default is +- 250 deg/s // TODO: set scale. Default is +- 250 deg/s
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ); ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ);
if (ret < 0) { if (ret < 0) {
goto fail; goto fail;
} }
ret = set_register(LSM6DS3_GYRO_I2C_REG_DRDY_CFG, LSM6DS3_GYRO_DRDY_PULSE_MODE);
if (ret < 0) {
goto fail;
}
// enable data ready interrupt for gyro on INT1
// (without resetting existing interrupts)
ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1);
if (ret < 0) {
goto fail;
}
value |= LSM6DS3_GYRO_INT1_DRDY_G;
ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value);
fail: fail:
return ret; return ret;
} }
void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) { int LSM6DS3_Gyro::shutdown() {
int ret = 0;
// disable data ready interrupt for accel on INT1
uint8_t value = 0;
ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1);
if (ret < 0) {
goto fail;
}
value &= ~(LSM6DS3_GYRO_INT1_DRDY_G);
ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value);
if (ret < 0) {
goto fail;
}
return ret;
fail:
LOGE("Could not disable lsm6ds3 gyroscope interrupt!")
return ret;
}
bool LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) {
if (has_interrupt_enabled()) {
// INT1 shared with accel, check STATUS_REG who triggered
uint8_t status_reg = 0;
read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg));
if ((status_reg & LSM6DS3_GYRO_DRDY_GDA) == 0) {
return false;
}
}
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6]; uint8_t buffer[6];
int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer));
assert(len == sizeof(buffer)); assert(len == sizeof(buffer));
@ -58,11 +107,11 @@ void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) {
event.setVersion(2); event.setVersion(2);
event.setSensor(SENSOR_GYRO_UNCALIBRATED); event.setSensor(SENSOR_GYRO_UNCALIBRATED);
event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED);
event.setTimestamp(start_time);
float xyz[] = {y, -x, z}; float xyz[] = {y, -x, z};
auto svec = event.initGyroUncalibrated(); auto svec = event.initGyroUncalibrated();
svec.setV(xyz); svec.setV(xyz);
svec.setStatus(true); svec.setStatus(true);
return true;
} }

@ -6,21 +6,28 @@
#define LSM6DS3_GYRO_I2C_ADDR 0x6A #define LSM6DS3_GYRO_I2C_ADDR 0x6A
// Registers of the chip // Registers of the chip
#define LSM6DS3_GYRO_I2C_REG_DRDY_CFG 0x0B
#define LSM6DS3_GYRO_I2C_REG_ID 0x0F #define LSM6DS3_GYRO_I2C_REG_ID 0x0F
#define LSM6DS3_GYRO_I2C_REG_INT1_CTRL 0x0D
#define LSM6DS3_GYRO_I2C_REG_CTRL2_G 0x11 #define LSM6DS3_GYRO_I2C_REG_CTRL2_G 0x11
#define LSM6DS3_GYRO_I2C_REG_STAT_REG 0x1E
#define LSM6DS3_GYRO_I2C_REG_OUTX_L_G 0x22 #define LSM6DS3_GYRO_I2C_REG_OUTX_L_G 0x22
// Constants // Constants
#define LSM6DS3_GYRO_CHIP_ID 0x69 #define LSM6DS3_GYRO_CHIP_ID 0x69
#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A #define LSM6DS3TRC_GYRO_CHIP_ID 0x6A
#define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4) #define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4)
#define LSM6DS3_GYRO_INT1_DRDY_G 0b10
#define LSM6DS3_GYRO_DRDY_GDA 0b10
#define LSM6DS3_GYRO_DRDY_PULSE_MODE (1 << 7)
class LSM6DS3_Gyro : public I2CSensor { class LSM6DS3_Gyro : public I2CSensor {
uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;} uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;}
cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3;
public: public:
LSM6DS3_Gyro(I2CBus *bus); LSM6DS3_Gyro(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown();
}; };

@ -31,7 +31,7 @@ fail:
return ret; return ret;
} }
void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) { bool LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[2]; uint8_t buffer[2];
@ -47,4 +47,5 @@ void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) {
event.setTimestamp(start_time); event.setTimestamp(start_time);
event.setTemperature(temp); event.setTemperature(temp);
return true;
} }

@ -21,5 +21,6 @@ class LSM6DS3_Temp : public I2CSensor {
public: public:
LSM6DS3_Temp(I2CBus *bus); LSM6DS3_Temp(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -51,7 +51,7 @@ fail:
return ret; return ret;
} }
void MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) { bool MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot(); uint64_t start_time = nanos_since_boot();
uint8_t buffer[9]; uint8_t buffer[9];
@ -74,4 +74,5 @@ void MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) {
svec.setV(xyz); svec.setV(xyz);
svec.setStatus(true); svec.setStatus(true);
return true;
} }

@ -25,5 +25,6 @@ class MMC5603NJ_Magn : public I2CSensor {
public: public:
MMC5603NJ_Magn(I2CBus *bus); MMC5603NJ_Magn(I2CBus *bus);
int init(); int init();
void get_event(cereal::SensorEventData::Builder &event); bool get_event(cereal::SensorEventData::Builder &event);
int shutdown() { return 0; }
}; };

@ -4,7 +4,10 @@
class Sensor { class Sensor {
public: public:
int gpio_fd = -1;
virtual ~Sensor() {}; virtual ~Sensor() {};
virtual int init() = 0; virtual int init() = 0;
virtual void get_event(cereal::SensorEventData::Builder &event) = 0; virtual bool get_event(cereal::SensorEventData::Builder &event) = 0;
virtual bool has_interrupt_enabled() = 0;
virtual int shutdown() = 0;
}; };

@ -3,6 +3,8 @@
#include <chrono> #include <chrono>
#include <thread> #include <thread>
#include <vector> #include <vector>
#include <poll.h>
#include <linux/gpio.h>
#include "cereal/messaging/messaging.h" #include "cereal/messaging/messaging.h"
#include "common/i2c.h" #include "common/i2c.h"
@ -24,6 +26,79 @@
#define I2C_BUS_IMU 1 #define I2C_BUS_IMU 1
ExitHandler do_exit; ExitHandler do_exit;
std::mutex pm_mutex;
void interrupt_loop(int fd, std::vector<Sensor *>& sensors, PubMaster& pm) {
struct pollfd fd_list[1] = {0};
fd_list[0].fd = fd;
fd_list[0].events = POLLIN | POLLPRI;
uint64_t offset = nanos_since_epoch() - nanos_since_boot();
while (!do_exit) {
int err = poll(fd_list, 1, 100);
if (err == -1) {
if (errno == EINTR) {
continue;
}
return;
} else if (err == 0) {
LOGE("poll timed out");
continue;
}
if ((fd_list[0].revents & (POLLIN | POLLPRI)) == 0) {
LOGE("no poll events set");
continue;
}
// Read all events
struct gpioevent_data evdata[16];
err = read(fd, evdata, sizeof(evdata));
if (err < 0 || err % sizeof(*evdata) != 0) {
LOGE("error reading event data %d", err);
continue;
}
int num_events = err / sizeof(*evdata);
uint64_t ts = evdata[num_events - 1].timestamp - offset;
MessageBuilder msg;
auto orphanage = msg.getOrphanage();
std::vector<capnp::Orphan<cereal::SensorEventData>> collected_events;
collected_events.reserve(sensors.size());
for (Sensor *sensor : sensors) {
auto orphan = orphanage.newOrphan<cereal::SensorEventData>();
auto event = orphan.get();
if (!sensor->get_event(event)) {
continue;
}
event.setTimestamp(ts);
collected_events.push_back(kj::mv(orphan));
}
if (collected_events.size() == 0) {
continue;
}
auto events = msg.initEvent().initSensorEvents(collected_events.size());
for (int i = 0; i < collected_events.size(); ++i) {
events.adoptWithCaveats(i, kj::mv(collected_events[i]));
}
{
std::lock_guard<std::mutex> lock(pm_mutex);
pm.send("sensorEvents", msg);
}
}
// poweroff sensors, disable interrupts
for (Sensor *sensor : sensors) {
sensor->shutdown();
}
}
int sensor_loop() { int sensor_loop() {
I2CBus *i2c_bus_imu; I2CBus *i2c_bus_imu;
@ -40,8 +115,8 @@ int sensor_loop() {
BMX055_Magn bmx055_magn(i2c_bus_imu); BMX055_Magn bmx055_magn(i2c_bus_imu);
BMX055_Temp bmx055_temp(i2c_bus_imu); BMX055_Temp bmx055_temp(i2c_bus_imu);
LSM6DS3_Accel lsm6ds3_accel(i2c_bus_imu); LSM6DS3_Accel lsm6ds3_accel(i2c_bus_imu, GPIO_LSM_INT);
LSM6DS3_Gyro lsm6ds3_gyro(i2c_bus_imu); LSM6DS3_Gyro lsm6ds3_gyro(i2c_bus_imu, GPIO_LSM_INT, true); // GPIO shared with accel
LSM6DS3_Temp lsm6ds3_temp(i2c_bus_imu); LSM6DS3_Temp lsm6ds3_temp(i2c_bus_imu);
MMC5603NJ_Magn mmc5603nj_magn(i2c_bus_imu); MMC5603NJ_Magn mmc5603nj_magn(i2c_bus_imu);
@ -73,23 +148,33 @@ int sensor_loop() {
// Fail on required sensors // Fail on required sensors
if (sensor.second) { if (sensor.second) {
LOGE("Error initializing sensors"); LOGE("Error initializing sensors");
delete i2c_bus_imu;
return -1; return -1;
} }
} else { } else {
if (sensor.first == &bmx055_magn || sensor.first == &mmc5603nj_magn) { if (sensor.first == &bmx055_magn || sensor.first == &mmc5603nj_magn) {
has_magnetometer = true; has_magnetometer = true;
} }
if (!sensor.first->has_interrupt_enabled()) {
sensors.push_back(sensor.first); sensors.push_back(sensor.first);
} }
} }
}
if (!has_magnetometer) { if (!has_magnetometer) {
LOGE("No magnetometer present"); LOGE("No magnetometer present");
delete i2c_bus_imu;
return -1; return -1;
} }
PubMaster pm({"sensorEvents"}); PubMaster pm({"sensorEvents"});
// thread for reading events via interrupts
std::vector<Sensor *> lsm_interrupt_sensors = {&lsm6ds3_accel, &lsm6ds3_gyro};
std::thread lsm_interrupt_thread(&interrupt_loop, lsm6ds3_accel.gpio_fd, std::ref(lsm_interrupt_sensors), std::ref(pm));
// polling loop for non interrupt handled sensors
while (!do_exit) { while (!do_exit) {
std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now();
@ -102,11 +187,17 @@ int sensor_loop() {
sensors[i]->get_event(event); sensors[i]->get_event(event);
} }
{
std::lock_guard<std::mutex> lock(pm_mutex);
pm.send("sensorEvents", msg); pm.send("sensorEvents", msg);
}
std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now();
std::this_thread::sleep_for(std::chrono::milliseconds(10) - (end - begin)); std::this_thread::sleep_for(std::chrono::milliseconds(10) - (end - begin));
} }
lsm_interrupt_thread.join();
delete i2c_bus_imu;
return 0; return 0;
} }

@ -2,12 +2,15 @@
import time import time
import unittest import unittest
import numpy as np
from collections import namedtuple
from smbus2 import SMBus
import cereal.messaging as messaging import cereal.messaging as messaging
from system.hardware import TICI from cereal import log
from system.hardware import TICI, HARDWARE
from selfdrive.test.helpers import with_processes from selfdrive.test.helpers import with_processes
from selfdrive.manager.process_config import managed_processes
TEST_TIMESPAN = 10
SENSOR_CONFIGURATIONS = ( SENSOR_CONFIGURATIONS = (
{ {
@ -46,6 +49,63 @@ SENSOR_CONFIGURATIONS = (
}, },
) )
Sensor = log.SensorEventData.SensorSource
SensorConfig = namedtuple('SensorConfig', ['type', 'min_samples', 'sanity_min', 'sanity_max'])
ALL_SENSORS = {
Sensor.rpr0521: {
SensorConfig("light", 100, 0, 150),
},
Sensor.lsm6ds3: {
SensorConfig("acceleration", 100, 5, 15),
SensorConfig("gyroUncalibrated", 100, 0, .2),
SensorConfig("temperature", 100, 0, 60),
},
Sensor.lsm6ds3trc: {
SensorConfig("acceleration", 100, 5, 15),
SensorConfig("gyroUncalibrated", 100, 0, .2),
SensorConfig("temperature", 100, 0, 60),
},
Sensor.bmx055: {
SensorConfig("acceleration", 100, 5, 15),
SensorConfig("gyroUncalibrated", 100, 0, .2),
SensorConfig("magneticUncalibrated", 100, 0, 300),
SensorConfig("temperature", 100, 0, 60),
},
Sensor.mmc5603nj: {
SensorConfig("magneticUncalibrated", 100, 0, 300),
}
}
SENSOR_BUS = 1
I2C_ADDR_LSM = 0x6A
LSM_INT_GPIO = 84
def read_sensor_events(duration_sec):
sensor_events = messaging.sub_sock("sensorEvents", timeout=0.1)
start_time_sec = time.monotonic()
events = []
while time.monotonic() - start_time_sec < duration_sec:
events += messaging.drain_sock(sensor_events)
time.sleep(0.01)
assert len(events) != 0, "No sensor events collected"
return events
def get_proc_interrupts(int_pin):
with open("/proc/interrupts") as f:
lines = f.read().split("\n")
for line in lines:
if f" {int_pin} " in line:
return ''.join(list(filter(lambda e: e != '', line.split(' ')))[1:6])
return ""
class TestSensord(unittest.TestCase): class TestSensord(unittest.TestCase):
@classmethod @classmethod
@ -53,26 +113,180 @@ class TestSensord(unittest.TestCase):
if not TICI: if not TICI:
raise unittest.SkipTest raise unittest.SkipTest
# make sure gpiochip0 is readable
HARDWARE.initialize_hardware()
@with_processes(['sensord']) @with_processes(['sensord'])
def test_sensors_present(self): def test_sensors_present(self):
sensor_events = messaging.sub_sock("sensorEvents", timeout=0.1) # verify correct sensors configuration
events = read_sensor_events(10)
start_time_sec = time.time()
events = []
while time.time() - start_time_sec < TEST_TIMESPAN:
events += messaging.drain_sock(sensor_events)
time.sleep(0.01)
seen = set() seen = set()
for event in events: for event in events:
for measurement in event.sensorEvents: for measurement in event.sensorEvents:
# Filter out unset events # filter unset events (bmx magn)
if measurement.version == 0: if measurement.version == 0:
continue continue
seen.add((str(measurement.source), measurement.which())) seen.add((str(measurement.source), measurement.which()))
self.assertIn(seen, SENSOR_CONFIGURATIONS) self.assertIn(seen, SENSOR_CONFIGURATIONS)
@with_processes(['sensord'])
def test_lsm6ds3_100Hz(self):
# verify measurements are sampled and published at a 100Hz rate
events = read_sensor_events(3) # 3sec (about 300 measurements)
data_points = set()
for event in events:
for measurement in event.sensorEvents:
# skip lsm6ds3 temperature measurements
if measurement.which() == 'temperature':
continue
if str(measurement.source).startswith("lsm6ds3"):
data_points.add(measurement.timestamp)
assert len(data_points) != 0, "No lsm6ds3 sensor events"
data_list = list(data_points)
data_list.sort()
tdiffs = np.diff(data_list)
high_delay_diffs = set(filter(lambda d: d >= 10.1*10**6, tdiffs))
assert len(high_delay_diffs) < 10, f"Too many high delay packages: {high_delay_diffs}"
avg_diff = sum(tdiffs)/len(tdiffs)
assert avg_diff > 9.6*10**6, f"avg difference {avg_diff}, below threshold"
stddev = np.std(tdiffs)
assert stddev < 1.5*10**6, f"Standard-dev to big {stddev}"
@with_processes(['sensord'])
def test_events_check(self):
# verify if all sensors produce events
events = read_sensor_events(3)
sensor_events = dict()
for event in events:
for measurement in event.sensorEvents:
# filter unset events (bmx magn)
if measurement.version == 0:
continue
if measurement.type in sensor_events:
sensor_events[measurement.type] += 1
else:
sensor_events[measurement.type] = 1
for s in sensor_events:
err_msg = f"Sensor {s}: 200 < {sensor_events[s]}"
assert sensor_events[s] > 200, err_msg
@with_processes(['sensord'])
def test_logmonottime_timestamp_diff(self):
# ensure diff between the message logMonotime and sample timestamp is small
events = read_sensor_events(3)
tdiffs = list()
for event in events:
for measurement in event.sensorEvents:
# filter unset events (bmx magn)
if measurement.version == 0:
continue
# check if gyro and accel timestamps are before logMonoTime
if str(measurement.source).startswith("lsm6ds3"):
if measurement.which() != 'temperature':
err_msg = f"Timestamp after logMonoTime: {measurement.timestamp} > {event.logMonoTime}"
assert measurement.timestamp < event.logMonoTime, err_msg
# negative values might occur, as non interrupt packages created
# before the sensor is read
tdiffs.append(abs(event.logMonoTime - measurement.timestamp))
high_delay_diffs = set(filter(lambda d: d >= 10*10**6, tdiffs))
assert len(high_delay_diffs) < 15, f"Too many high delay packages: {high_delay_diffs}"
avg_diff = round(sum(tdiffs)/len(tdiffs), 4)
assert avg_diff < 4*10**6, f"Avg packet diff: {avg_diff:.1f}ns"
stddev = np.std(tdiffs)
assert stddev < 2*10**6, f"Timing diffs have to high stddev: {stddev}"
@with_processes(['sensord'])
def test_sensor_values_sanity_check(self):
events = read_sensor_events(2)
sensor_values = dict()
for event in events:
for m in event.sensorEvents:
# filter unset events (bmx magn)
if m.version == 0:
continue
key = (m.source.raw, m.which())
values = getattr(m, m.which())
if hasattr(values, 'v'):
values = values.v
values = np.atleast_1d(values)
if key in sensor_values:
sensor_values[key].append(values)
else:
sensor_values[key] = [values]
# Sanity check sensor values and counts
for sensor, stype in sensor_values:
for s in ALL_SENSORS[sensor]:
if s.type != stype:
continue
key = (sensor, s.type)
val_cnt = len(sensor_values[key])
err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {s.min_samples}"
assert val_cnt > s.min_samples, err_msg
mean_norm = np.mean(np.linalg.norm(sensor_values[key], axis=1))
err_msg = f"Sensor '{sensor} {s.type}' failed sanity checks {mean_norm} is not between {s.sanity_min} and {s.sanity_max}"
assert s.sanity_min <= mean_norm <= s.sanity_max, err_msg
def test_sensor_verify_no_interrupts_after_stop(self):
managed_processes["sensord"].start()
time.sleep(1)
# check if the interrupts are enableds
with SMBus(SENSOR_BUS, force=True) as bus:
int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D)
assert int1_ctrl_reg == 3, "Interrupts not enabled!"
# read /proc/interrupts to verify interrupts are received
state_one = get_proc_interrupts(LSM_INT_GPIO)
time.sleep(1)
state_two = get_proc_interrupts(LSM_INT_GPIO)
assert state_one != state_two, "no Interrupts received after sensord start!"
managed_processes["sensord"].stop()
# check if the interrupts got disabled
with SMBus(SENSOR_BUS, force=True) as bus:
int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D)
assert int1_ctrl_reg == 0, "Interrupts not disabled!"
# read /proc/interrupts to verify no more interrupts are received
state_one = get_proc_interrupts(LSM_INT_GPIO)
time.sleep(1)
state_two = get_proc_interrupts(LSM_INT_GPIO)
assert state_one == state_two, "Interrupts received after sensord stop!"
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

@ -1 +1 @@
bd712b78c1ef351343b60e7ea527d09583e8acb7 48db2dee177706285226d1287912e191f1699865

@ -183,7 +183,9 @@ void OffroadHome::hideEvent(QHideEvent *event) {
} }
void OffroadHome::refresh() { void OffroadHome::refresh() {
date->setText(QDateTime::currentDateTime().toString("dddd, MMMM d")); QString locale_name = QString(uiState()->language).replace("main_", "");
QString dateString = QLocale(locale_name).toString(QDateTime::currentDateTime(), "dddd, MMMM d");
date->setText(dateString);
bool updateAvailable = update_widget->refresh(); bool updateAvailable = update_widget->refresh();
int alerts = alerts_widget->refresh(); int alerts = alerts_widget->refresh();

@ -486,9 +486,9 @@ void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruct
// for rhd, reflect direction and then flip // for rhd, reflect direction and then flip
if (is_rhd) { if (is_rhd) {
if (fn.contains("left")) { if (fn.contains("left")) {
fn.replace(QString("left"), QString("right")); fn.replace("left", "right");
} else if (fn.contains("right")) { } else if (fn.contains("right")) {
fn.replace(QString("right"), QString("left")); fn.replace("right", "left");
} }
} }

@ -44,61 +44,31 @@ QMapbox::CoordinatesCollections model_to_collection(
for (int i = 0; i < x.size(); i++) { for (int i = 0; i < x.size(); i++) {
Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef; Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef;
Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]}); Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]});
QMapbox::Coordinate coordinate(point_geodetic.lat, point_geodetic.lon); coordinates.push_back({point_geodetic.lat, point_geodetic.lon});
coordinates.push_back(coordinate);
} }
QMapbox::CoordinatesCollection collection; return {QMapbox::CoordinatesCollection{coordinates}};
collection.push_back(coordinates);
QMapbox::CoordinatesCollections collections;
collections.push_back(collection);
return collections;
} }
QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c) { QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c) {
QMapbox::Coordinates coordinates; QMapbox::Coordinates coordinates{c};
coordinates.push_back(c); return {QMapbox::CoordinatesCollection{coordinates}};
QMapbox::CoordinatesCollection collection;
collection.push_back(coordinates);
QMapbox::CoordinatesCollections collections;
collections.push_back(collection);
return collections;
} }
QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List<cereal::NavRoute::Coordinate>::Reader& coordinate_list) { QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List<cereal::NavRoute::Coordinate>::Reader& coordinate_list) {
QMapbox::Coordinates coordinates; QMapbox::Coordinates coordinates;
for (auto const &c: coordinate_list) { for (auto const &c: coordinate_list) {
QMapbox::Coordinate coordinate(c.getLatitude(), c.getLongitude()); coordinates.push_back({c.getLatitude(), c.getLongitude()});
coordinates.push_back(coordinate);
} }
return {QMapbox::CoordinatesCollection{coordinates}};
QMapbox::CoordinatesCollection collection;
collection.push_back(coordinates);
QMapbox::CoordinatesCollections collections;
collections.push_back(collection);
return collections;
} }
QMapbox::CoordinatesCollections coordinate_list_to_collection(QList<QGeoCoordinate> coordinate_list) { QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList<QGeoCoordinate> &coordinate_list) {
QMapbox::Coordinates coordinates; QMapbox::Coordinates coordinates;
for (auto &c : coordinate_list) { for (auto &c : coordinate_list) {
QMapbox::Coordinate coordinate(c.latitude(), c.longitude()); coordinates.push_back({c.latitude(), c.longitude()});
coordinates.push_back(coordinate);
} }
return {QMapbox::CoordinatesCollection{coordinates}};
QMapbox::CoordinatesCollection collection;
collection.push_back(coordinates);
QMapbox::CoordinatesCollections collections;
collections.push_back(collection);
return collections;
} }
QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString) { QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString) {
@ -143,7 +113,7 @@ QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString)
return path; return path;
} }
std::optional<QMapbox::Coordinate> coordinate_from_param(std::string param) { std::optional<QMapbox::Coordinate> coordinate_from_param(const std::string &param) {
QString json_str = QString::fromStdString(Params().get(param)); QString json_str = QString::fromStdString(Params().get(param));
if (json_str.isEmpty()) return {}; if (json_str.isEmpty()) return {};

@ -21,10 +21,10 @@ QMapbox::CoordinatesCollections model_to_collection(
const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF,
const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF,
const cereal::ModelDataV2::XYZTData::Reader &line); const cereal::ModelDataV2::XYZTData::Reader &line);
QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c); QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c);
QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List<cereal::NavRoute::Coordinate>::Reader &coordinate_list); QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List<cereal::NavRoute::Coordinate>::Reader &coordinate_list);
QMapbox::CoordinatesCollections coordinate_list_to_collection(QList<QGeoCoordinate> coordinate_list); QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList<QGeoCoordinate> &coordinate_list);
QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString); QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString);
std::optional<QMapbox::Coordinate> coordinate_from_param(std::string param); std::optional<QMapbox::Coordinate> coordinate_from_param(const std::string &param);
double angle_difference(double angle1, double angle2); double angle_difference(double angle1, double angle2);

@ -156,6 +156,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) {
void MapPanel::showEvent(QShowEvent *event) { void MapPanel::showEvent(QShowEvent *event) {
updateCurrentRoute(); updateCurrentRoute();
refresh();
} }
void MapPanel::clear() { void MapPanel::clear() {
@ -184,18 +185,25 @@ void MapPanel::updateCurrentRoute() {
} }
void MapPanel::parseResponse(const QString &response, bool success) { void MapPanel::parseResponse(const QString &response, bool success) {
stack->setCurrentIndex((uiState()->prime_type || success) ? 0 : 1); if (!success) return;
if (!success) { cur_destinations = response;
return; if (isVisible()) {
refresh();
}
} }
QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); void MapPanel::refresh() {
stack->setCurrentIndex(uiState()->prime_type ? 0 : 1);
if (cur_destinations == prev_destinations) return;
QJsonDocument doc = QJsonDocument::fromJson(cur_destinations.trimmed().toUtf8());
if (doc.isNull()) { if (doc.isNull()) {
qDebug() << "JSON Parse failed on navigation locations"; qDebug() << "JSON Parse failed on navigation locations";
return; return;
} }
prev_destinations = cur_destinations;
clear(); clear();
bool has_recents = false; bool has_recents = false;

@ -23,8 +23,10 @@ public:
private: private:
void showEvent(QShowEvent *event) override; void showEvent(QShowEvent *event) override;
void refresh();
Params params; Params params;
QString prev_destinations, cur_destinations;
QStackedWidget *stack; QStackedWidget *stack;
QPushButton *home_button, *work_button; QPushButton *home_button, *work_button;
QLabel *home_address, *work_address; QLabel *home_address, *work_address;

@ -189,8 +189,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), ""); auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), "");
connect(translateBtn, &ButtonControl::clicked, [=]() { connect(translateBtn, &ButtonControl::clicked, [=]() {
QMap<QString, QString> langs = getSupportedLanguages(); QMap<QString, QString> langs = getSupportedLanguages();
QString currentLang = QString::fromStdString(Params().get("LanguageSetting")); QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(uiState()->language), this);
QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(currentLang), this);
if (!selection.isEmpty()) { if (!selection.isEmpty()) {
// put language setting, exit Qt UI, and trigger fast restart // put language setting, exit Qt UI, and trigger fast restart
Params().put("LanguageSetting", langs[selection].toStdString()); Params().put("LanguageSetting", langs[selection].toStdString());

@ -165,7 +165,7 @@ private:
p.setPen(Qt::gray); p.setPen(Qt::gray);
for (int i = 0; i < inner_layout.count() - 1; ++i) { for (int i = 0; i < inner_layout.count() - 1; ++i) {
QWidget *widget = inner_layout.itemAt(i)->widget(); QWidget *widget = inner_layout.itemAt(i)->widget();
if (widget->isVisible()) { if (widget == nullptr || widget->isVisible()) {
QRect r = inner_layout.itemAt(i)->geometry(); QRect r = inner_layout.itemAt(i)->geometry();
int bottom = r.bottom() + inner_layout.spacing() / 2; int bottom = r.bottom() + inner_layout.spacing() / 2;
p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom); p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom);

@ -18,21 +18,24 @@
using qrcodegen::QrCode; using qrcodegen::QrCode;
PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) { PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) {
QTimer* timer = new QTimer(this); timer = new QTimer(this);
timer->start(5 * 60 * 1000);
connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh); connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh);
} }
void PairingQRWidget::showEvent(QShowEvent *event) { void PairingQRWidget::showEvent(QShowEvent *event) {
refresh(); refresh();
timer->start(5 * 60 * 1000);
}
void PairingQRWidget::hideEvent(QHideEvent *event) {
timer->stop();
} }
void PairingQRWidget::refresh() { void PairingQRWidget::refresh() {
if (isVisible()) {
QString pairToken = CommaApi::create_jwt({{"pair", true}}); QString pairToken = CommaApi::create_jwt({{"pair", true}});
QString qrString = "https://connect.comma.ai/?pair=" + pairToken; QString qrString = "https://connect.comma.ai/?pair=" + pairToken;
this->updateQrCode(qrString); this->updateQrCode(qrString);
} update();
} }
void PairingQRWidget::updateQrCode(const QString &text) { void PairingQRWidget::updateQrCode(const QString &text) {

@ -25,8 +25,10 @@ public:
private: private:
QPixmap img; QPixmap img;
QTimer *timer;
void updateQrCode(const QString &text); void updateQrCode(const QString &text);
void showEvent(QShowEvent *event) override; void showEvent(QShowEvent *event) override;
void hideEvent(QHideEvent *event) override;
private slots: private slots:
void refresh(); void refresh();

@ -526,7 +526,7 @@ location set</source>
<translation></translation> <translation></translation>
</message> </message>
<message> <message>
<location line="+91"/> <location line="+93"/>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation> </translation>
</message> </message>
@ -539,7 +539,7 @@ location set</source>
<context> <context>
<name>PairingPopup</name> <name>PairingPopup</name>
<message> <message>
<location filename="../qt/widgets/prime.cc" line="+86"/> <location filename="../qt/widgets/prime.cc" line="+89"/>
<source>Pair your device to your comma account</source> <source>Pair your device to your comma account</source>
<translation> comma </translation> <translation> comma </translation>
</message> </message>
@ -1170,7 +1170,7 @@ location set</source>
<message> <message>
<location line="+1"/> <location line="+1"/>
<source>Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).</source> <source>Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).</source>
<translation>3150km</translation> <translation>3150km</translation>
</message> </message>
<message> <message>
<location line="+5"/> <location line="+5"/>
@ -1195,22 +1195,22 @@ location set</source>
<message> <message>
<location line="+11"/> <location line="+11"/>
<source>🌮 End-to-end longitudinal (extremely alpha) 🌮</source> <source>🌮 End-to-end longitudinal (extremely alpha) 🌮</source>
<translation type="unfinished"></translation> <translation>🌮 () 🌮</translation>
</message> </message>
<message> <message>
<location line="+6"/> <location line="+6"/>
<source>Experimental openpilot longitudinal control</source> <source>Experimental openpilot longitudinal control</source>
<translation type="unfinished"></translation> <translation>openpilotによるアクセル制御</translation>
</message> </message>
<message> <message>
<location line="+1"/> <location line="+1"/>
<source>&lt;b&gt;WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.&lt;/b&gt;</source> <source>&lt;b&gt;WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.&lt;/b&gt;</source>
<translation type="unfinished"></translation> <translation>&lt;b&gt;警告: openpilotによるアクセル制御は実験段階でありAEBを無効化します&lt;/b&gt;</translation>
</message> </message>
<message> <message>
<location line="+42"/> <location line="+42"/>
<source>Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.</source> <source>Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.</source>
<translation type="unfinished"></translation> <translation>openpilotに任せますopenpilotが人間と同じように運転します</translation>
</message> </message>
<message> <message>
<location line="-55"/> <location line="-55"/>

@ -70,7 +70,7 @@
<message> <message>
<location line="+0"/> <location line="+0"/>
<source>leave blank for automatic configuration</source> <source>leave blank for automatic configuration</source>
<translation> </translation> <translation> </translation>
</message> </message>
</context> </context>
<context> <context>
@ -140,7 +140,7 @@
<message> <message>
<location line="+4"/> <location line="+4"/>
<source>Reset Calibration</source> <source>Reset Calibration</source>
<translation> </translation> <translation></translation>
</message> </message>
<message> <message>
<location line="+0"/> <location line="+0"/>
@ -155,7 +155,7 @@
<message> <message>
<location line="+7"/> <location line="+7"/>
<source>Review Training Guide</source> <source>Review Training Guide</source>
<translation> </translation> <translation> </translation>
</message> </message>
<message> <message>
<location line="+0"/> <location line="+0"/>
@ -210,12 +210,12 @@
<message> <message>
<location line="+20"/> <location line="+20"/>
<source>openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.</source> <source>openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.</source>
<translation>openpilot은 4° , 5° 8° . openpilot은 .</translation> <translation>openpilot은 4° , 5° 8° . openpilot은 .</translation>
</message> </message>
<message> <message>
<location line="+11"/> <location line="+11"/>
<source> Your device is pointed %1° %2 and %3° %4.</source> <source> Your device is pointed %1° %2 and %3° %4.</source>
<translation> %1° %2 %3° %4 .</translation> <translation> %1° %2 %3° %4 .</translation>
</message> </message>
<message> <message>
<location line="+1"/> <location line="+1"/>
@ -479,7 +479,7 @@ location set</source>
<location line="+0"/> <location line="+0"/>
<location line="+10"/> <location line="+10"/>
<source>for &quot;%1&quot;</source> <source>for &quot;%1&quot;</source>
<translation> &quot;%1&quot;</translation> <translation>&quot;%1&quot; </translation>
</message> </message>
<message> <message>
<location line="+0"/> <location line="+0"/>
@ -526,7 +526,7 @@ location set</source>
<translation></translation> <translation></translation>
</message> </message>
<message> <message>
<location line="+91"/> <location line="+93"/>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation> </translation>
</message> </message>
@ -539,7 +539,7 @@ location set</source>
<context> <context>
<name>PairingPopup</name> <name>PairingPopup</name>
<message> <message>
<location filename="../qt/widgets/prime.cc" line="+86"/> <location filename="../qt/widgets/prime.cc" line="+89"/>
<source>Pair your device to your comma account</source> <source>Pair your device to your comma account</source>
<translation> </translation> <translation> </translation>
</message> </message>
@ -684,7 +684,7 @@ location set</source>
<message> <message>
<location line="+6"/> <location line="+6"/>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source> <source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation> . . .</translation> <translation> . . .</translation>
</message> </message>
<message> <message>
<location line="+9"/> <location line="+9"/>
@ -797,7 +797,7 @@ location set</source>
<message> <message>
<location line="-81"/> <location line="-81"/>
<source>Continue without Wi-Fi</source> <source>Continue without Wi-Fi</source>
<translation>wifi </translation> <translation>wifi </translation>
</message> </message>
<message> <message>
<location line="+2"/> <location line="+2"/>
@ -842,7 +842,7 @@ location set</source>
<message> <message>
<location line="+6"/> <location line="+6"/>
<source>Ensure the entered URL is valid, and the devices internet connection is good.</source> <source>Ensure the entered URL is valid, and the devices internet connection is good.</source>
<translation> URL이 .</translation> <translation> URL이 .</translation>
</message> </message>
<message> <message>
<location line="+13"/> <location line="+13"/>
@ -1080,7 +1080,7 @@ location set</source>
<message> <message>
<location line="+0"/> <location line="+0"/>
<source>Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.</source> <source>Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.</source>
<translation> GitHub SSH . GitHub . comma GitHub .</translation> <translation>경고: 허용으로 GitHub SSH . GitHub ID . comma에서는 GitHub ID를 .</translation>
</message> </message>
<message> <message>
<location line="+6"/> <location line="+6"/>
@ -1160,7 +1160,7 @@ location set</source>
<message> <message>
<location line="+1"/> <location line="+1"/>
<source>Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off.</source> <source>Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off.</source>
<translation> openpilot . . .</translation> <translation> openpilot . . .</translation>
</message> </message>
<message> <message>
<location line="+5"/> <location line="+5"/>
@ -1170,7 +1170,7 @@ location set</source>
<message> <message>
<location line="+1"/> <location line="+1"/>
<source>Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).</source> <source>Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).</source>
<translation> 50km/h(31mph) .</translation> <translation> 50km/h(31mph) .</translation>
</message> </message>
<message> <message>
<location line="+5"/> <location line="+5"/>
@ -1195,22 +1195,22 @@ location set</source>
<message> <message>
<location line="+11"/> <location line="+11"/>
<source>🌮 End-to-end longitudinal (extremely alpha) 🌮</source> <source>🌮 End-to-end longitudinal (extremely alpha) 🌮</source>
<translation>🌮 e2e long ( ) 🌮 </translation> <translation>🌮 e2e ( ) 🌮 </translation>
</message> </message>
<message> <message>
<location line="+6"/> <location line="+6"/>
<source>Experimental openpilot longitudinal control</source> <source>Experimental openpilot longitudinal control</source>
<translation type="unfinished"></translation> <translation>openpilot ()</translation>
</message> </message>
<message> <message>
<location line="+1"/> <location line="+1"/>
<source>&lt;b&gt;WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.&lt;/b&gt;</source> <source>&lt;b&gt;WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.&lt;/b&gt;</source>
<translation type="unfinished"></translation> <translation>&lt;b&gt;경고: openpilot AEB를 .&lt;/b&gt;</translation>
</message> </message>
<message> <message>
<location line="+42"/> <location line="+42"/>
<source>Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.</source> <source>Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.</source>
<translation type="unfinished"></translation> <translation> openpilot은 . ( )</translation>
</message> </message>
<message> <message>
<location line="-55"/> <location line="-55"/>
@ -1253,7 +1253,7 @@ location set</source>
<message> <message>
<location line="+6"/> <location line="+6"/>
<source>An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.</source> <source>An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.</source>
<translation>OS . wifi에 . 1GB입니다.</translation> <translation>OS . wifi에 . 1GB입니다.</translation>
</message> </message>
<message> <message>
<location line="+11"/> <location line="+11"/>

@ -527,7 +527,7 @@ trabalho definido</translation>
<translation>ATUALIZAÇÃO</translation> <translation>ATUALIZAÇÃO</translation>
</message> </message>
<message> <message>
<location line="+91"/> <location line="+93"/>
<source> ALERTS</source> <source> ALERTS</source>
<translation> ALERTAS</translation> <translation> ALERTAS</translation>
</message> </message>
@ -540,7 +540,7 @@ trabalho definido</translation>
<context> <context>
<name>PairingPopup</name> <name>PairingPopup</name>
<message> <message>
<location filename="../qt/widgets/prime.cc" line="+86"/> <location filename="../qt/widgets/prime.cc" line="+89"/>
<source>Pair your device to your comma account</source> <source>Pair your device to your comma account</source>
<translation>Pareie seu dispositivo à sua conta comma</translation> <translation>Pareie seu dispositivo à sua conta comma</translation>
</message> </message>

@ -524,7 +524,7 @@ location set</source>
<translation></translation> <translation></translation>
</message> </message>
<message> <message>
<location line="+91"/> <location line="+93"/>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation> </translation>
</message> </message>
@ -537,7 +537,7 @@ location set</source>
<context> <context>
<name>PairingPopup</name> <name>PairingPopup</name>
<message> <message>
<location filename="../qt/widgets/prime.cc" line="+86"/> <location filename="../qt/widgets/prime.cc" line="+89"/>
<source>Pair your device to your comma account</source> <source>Pair your device to your comma account</source>
<translation>comma账号配对</translation> <translation>comma账号配对</translation>
</message> </message>

@ -526,7 +526,7 @@ location set</source>
<translation></translation> <translation></translation>
</message> </message>
<message> <message>
<location line="+91"/> <location line="+93"/>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation> </translation>
</message> </message>
@ -539,7 +539,7 @@ location set</source>
<context> <context>
<name>PairingPopup</name> <name>PairingPopup</name>
<message> <message>
<location filename="../qt/widgets/prime.cc" line="+86"/> <location filename="../qt/widgets/prime.cc" line="+89"/>
<source>Pair your device to your comma account</source> <source>Pair your device to your comma account</source>
<translation> comma </translation> <translation> comma </translation>
</message> </message>

@ -236,6 +236,7 @@ UIState::UIState(QObject *parent) : QObject(parent) {
Params params; Params params;
wide_camera = params.getBool("WideCameraOnly"); wide_camera = params.getBool("WideCameraOnly");
prime_type = std::atoi(params.get("PrimeType").c_str()); prime_type = std::atoi(params.get("PrimeType").c_str());
language = QString::fromStdString(params.get("LanguageSetting"));
// update timer // update timer
timer = new QTimer(this); timer = new QTimer(this);

@ -127,6 +127,7 @@ public:
bool awake; bool awake;
int prime_type = 0; int prime_type = 0;
QString language;
QTransform car_space_transform; QTransform car_space_transform;
bool wide_camera; bool wide_camera;

@ -249,13 +249,14 @@ def finalize_update(wait_helper: WaitTimeHelper) -> None:
run(["git", "reset", "--hard"], FINALIZED) run(["git", "reset", "--hard"], FINALIZED)
run(["git", "submodule", "foreach", "--recursive", "git", "reset"], FINALIZED) run(["git", "submodule", "foreach", "--recursive", "git", "reset"], FINALIZED)
cloudlog.info("Starting git gc") cloudlog.info("Starting git cleanup in finalized update")
t = time.monotonic() t = time.monotonic()
try: try:
run(["git", "gc"], FINALIZED) run(["git", "gc"], FINALIZED)
cloudlog.event("Done git gc", duration=time.monotonic() - t) run(["git", "lfs", "prune"], FINALIZED)
cloudlog.event("Done git cleanup", duration=time.monotonic() - t)
except subprocess.CalledProcessError: except subprocess.CalledProcessError:
cloudlog.exception(f"Failed git gc, took {time.monotonic() - t:.3f} s") cloudlog.exception(f"Failed git cleanup, took {time.monotonic() - t:.3f} s")
if wait_helper.shutdown: if wait_helper.shutdown:
cloudlog.info("got interrupted finalizing overlay") cloudlog.info("got interrupted finalizing overlay")

@ -1,21 +1,18 @@
Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc')
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic']
cameras = [] cenv = env.Clone()
if arch == "larch64": cenv['CPPPATH'].append('include/')
libs += ['atomic']
cameras = ['cameras/camera_qcom2.cc']
env.Program('camerad', [ camera_obj = cenv.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
cenv.Program('camerad', [
'main.cc', 'main.cc',
'cameras/camera_common.cc', camera_obj,
'imgproc/utils.cc',
cameras,
], LIBS=libs) ], LIBS=libs)
if GetOption("test") and arch == "x86_64": if GetOption("test") and arch == "x86_64":
env.Program('test/ae_gray_test', [ cenv.Program('test/ae_gray_test', [
'test/ae_gray_test.cc', 'test/ae_gray_test.cc',
'cameras/camera_common.cc', camera_obj,
], LIBS=libs) ], LIBS=libs)

@ -18,11 +18,9 @@
#include "system/hardware/hw.h" #include "system/hardware/hw.h"
#include "msm_media_info.h" #include "msm_media_info.h"
#include "system/camerad/cameras/camera_qcom2.h"
#ifdef QCOM2 #ifdef QCOM2
#include "CL/cl_ext_qcom.h" #include "CL/cl_ext_qcom.h"
#include "system/camerad/cameras/camera_qcom2.h"
#else
#include "system/camerad/test/camera_test.h"
#endif #endif
ExitHandler do_exit; ExitHandler do_exit;
@ -36,10 +34,10 @@ public:
"-cl-fast-relaxed-math -cl-denorms-are-zero " "-cl-fast-relaxed-math -cl-denorms-are-zero "
"-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d "
"-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d "
"-DCAM_NUM=%d%s", "-DIS_OX=%d -DCAM_NUM=%d%s",
ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset,
b->rgb_width, b->rgb_height, b->rgb_stride, buf_width, uv_offset, b->rgb_width, b->rgb_height, b->rgb_stride, buf_width, uv_offset,
s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); s->camera_id==CAMERA_ID_OX03C10 ? 1 : 0, s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : "");
const char *cl_file = "cameras/real_debayer.cl"; const char *cl_file = "cameras/real_debayer.cl";
cl_program prg_debayer = cl_program_from_file(context, device_id, cl_file, args); cl_program prg_debayer = cl_program_from_file(context, device_id, cl_file, args);
krnl_ = CL_CHECK_ERR(clCreateKernel(prg_debayer, "debayer10", &err)); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_debayer, "debayer10", &err));
@ -348,8 +346,8 @@ void camerad_thread() {
MultiCameraState cameras = {}; MultiCameraState cameras = {};
VisionIpcServer vipc_server("camerad", device_id, context); VisionIpcServer vipc_server("camerad", device_id, context);
cameras_init(&vipc_server, &cameras, device_id, context);
cameras_open(&cameras); cameras_open(&cameras);
cameras_init(&vipc_server, &cameras, device_id, context);
vipc_server.start_listener(); vipc_server.start_listener();

@ -23,7 +23,7 @@
#define CAMERA_ID_LGC920 6 #define CAMERA_ID_LGC920 6
#define CAMERA_ID_LGC615 7 #define CAMERA_ID_LGC615 7
#define CAMERA_ID_AR0231 8 #define CAMERA_ID_AR0231 8
#define CAMERA_ID_IMX390 9 #define CAMERA_ID_OX03C10 9
#define CAMERA_ID_MAX 10 #define CAMERA_ID_MAX 10
const int YUV_BUFFER_COUNT = 40; const int YUV_BUFFER_COUNT = 40;

@ -32,7 +32,8 @@ const size_t FRAME_HEIGHT = 1208;
const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment)
const size_t AR0231_REGISTERS_HEIGHT = 2; const size_t AR0231_REGISTERS_HEIGHT = 2;
const size_t AR0231_STATS_HEIGHT = 2; // TODO: this extra height is universal and doesn't apply per camera
const size_t AR0231_STATS_HEIGHT = 2+8;
const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py
@ -47,153 +48,60 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = {
.frame_offset = AR0231_REGISTERS_HEIGHT, .frame_offset = AR0231_REGISTERS_HEIGHT,
.stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT, .stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT,
}, },
[CAMERA_ID_IMX390] = { [CAMERA_ID_OX03C10] = {
.frame_width = FRAME_WIDTH, .frame_width = FRAME_WIDTH,
.frame_height = FRAME_HEIGHT, .frame_height = FRAME_HEIGHT,
.frame_stride = FRAME_STRIDE, .frame_stride = FRAME_STRIDE, // (0xa80*12//8)
.extra_height = 16, // this right?
}, },
}; };
const float DC_GAIN = 2.5; const float DC_GAIN_AR0231 = 2.5;
const float sensor_analog_gains[] = { const float DC_GAIN_OX03C10 = 7.32;
const float DC_GAIN_ON_GREY_AR0231= 0.2;
const float DC_GAIN_OFF_GREY_AR0231 = 0.3;
const float DC_GAIN_ON_GREY_OX03C10= 0.3;
const float DC_GAIN_OFF_GREY_OX03C10 = 0.375;
const int DC_GAIN_MIN_WEIGHT = 0;
const int DC_GAIN_MAX_WEIGHT_AR0231 = 1;
const int DC_GAIN_MAX_WEIGHT_OX03C10 = 32;
const float sensor_analog_gains_AR0231[] = {
1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3
3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7 3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7
5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11
7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass 7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass
const int ANALOG_GAIN_MIN_IDX = 0x1; // 0.25x // similar gain curve to AR
const int ANALOG_GAIN_REC_IDX = 0x6; // 0.8x const float sensor_analog_gains_OX03C10[] = {
const int ANALOG_GAIN_MAX_IDX = 0xD; // 4.0x 1.0, 1.25, 1.3125, 1.5625,
1.6875, 2.0, 2.25, 2.625,
const int EXPOSURE_TIME_MIN = 2; // with HDR, fastest ss 3.125, 3.625, 4.5, 5.0,
const int EXPOSURE_TIME_MAX = 0x0855; // with HDR, slowest ss, 40ms 7.25, 8.5, 12.0, 15.5};
// ************** low level camera helpers ****************
int do_cam_control(int fd, int op_code, void *handle, int size) {
struct cam_control camcontrol = {0};
camcontrol.op_code = op_code;
camcontrol.handle = (uint64_t)handle;
if (size == 0) {
camcontrol.size = 8;
camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE;
} else {
camcontrol.size = size;
camcontrol.handle_type = CAM_HANDLE_USER_POINTER;
}
int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol));
if (ret == -1) {
LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno);
}
return ret;
}
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1) {
struct cam_acquire_dev_cmd cmd = {
.session_handle = session_handle,
.handle_type = CAM_HANDLE_USER_POINTER,
.num_resources = (uint32_t)(data ? num_resources : 0),
.resource_hdl = (uint64_t)data,
};
int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd));
return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt;
};
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) {
struct cam_config_dev_cmd cmd = {
.session_handle = session_handle,
.dev_handle = dev_handle,
.packet_handle = packet_handle,
};
return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd));
}
int device_control(int fd, int op_code, int session_handle, int dev_handle) {
// start stop and release are all the same
struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle };
return do_cam_control(fd, op_code, &cmd, sizeof(cmd));
}
void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, const uint32_t ox03c10_analog_gains_reg[] = {
int mmu_hdl = 0, int mmu_hdl2 = 0) { 0x100, 0x140, 0x150, 0x190,
struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; 0x1B0, 0x200, 0x240, 0x2A0,
mem_mgr_alloc_cmd.len = len; 0x320, 0x3A0, 0x480, 0x500,
mem_mgr_alloc_cmd.align = align; 0x740, 0x880, 0xC00, 0xF80};
mem_mgr_alloc_cmd.flags = flags;
mem_mgr_alloc_cmd.num_hdl = 0;
if (mmu_hdl != 0) {
mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl;
mem_mgr_alloc_cmd.num_hdl++;
}
if (mmu_hdl2 != 0) {
mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2;
mem_mgr_alloc_cmd.num_hdl++;
}
do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); const int ANALOG_GAIN_MIN_IDX_AR0231 = 0x1; // 0.25x
*handle = mem_mgr_alloc_cmd.out.buf_handle; const int ANALOG_GAIN_REC_IDX_AR0231 = 0x6; // 0.8x
const int ANALOG_GAIN_MAX_IDX_AR0231 = 0xD; // 4.0x
void *ptr = NULL; const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0;
if (mem_mgr_alloc_cmd.out.fd > 0) { const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x5; // 2x
ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0xF;
assert(ptr != MAP_FAILED);
}
// LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); const int EXPOSURE_TIME_MIN_AR0231 = 2; // with HDR, fastest ss
const int EXPOSURE_TIME_MAX_AR0231 = 0x0855; // with HDR, slowest ss, 40ms
return ptr; const int EXPOSURE_TIME_MIN_OX03C10 = 2; // 1x
} const int EXPOSURE_TIME_MAX_OX03C10 = 2016;
const uint32_t VS_TIME_MIN_OX03C10 = 1;
void release(int video0_fd, uint32_t handle) { const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35
int ret;
struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0};
mem_mgr_release_cmd.buf_handle = handle;
ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd));
assert(ret == 0);
}
void release_fd(int video0_fd, uint32_t handle) {
// handle to fd
close(handle>>16);
release(video0_fd, handle);
}
void *MemoryManager::alloc(int size, uint32_t *handle) {
lock.lock();
void *ptr;
if (!cached_allocations[size].empty()) {
ptr = cached_allocations[size].front();
cached_allocations[size].pop();
*handle = handle_lookup[ptr];
} else {
ptr = alloc_w_mmu_hdl(video0_fd, size, handle);
handle_lookup[ptr] = *handle;
size_lookup[ptr] = size;
}
lock.unlock();
return ptr;
}
void MemoryManager::free(void *ptr) {
lock.lock();
cached_allocations[size_lookup[ptr]].push(ptr);
lock.unlock();
}
MemoryManager::~MemoryManager() {
for (auto& x : cached_allocations) {
while (!x.second.empty()) {
void *ptr = x.second.front();
x.second.pop();
LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]);
munmap(ptr, size_lookup[ptr]);
release_fd(video0_fd, handle_lookup[ptr]);
handle_lookup.erase(ptr);
size_lookup.erase(ptr);
}
}
}
int CameraState::clear_req_queue() { int CameraState::clear_req_queue() {
struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; struct cam_req_mgr_flush_info req_mgr_flush_request = {0};
@ -213,8 +121,8 @@ void CameraState::sensors_start() {
LOGD("starting sensor %d", camera_num); LOGD("starting sensor %d", camera_num);
if (camera_id == CAMERA_ID_AR0231) { if (camera_id == CAMERA_ID_AR0231) {
sensors_i2c(start_reg_array_ar0231, std::size(start_reg_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); sensors_i2c(start_reg_array_ar0231, std::size(start_reg_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true);
} else if (camera_id == CAMERA_ID_IMX390) { } else if (camera_id == CAMERA_ID_OX03C10) {
sensors_i2c(start_reg_array_imx390, std::size(start_reg_array_imx390), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); sensors_i2c(start_reg_array_ox03c10, std::size(start_reg_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false);
} else { } else {
assert(false); assert(false);
} }
@ -300,15 +208,15 @@ int CameraState::sensors_init() {
switch (camera_num) { switch (camera_num) {
case 0: case 0:
// port 0 // port 0
i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x34; i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C; // 6C = 0x36*2
break; break;
case 1: case 1:
// port 1 // port 1
i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x30 : 0x36; i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x30 : 0x20;
break; break;
case 2: case 2:
// port 2 // port 2
i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x34; i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C;
break; break;
} }
@ -324,9 +232,9 @@ int CameraState::sensors_init() {
if (camera_id == CAMERA_ID_AR0231) { if (camera_id == CAMERA_ID_AR0231) {
probe->reg_addr = 0x3000; probe->reg_addr = 0x3000;
probe->expected_data = 0x354; probe->expected_data = 0x354;
} else if (camera_id == CAMERA_ID_IMX390) { } else if (camera_id == CAMERA_ID_OX03C10) {
probe->reg_addr = 0x330; probe->reg_addr = 0x300a;
probe->expected_data = 0x1538; probe->expected_data = 0x5803;
} else { } else {
assert(false); assert(false);
} }
@ -393,8 +301,8 @@ int CameraState::sensors_init() {
power->power_settings[1].power_seq_type = 1; power->power_settings[1].power_seq_type = 1;
power->power_settings[2].power_seq_type = 3; power->power_settings[2].power_seq_type = 3;
LOGD("probing the sensor");
int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0);
LOGD("probing the sensor: %d", ret);
mm.free(i2c_info); mm.free(i2c_info);
mm.free(power_settings); mm.free(power_settings);
@ -606,12 +514,67 @@ void CameraState::enqueue_req_multi(int start, int n, bool dp) {
// ******************* camera ******************* // ******************* camera *******************
void CameraState::camera_init(MultiCameraState *multi_cam_state_, VisionIpcServer * v, int camera_id_, int camera_num_, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, bool enabled_) { void CameraState::camera_set_parameters() {
multi_cam_state = multi_cam_state_; if (camera_id == CAMERA_ID_AR0231) {
camera_id = camera_id_; dc_gain_factor = DC_GAIN_AR0231;
camera_num = camera_num_; dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_AR0231;
enabled = enabled_; dc_gain_on_grey = DC_GAIN_ON_GREY_AR0231;
dc_gain_off_grey = DC_GAIN_OFF_GREY_AR0231;
exposure_time_min = EXPOSURE_TIME_MIN_AR0231;
exposure_time_max = EXPOSURE_TIME_MAX_AR0231;
analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_AR0231;
analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_AR0231;
analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_AR0231;
for (int i=0; i<=analog_gain_max_idx; i++) {
sensor_analog_gains[i] = sensor_analog_gains_AR0231[i];
}
min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx];
} else if (camera_id == CAMERA_ID_OX03C10) {
dc_gain_factor = DC_GAIN_OX03C10;
dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_OX03C10;
dc_gain_on_grey = DC_GAIN_ON_GREY_OX03C10;
dc_gain_off_grey = DC_GAIN_OFF_GREY_OX03C10;
exposure_time_min = EXPOSURE_TIME_MIN_OX03C10;
exposure_time_max = EXPOSURE_TIME_MAX_OX03C10;
analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_OX03C10;
analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_OX03C10;
analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_OX03C10;
for (int i=0; i<=analog_gain_max_idx; i++) {
sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i];
}
min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx];
} else {
assert(false);
}
max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx];
target_grey_fraction = 0.3;
dc_gain_enabled = false;
dc_gain_weight = DC_GAIN_MIN_WEIGHT;
gain_idx = analog_gain_rec_idx;
exposure_time = 5;
cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight) * sensor_analog_gains[gain_idx] * exposure_time;
}
void CameraState::camera_map_bufs(MultiCameraState *s) {
for (int i = 0; i < FRAME_BUF_COUNT; i++) {
// configure ISP to put the image in place
struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0};
mem_mgr_map_cmd.mmu_hdls[0] = s->device_iommu;
mem_mgr_map_cmd.num_hdl = 1;
mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE;
mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd;
int ret = do_cam_control(s->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd));
LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret);
buf_handle[i] = mem_mgr_map_cmd.out.buf_handle;
}
enqueue_req_multi(1, FRAME_BUF_COUNT, 0);
}
void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, int camera_id_, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type) {
if (!enabled) return; if (!enabled) return;
camera_id = camera_id_;
LOGD("camera init %d", camera_num); LOGD("camera init %d", camera_num);
assert(camera_id < std::size(cameras_supported)); assert(camera_id < std::size(cameras_supported));
@ -621,19 +584,18 @@ void CameraState::camera_init(MultiCameraState *multi_cam_state_, VisionIpcServe
request_id_last = 0; request_id_last = 0;
skipped = true; skipped = true;
min_ev = EXPOSURE_TIME_MIN * sensor_analog_gains[ANALOG_GAIN_MIN_IDX]; camera_set_parameters();
max_ev = EXPOSURE_TIME_MAX * sensor_analog_gains[ANALOG_GAIN_MAX_IDX] * DC_GAIN;
target_grey_fraction = 0.3;
dc_gain_enabled = false;
gain_idx = ANALOG_GAIN_REC_IDX;
exposure_time = 5;
cur_ev[0] = cur_ev[1] = cur_ev[2] = (dc_gain_enabled ? DC_GAIN : 1) * sensor_analog_gains[gain_idx] * exposure_time;
buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type); buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type);
camera_map_bufs(s);
} }
void CameraState::camera_open() { void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num_, bool enabled_) {
multi_cam_state = multi_cam_state_;
camera_num = camera_num_;
enabled = enabled_;
if (!enabled) return;
int ret; int ret;
sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num); sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num);
assert(sensor_fd >= 0); assert(sensor_fd >= 0);
@ -644,10 +606,12 @@ void CameraState::camera_open() {
// probe the sensor // probe the sensor
LOGD("-- Probing sensor %d", camera_num); LOGD("-- Probing sensor %d", camera_num);
camera_id = CAMERA_ID_AR0231;
ret = sensors_init(); ret = sensors_init();
if (ret != 0) { if (ret != 0) {
LOGD("AR0231 init failed, trying IMX390"); // TODO: use build flag instead?
camera_id = CAMERA_ID_IMX390; LOGD("AR0231 init failed, trying OX03C10");
camera_id = CAMERA_ID_OX03C10;
ret = sensors_init(); ret = sensors_init();
} }
LOGD("-- Probing sensor %d done with %d", camera_num, ret); LOGD("-- Probing sensor %d done with %d", camera_num, ret);
@ -671,13 +635,18 @@ void CameraState::camera_open() {
LOGD("acquire sensor dev"); LOGD("acquire sensor dev");
LOG("-- Configuring sensor"); LOG("-- Configuring sensor");
uint32_t dt;
if (camera_id == CAMERA_ID_AR0231) { if (camera_id == CAMERA_ID_AR0231) {
sensors_i2c(init_array_ar0231, std::size(init_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); sensors_i2c(init_array_ar0231, std::size(init_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true);
} else if (camera_id == CAMERA_ID_IMX390) { dt = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead
sensors_i2c(init_array_imx390, std::size(init_array_imx390), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); } else if (camera_id == CAMERA_ID_OX03C10) {
sensors_i2c(init_array_ox03c10, std::size(init_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false);
// one is 0x2a, two are 0x2b
dt = 0x2c;
} else { } else {
assert(false); assert(false);
} }
printf("dt is %x\n", dt);
// NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c
// If you don't do this, the strobe GPIO is an output (even in reset it seems!) // If you don't do this, the strobe GPIO is an output (even in reset it seems!)
@ -691,7 +660,7 @@ void CameraState::camera_open() {
.lane_cfg = 0x3210, .lane_cfg = 0x3210,
.vc = 0x0, .vc = 0x0,
.dt = 0x12, // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead .dt = dt,
.format = CAM_FORMAT_MIPI_RAW_12, .format = CAM_FORMAT_MIPI_RAW_12,
.test_pattern = 0x2, // 0x3? .test_pattern = 0x2, // 0x3?
@ -805,29 +774,15 @@ void CameraState::camera_open() {
ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle);
LOGD("start isp: %d", ret); LOGD("start isp: %d", ret);
for (int i = 0; i < FRAME_BUF_COUNT; i++) {
// configure ISP to put the image in place
struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0};
mem_mgr_map_cmd.mmu_hdls[0] = multi_cam_state->device_iommu;
mem_mgr_map_cmd.num_hdl = 1;
mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE;
mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd;
ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd));
LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret);
buf_handle[i] = mem_mgr_map_cmd.out.buf_handle;
}
// TODO: this is unneeded, should we be doing the start i2c in a different way? // TODO: this is unneeded, should we be doing the start i2c in a different way?
//ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle); //ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle);
//LOGD("start sensor: %d", ret); //LOGD("start sensor: %d", ret);
enqueue_req_multi(1, FRAME_BUF_COUNT, 0);
} }
void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) {
s->driver_cam.camera_init(s, v, CAMERA_ID_AR0231, 2, 20, device_id, ctx, VISION_STREAM_DRIVER, !env_disable_driver); s->driver_cam.camera_init(s, v, s->driver_cam.camera_id, 20, device_id, ctx, VISION_STREAM_DRIVER);
s->road_cam.camera_init(s, v, CAMERA_ID_AR0231, 1, 20, device_id, ctx, VISION_STREAM_ROAD, !env_disable_road); s->road_cam.camera_init(s, v, s->road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_ROAD);
s->wide_road_cam.camera_init(s, v, CAMERA_ID_AR0231, 0, 20, device_id, ctx, VISION_STREAM_WIDE_ROAD, !env_disable_wide_road); s->wide_road_cam.camera_init(s, v, s->wide_road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_WIDE_ROAD);
s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"});
} }
@ -873,11 +828,11 @@ void cameras_open(MultiCameraState *s) {
ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub));
LOGD("req mgr subscribe: %d", ret); LOGD("req mgr subscribe: %d", ret);
s->driver_cam.camera_open(); s->driver_cam.camera_open(s, 2, !env_disable_driver);
LOGD("driver camera opened"); LOGD("driver camera opened");
s->road_cam.camera_open(); s->road_cam.camera_open(s, 1, !env_disable_road);
LOGD("road camera opened"); LOGD("road camera opened");
s->wide_road_cam.camera_open(); s->wide_road_cam.camera_open(s, 0, !env_disable_wide_road);
LOGD("wide road camera opened"); LOGD("wide road camera opened");
} }
@ -1044,7 +999,7 @@ void CameraState::handle_camera_event(void *evdat) {
meta_data.frame_id = main_id - idx_offset; meta_data.frame_id = main_id - idx_offset;
meta_data.timestamp_sof = timestamp; meta_data.timestamp_sof = timestamp;
exp_lock.lock(); exp_lock.lock();
meta_data.gain = dc_gain_enabled ? analog_gain_frac * DC_GAIN : analog_gain_frac; meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight);
meta_data.high_conversion_gain = dc_gain_enabled; meta_data.high_conversion_gain = dc_gain_enabled;
meta_data.integ_lines = exposure_time; meta_data.integ_lines = exposure_time;
meta_data.measured_grey_fraction = measured_grey_fraction; meta_data.measured_grey_fraction = measured_grey_fraction;
@ -1096,12 +1051,17 @@ void CameraState::set_camera_exposure(float grey_frac) {
// Hysteresis around high conversion gain // Hysteresis around high conversion gain
// We usually want this on since it results in lower noise, but turn off in very bright day scenes // We usually want this on since it results in lower noise, but turn off in very bright day scenes
bool enable_dc_gain = dc_gain_enabled; bool enable_dc_gain = dc_gain_enabled;
if (!enable_dc_gain && target_grey < 0.2) { if (!enable_dc_gain && target_grey < dc_gain_on_grey) {
enable_dc_gain = true; enable_dc_gain = true;
} else if (enable_dc_gain && target_grey > 0.3) { dc_gain_weight = DC_GAIN_MIN_WEIGHT;
} else if (enable_dc_gain && target_grey > dc_gain_off_grey) {
enable_dc_gain = false; enable_dc_gain = false;
dc_gain_weight = dc_gain_max_weight;
} }
if (enable_dc_gain && dc_gain_weight < dc_gain_max_weight) {dc_gain_weight += 1;}
if (!enable_dc_gain && dc_gain_weight > DC_GAIN_MIN_WEIGHT) {dc_gain_weight -= 1;}
std::string gain_bytes, time_bytes; std::string gain_bytes, time_bytes;
if (env_ctrl_exp_from_params) { if (env_ctrl_exp_from_params) {
gain_bytes = Params().get("CameraDebugExpGain"); gain_bytes = Params().get("CameraDebugExpGain");
@ -1119,14 +1079,14 @@ void CameraState::set_camera_exposure(float grey_frac) {
} else { } else {
// Simple brute force optimizer to choose sensor parameters // Simple brute force optimizer to choose sensor parameters
// to reach desired EV // to reach desired EV
for (int g = std::max((int)ANALOG_GAIN_MIN_IDX, gain_idx - 1); g <= std::min((int)ANALOG_GAIN_MAX_IDX, gain_idx + 1); g++) { for (int g = std::max((int)analog_gain_min_idx, gain_idx - 1); g <= std::min((int)analog_gain_max_idx, gain_idx + 1); g++) {
float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1); float gain = sensor_analog_gains[g] * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight);
// Compute optimal time for given gain // Compute optimal time for given gain
int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); int t = std::clamp(int(std::round(desired_ev / gain)), exposure_time_min, exposure_time_max);
// Only go below recommended 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) { if (g < analog_gain_rec_idx && t > 20 && g < gain_idx) {
continue; continue;
} }
@ -1134,8 +1094,8 @@ void CameraState::set_camera_exposure(float grey_frac) {
float score = std::abs(desired_ev - (t * gain)) * 10; float score = std::abs(desired_ev - (t * gain)) * 10;
// Going below recommended 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; float m = g > analog_gain_rec_idx ? 5.0 : 0.1;
score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; score += std::abs(g - (int)analog_gain_rec_idx) * m;
// LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev); // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev);
@ -1160,7 +1120,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
exposure_time = new_t; exposure_time = new_t;
dc_gain_enabled = enable_dc_gain; dc_gain_enabled = enable_dc_gain;
float gain = analog_gain_frac * (dc_gain_enabled ? DC_GAIN : 1.0); float gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight);
cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain;
exp_lock.unlock(); exp_lock.unlock();
@ -1181,17 +1141,25 @@ void CameraState::set_camera_exposure(float grey_frac) {
{0x3012, (uint16_t)exposure_time}, {0x3012, (uint16_t)exposure_time},
}; };
sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true);
} else if (camera_id == CAMERA_ID_IMX390) { } else if (camera_id == CAMERA_ID_OX03C10) {
// if gain is sub 1, we have to use exposure to mimic sub 1 gains // t_HCG + t_LCG + t_VS on LPD, t_SPD on SPD
uint32_t real_exposure_time = (gain < 1.0) ? (exposure_time*gain) : exposure_time; uint32_t hcg_time = std::max((dc_gain_weight * exposure_time / dc_gain_max_weight), 0);
// invert real_exposure_time, max exposure is 2 uint32_t lcg_time = std::max(((dc_gain_max_weight - dc_gain_weight) * exposure_time / dc_gain_max_weight), 0);
real_exposure_time = (exposure_time >= 0x7cf) ? 2 : (0x7cf - exposure_time); uint32_t spd_time = std::max(hcg_time / 16, (uint32_t)exposure_time_min);
uint32_t real_gain = int((10*log10(fmax(1.0, gain)))/0.3); uint32_t vs_time = std::min(std::max(hcg_time / 64, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10);
//printf("%d expose: %d gain: %f = %d\n", camera_num, exposure_time, gain, real_gain);
uint32_t real_gain = ox03c10_analog_gains_reg[new_g];
struct i2c_random_wr_payload exp_reg_array[] = { struct i2c_random_wr_payload exp_reg_array[] = {
{0x000c, real_exposure_time&0xFF}, {0x000d, real_exposure_time>>8},
{0x0010, real_exposure_time&0xFF}, {0x0011, real_exposure_time>>8}, {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF},
{0x0018, real_gain&0xFF}, {0x0019, real_gain>>8}, {0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF},
{0x3541, spd_time>>8}, {0x3542, spd_time&0xFF},
{0x35c1, vs_time>>8}, {0x35c2, vs_time&0xFF},
{0x3508, real_gain>>8}, {0x3509, real_gain&0xFF},
{0x3588, real_gain>>8}, {0x3589, real_gain&0xFF},
{0x3548, real_gain>>8}, {0x3549, real_gain&0xFF},
{0x35c8, real_gain>>8}, {0x35c9, real_gain&0xFF},
}; };
sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false);
} }
@ -1336,4 +1304,3 @@ void cameras_run(MultiCameraState *s) {
cameras_close(s); cameras_close(s);
} }

@ -7,25 +7,12 @@
#include <media/cam_req_mgr.h> #include <media/cam_req_mgr.h>
#include "system/camerad/cameras/camera_common.h" #include "system/camerad/cameras/camera_common.h"
#include "system/camerad/cameras/camera_util.h"
#include "common/params.h" #include "common/params.h"
#include "common/util.h" #include "common/util.h"
#define FRAME_BUF_COUNT 4 #define FRAME_BUF_COUNT 4
class MemoryManager {
public:
void init(int _video0_fd) { video0_fd = _video0_fd; }
void *alloc(int len, uint32_t *handle);
void free(void *ptr);
~MemoryManager();
private:
std::mutex lock;
std::map<void *, uint32_t> handle_lookup;
std::map<void *, int> size_lookup;
std::map<int, std::queue<void *> > cached_allocations;
int video0_fd;
};
class CameraState { class CameraState {
public: public:
MultiCameraState *multi_cam_state; MultiCameraState *multi_cam_state;
@ -36,14 +23,28 @@ public:
int exposure_time; int exposure_time;
bool dc_gain_enabled; bool dc_gain_enabled;
int dc_gain_weight;
int gain_idx;
float analog_gain_frac; float analog_gain_frac;
int exposure_time_min;
int exposure_time_max;
float dc_gain_factor;
int dc_gain_max_weight;
float dc_gain_on_grey;
float dc_gain_off_grey;
float sensor_analog_gains[16];
int analog_gain_min_idx;
int analog_gain_max_idx;
int analog_gain_rec_idx;
float cur_ev[3]; float cur_ev[3];
float min_ev, max_ev; float min_ev, max_ev;
float measured_grey_fraction; float measured_grey_fraction;
float target_grey_fraction; float target_grey_fraction;
int gain_idx;
unique_fd sensor_fd; unique_fd sensor_fd;
unique_fd csiphy_fd; unique_fd csiphy_fd;
@ -55,8 +56,10 @@ public:
void sensors_start(); void sensors_start();
void camera_open(); void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled);
void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, int camera_id, int camera_num, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, bool enabled); void camera_set_parameters();
void camera_map_bufs(MultiCameraState *s);
void camera_init(MultiCameraState *s, VisionIpcServer *v, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type);
void camera_close(); void camera_close();
std::map<uint16_t, uint16_t> ar0231_parse_registers(uint8_t *data, std::initializer_list<uint16_t> addrs); std::map<uint16_t, uint16_t> ar0231_parse_registers(uint8_t *data, std::initializer_list<uint16_t> addrs);

@ -0,0 +1,135 @@
#include "system/camerad/cameras/camera_util.h"
#include <cassert>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include "common/swaglog.h"
#include "common/util.h"
// ************** low level camera helpers ****************
int do_cam_control(int fd, int op_code, void *handle, int size) {
struct cam_control camcontrol = {0};
camcontrol.op_code = op_code;
camcontrol.handle = (uint64_t)handle;
if (size == 0) {
camcontrol.size = 8;
camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE;
} else {
camcontrol.size = size;
camcontrol.handle_type = CAM_HANDLE_USER_POINTER;
}
int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol));
if (ret == -1) {
LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno);
}
return ret;
}
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) {
struct cam_acquire_dev_cmd cmd = {
.session_handle = session_handle,
.handle_type = CAM_HANDLE_USER_POINTER,
.num_resources = (uint32_t)(data ? num_resources : 0),
.resource_hdl = (uint64_t)data,
};
int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd));
return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt;
};
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) {
struct cam_config_dev_cmd cmd = {
.session_handle = session_handle,
.dev_handle = dev_handle,
.packet_handle = packet_handle,
};
return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd));
}
int device_control(int fd, int op_code, int session_handle, int dev_handle) {
// start stop and release are all the same
struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle };
return do_cam_control(fd, op_code, &cmd, sizeof(cmd));
}
void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) {
struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0};
mem_mgr_alloc_cmd.len = len;
mem_mgr_alloc_cmd.align = align;
mem_mgr_alloc_cmd.flags = flags;
mem_mgr_alloc_cmd.num_hdl = 0;
if (mmu_hdl != 0) {
mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl;
mem_mgr_alloc_cmd.num_hdl++;
}
if (mmu_hdl2 != 0) {
mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2;
mem_mgr_alloc_cmd.num_hdl++;
}
do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd));
*handle = mem_mgr_alloc_cmd.out.buf_handle;
void *ptr = NULL;
if (mem_mgr_alloc_cmd.out.fd > 0) {
ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0);
assert(ptr != MAP_FAILED);
}
// LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr);
return ptr;
}
void release(int video0_fd, uint32_t handle) {
int ret;
struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0};
mem_mgr_release_cmd.buf_handle = handle;
ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd));
assert(ret == 0);
}
void release_fd(int video0_fd, uint32_t handle) {
// handle to fd
close(handle>>16);
release(video0_fd, handle);
}
void *MemoryManager::alloc(int size, uint32_t *handle) {
lock.lock();
void *ptr;
if (!cached_allocations[size].empty()) {
ptr = cached_allocations[size].front();
cached_allocations[size].pop();
*handle = handle_lookup[ptr];
} else {
ptr = alloc_w_mmu_hdl(video0_fd, size, handle);
handle_lookup[ptr] = *handle;
size_lookup[ptr] = size;
}
lock.unlock();
return ptr;
}
void MemoryManager::free(void *ptr) {
lock.lock();
cached_allocations[size_lookup[ptr]].push(ptr);
lock.unlock();
}
MemoryManager::~MemoryManager() {
for (auto& x : cached_allocations) {
while (!x.second.empty()) {
void *ptr = x.second.front();
x.second.pop();
LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]);
munmap(ptr, size_lookup[ptr]);
release_fd(video0_fd, handle_lookup[ptr]);
handle_lookup.erase(ptr);
size_lookup.erase(ptr);
}
}
}

@ -0,0 +1,30 @@
#pragma once
#include <map>
#include <mutex>
#include <optional>
#include <queue>
#include <media/cam_req_mgr.h>
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1);
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle);
int device_control(int fd, int op_code, int session_handle, int dev_handle);
int do_cam_control(int fd, int op_code, void *handle, int size);
void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE,
int mmu_hdl = 0, int mmu_hdl2 = 0);
void release(int video0_fd, uint32_t handle);
class MemoryManager {
public:
void init(int _video0_fd) { video0_fd = _video0_fd; }
void *alloc(int len, uint32_t *handle);
void free(void *ptr);
~MemoryManager();
private:
std::mutex lock;
std::map<void *, uint32_t> handle_lookup;
std::map<void *, int> size_lookup;
std::map<int, std::queue<void *> > cached_allocations;
int video0_fd;
};

@ -8,9 +8,15 @@
float3 color_correct(float3 rgb) { float3 color_correct(float3 rgb) {
// color correction // color correction
#if IS_OX
float3 x = rgb.x * (float3)(1.81485125, -0.51650643, -0.06985117);
x += rgb.y * (float3)(-0.51681964, 1.85935946, -0.49871889);
x += rgb.z * (float3)(-0.29803161, -0.34285304, 1.56857006);
#else
float3 x = rgb.x * (float3)(1.82717181, -0.31231438, 0.07307673); float3 x = rgb.x * (float3)(1.82717181, -0.31231438, 0.07307673);
x += rgb.y * (float3)(-0.5743977, 1.36858544, -0.53183455); x += rgb.y * (float3)(-0.5743977, 1.36858544, -0.53183455);
x += rgb.z * (float3)(-0.25277411, -0.05627105, 1.45875782); x += rgb.z * (float3)(-0.25277411, -0.05627105, 1.45875782);
#endif
// tone mapping params // tone mapping params
const float gamma_k = 0.75; const float gamma_k = 0.75;
@ -36,14 +42,43 @@ float get_vignetting_s(float r) {
} }
} }
constant float ox03c10_lut[] = {
0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05,
1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05,
3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05,
6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04,
1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04,
1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04,
2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04,
4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04,
9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03,
1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03,
3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03,
7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02,
1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02,
6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01,
1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01,
3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00
};
float4 val4_from_12(uchar8 pvs, float gain) { float4 val4_from_12(uchar8 pvs, float gain) {
uint4 parsed = (uint4)(((uint)pvs.s0<<4) + (pvs.s1>>4), // is from the previous 10 bit uint4 parsed = (uint4)(((uint)pvs.s0<<4) + (pvs.s1>>4), // is from the previous 10 bit
((uint)pvs.s2<<4) + (pvs.s4&0xF), ((uint)pvs.s2<<4) + (pvs.s4&0xF),
((uint)pvs.s3<<4) + (pvs.s4>>4), ((uint)pvs.s3<<4) + (pvs.s4>>4),
((uint)pvs.s5<<4) + (pvs.s7&0xF)); ((uint)pvs.s5<<4) + (pvs.s7&0xF));
#if IS_OX
// PWL
//float4 pv = (convert_float4(parsed) - 64.0) / (4096.0 - 64.0);
float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]};
// it's a 24 bit signal, center in the middle 8 bits
return pv*256.0;
#else // AR
// normalize and scale // normalize and scale
float4 pv = (convert_float4(parsed) - 168.0) / (4096.0 - 168.0); float4 pv = (convert_float4(parsed) - 168.0) / (4096.0 - 168.0);
return clamp(pv*gain, 0.0, 1.0); return clamp(pv*gain, 0.0, 1.0);
#endif
} }
float get_k(float a, float b, float c, float d) { float get_k(float a, float b, float c, float d) {

@ -1,48 +1,754 @@
struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}};
struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}};
struct i2c_random_wr_payload start_reg_array_imx390[] = {{0x0, 0}}; struct i2c_random_wr_payload start_reg_array_ox03c10[] = {{0x100, 1}};
struct i2c_random_wr_payload stop_reg_array_imx390[] = {{0x0, 1}}; struct i2c_random_wr_payload stop_reg_array_ox03c10[] = {{0x100, 0}};
struct i2c_random_wr_payload init_array_imx390[] = { struct i2c_random_wr_payload init_array_ox03c10[] = {
{0x2008, 0xd0}, {0x2009, 0x07}, {0x200a, 0x00}, // MODE_VMAX = time between frames {0x103, 1},
{0x200C, 0xe4}, {0x200D, 0x0c}, // MODE_HMAX {0x107, 1},
// crop // X3C_1920x1280_60fps_HDR4_LFR_PWL12_mipi1200
{0x3410, 0x88}, {0x3411, 0x7}, // CROP_H_SIZE
{0x3418, 0xb8}, {0x3419, 0x4}, // CROP_V_SIZE
{0x0078, 1}, {0x03c0, 1},
// external trigger (off) // TPM
// while images still come in, they are blank with this {0x4d5a, 0x1a}, {0x4d09, 0xff}, {0x4d09, 0xdf},
{0x3650, 0}, // CU_MODE
// exposure /*)
{0x000c, 0xc0}, {0x000d, 0x07}, // group 4
{0x0010, 0xc0}, {0x0011, 0x07}, {0x3208, 0x04},
{0x4620, 0x04},
{0x3208, 0x14},
// WUXGA mode // group 5
// not in datasheet, from https://github.com/bogsen/STLinux-Kernel/blob/master/drivers/media/platform/tegra/imx185.c {0x3208, 0x05},
{0x0086, 0xc4}, {0x0087, 0xff}, // WND_SHIFT_V = -60 {0x4620, 0x04},
{0x03c6, 0xc4}, {0x03c7, 0xff}, // SM_WND_SHIFT_V_APL = -60 {0x3208, 0x15},
{0x201c, 0xe1}, {0x201d, 0x12}, // image read amount // group 2
{0x21ee, 0xc4}, {0x21ef, 0x04}, // image send amount (1220 is the end) {0x3208, 0x02},
{0x21f0, 0xc4}, {0x21f1, 0x04}, // image processing amount {0x3507, 0x00},
{0x3208, 0x12},
// disable a bunch of errors causing blanking // delay launch group 2
{0x0390, 0x00}, {0x0391, 0x00}, {0x0392, 0x00}, {0x3208, 0xa2},*/
// flip bayer // PLL setup
{0x2D64, 0x64 + 2}, {0x0301, 0xc8}, // pll1_divs, pll1_predivp, pll1_divpix
{0x0303, 0x01}, // pll1_prediv
{0x0304, 0x01}, {0x0305, 0x2c}, // pll1_loopdiv = 300
{0x0306, 0x04}, // pll1_divmipi = 4
{0x0307, 0x01}, // pll1_divm = 1
{0x0316, 0x00},
{0x0317, 0x00},
{0x0318, 0x00},
{0x0323, 0x05}, // pll2_prediv
{0x0324, 0x01}, {0x0325, 0x2c}, // pll2_divp = 300
// color correction // SCLK/PCLK
{0x0030, 0xf8}, {0x0031, 0x00}, // red gain {0x0400, 0xe0}, {0x0401, 0x80},
{0x0032, 0x9a}, {0x0033, 0x00}, // gr gain {0x0403, 0xde}, {0x0404, 0x34},
{0x0034, 0x9a}, {0x0035, 0x00}, // gb gain {0x0405, 0x3b}, {0x0406, 0xde},
{0x0036, 0x22}, {0x0037, 0x01}, // blue gain {0x0407, 0x08},
{0x0408, 0xe0}, {0x0409, 0x7f},
{0x040a, 0xde}, {0x040b, 0x34},
{0x040c, 0x47}, {0x040d, 0xd8},
{0x040e, 0x08},
// hdr enable (noise with this on for now) // xchk
{0x00f9, 0} {0x2803, 0xfe}, {0x280b, 0x00}, {0x280c, 0x79},
// SC ctrl
{0x3001, 0x03}, // io_pad_oen
{0x3002, 0xf8}, // io_pad_oen
{0x3005, 0x80}, // io_pad_out
{0x3007, 0x01}, // io_pad_sel
{0x3008, 0x80}, // io_pad_sel
// FSIN first frame
/*
{0x3009, 0x2},
{0x3015, 0x2},
{0x3822, 0x20},
{0x3823, 0x58},
{0x3826, 0x0}, {0x3827, 0x8},
{0x3881, 0x4},
{0x3882, 0x8}, {0x3883, 0x0D},
{0x3836, 0x1F}, {0x3837, 0x40},
*/
// FSIN with external pulses
{0x3009, 0x2},
{0x3015, 0x2},
{0x383E, 0x80},
{0x3881, 0x4},
{0x3882, 0x8}, {0x3883, 0x0D},
{0x3836, 0x1F}, {0x3837, 0x40},
{0x3012, 0x41}, // SC_PHY_CTRL = 4 lane MIPI
{0x3020, 0x05}, // SC_CTRL_20
// this is not in the datasheet, listed as RSVD
// but the camera doesn't work without it
{0x3700, 0x28}, {0x3701, 0x15}, {0x3702, 0x19}, {0x3703, 0x23},
{0x3704, 0x0a}, {0x3705, 0x00}, {0x3706, 0x3e}, {0x3707, 0x0d},
{0x3708, 0x50}, {0x3709, 0x5a}, {0x370a, 0x00}, {0x370b, 0x96},
{0x3711, 0x11}, {0x3712, 0x13}, {0x3717, 0x02}, {0x3718, 0x73},
{0x372c, 0x40}, {0x3733, 0x01}, {0x3738, 0x36}, {0x3739, 0x36},
{0x373a, 0x25}, {0x373b, 0x25}, {0x373f, 0x21}, {0x3740, 0x21},
{0x3741, 0x21}, {0x3742, 0x21}, {0x3747, 0x28}, {0x3748, 0x28},
{0x3749, 0x19}, {0x3755, 0x1a}, {0x3756, 0x0a}, {0x3757, 0x1c},
{0x3765, 0x19}, {0x3766, 0x05}, {0x3767, 0x05}, {0x3768, 0x13},
{0x376c, 0x07}, {0x3778, 0x20}, {0x377c, 0xc8}, {0x3781, 0x02},
{0x3783, 0x02}, {0x379c, 0x58}, {0x379e, 0x00}, {0x379f, 0x00},
{0x37a0, 0x00}, {0x37bc, 0x22}, {0x37c0, 0x01}, {0x37c4, 0x3e},
{0x37c5, 0x3e}, {0x37c6, 0x2a}, {0x37c7, 0x28}, {0x37c8, 0x02},
{0x37c9, 0x12}, {0x37cb, 0x29}, {0x37cd, 0x29}, {0x37d2, 0x00},
{0x37d3, 0x73}, {0x37d6, 0x00}, {0x37d7, 0x6b}, {0x37dc, 0x00},
{0x37df, 0x54}, {0x37e2, 0x00}, {0x37e3, 0x00}, {0x37f8, 0x00},
{0x37f9, 0x01}, {0x37fa, 0x00}, {0x37fb, 0x19},
// also RSVD
{0x3c03, 0x01}, {0x3c04, 0x01}, {0x3c06, 0x21}, {0x3c08, 0x01},
{0x3c09, 0x01}, {0x3c0a, 0x01}, {0x3c0b, 0x21}, {0x3c13, 0x21},
{0x3c14, 0x82}, {0x3c16, 0x13}, {0x3c21, 0x00}, {0x3c22, 0xf3},
{0x3c37, 0x12}, {0x3c38, 0x31}, {0x3c3c, 0x00}, {0x3c3d, 0x03},
{0x3c44, 0x16}, {0x3c5c, 0x8a}, {0x3c5f, 0x03}, {0x3c61, 0x80},
{0x3c6f, 0x2b}, {0x3c70, 0x5f}, {0x3c71, 0x2c}, {0x3c72, 0x2c},
{0x3c73, 0x2c}, {0x3c76, 0x12},
// PEC checks
{0x3182, 0x12},
{0x320e, 0x00}, {0x320f, 0x00}, // RSVD
{0x3211, 0x61},
{0x3215, 0xcd},
{0x3219, 0x08},
{0x3506, 0x20}, {0x3507, 0x00}, // hcg fine exposure
{0x350a, 0x04}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain
{0x3586, 0x40}, {0x3587, 0x00}, // lcg fine exposure
{0x358a, 0x04}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain
{0x3546, 0x20}, {0x3547, 0x00}, // spd fine exposure
{0x354a, 0x04}, {0x354b, 0x00}, {0x354c, 0x00}, // spd digital gain
{0x35c6, 0xb0}, {0x35c7, 0x00}, // vs fine exposure
{0x35ca, 0x04}, {0x35cb, 0x00}, {0x35cc, 0x00}, // vs digital gain
// also RSVD
{0x3600, 0x8f}, {0x3605, 0x16}, {0x3609, 0xf0}, {0x360a, 0x01},
{0x360e, 0x1d}, {0x360f, 0x10}, {0x3610, 0x70}, {0x3611, 0x3a},
{0x3612, 0x28}, {0x361a, 0x29}, {0x361b, 0x6c}, {0x361c, 0x0b},
{0x361d, 0x00}, {0x361e, 0xfc}, {0x362a, 0x00}, {0x364d, 0x0f},
{0x364e, 0x18}, {0x364f, 0x12}, {0x3653, 0x1c}, {0x3654, 0x00},
{0x3655, 0x1f}, {0x3656, 0x1f}, {0x3657, 0x0c}, {0x3658, 0x0a},
{0x3659, 0x14}, {0x365a, 0x18}, {0x365b, 0x14}, {0x365c, 0x10},
{0x365e, 0x12}, {0x3674, 0x08}, {0x3677, 0x3a}, {0x3678, 0x3a},
{0x3679, 0x19},
// Y_ADDR_START = 4
{0x3802, 0x00}, {0x3803, 0x04},
// Y_ADDR_END = 0x50b
{0x3806, 0x05}, {0x3807, 0x0b},
// X_OUTPUT_SIZE = 0x780 = 1920 (changed to 1928)
{0x3808, 0x07}, {0x3809, 0x88},
// Y_OUTPUT_SIZE = 0x500 = 1280 (changed to 1208)
{0x380a, 0x04}, {0x380b, 0xb8},
// horizontal timing 0x447
{0x380c, 0x04}, {0x380d, 0x47},
// rows per frame (was 0x2ae)
// 0x8ae = 53.65 ms
{0x380e, 0x08}, {0x380f, 0x15},
// this should be triggered by FSIN, not free running
{0x3810, 0x00}, {0x3811, 0x08}, // x cutoff
{0x3812, 0x00}, {0x3813, 0x04}, // y cutoff
{0x3816, 0x01},
{0x3817, 0x01},
{0x381c, 0x18},
{0x381e, 0x01},
{0x381f, 0x01},
// don't mirror, just flip
{0x3820, 0x04},
{0x3821, 0x19},
{0x3832, 0x00},
{0x3834, 0x00},
{0x384c, 0x02},
{0x384d, 0x0d},
{0x3850, 0x00},
{0x3851, 0x42},
{0x3852, 0x00},
{0x3853, 0x40},
{0x3858, 0x04},
{0x388c, 0x02},
{0x388d, 0x2b},
// APC
{0x3b40, 0x05}, {0x3b41, 0x40}, {0x3b42, 0x00}, {0x3b43, 0x90},
{0x3b44, 0x00}, {0x3b45, 0x20}, {0x3b46, 0x00}, {0x3b47, 0x20},
{0x3b48, 0x19}, {0x3b49, 0x12}, {0x3b4a, 0x16}, {0x3b4b, 0x2e},
{0x3b4c, 0x00}, {0x3b4d, 0x00},
{0x3b86, 0x00}, {0x3b87, 0x34}, {0x3b88, 0x00}, {0x3b89, 0x08},
{0x3b8a, 0x05}, {0x3b8b, 0x00}, {0x3b8c, 0x07}, {0x3b8d, 0x80},
{0x3b8e, 0x00}, {0x3b8f, 0x00}, {0x3b92, 0x05}, {0x3b93, 0x00},
{0x3b94, 0x07}, {0x3b95, 0x80}, {0x3b9e, 0x09},
// OTP
{0x3d82, 0x73},
{0x3d85, 0x05},
{0x3d8a, 0x03},
{0x3d8b, 0xff},
{0x3d99, 0x00},
{0x3d9a, 0x9f},
{0x3d9b, 0x00},
{0x3d9c, 0xa0},
{0x3da4, 0x00},
{0x3da7, 0x50},
// DTR
{0x420e, 0x6b},
{0x420f, 0x6e},
{0x4210, 0x06},
{0x4211, 0xc1},
{0x421e, 0x02},
{0x421f, 0x45},
{0x4220, 0xe1},
{0x4221, 0x01},
{0x4301, 0xff},
{0x4307, 0x03},
{0x4308, 0x13},
{0x430a, 0x13},
{0x430d, 0x93},
{0x430f, 0x57},
{0x4310, 0x95},
{0x4311, 0x16},
{0x4316, 0x00},
{0x4317, 0x38}, // both embedded rows are enabled
{0x4319, 0x03}, // spd dcg
{0x431a, 0x00}, // 8 bit mipi
{0x431b, 0x00},
{0x431d, 0x2a},
{0x431e, 0x11},
{0x431f, 0x20}, // enable PWL (pwl0_en), 12 bits
//{0x431f, 0x00}, // disable PWL
{0x4320, 0x19},
{0x4323, 0x80},
{0x4324, 0x00},
{0x4503, 0x4e},
{0x4505, 0x00},
{0x4509, 0x00},
{0x450a, 0x00},
{0x4580, 0xf8},
{0x4583, 0x07},
{0x4584, 0x6a},
{0x4585, 0x08},
{0x4586, 0x05},
{0x4587, 0x04},
{0x4588, 0x73},
{0x4589, 0x05},
{0x458a, 0x1f},
{0x458b, 0x02},
{0x458c, 0xdc},
{0x458d, 0x03},
{0x458e, 0x02},
{0x4597, 0x07},
{0x4598, 0x40},
{0x4599, 0x0e},
{0x459a, 0x0e},
{0x459b, 0xfb},
{0x459c, 0xf3},
{0x4602, 0x00},
{0x4603, 0x13},
{0x4604, 0x00},
{0x4609, 0x0a},
{0x460a, 0x30},
{0x4610, 0x00},
{0x4611, 0x70},
{0x4612, 0x01},
{0x4613, 0x00},
{0x4614, 0x00},
{0x4615, 0x70},
{0x4616, 0x01},
{0x4617, 0x00},
{0x4800, 0x04}, // invert output PCLK
{0x480a, 0x22},
{0x4813, 0xe4},
// mipi
{0x4814, 0x2a},
{0x4837, 0x0d},
{0x484b, 0x47},
{0x484f, 0x00},
{0x4887, 0x51},
{0x4d00, 0x4a},
{0x4d01, 0x18},
{0x4d05, 0xff},
{0x4d06, 0x88},
{0x4d08, 0x63},
{0x4d09, 0xdf},
{0x4d15, 0x7d},
{0x4d1a, 0x20},
{0x4d30, 0x0a},
{0x4d31, 0x00},
{0x4d34, 0x7d},
{0x4d3c, 0x7d},
{0x4f00, 0x00},
{0x4f01, 0x00},
{0x4f02, 0x00},
{0x4f03, 0x20},
{0x4f04, 0xe0},
{0x6a00, 0x00},
{0x6a01, 0x20},
{0x6a02, 0x00},
{0x6a03, 0x20},
{0x6a04, 0x02},
{0x6a05, 0x80},
{0x6a06, 0x01},
{0x6a07, 0xe0},
{0x6a08, 0xcf},
{0x6a09, 0x01},
{0x6a0a, 0x40},
{0x6a20, 0x00},
{0x6a21, 0x02},
{0x6a22, 0x00},
{0x6a23, 0x00},
{0x6a24, 0x00},
{0x6a25, 0x00},
{0x6a26, 0x00},
{0x6a27, 0x00},
{0x6a28, 0x00},
// isp
{0x5000, 0x8f},
{0x5001, 0x75},
{0x5002, 0x7f}, // PWL0
//{0x5002, 0x3f}, // PWL disable
{0x5003, 0x7a},
{0x5004, 0x3e},
{0x5005, 0x1e},
{0x5006, 0x1e},
{0x5007, 0x1e},
{0x5008, 0x00},
{0x500c, 0x00},
{0x502c, 0x00},
{0x502e, 0x00},
{0x502f, 0x00},
{0x504b, 0x00},
{0x5053, 0x00},
{0x505b, 0x00},
{0x5063, 0x00},
{0x5070, 0x00},
{0x5074, 0x04},
{0x507a, 0x04},
{0x507b, 0x09},
{0x5500, 0x02},
{0x5700, 0x02},
{0x5900, 0x02},
{0x6007, 0x04},
{0x6008, 0x05},
{0x6009, 0x02},
{0x600b, 0x08},
{0x600c, 0x07},
{0x600d, 0x88},
{0x6016, 0x00},
{0x6027, 0x04},
{0x6028, 0x05},
{0x6029, 0x02},
{0x602b, 0x08},
{0x602c, 0x07},
{0x602d, 0x88},
{0x6047, 0x04},
{0x6048, 0x05},
{0x6049, 0x02},
{0x604b, 0x08},
{0x604c, 0x07},
{0x604d, 0x88},
{0x6067, 0x04},
{0x6068, 0x05},
{0x6069, 0x02},
{0x606b, 0x08},
{0x606c, 0x07},
{0x606d, 0x88},
{0x6087, 0x04},
{0x6088, 0x05},
{0x6089, 0x02},
{0x608b, 0x08},
{0x608c, 0x07},
{0x608d, 0x88},
// 12-bit PWL0
{0x5e00, 0x00},
// m_ndX_exp[0:32]
// 9*2+0xa*3+0xb*2+0xc*2+0xd*2+0xe*2+0xf*2+0x10*2+0x11*2+0x12*4+0x13*3+0x14*3+0x15*3+0x16 = 518
{0x5e01, 0x09},
{0x5e02, 0x09},
{0x5e03, 0x0a},
{0x5e04, 0x0a},
{0x5e05, 0x0a},
{0x5e06, 0x0b},
{0x5e07, 0x0b},
{0x5e08, 0x0c},
{0x5e09, 0x0c},
{0x5e0a, 0x0d},
{0x5e0b, 0x0d},
{0x5e0c, 0x0e},
{0x5e0d, 0x0e},
{0x5e0e, 0x0f},
{0x5e0f, 0x0f},
{0x5e10, 0x10},
{0x5e11, 0x10},
{0x5e12, 0x11},
{0x5e13, 0x11},
{0x5e14, 0x12},
{0x5e15, 0x12},
{0x5e16, 0x12},
{0x5e17, 0x12},
{0x5e18, 0x13},
{0x5e19, 0x13},
{0x5e1a, 0x13},
{0x5e1b, 0x14},
{0x5e1c, 0x14},
{0x5e1d, 0x14},
{0x5e1e, 0x15},
{0x5e1f, 0x15},
{0x5e20, 0x15},
{0x5e21, 0x16},
// m_ndY_val[0:32]
// 0x200+0xff+0x100*3+0x80*12+0x40*16 = 4095
{0x5e22, 0x00}, {0x5e23, 0x02}, {0x5e24, 0x00},
{0x5e25, 0x00}, {0x5e26, 0x00}, {0x5e27, 0xff},
{0x5e28, 0x00}, {0x5e29, 0x01}, {0x5e2a, 0x00},
{0x5e2b, 0x00}, {0x5e2c, 0x01}, {0x5e2d, 0x00},
{0x5e2e, 0x00}, {0x5e2f, 0x01}, {0x5e30, 0x00},
{0x5e31, 0x00}, {0x5e32, 0x00}, {0x5e33, 0x80},
{0x5e34, 0x00}, {0x5e35, 0x00}, {0x5e36, 0x80},
{0x5e37, 0x00}, {0x5e38, 0x00}, {0x5e39, 0x80},
{0x5e3a, 0x00}, {0x5e3b, 0x00}, {0x5e3c, 0x80},
{0x5e3d, 0x00}, {0x5e3e, 0x00}, {0x5e3f, 0x80},
{0x5e40, 0x00}, {0x5e41, 0x00}, {0x5e42, 0x80},
{0x5e43, 0x00}, {0x5e44, 0x00}, {0x5e45, 0x80},
{0x5e46, 0x00}, {0x5e47, 0x00}, {0x5e48, 0x80},
{0x5e49, 0x00}, {0x5e4a, 0x00}, {0x5e4b, 0x80},
{0x5e4c, 0x00}, {0x5e4d, 0x00}, {0x5e4e, 0x80},
{0x5e4f, 0x00}, {0x5e50, 0x00}, {0x5e51, 0x80},
{0x5e52, 0x00}, {0x5e53, 0x00}, {0x5e54, 0x80},
{0x5e55, 0x00}, {0x5e56, 0x00}, {0x5e57, 0x40},
{0x5e58, 0x00}, {0x5e59, 0x00}, {0x5e5a, 0x40},
{0x5e5b, 0x00}, {0x5e5c, 0x00}, {0x5e5d, 0x40},
{0x5e5e, 0x00}, {0x5e5f, 0x00}, {0x5e60, 0x40},
{0x5e61, 0x00}, {0x5e62, 0x00}, {0x5e63, 0x40},
{0x5e64, 0x00}, {0x5e65, 0x00}, {0x5e66, 0x40},
{0x5e67, 0x00}, {0x5e68, 0x00}, {0x5e69, 0x40},
{0x5e6a, 0x00}, {0x5e6b, 0x00}, {0x5e6c, 0x40},
{0x5e6d, 0x00}, {0x5e6e, 0x00}, {0x5e6f, 0x40},
{0x5e70, 0x00}, {0x5e71, 0x00}, {0x5e72, 0x40},
{0x5e73, 0x00}, {0x5e74, 0x00}, {0x5e75, 0x40},
{0x5e76, 0x00}, {0x5e77, 0x00}, {0x5e78, 0x40},
{0x5e79, 0x00}, {0x5e7a, 0x00}, {0x5e7b, 0x40},
{0x5e7c, 0x00}, {0x5e7d, 0x00}, {0x5e7e, 0x40},
{0x5e7f, 0x00}, {0x5e80, 0x00}, {0x5e81, 0x40},
{0x5e82, 0x00}, {0x5e83, 0x00}, {0x5e84, 0x40},
// disable PWL
/*{0x5e01, 0x18}, {0x5e02, 0x00}, {0x5e03, 0x00}, {0x5e04, 0x00},
{0x5e05, 0x00}, {0x5e06, 0x00}, {0x5e07, 0x00}, {0x5e08, 0x00},
{0x5e09, 0x00}, {0x5e0a, 0x00}, {0x5e0b, 0x00}, {0x5e0c, 0x00},
{0x5e0d, 0x00}, {0x5e0e, 0x00}, {0x5e0f, 0x00}, {0x5e10, 0x00},
{0x5e11, 0x00}, {0x5e12, 0x00}, {0x5e13, 0x00}, {0x5e14, 0x00},
{0x5e15, 0x00}, {0x5e16, 0x00}, {0x5e17, 0x00}, {0x5e18, 0x00},
{0x5e19, 0x00}, {0x5e1a, 0x00}, {0x5e1b, 0x00}, {0x5e1c, 0x00},
{0x5e1d, 0x00}, {0x5e1e, 0x00}, {0x5e1f, 0x00}, {0x5e20, 0x00},
{0x5e21, 0x00},
{0x5e22, 0x00}, {0x5e23, 0x0f}, {0x5e24, 0xFF},*/
{0x4001, 0x2b}, // BLC_CTRL_1
{0x4008, 0x02}, {0x4009, 0x03},
{0x4018, 0x12},
{0x4022, 0x40},
{0x4023, 0x20},
// all black level targets are 0x40
{0x4026, 0x00}, {0x4027, 0x40},
{0x4028, 0x00}, {0x4029, 0x40},
{0x402a, 0x00}, {0x402b, 0x40},
{0x402c, 0x00}, {0x402d, 0x40},
{0x407e, 0xcc},
{0x407f, 0x18},
{0x4080, 0xff},
{0x4081, 0xff},
{0x4082, 0x01},
{0x4083, 0x53},
{0x4084, 0x01},
{0x4085, 0x2b},
{0x4086, 0x00},
{0x4087, 0xb3},
{0x4640, 0x40},
{0x4641, 0x11},
{0x4642, 0x0e},
{0x4643, 0xee},
{0x4646, 0x0f},
{0x4648, 0x00},
{0x4649, 0x03},
{0x4f00, 0x00},
{0x4f01, 0x00},
{0x4f02, 0x80},
{0x4f03, 0x2c},
{0x4f04, 0xf8},
{0x4d09, 0xff},
{0x4d09, 0xdf},
{0x5003, 0x7a},
{0x5b80, 0x08},
{0x5c00, 0x08},
{0x5c80, 0x00},
{0x5bbe, 0x12},
{0x5c3e, 0x12},
{0x5cbe, 0x12},
{0x5b8a, 0x80},
{0x5b8b, 0x80},
{0x5b8c, 0x80},
{0x5b8d, 0x80},
{0x5b8e, 0x60},
{0x5b8f, 0x80},
{0x5b90, 0x80},
{0x5b91, 0x80},
{0x5b92, 0x80},
{0x5b93, 0x20},
{0x5b94, 0x80},
{0x5b95, 0x80},
{0x5b96, 0x80},
{0x5b97, 0x20},
{0x5b98, 0x00},
{0x5b99, 0x80},
{0x5b9a, 0x40},
{0x5b9b, 0x20},
{0x5b9c, 0x00},
{0x5b9d, 0x00},
{0x5b9e, 0x80},
{0x5b9f, 0x00},
{0x5ba0, 0x00},
{0x5ba1, 0x00},
{0x5ba2, 0x00},
{0x5ba3, 0x00},
{0x5ba4, 0x00},
{0x5ba5, 0x00},
{0x5ba6, 0x00},
{0x5ba7, 0x00},
{0x5ba8, 0x02},
{0x5ba9, 0x00},
{0x5baa, 0x02},
{0x5bab, 0x76},
{0x5bac, 0x03},
{0x5bad, 0x08},
{0x5bae, 0x00},
{0x5baf, 0x80},
{0x5bb0, 0x00},
{0x5bb1, 0xc0},
{0x5bb2, 0x01},
{0x5bb3, 0x00},
// m_nNormCombineWeight
{0x5c0a, 0x80}, {0x5c0b, 0x80}, {0x5c0c, 0x80}, {0x5c0d, 0x80}, {0x5c0e, 0x60},
{0x5c0f, 0x80}, {0x5c10, 0x80}, {0x5c11, 0x80}, {0x5c12, 0x60}, {0x5c13, 0x20},
{0x5c14, 0x80}, {0x5c15, 0x80}, {0x5c16, 0x80}, {0x5c17, 0x20}, {0x5c18, 0x00},
{0x5c19, 0x80}, {0x5c1a, 0x40}, {0x5c1b, 0x20}, {0x5c1c, 0x00}, {0x5c1d, 0x00},
{0x5c1e, 0x80}, {0x5c1f, 0x00}, {0x5c20, 0x00}, {0x5c21, 0x00}, {0x5c22, 0x00},
{0x5c23, 0x00}, {0x5c24, 0x00}, {0x5c25, 0x00}, {0x5c26, 0x00}, {0x5c27, 0x00},
// m_nCombinThreL
{0x5c28, 0x02}, {0x5c29, 0x00},
{0x5c2a, 0x02}, {0x5c2b, 0x76},
{0x5c2c, 0x03}, {0x5c2d, 0x08},
// m_nCombinThreS
{0x5c2e, 0x00}, {0x5c2f, 0x80},
{0x5c30, 0x00}, {0x5c31, 0xc0},
{0x5c32, 0x01}, {0x5c33, 0x00},
// m_nNormCombineWeight
{0x5c8a, 0x80}, {0x5c8b, 0x80}, {0x5c8c, 0x80}, {0x5c8d, 0x80}, {0x5c8e, 0x80},
{0x5c8f, 0x80}, {0x5c90, 0x80}, {0x5c91, 0x80}, {0x5c92, 0x80}, {0x5c93, 0x60},
{0x5c94, 0x80}, {0x5c95, 0x80}, {0x5c96, 0x80}, {0x5c97, 0x60}, {0x5c98, 0x40},
{0x5c99, 0x80}, {0x5c9a, 0x80}, {0x5c9b, 0x80}, {0x5c9c, 0x40}, {0x5c9d, 0x00},
{0x5c9e, 0x80}, {0x5c9f, 0x80}, {0x5ca0, 0x80}, {0x5ca1, 0x20}, {0x5ca2, 0x00},
{0x5ca3, 0x80}, {0x5ca4, 0x80}, {0x5ca5, 0x00}, {0x5ca6, 0x00}, {0x5ca7, 0x00},
{0x5ca8, 0x01}, {0x5ca9, 0x00},
{0x5caa, 0x02}, {0x5cab, 0x00},
{0x5cac, 0x03}, {0x5cad, 0x08},
{0x5cae, 0x01}, {0x5caf, 0x00},
{0x5cb0, 0x02}, {0x5cb1, 0x00},
{0x5cb2, 0x03}, {0x5cb3, 0x08},
// combine ISP
{0x5be7, 0x80},
{0x5bc9, 0x80},
{0x5bca, 0x80},
{0x5bcb, 0x80},
{0x5bcc, 0x80},
{0x5bcd, 0x80},
{0x5bce, 0x80},
{0x5bcf, 0x80},
{0x5bd0, 0x80},
{0x5bd1, 0x80},
{0x5bd2, 0x20},
{0x5bd3, 0x80},
{0x5bd4, 0x40},
{0x5bd5, 0x20},
{0x5bd6, 0x00},
{0x5bd7, 0x00},
{0x5bd8, 0x00},
{0x5bd9, 0x00},
{0x5bda, 0x00},
{0x5bdb, 0x00},
{0x5bdc, 0x00},
{0x5bdd, 0x00},
{0x5bde, 0x00},
{0x5bdf, 0x00},
{0x5be0, 0x00},
{0x5be1, 0x00},
{0x5be2, 0x00},
{0x5be3, 0x00},
{0x5be4, 0x00},
{0x5be5, 0x00},
{0x5be6, 0x00},
// m_nSPDCombineWeight
{0x5c49, 0x80}, {0x5c4a, 0x80}, {0x5c4b, 0x80}, {0x5c4c, 0x80}, {0x5c4d, 0x40},
{0x5c4e, 0x80}, {0x5c4f, 0x80}, {0x5c50, 0x80}, {0x5c51, 0x60}, {0x5c52, 0x20},
{0x5c53, 0x80}, {0x5c54, 0x80}, {0x5c55, 0x80}, {0x5c56, 0x20}, {0x5c57, 0x00},
{0x5c58, 0x80}, {0x5c59, 0x40}, {0x5c5a, 0x20}, {0x5c5b, 0x00}, {0x5c5c, 0x00},
{0x5c5d, 0x80}, {0x5c5e, 0x00}, {0x5c5f, 0x00}, {0x5c60, 0x00}, {0x5c61, 0x00},
{0x5c62, 0x00}, {0x5c63, 0x00}, {0x5c64, 0x00}, {0x5c65, 0x00}, {0x5c66, 0x00},
// m_nSPDCombineWeight
{0x5cc9, 0x80}, {0x5cca, 0x80}, {0x5ccb, 0x80}, {0x5ccc, 0x80}, {0x5ccd, 0x80},
{0x5cce, 0x80}, {0x5ccf, 0x80}, {0x5cd0, 0x80}, {0x5cd1, 0x80}, {0x5cd2, 0x60},
{0x5cd3, 0x80}, {0x5cd4, 0x80}, {0x5cd5, 0x80}, {0x5cd6, 0x60}, {0x5cd7, 0x40},
{0x5cd8, 0x80}, {0x5cd9, 0x80}, {0x5cda, 0x80}, {0x5cdb, 0x40}, {0x5cdc, 0x20},
{0x5cdd, 0x80}, {0x5cde, 0x80}, {0x5cdf, 0x80}, {0x5ce0, 0x20}, {0x5ce1, 0x00},
{0x5ce2, 0x80}, {0x5ce3, 0x80}, {0x5ce4, 0x80}, {0x5ce5, 0x00}, {0x5ce6, 0x00},
{0x5d74, 0x01},
{0x5d75, 0x00},
{0x5d1f, 0x81},
{0x5d11, 0x00},
{0x5d12, 0x10},
{0x5d13, 0x10},
{0x5d15, 0x05},
{0x5d16, 0x05},
{0x5d17, 0x05},
{0x5d08, 0x03},
{0x5d09, 0xb6},
{0x5d0a, 0x03},
{0x5d0b, 0xb6},
{0x5d18, 0x03},
{0x5d19, 0xb6},
{0x5d62, 0x01},
{0x5d40, 0x02},
{0x5d41, 0x01},
{0x5d63, 0x1f},
{0x5d64, 0x00},
{0x5d65, 0x80},
{0x5d56, 0x00},
{0x5d57, 0x20},
{0x5d58, 0x00},
{0x5d59, 0x20},
{0x5d5a, 0x00},
{0x5d5b, 0x0c},
{0x5d5c, 0x02},
{0x5d5d, 0x40},
{0x5d5e, 0x02},
{0x5d5f, 0x40},
{0x5d60, 0x03},
{0x5d61, 0x40},
{0x5d4a, 0x02},
{0x5d4b, 0x40},
{0x5d4c, 0x02},
{0x5d4d, 0x40},
{0x5d4e, 0x02},
{0x5d4f, 0x40},
{0x5d50, 0x18},
{0x5d51, 0x80},
{0x5d52, 0x18},
{0x5d53, 0x80},
{0x5d54, 0x18},
{0x5d55, 0x80},
{0x5d46, 0x20},
{0x5d47, 0x00},
{0x5d48, 0x22},
{0x5d49, 0x00},
{0x5d42, 0x20},
{0x5d43, 0x00},
{0x5d44, 0x22},
{0x5d45, 0x00},
{0x5004, 0x1e},
{0x4221, 0x03}, // this is changed from 1 -> 3
// DCG exposure coarse
{0x3501, 0x01}, {0x3502, 0xc8},
// SPD exposure coarse
{0x3541, 0x01}, {0x3542, 0xc8},
// VS exposure coarse
{0x35c1, 0x00}, {0x35c2, 0x01},
// crc reference
{0x420e, 0x66}, {0x420f, 0x5d}, {0x4210, 0xa8}, {0x4211, 0x55},
// crc stat check
{0x507a, 0x5f}, {0x507b, 0x46},
// watchdog control
{0x4f00, 0x00}, {0x4f01, 0x01}, {0x4f02, 0x80}, {0x4f04, 0x2c},
// color balance gains
// blue
{0x5280, 0x06}, {0x5281, 0x4A}, // hcg
{0x5480, 0x06}, {0x5481, 0x4A}, // lcg
{0x5680, 0x07}, {0x5681, 0xDD}, // spd
{0x5880, 0x06}, {0x5881, 0x4A}, // vs
// green(blue)
{0x5282, 0x04}, {0x5283, 0x00},
{0x5482, 0x04}, {0x5483, 0x00},
{0x5682, 0x04}, {0x5683, 0x00},
{0x5882, 0x04}, {0x5883, 0x00},
// green(red)
{0x5284, 0x04}, {0x5285, 0x00},
{0x5484, 0x04}, {0x5485, 0x00},
{0x5684, 0x04}, {0x5685, 0x00},
{0x5884, 0x04}, {0x5885, 0x00},
// red
{0x5286, 0x08}, {0x5287, 0x6C},
{0x5486, 0x08}, {0x5487, 0x6C},
{0x5686, 0x08}, {0x5687, 0xAA},
{0x5886, 0x08}, {0x5887, 0x6C},
}; };
struct i2c_random_wr_payload init_array_ar0231[] = { struct i2c_random_wr_payload init_array_ar0231[] = {

@ -7,13 +7,16 @@
#include "system/hardware/hw.h" #include "system/hardware/hw.h"
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
if (!Hardware::PC()) { if (Hardware::PC()) {
printf("camerad is not meant to run on PC\n");
return 0;
}
int ret; int ret;
ret = util::set_realtime_priority(53); ret = util::set_realtime_priority(53);
assert(ret == 0); assert(ret == 0);
ret = util::set_core_affinity({6}); ret = util::set_core_affinity({6});
assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores
}
camerad_thread(); camerad_thread();
return 0; return 0;

@ -1,25 +0,0 @@
// TODO: cleanup AE tests
// needed by camera_common.cc
void camera_autoexposure(CameraState *s, float grey_frac) {}
void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) {}
void cameras_open(MultiCameraState *s) {}
void cameras_run(MultiCameraState *s) {}
typedef struct CameraState {
int camera_num;
CameraInfo ci;
int fps;
float digital_gain = 0;
CameraBuf buf;
} CameraState;
typedef struct MultiCameraState {
CameraState road_cam;
CameraState driver_cam;
PubMaster *pm = nullptr;
} MultiCameraState;

@ -462,6 +462,17 @@ class Tici(HardwareBase):
sudo_write("N", "/sys/kernel/debug/msm_vidc/clock_scaling") sudo_write("N", "/sys/kernel/debug/msm_vidc/clock_scaling")
sudo_write("Y", "/sys/kernel/debug/msm_vidc/disable_thermal_mitigation") sudo_write("Y", "/sys/kernel/debug/msm_vidc/disable_thermal_mitigation")
# *** unexport GPIO for sensors ***
# remove from /userspace/usr/comma/gpio.sh
sudo_write(str(GPIO.BMX055_ACCEL_INT), "/sys/class/gpio/unexport")
sudo_write(str(GPIO.BMX055_GYRO_INT), "/sys/class/gpio/unexport")
sudo_write(str(GPIO.BMX055_MAGN_INT), "/sys/class/gpio/unexport")
sudo_write(str(GPIO.LSM_INT), "/sys/class/gpio/unexport")
# *** set /dev/gpiochip0 rights to make accessible by sensord
os.system("sudo chmod +r /dev/gpiochip0")
def configure_modem(self): def configure_modem(self):
sim_id = self.get_sim_info().get('sim_id', '') sim_id = self.get_sim_info().get('sim_id', '')

@ -19,3 +19,9 @@ class GPIO:
CAM0_RSTN = 9 CAM0_RSTN = 9
CAM1_RSTN = 7 CAM1_RSTN = 7
CAM2_RSTN = 12 CAM2_RSTN = 12
# Sensor interrupts
BMX055_ACCEL_INT = 21
BMX055_GYRO_INT = 23
BMX055_MAGN_INT = 87
LSM_INT = 84

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save