Merge branch 'master' into mqb-long

# Conflicts:
#	panda
#	selfdrive/controls/lib/drive_helpers.py
pull/81/head
Jason Young 3 years ago
commit 563959dbe5
  1. 4
      Jenkinsfile
  2. 6
      RELEASES.md
  3. 2
      cereal
  4. 13
      common/realtime.py
  5. 3
      docs/CARS.md
  6. 2
      panda
  7. 4
      selfdrive/boardd/panda.cc
  8. 160
      selfdrive/camerad/cameras/camera_qcom2.cc
  9. 17
      selfdrive/camerad/cameras/camera_qcom2.h
  10. 1
      selfdrive/car/interfaces.py
  11. 1
      selfdrive/car/tests/routes.py
  12. 3
      selfdrive/car/tests/test_car_interfaces.py
  13. 23
      selfdrive/car/toyota/carstate.py
  14. 11
      selfdrive/car/toyota/interface.py
  15. 5
      selfdrive/car/toyota/radar_interface.py
  16. 33
      selfdrive/car/toyota/values.py
  17. 5
      selfdrive/car/volkswagen/values.py
  18. 83
      selfdrive/controls/controlsd.py
  19. 2
      selfdrive/controls/lib/drive_helpers.py
  20. 5
      selfdrive/controls/lib/events.py
  21. 4
      selfdrive/controls/lib/latcontrol.py
  22. 2
      selfdrive/controls/lib/latcontrol_angle.py
  23. 2
      selfdrive/controls/lib/latcontrol_indi.py
  24. 13
      selfdrive/controls/lib/latcontrol_pid.py
  25. 23
      selfdrive/controls/lib/latcontrol_torque.py
  26. 27
      selfdrive/controls/lib/longcontrol.py
  27. 43
      selfdrive/hardware/tici/test_power_draw.py
  28. 2
      selfdrive/test/process_replay/ref_commit
  29. 4
      selfdrive/test/process_replay/test_processes.py
  30. 4
      selfdrive/test/test_onroad.py
  31. 2
      selfdrive/ui/qt/maps/map.cc
  32. 42
      selfdrive/ui/qt/onroad.cc
  33. 64
      selfdrive/ui/qt/onroad.h
  34. 1
      selfdrive/ui/qt/widgets/cameraview.cc
  35. 35
      tools/latencylogger/latency_logger.py
  36. 4
      tools/lib/logreader.py
  37. 36
      tools/plotjuggler/layouts/tuning.xml
  38. 4
      tools/replay/can_replay.py
  39. 58
      tools/sim/README.md
  40. 94
      tools/sim/bridge.py
  41. 2
      tools/sim/lib/keyboard_ctrl.py
  42. 2
      tools/sim/start_carla.sh
  43. 28
      tools/sim/test/test_carla_integration.py

4
Jenkinsfile vendored

@ -30,7 +30,7 @@ END"""
def phone_steps(String device_type, steps) { def phone_steps(String device_type, steps) {
lock(resource: "", label: device_type, inversePrecedence: true, variable: 'device_ip', quantity: 1) { lock(resource: "", label: device_type, inversePrecedence: true, variable: 'device_ip', quantity: 1) {
timeout(time: 60, unit: 'MINUTES') { timeout(time: 20, unit: 'MINUTES') {
phone(device_ip, "git checkout", readFile("selfdrive/test/setup_device_ci.sh"),) phone(device_ip, "git checkout", readFile("selfdrive/test/setup_device_ci.sh"),)
steps.each { item -> steps.each { item ->
phone(device_ip, item[0], item[1]) phone(device_ip, item[0], item[1])
@ -46,7 +46,7 @@ pipeline {
SOURCE_DIR = "/data/openpilot_source/" SOURCE_DIR = "/data/openpilot_source/"
} }
options { options {
timeout(time: 4, unit: 'HOURS') timeout(time: 4, unit: 'HOURS')
} }
stages { stages {

@ -10,14 +10,16 @@ Version 0.8.14 (2022-0X-XX)
* New lateral controller based on physical wheel torque model * New lateral controller based on physical wheel torque model
* Much smoother control, consistent across the speed range * Much smoother control, consistent across the speed range
* Effective feedforward that uses road roll * Effective feedforward that uses road roll
* Simplified tuning, all car specific parameters can be derived from data * Simplified tuning, all car-specific parameters can be derived from data
* Initially used on TSS2 Corolla and TSS-P Rav4 * Initially used on TSS2 Corolla and TSS-P RAV4
* Added toggle to disable disengaging on the accelerator pedal
* comma body support * comma body support
* Audi RS3 support thanks to jyoung8607! * Audi RS3 support thanks to jyoung8607!
* Hyundai Ioniq Plug-in Hybrid 2019 support thanks to sunnyhaibin! * Hyundai Ioniq Plug-in Hybrid 2019 support thanks to sunnyhaibin!
* Hyundai Tucson Diesel 2019 support thanks to sunnyhaibin! * Hyundai Tucson Diesel 2019 support thanks to sunnyhaibin!
* Toyota Alphard Hybrid 2021 support * Toyota Alphard Hybrid 2021 support
* Toyota Avalon Hybrid 2022 support * Toyota Avalon Hybrid 2022 support
* Toyota RAV4 Hybrid 2022 support
Version 0.8.13 (2022-02-18) Version 0.8.13 (2022-02-18)
======================== ========================

@ -1 +1 @@
Subproject commit 29f4fe89ef710ff86a5aeb998a357187d0619fb8 Subproject commit a057aed16747d0e414145d83d4861c50315781ad

@ -2,6 +2,7 @@
import gc import gc
import os import os
import time import time
from collections import deque
from typing import Optional, List, Union from typing import Optional, List, Union
from setproctitle import getproctitle # pylint: disable=no-name-in-module from setproctitle import getproctitle # pylint: disable=no-name-in-module
@ -59,6 +60,8 @@ class Ratekeeper:
self._frame = 0 self._frame = 0
self._remaining = 0.0 self._remaining = 0.0
self._process_name = getproctitle() self._process_name = getproctitle()
self._dts = deque([self._interval], maxlen=100)
self._last_monitor_time = sec_since_boot()
@property @property
def frame(self) -> int: def frame(self) -> int:
@ -68,6 +71,12 @@ class Ratekeeper:
def remaining(self) -> float: def remaining(self) -> float:
return self._remaining return self._remaining
@property
def lagging(self) -> bool:
avg_dt = sum(self._dts) / len(self._dts)
expected_dt = self._interval * (1 / 0.9)
return avg_dt > expected_dt
# Maintain loop rate by calling this at the end of each loop # Maintain loop rate by calling this at the end of each loop
def keep_time(self) -> bool: def keep_time(self) -> bool:
lagged = self.monitor_time() lagged = self.monitor_time()
@ -77,6 +86,10 @@ class Ratekeeper:
# this only monitor the cumulative lag, but does not enforce a rate # this only monitor the cumulative lag, but does not enforce a rate
def monitor_time(self) -> bool: def monitor_time(self) -> bool:
prev = self._last_monitor_time
self._last_monitor_time = sec_since_boot()
self._dts.append(self._last_monitor_time - prev)
lagged = False lagged = False
remaining = self._next_frame_time - sec_since_boot() remaining = self._next_frame_time - sec_since_boot()
self._next_frame_time += self._interval self._next_frame_time += self._interval

@ -130,6 +130,7 @@ How We Rate The Cars
|Toyota|Highlander 2017-19|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Toyota|Highlander 2017-19|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Toyota|Highlander Hybrid 2017-19|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Toyota|Highlander Hybrid 2017-19|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Toyota|RAV4 Hybrid 2016-18|TSS-P|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Toyota|RAV4 Hybrid 2016-18|TSS-P|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Toyota|RAV4 Hybrid 2022|All|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Toyota|Sienna 2018-20|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Toyota|Sienna 2018-20|All|<a href="#"><img valign="top" src="assets/icon-star-half.svg" width="22" /></a>[<sup>3</sup>](#footnotes)|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|Arteon 2018, 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|Arteon 2018, 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|Atlas 2018-19, 2022[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|Atlas 2018-19, 2022[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
@ -148,7 +149,7 @@ How We Rate The Cars
|Volkswagen|T-Cross 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|T-Cross 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|T-Roc 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|T-Roc 2021[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|Taos 2022[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|Taos 2022[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|Tiguan 2020-22[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|Tiguan 2019-22[<sup>8</sup>](#footnotes)|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
|Volkswagen|Touran 2017|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>| |Volkswagen|Touran 2017|Driver Assistance|<a href="#"><img valign="top" src="assets/icon-star-empty.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|<a href="#"><img valign="top" src="assets/icon-star-full.svg" width="22" /></a>|
## Bronze Cars ## Bronze Cars

@ -1 +1 @@
Subproject commit c70dbb760648b1381bc7c49a681489e572e2876e Subproject commit 326cc2a8dbabbfe6c442f4b0192b18178a83b6a6

@ -248,7 +248,9 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length
} }
void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint32_t safety_param) { void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint32_t safety_param) {
usb_write(0xdc, (uint16_t)safety_model, safety_param); // FIXME: last two bytes must be empty
assert((safety_param >> 16) == 0U);
usb_write(0xdc, (uint16_t)safety_model, (uint16_t)safety_param);
} }
void Panda::set_alternative_experience(uint16_t alternative_experience) { void Panda::set_alternative_experience(uint16_t alternative_experience) {

@ -87,11 +87,11 @@ int do_cam_control(int fd, int op_code, void *handle, int size) {
return ret; return ret;
} }
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data) { 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 = { struct cam_acquire_dev_cmd cmd = {
.session_handle = session_handle, .session_handle = session_handle,
.handle_type = CAM_HANDLE_USER_POINTER, .handle_type = CAM_HANDLE_USER_POINTER,
.num_resources = (uint32_t)(data ? 1 : 0), .num_resources = (uint32_t)(data ? num_resources : 0),
.resource_hdl = (uint64_t)data, .resource_hdl = (uint64_t)data,
}; };
int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd));
@ -158,6 +158,42 @@ void release_fd(int video0_fd, uint32_t handle) {
release(video0_fd, handle); 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};
req_mgr_flush_request.session_hdl = session_handle; req_mgr_flush_request.session_hdl = session_handle;
@ -186,7 +222,7 @@ void CameraState::sensors_start() {
void CameraState::sensors_poke(int request_id) { void CameraState::sensors_poke(int request_id) {
uint32_t cam_packet_handle = 0; uint32_t cam_packet_handle = 0;
int size = sizeof(struct cam_packet); int size = sizeof(struct cam_packet);
struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, size, &cam_packet_handle); struct cam_packet *pkt = (struct cam_packet *)mm.alloc(size, &cam_packet_handle);
pkt->num_cmd_buf = 0; pkt->num_cmd_buf = 0;
pkt->kmd_cmd_buf_index = -1; pkt->kmd_cmd_buf_index = -1;
pkt->header.size = size; pkt->header.size = size;
@ -200,15 +236,14 @@ void CameraState::sensors_poke(int request_id) {
return; return;
} }
munmap(pkt, size); mm.free(pkt);
release_fd(multi_cam_state->video0_fd, cam_packet_handle);
} }
void CameraState::sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { void CameraState::sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) {
// LOGD("sensors_i2c: %d", len); // LOGD("sensors_i2c: %d", len);
uint32_t cam_packet_handle = 0; uint32_t cam_packet_handle = 0;
int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1;
struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, size, &cam_packet_handle); struct cam_packet *pkt = (struct cam_packet *)mm.alloc(size, &cam_packet_handle);
pkt->num_cmd_buf = 1; pkt->num_cmd_buf = 1;
pkt->kmd_cmd_buf_index = -1; pkt->kmd_cmd_buf_index = -1;
pkt->header.size = size; pkt->header.size = size;
@ -218,7 +253,7 @@ void CameraState::sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op
buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload);
buf_desc[0].type = CAM_CMD_BUF_I2C; buf_desc[0].type = CAM_CMD_BUF_I2C;
struct cam_cmd_i2c_random_wr *i2c_random_wr = (struct cam_cmd_i2c_random_wr *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); struct cam_cmd_i2c_random_wr *i2c_random_wr = (struct cam_cmd_i2c_random_wr *)mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle);
i2c_random_wr->header.count = len; i2c_random_wr->header.count = len;
i2c_random_wr->header.op_code = 1; i2c_random_wr->header.op_code = 1;
i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR;
@ -233,10 +268,8 @@ void CameraState::sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op
return; return;
} }
munmap(i2c_random_wr, buf_desc[0].size); mm.free(i2c_random_wr);
release_fd(multi_cam_state->video0_fd, buf_desc[0].mem_handle); mm.free(pkt);
munmap(pkt, size);
release_fd(multi_cam_state->video0_fd, cam_packet_handle);
} }
static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) {
@ -248,10 +281,9 @@ static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) {
}; };
int CameraState::sensors_init() { int CameraState::sensors_init() {
int video0_fd = multi_cam_state->video0_fd;
uint32_t cam_packet_handle = 0; uint32_t cam_packet_handle = 0;
int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2;
struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(video0_fd, size, &cam_packet_handle); struct cam_packet *pkt = (struct cam_packet *)mm.alloc(size, &cam_packet_handle);
pkt->num_cmd_buf = 2; pkt->num_cmd_buf = 2;
pkt->kmd_cmd_buf_index = -1; pkt->kmd_cmd_buf_index = -1;
pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE;
@ -260,7 +292,7 @@ int CameraState::sensors_init() {
buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe);
buf_desc[0].type = CAM_CMD_BUF_LEGACY; buf_desc[0].type = CAM_CMD_BUF_LEGACY;
struct cam_cmd_i2c_info *i2c_info = (struct cam_cmd_i2c_info *)alloc_w_mmu_hdl(video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); struct cam_cmd_i2c_info *i2c_info = (struct cam_cmd_i2c_info *)mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle);
auto probe = (struct cam_cmd_probe *)(i2c_info + 1); auto probe = (struct cam_cmd_probe *)(i2c_info + 1);
probe->camera_id = camera_num; probe->camera_id = camera_num;
@ -302,7 +334,7 @@ int CameraState::sensors_init() {
//buf_desc[1].size = buf_desc[1].length = 148; //buf_desc[1].size = buf_desc[1].length = 148;
buf_desc[1].size = buf_desc[1].length = 196; buf_desc[1].size = buf_desc[1].length = 196;
buf_desc[1].type = CAM_CMD_BUF_I2C; buf_desc[1].type = CAM_CMD_BUF_I2C;
struct cam_cmd_power *power_settings = (struct cam_cmd_power *)alloc_w_mmu_hdl(video0_fd, buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); struct cam_cmd_power *power_settings = (struct cam_cmd_power *)mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle);
memset(power_settings, 0, buf_desc[1].size); memset(power_settings, 0, buf_desc[1].size);
// power on // power on
@ -363,12 +395,9 @@ int CameraState::sensors_init() {
LOGD("probing the sensor"); 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);
munmap(i2c_info, buf_desc[0].size); mm.free(i2c_info);
release_fd(video0_fd, buf_desc[0].mem_handle); mm.free(power_settings);
munmap(power_settings, buf_desc[1].size); mm.free(pkt);
release_fd(video0_fd, buf_desc[1].mem_handle);
munmap(pkt, size);
release_fd(video0_fd, cam_packet_handle);
return ret; return ret;
} }
@ -379,7 +408,7 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b
if (io_mem_handle != 0) { if (io_mem_handle != 0) {
size += sizeof(struct cam_buf_io_cfg); size += sizeof(struct cam_buf_io_cfg);
} }
struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, size, &cam_packet_handle); struct cam_packet *pkt = (struct cam_packet *)mm.alloc(size, &cam_packet_handle);
pkt->num_cmd_buf = 2; pkt->num_cmd_buf = 2;
pkt->kmd_cmd_buf_index = 0; pkt->kmd_cmd_buf_index = 0;
// YUV has kmd_cmd_buf_offset = 1780 // YUV has kmd_cmd_buf_offset = 1780
@ -387,7 +416,7 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b
// YUV also has patch_offset = 0x1030 and num_patches = 10 // YUV also has patch_offset = 0x1030 and num_patches = 10
if (io_mem_handle != 0) { if (io_mem_handle != 0) {
pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*2; pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf;
pkt->num_io_configs = 1; pkt->num_io_configs = 1;
} }
@ -474,7 +503,7 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b
buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset;
buf_desc[1].type = CAM_CMD_BUF_GENERIC; buf_desc[1].type = CAM_CMD_BUF_GENERIC;
buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON;
uint32_t *buf2 = (uint32_t *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle, 0x20); uint32_t *buf2 = (uint32_t *)mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle);
memcpy(buf2, &tmp, sizeof(tmp)); memcpy(buf2, &tmp, sizeof(tmp));
if (io_mem_handle != 0) { if (io_mem_handle != 0) {
@ -510,24 +539,20 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b
printf("ISP CONFIG FAILED\n"); printf("ISP CONFIG FAILED\n");
} }
munmap(buf2, buf_desc[1].size); mm.free(buf2);
release_fd(multi_cam_state->video0_fd, buf_desc[1].mem_handle); mm.free(pkt);
// release_fd(multi_cam_state->video0_fd, buf_desc[0].mem_handle);
munmap(pkt, size);
release_fd(multi_cam_state->video0_fd, cam_packet_handle);
} }
void CameraState::enqueue_buffer(int i, bool dp) { void CameraState::enqueue_buffer(int i, bool dp) {
int ret; int ret;
int request_id = request_ids[i]; int request_id = request_ids[i];
if (buf_handle[i]) { if (buf_handle[i] && sync_objs[i]) {
release(multi_cam_state->video0_fd, buf_handle[i]);
// wait // wait
struct cam_sync_wait sync_wait = {0}; struct cam_sync_wait sync_wait = {0};
sync_wait.sync_obj = sync_objs[i]; sync_wait.sync_obj = sync_objs[i];
sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23
ret = do_cam_control(multi_cam_state->video1_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait));
// LOGD("fence wait: %d %d", ret, sync_wait.sync_obj); // LOGD("fence wait: %d %d", ret, sync_wait.sync_obj);
buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof
@ -535,13 +560,19 @@ void CameraState::enqueue_buffer(int i, bool dp) {
// destroy old output fence // destroy old output fence
struct cam_sync_info sync_destroy = {0}; struct cam_sync_info sync_destroy = {0};
strcpy(sync_destroy.name, "NodeOutputPortFence");
sync_destroy.sync_obj = sync_objs[i]; sync_destroy.sync_obj = sync_objs[i];
ret = do_cam_control(multi_cam_state->video1_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy));
// LOGD("fence destroy: %d %d", ret, sync_destroy.sync_obj); // LOGD("fence destroy: %d %d", ret, sync_destroy.sync_obj);
} }
// do stuff // create output fence
struct cam_sync_info sync_create = {0};
strcpy(sync_create.name, "NodeOutputPortFence");
ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create));
// LOGD("fence req: %d %d", ret, sync_create.sync_obj);
sync_objs[i] = sync_create.sync_obj;
// schedule request with camera request manager
struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; struct cam_req_mgr_sched_request req_mgr_sched_request = {0};
req_mgr_sched_request.session_hdl = session_handle; req_mgr_sched_request.session_hdl = session_handle;
req_mgr_sched_request.link_hdl = link_handle; req_mgr_sched_request.link_hdl = link_handle;
@ -549,28 +580,11 @@ void CameraState::enqueue_buffer(int i, bool dp) {
ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request));
// LOGD("sched req: %d %d", ret, request_id); // LOGD("sched req: %d %d", ret, request_id);
// create output fence // poke sensor, must happen after schedule
struct cam_sync_info sync_create = {0};
strcpy(sync_create.name, "NodeOutputPortFence");
ret = do_cam_control(multi_cam_state->video1_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create));
// LOGD("fence req: %d %d", ret, sync_create.sync_obj);
sync_objs[i] = sync_create.sync_obj;
// 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", bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret);
buf_handle[i] = mem_mgr_map_cmd.out.buf_handle;
// poke sensor
sensors_poke(request_id); sensors_poke(request_id);
// LOGD("Poked sensor"); // LOGD("Poked sensor");
// push the buffer // submit request to the ife
config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1));
} }
@ -616,6 +630,9 @@ void CameraState::camera_open() {
assert(sensor_fd >= 0); assert(sensor_fd >= 0);
LOGD("opened sensor for %d", camera_num); LOGD("opened sensor for %d", camera_num);
// init memorymanager for this camera
mm.init(multi_cam_state->video0_fd);
// probe the sensor // probe the sensor
LOGD("-- Probing sensor %d", camera_num); LOGD("-- Probing sensor %d", camera_num);
ret = sensors_init(); ret = sensors_init();
@ -729,7 +746,7 @@ void CameraState::camera_open() {
{ {
uint32_t cam_packet_handle = 0; uint32_t cam_packet_handle = 0;
int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1;
struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, size, &cam_packet_handle); struct cam_packet *pkt = (struct cam_packet *)mm.alloc(size, &cam_packet_handle);
pkt->num_cmd_buf = 1; pkt->num_cmd_buf = 1;
pkt->kmd_cmd_buf_index = -1; pkt->kmd_cmd_buf_index = -1;
pkt->header.size = size; pkt->header.size = size;
@ -738,7 +755,7 @@ void CameraState::camera_open() {
buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info);
buf_desc[0].type = CAM_CMD_BUF_GENERIC; buf_desc[0].type = CAM_CMD_BUF_GENERIC;
struct cam_csiphy_info *csiphy_info = (struct cam_csiphy_info *)alloc_w_mmu_hdl(multi_cam_state->video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); struct cam_csiphy_info *csiphy_info = (struct cam_csiphy_info *)mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle);
csiphy_info->lane_mask = 0x1f; csiphy_info->lane_mask = 0x1f;
csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels??
csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane
@ -751,10 +768,8 @@ void CameraState::camera_open() {
int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle);
assert(ret_ == 0); assert(ret_ == 0);
munmap(csiphy_info, buf_desc[0].size); mm.free(csiphy_info);
release_fd(multi_cam_state->video0_fd, buf_desc[0].mem_handle); mm.free(pkt);
munmap(pkt, size);
release_fd(multi_cam_state->video0_fd, cam_packet_handle);
} }
// link devices // link devices
@ -781,6 +796,18 @@ 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);
@ -807,9 +834,9 @@ void cameras_open(MultiCameraState *s) {
LOGD("opened video0"); LOGD("opened video0");
// video1 is cam_sync, the target of some ioctls // video1 is cam_sync, the target of some ioctls
s->video1_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); s->cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK));
assert(s->video1_fd >= 0); assert(s->cam_sync_fd >= 0);
LOGD("opened video1"); LOGD("opened video1 (cam_sync)");
// looks like there's only one of these // looks like there's only one of these
s->isp_fd = open_v4l_by_name_and_index("cam-isp"); s->isp_fd = open_v4l_by_name_and_index("cam-isp");
@ -834,7 +861,7 @@ void cameras_open(MultiCameraState *s) {
LOG("-- Subscribing"); LOG("-- Subscribing");
static struct v4l2_event_subscription sub = {0}; static struct v4l2_event_subscription sub = {0};
sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT;
sub.id = 2; // should use boot time for sof sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS;
ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub));
printf("req mgr subscribe: %d\n", ret); printf("req mgr subscribe: %d\n", ret);
@ -883,6 +910,11 @@ void CameraState::camera_close() {
LOGD("release isp: %d", ret); LOGD("release isp: %d", ret);
ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle);
LOGD("release csiphy: %d", ret); LOGD("release csiphy: %d", ret);
for (int i = 0; i < FRAME_BUF_COUNT; i++) {
release(multi_cam_state->video0_fd, buf_handle[i]);
}
LOGD("released buffers");
} }
ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle);

@ -9,6 +9,20 @@
#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;
@ -60,6 +74,7 @@ public:
int camera_id; int camera_id;
CameraBuf buf; CameraBuf buf;
MemoryManager mm;
private: private:
void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset);
void enqueue_req_multi(int start, int n, bool dp); void enqueue_req_multi(int start, int n, bool dp);
@ -73,7 +88,7 @@ private:
typedef struct MultiCameraState { typedef struct MultiCameraState {
unique_fd video0_fd; unique_fd video0_fd;
unique_fd video1_fd; unique_fd cam_sync_fd;
unique_fd isp_fd; unique_fd isp_fd;
int device_iommu; int device_iommu;
int cdm_iommu; int cdm_iommu;

@ -187,6 +187,7 @@ class CarInterfaceBase(ABC):
class RadarInterfaceBase(ABC): class RadarInterfaceBase(ABC):
def __init__(self, CP): def __init__(self, CP):
self.rcp = None
self.pts = {} self.pts = {}
self.delay = 0 self.delay = 0
self.radar_ts = CP.radarTimeStep self.radar_ts = CP.radarTimeStep

@ -128,6 +128,7 @@ routes = [
TestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H), TestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H),
TestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2), TestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2),
TestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), TestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2),
TestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022),
TestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), TestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2),
TestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), TestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH),
TestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), TestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2),

@ -64,7 +64,8 @@ class TestCarInterfaces(unittest.TestCase):
# Run radar interface once # Run radar interface once
radar_interface.update([]) radar_interface.update([])
if not car_params.radarOffCan and hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'): if not car_params.radarOffCan and radar_interface.rcp is not None and \
hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'):
radar_interface._update([radar_interface.trigger_msg]) radar_interface._update([radar_interface.trigger_msg])
if __name__ == "__main__": if __name__ == "__main__":

@ -6,7 +6,7 @@ from common.realtime import DT_CTRL
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.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR, EPS_SCALE from selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE
class CarState(CarStateBase): class CarState(CarStateBase):
@ -91,8 +91,12 @@ class CarState(CarStateBase):
ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0
ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS
if self.CP.carFingerprint in TSS2_CAR: if self.CP.carFingerprint in RADAR_ACC_CAR:
self.acc_type = cp.vl["ACC_CONTROL"]["ACC_TYPE"]
ret.stockFcw = bool(cp.vl["ACC_HUD"]["FCW"])
elif self.CP.carFingerprint in TSS2_CAR:
self.acc_type = cp_cam.vl["ACC_CONTROL"]["ACC_TYPE"] self.acc_type = cp_cam.vl["ACC_CONTROL"]["ACC_TYPE"]
ret.stockFcw = bool(cp_cam.vl["ACC_HUD"]["FCW"])
# some TSS2 cars have low speed lockout permanently set, so ignore on those cars # some TSS2 cars have low speed lockout permanently set, so ignore on those cars
# these cars are identified by an ACC_TYPE value of 2. # these cars are identified by an ACC_TYPE value of 2.
@ -115,9 +119,6 @@ class CarState(CarStateBase):
ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"])
ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5)
if self.CP.carFingerprint in TSS2_CAR:
ret.stockFcw = bool(cp_cam.vl["ACC_HUD"]["FCW"])
ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0
# 2 is standby, 10 is active. TODO: check that everything else is really a faulty state # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state
self.steer_state = cp.vl["EPS_STATUS"]["LKA_STATE"] self.steer_state = cp.vl["EPS_STATUS"]["LKA_STATE"]
@ -207,6 +208,16 @@ class CarState(CarStateBase):
] ]
checks.append(("BSM", 1)) checks.append(("BSM", 1))
if CP.carFingerprint in RADAR_ACC_CAR:
signals += [
("ACC_TYPE", "ACC_CONTROL"),
("FCW", "ACC_HUD"),
]
checks += [
("ACC_CONTROL", 33),
("ACC_HUD", 1),
]
return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod @staticmethod
@ -222,7 +233,7 @@ class CarState(CarStateBase):
("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent
] ]
if CP.carFingerprint in TSS2_CAR: if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR):
signals += [ signals += [
("ACC_TYPE", "ACC_CONTROL"), ("ACC_TYPE", "ACC_CONTROL"),
("FCW", "ACC_HUD"), ("FCW", "ACC_HUD"),

@ -3,7 +3,7 @@ from cereal import car
from common.conversions import Conversions as CV from common.conversions import Conversions as CV
from panda import Panda from panda import Panda
from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune
from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams
from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config
from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.interfaces import CarInterfaceBase
@ -115,7 +115,7 @@ class CarInterface(CarInterfaceBase):
ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid
set_lat_tune(ret.lateralTuning, LatTunes.PID_H) set_lat_tune(ret.lateralTuning, LatTunes.PID_H)
elif candidate in (CAR.RAV4_TSS2, CAR.RAV4H_TSS2): elif candidate in (CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022):
stop_and_go = True stop_and_go = True
ret.wheelbase = 2.68986 ret.wheelbase = 2.68986
ret.steerRatio = 14.3 ret.steerRatio = 14.3
@ -123,7 +123,7 @@ class CarInterface(CarInterfaceBase):
ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid
set_lat_tune(ret.lateralTuning, LatTunes.PID_D) set_lat_tune(ret.lateralTuning, LatTunes.PID_D)
# 2019+ Rav4 TSS2 uses two different steering racks and specific tuning seems to be necessary. # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary.
# See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891
for fw in car_fw: for fw in car_fw:
if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']):
@ -221,7 +221,10 @@ class CarInterface(CarInterfaceBase):
ret.enableDsu = (len(found_ecus) > 0) and (Ecu.dsu not in found_ecus) and (candidate not in NO_DSU_CAR) and (not smartDsu) ret.enableDsu = (len(found_ecus) > 0) and (Ecu.dsu not in found_ecus) and (candidate not in NO_DSU_CAR) and (not smartDsu)
ret.enableGasInterceptor = 0x201 in fingerprint[0] ret.enableGasInterceptor = 0x201 in fingerprint[0]
# if the smartDSU is detected, openpilot can send ACC_CMD (and the smartDSU will block it from the DSU) or not (the DSU is "connected") # if the smartDSU is detected, openpilot can send ACC_CMD (and the smartDSU will block it from the DSU) or not (the DSU is "connected")
ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in TSS2_CAR ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR)
if not ret.openpilotLongitudinalControl:
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL
# we can't use the fingerprint to detect this reliably, since # we can't use the fingerprint to detect this reliably, since
# the EV gas pedal signal can take a couple seconds to appear # the EV gas pedal signal can take a couple seconds to appear

@ -6,6 +6,9 @@ from selfdrive.car.interfaces import RadarInterfaceBase
def _create_radar_can_parser(car_fingerprint): def _create_radar_can_parser(car_fingerprint):
if DBC[car_fingerprint]['radar'] is None:
return None
if car_fingerprint in TSS2_CAR: if car_fingerprint in TSS2_CAR:
RADAR_A_MSGS = list(range(0x180, 0x190)) RADAR_A_MSGS = list(range(0x180, 0x190))
RADAR_B_MSGS = list(range(0x190, 0x1a0)) RADAR_B_MSGS = list(range(0x190, 0x1a0))
@ -48,7 +51,7 @@ class RadarInterface(RadarInterfaceBase):
self.no_radar = CP.carFingerprint in NO_DSU_CAR and CP.carFingerprint not in TSS2_CAR self.no_radar = CP.carFingerprint in NO_DSU_CAR and CP.carFingerprint not in TSS2_CAR
def update(self, can_strings): def update(self, can_strings):
if self.no_radar: if self.no_radar or self.rcp is None:
return super().update(None) return super().update(None)
vls = self.rcp.update_strings(can_strings) vls = self.rcp.update_strings(can_strings)

@ -63,6 +63,7 @@ class CAR:
RAV4H = "TOYOTA RAV4 HYBRID 2017" RAV4H = "TOYOTA RAV4 HYBRID 2017"
RAV4_TSS2 = "TOYOTA RAV4 2019" RAV4_TSS2 = "TOYOTA RAV4 2019"
RAV4H_TSS2 = "TOYOTA RAV4 HYBRID 2019" RAV4H_TSS2 = "TOYOTA RAV4 HYBRID 2019"
RAV4H_TSS2_2022 = "TOYOTA RAV4 HYBRID 2022"
MIRAI = "TOYOTA MIRAI 2021" # TSS 2.5 MIRAI = "TOYOTA MIRAI 2021" # TSS 2.5
SIENNA = "TOYOTA SIENNA 2018" SIENNA = "TOYOTA SIENNA 2018"
@ -142,6 +143,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.RAV4H: ToyotaCarInfo("Toyota RAV4 Hybrid 2016-18", "TSS-P", footnotes=[Footnote.DSU]), CAR.RAV4H: ToyotaCarInfo("Toyota RAV4 Hybrid 2016-18", "TSS-P", footnotes=[Footnote.DSU]),
CAR.RAV4_TSS2: ToyotaCarInfo("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), CAR.RAV4_TSS2: ToyotaCarInfo("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"),
CAR.RAV4H_TSS2: ToyotaCarInfo("Toyota RAV4 Hybrid 2019-21"), CAR.RAV4H_TSS2: ToyotaCarInfo("Toyota RAV4 Hybrid 2019-21"),
CAR.RAV4H_TSS2_2022: ToyotaCarInfo("Toyota RAV4 Hybrid 2022"),
CAR.MIRAI: ToyotaCarInfo("Toyota Mirai 2021"), CAR.MIRAI: ToyotaCarInfo("Toyota Mirai 2021"),
CAR.SIENNA: ToyotaCarInfo("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", footnotes=[Footnote.DSU]), CAR.SIENNA: ToyotaCarInfo("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", footnotes=[Footnote.DSU]),
@ -1330,6 +1332,29 @@ FW_VERSIONS = {
b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00',
], ],
}, },
CAR.RAV4H_TSS2_2022: {
(Ecu.esp, 0x7b0, None): [
b'\x01F15264283100\x00\x00\x00\x00',
b'\x01F15264286200\x00\x00\x00\x00',
b'\x01F15264286100\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00',
b'8965B42182\x00\x00\x00\x00\x00\x00',
b'8965B42172\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
b'\x01896634A62000\x00\x00\x00\x00',
b'\x01896634A08000\x00\x00\x00\x00',
b'\x01896634A61000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F0R01100\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00',
],
},
CAR.SIENNA: { CAR.SIENNA: {
(Ecu.engine, 0x700, None): [ (Ecu.engine, 0x700, None): [
b'\x01896630832100\x00\x00\x00\x00', b'\x01896630832100\x00\x00\x00\x00',
@ -1840,6 +1865,7 @@ DBC = {
CAR.LEXUS_IS: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_IS: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'),
CAR.LEXUS_CTH: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), CAR.LEXUS_CTH: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'),
CAR.RAV4H_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.RAV4H_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'),
CAR.RAV4H_TSS2_2022: dbc_dict('toyota_nodsu_pt_generated', None),
CAR.LEXUS_NXH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_NXH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'),
CAR.LEXUS_NX: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_NX: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'),
CAR.LEXUS_NX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.LEXUS_NX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'),
@ -1853,14 +1879,17 @@ DBC = {
EPS_SCALE = defaultdict(lambda: 73, {CAR.PRIUS: 66, CAR.COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.PRIUS_V: 100}) EPS_SCALE = defaultdict(lambda: 73, {CAR.PRIUS: 66, CAR.COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.PRIUS_V: 100})
# Toyota/Lexus Safety Sense 2.0 and 2.5 # Toyota/Lexus Safety Sense 2.0 and 2.5
TSS2_CAR = {CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, TSS2_CAR = {CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022,
CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2,
CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, CAR.AVALONH_TSS2, CAR.ALPHARDH_TSS2} CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, CAR.AVALONH_TSS2, CAR.ALPHARDH_TSS2}
NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH} NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH}
# these cars have a radar which sends ACC messages instead of the camera
RADAR_ACC_CAR = {CAR.RAV4H_TSS2_2022}
EV_HYBRID_CAR = {CAR.AVALONH_2019, CAR.AVALONH_TSS2, CAR.CAMRYH, CAR.CAMRYH_TSS2, CAR.CHRH, CAR.COROLLAH_TSS2, CAR.HIGHLANDERH, CAR.HIGHLANDERH_TSS2, CAR.PRIUS, EV_HYBRID_CAR = {CAR.AVALONH_2019, CAR.AVALONH_TSS2, CAR.CAMRYH, CAR.CAMRYH_TSS2, CAR.CHRH, CAR.COROLLAH_TSS2, CAR.HIGHLANDERH, CAR.HIGHLANDERH_TSS2, CAR.PRIUS,
CAR.PRIUS_V, CAR.RAV4H, CAR.RAV4H_TSS2, CAR.LEXUS_CTH, CAR.MIRAI, CAR.LEXUS_ESH, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_NXH, CAR.LEXUS_RXH, CAR.PRIUS_V, CAR.RAV4H, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022, CAR.LEXUS_CTH, CAR.MIRAI, CAR.LEXUS_ESH, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_NXH, CAR.LEXUS_RXH,
CAR.LEXUS_RXH_TSS2, CAR.PRIUS_TSS2, CAR.ALPHARDH_TSS2} CAR.LEXUS_RXH_TSS2, CAR.PRIUS_TSS2, CAR.ALPHARDH_TSS2}
# no resume button press required # no resume button press required

@ -138,7 +138,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
CAR.POLO_MK6: VWCarInfo("Volkswagen Polo 2020"), CAR.POLO_MK6: VWCarInfo("Volkswagen Polo 2020"),
CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS]), CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS]),
CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS]), CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS]),
CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2020-22", footnotes=[Footnote.VW_HARNESS]), CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS]),
CAR.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2017"), CAR.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2017"),
CAR.TRANSPORTER_T61: [ CAR.TRANSPORTER_T61: [
VWCarInfo("Volkswagen Caravelle 2020", footnotes=[Footnote.VW_HARNESS]), VWCarInfo("Volkswagen Caravelle 2020", footnotes=[Footnote.VW_HARNESS]),
@ -522,6 +522,7 @@ FW_VERSIONS = {
b'\xf1\x8704L906026EJ\xf1\x893661', b'\xf1\x8704L906026EJ\xf1\x893661',
b'\xf1\x8704L906027G \xf1\x899893', b'\xf1\x8704L906027G \xf1\x899893',
b'\xf1\x875N0906259 \xf1\x890002', b'\xf1\x875N0906259 \xf1\x890002',
b'\xf1\x875NA907115E \xf1\x890005',
b'\xf1\x8783A907115B \xf1\x890005', b'\xf1\x8783A907115B \xf1\x890005',
b'\xf1\x8783A907115G \xf1\x890001', b'\xf1\x8783A907115G \xf1\x890001',
], ],
@ -532,6 +533,7 @@ FW_VERSIONS = {
b'\xf1\x870DL300011N \xf1\x892001', b'\xf1\x870DL300011N \xf1\x892001',
b'\xf1\x870DL300011N \xf1\x892012', b'\xf1\x870DL300011N \xf1\x892012',
b'\xf1\x870DL300013A \xf1\x893005', b'\xf1\x870DL300013A \xf1\x893005',
b'\xf1\x870DL300013G \xf1\x892119',
b'\xf1\x870DL300013G \xf1\x892120', b'\xf1\x870DL300013G \xf1\x892120',
], ],
(Ecu.srs, 0x715, None): [ (Ecu.srs, 0x715, None): [
@ -539,6 +541,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02316143231313500314641011750179333423100', b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02316143231313500314641011750179333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02312110031333300314240583752379333423100', b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02312110031333300314240583752379333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02331310031333336313140013950399333423100', b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02331310031333336313140013950399333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100',
b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100',
], ],
(Ecu.eps, 0x712, None): [ (Ecu.eps, 0x712, None): [

@ -59,7 +59,7 @@ ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES)
class Controls: class Controls:
def __init__(self, sm=None, pm=None, can_sock=None, CI=None): def __init__(self, sm=None, pm=None, can_sock=None, CI=None):
config_realtime_process(4 if TICI else 3, Priority.CTRL_HIGH) config_realtime_process(4, Priority.CTRL_HIGH)
# Setup sockets # Setup sockets
self.pm = pm self.pm = pm
@ -73,7 +73,7 @@ class Controls:
self.can_sock = can_sock self.can_sock = can_sock
if can_sock is None: if can_sock is None:
can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 20
self.can_sock = messaging.sub_sock('can', timeout=can_timeout) self.can_sock = messaging.sub_sock('can', timeout=can_timeout)
if TICI: if TICI:
@ -98,8 +98,7 @@ class Controls:
self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration',
'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman',
'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet, 'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet,
ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan'])
# set alternative experiences from parameters # set alternative experiences from parameters
self.disengage_on_accelerator = params.get_bool("DisengageOnAccelerator") self.disengage_on_accelerator = params.get_bool("DisengageOnAccelerator")
@ -163,7 +162,7 @@ class Controls:
self.last_functional_fan_frame = 0 self.last_functional_fan_frame = 0
self.events_prev = [] self.events_prev = []
self.current_alert_types = [ET.PERMANENT] self.current_alert_types = [ET.PERMANENT]
self.logged_comm_issue = False self.logged_comm_issue = None
self.button_timers = {ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0} self.button_timers = {ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0}
self.last_actuators = car.CarControl.Actuators.new_message() self.last_actuators = car.CarControl.Actuators.new_message()
@ -214,11 +213,17 @@ class Controls:
self.events.add(EventName.pedalPressedPreEnable if self.disengage_on_accelerator else self.events.add(EventName.pedalPressedPreEnable if self.disengage_on_accelerator else
EventName.gasPressedOverride) EventName.gasPressedOverride)
self.events.add_from_msg(CS.events)
if not self.CP.notCar: if not self.CP.notCar:
self.events.add_from_msg(self.sm['driverMonitoringState'].events) self.events.add_from_msg(self.sm['driverMonitoringState'].events)
# Handle car events. Ignore when CAN is invalid
if CS.canTimeout:
self.events.add(EventName.canBusMissing)
elif not CS.canValid:
self.events.add(EventName.canError)
else:
self.events.add_from_msg(CS.events)
# Create events for temperature, disk space, and memory # Create events for temperature, disk space, and memory
if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: if self.sm['deviceState'].thermalStatus >= ThermalStatus.red:
self.events.add(EventName.overheat) self.events.add(EventName.overheat)
@ -226,7 +231,7 @@ class Controls:
# under 7% of space free no enable allowed # under 7% of space free no enable allowed
self.events.add(EventName.outOfSpace) self.events.add(EventName.outOfSpace)
# TODO: make tici threshold the same # TODO: make tici threshold the same
if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65) and not SIMULATION: if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION:
self.events.add(EventName.lowMemory) self.events.add(EventName.lowMemory)
# TODO: enable this once loggerd CPU usage is more reasonable # TODO: enable this once loggerd CPU usage is more reasonable
@ -235,7 +240,7 @@ class Controls:
# self.events.add(EventName.highCpuUsage) # self.events.add(EventName.highCpuUsage)
# Alert if fan isn't spinning for 5 seconds # Alert if fan isn't spinning for 5 seconds
if self.sm['peripheralState'].pandaType in (PandaType.uno, PandaType.dos): if self.sm['peripheralState'].pandaType == PandaType.dos:
if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50: if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50:
if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0: if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0:
self.events.add(EventName.fanMalfunction) self.events.add(EventName.fanMalfunction)
@ -265,11 +270,6 @@ class Controls:
LaneChangeState.laneChangeFinishing): LaneChangeState.laneChangeFinishing):
self.events.add(EventName.laneChange) self.events.add(EventName.laneChange)
if CS.canTimeout:
self.events.add(EventName.canBusMissing)
elif not CS.canValid:
self.events.add(EventName.canError)
for i, pandaState in enumerate(self.sm['pandaStates']): for i, pandaState in enumerate(self.sm['pandaStates']):
# All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput
if i < len(self.CP.safetyConfigs): if i < len(self.CP.safetyConfigs):
@ -285,13 +285,29 @@ class Controls:
if log.PandaState.FaultType.relayMalfunction in pandaState.faults: if log.PandaState.FaultType.relayMalfunction in pandaState.faults:
self.events.add(EventName.relayMalfunction) self.events.add(EventName.relayMalfunction)
# Check for HW or system issues # Handle HW and system malfunctions
# Order is very intentional here. Be careful when modifying this.
num_events = len(self.events)
not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning}
if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES):
self.events.add(EventName.processNotRunning)
else:
if not SIMULATION and not self.rk.lagging:
if not self.sm.all_alive(self.camera_packets):
self.events.add(EventName.cameraMalfunction)
elif not self.sm.all_freq_ok(self.camera_packets):
self.events.add(EventName.cameraFrameRate)
if self.rk.lagging:
self.events.add(EventName.controlsdLagging)
if len(self.sm['radarState'].radarErrors): if len(self.sm['radarState'].radarErrors):
self.events.add(EventName.radarFault) self.events.add(EventName.radarFault)
elif not self.sm.valid["pandaStates"]: if not self.sm.valid['pandaStates']:
self.events.add(EventName.usbError) self.events.add(EventName.usbError)
elif not self.sm.all_checks() or self.can_rcv_error:
# generic catch-all. ideally, a more specific event should be added above instead
no_system_errors = len(self.events) != num_events
if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors and CS.canValid and not CS.canTimeout:
if not self.sm.all_alive(): if not self.sm.all_alive():
self.events.add(EventName.commIssue) self.events.add(EventName.commIssue)
elif not self.sm.all_freq_ok(): elif not self.sm.all_freq_ok():
@ -299,14 +315,17 @@ class Controls:
else: # invalid or can_rcv_error. else: # invalid or can_rcv_error.
self.events.add(EventName.commIssue) self.events.add(EventName.commIssue)
if not self.logged_comm_issue: logs = {
invalid = [s for s, valid in self.sm.valid.items() if not valid] 'invalid': [s for s, valid in self.sm.valid.items() if not valid],
not_alive = [s for s, alive in self.sm.alive.items() if not alive] 'not_alive': [s for s, alive in self.sm.alive.items() if not alive],
not_freq_ok = [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok] 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok],
cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive, not_freq_ok=not_freq_ok, can_error=self.can_rcv_error, error=True) 'can_error': self.can_rcv_error,
self.logged_comm_issue = True }
if logs != self.logged_comm_issue:
cloudlog.event("commIssue", error=True, **logs)
self.logged_comm_issue = logs
else: else:
self.logged_comm_issue = False self.logged_comm_issue = None
if not self.sm['liveParameters'].valid: if not self.sm['liveParameters'].valid:
self.events.add(EventName.vehicleModelInvalid) self.events.add(EventName.vehicleModelInvalid)
@ -353,21 +372,11 @@ class Controls:
# Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes
self.events.add(EventName.noGps) self.events.add(EventName.noGps)
if not self.sm.all_alive(self.camera_packets):
self.events.add(EventName.cameraMalfunction)
elif not self.sm.all_freq_ok(self.camera_packets):
self.events.add(EventName.cameraFrameRate)
if self.sm['modelV2'].frameDropPerc > 20: if self.sm['modelV2'].frameDropPerc > 20:
self.events.add(EventName.modeldLagging) self.events.add(EventName.modeldLagging)
if self.sm['liveLocationKalman'].excessiveResets: if self.sm['liveLocationKalman'].excessiveResets:
self.events.add(EventName.localizerMalfunction) self.events.add(EventName.localizerMalfunction)
# Check if all manager processes are running
not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning}
if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES):
self.events.add(EventName.processNotRunning)
# Only allow engagement with brake pressed when stopped behind another stopped car # Only allow engagement with brake pressed when stopped behind another stopped car
speeds = self.sm['longitudinalPlan'].speeds speeds = self.sm['longitudinalPlan'].speeds
if len(speeds) > 1: if len(speeds) > 1:
@ -557,15 +566,15 @@ class Controls:
# accel PID loop # accel PID loop
pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_kph * CV.KPH_TO_MS) pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_kph * CV.KPH_TO_MS)
t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL
actuators.accel = self.LoC.update(CC.longActive, CS, self.CP, long_plan, pid_accel_limits, t_since_plan) actuators.accel = self.LoC.update(CC.longActive, CS, long_plan, pid_accel_limits, t_since_plan)
# Steering PID loop and lateral MPC # Steering PID loop and lateral MPC
desired_curvature, desired_curvature_rate = get_lag_adjusted_curvature(self.CP, CS.vEgo, desired_curvature, desired_curvature_rate = get_lag_adjusted_curvature(self.CP, CS.vEgo,
lat_plan.psis, lat_plan.psis,
lat_plan.curvatures, lat_plan.curvatures,
lat_plan.curvatureRates) lat_plan.curvatureRates)
actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.CP, self.VM, actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, params,
params, self.last_actuators, desired_curvature, self.last_actuators, desired_curvature,
desired_curvature_rate, self.sm['liveLocationKalman']) desired_curvature_rate, self.sm['liveLocationKalman'])
else: else:
lac_log = log.ControlsState.LateralDebugState.new_message() lac_log = log.ControlsState.LateralDebugState.new_message()

@ -79,7 +79,7 @@ def update_v_cruise(v_cruise_kph, buttonEvents, button_timers, enabled, metric):
def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last): def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last):
for b in buttonEvents: for b in buttonEvents:
# 250kph or above probably means we never had a set speed # 250kph or above probably means we never had a set speed
if b.type in [car.CarState.ButtonEvent.Type.accelCruise, car.CarState.ButtonEvent.Type.resumeCruise] and v_cruise_last < 250: if b.type in (car.CarState.ButtonEvent.Type.accelCruise, car.CarState.ButtonEvent.Type.resumeCruise) and v_cruise_last < 250:
return v_cruise_last return v_cruise_last
return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX))) return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX)))

@ -695,6 +695,11 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = {
ET.NO_ENTRY: NoEntryAlert("Low Communication Rate between Processes"), ET.NO_ENTRY: NoEntryAlert("Low Communication Rate between Processes"),
}, },
EventName.controlsdLagging: {
ET.SOFT_DISABLE: soft_disable_alert("Controls Lagging"),
ET.NO_ENTRY: NoEntryAlert("Controls Process Lagging: Reboot Your Device"),
},
# Thrown when manager detects a service exited unexpectedly while driving # Thrown when manager detects a service exited unexpectedly while driving
EventName.processNotRunning: { EventName.processNotRunning: {
ET.NO_ENTRY: NoEntryAlert("System Malfunction: Reboot Your Device"), ET.NO_ENTRY: NoEntryAlert("System Malfunction: Reboot Your Device"),

@ -1,7 +1,7 @@
from abc import abstractmethod, ABC from abc import abstractmethod, ABC
from common.realtime import DT_CTRL
from common.numpy_fast import clip from common.numpy_fast import clip
from common.realtime import DT_CTRL
MIN_STEER_SPEED = 0.3 MIN_STEER_SPEED = 0.3
@ -16,7 +16,7 @@ class LatControl(ABC):
self.steer_max = 1.0 self.steer_max = 1.0
@abstractmethod @abstractmethod
def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk):
pass pass
def reset(self): def reset(self):

@ -7,7 +7,7 @@ STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees
class LatControlAngle(LatControl): class LatControlAngle(LatControl):
def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk):
angle_log = log.ControlsState.LateralAngleState.new_message() angle_log = log.ControlsState.LateralAngleState.new_message()
if CS.vEgo < MIN_STEER_SPEED or not active: if CS.vEgo < MIN_STEER_SPEED or not active:

@ -63,7 +63,7 @@ class LatControlINDI(LatControl):
self.steer_filter.x = 0. self.steer_filter.x = 0.
self.speed = 0. self.speed = 0.
def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk):
self.speed = CS.vEgo self.speed = CS.vEgo
# Update Kalman filter # Update Kalman filter
y = np.array([[math.radians(CS.steeringAngleDeg)], [math.radians(CS.steeringRateDeg)]]) y = np.array([[math.radians(CS.steeringAngleDeg)], [math.radians(CS.steeringRateDeg)]])

@ -1,23 +1,23 @@
import math import math
from selfdrive.controls.lib.pid import PIDController
from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
from cereal import log from cereal import log
from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
from selfdrive.controls.lib.pid import PIDController
class LatControlPID(LatControl): class LatControlPID(LatControl):
def __init__(self, CP, CI): def __init__(self, CP, CI):
super().__init__(CP, CI) super().__init__(CP, CI)
self.pid = PIDController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV), self.pid = PIDController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV),
(CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV), (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV),
k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, neg_limit=-1.0) k_f=CP.lateralTuning.pid.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max)
self.get_steer_feedforward = CI.get_steer_feedforward_function() self.get_steer_feedforward = CI.get_steer_feedforward_function()
def reset(self): def reset(self):
super().reset() super().reset()
self.pid.reset() self.pid.reset()
def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk):
pid_log = log.ControlsState.LateralPIDState.new_message() pid_log = log.ControlsState.LateralPIDState.new_message()
pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringAngleDeg = float(CS.steeringAngleDeg)
pid_log.steeringRateDeg = float(CS.steeringRateDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg)
@ -33,9 +33,6 @@ class LatControlPID(LatControl):
pid_log.active = False pid_log.active = False
self.pid.reset() self.pid.reset()
else: else:
self.pid.pos_limit = self.steer_max
self.pid.neg_limit = -self.steer_max
# offset does not contribute to resistive torque # offset does not contribute to resistive torque
steer_feedforward = self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo) steer_feedforward = self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo)

@ -1,9 +1,10 @@
import math import math
from selfdrive.controls.lib.pid import PIDController
from cereal import log
from common.numpy_fast import interp from common.numpy_fast import interp
from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
from selfdrive.controls.lib.pid import PIDController
from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
from cereal import log
# At higher speeds (25+mph) we can assume: # At higher speeds (25+mph) we can assume:
# Lateral acceleration achieved by a specific car correlates to # Lateral acceleration achieved by a specific car correlates to
@ -12,7 +13,7 @@ from cereal import log
# This controller applies torque to achieve desired lateral # This controller applies torque to achieve desired lateral
# accelerations. To compensate for the low speed effects we # accelerations. To compensate for the low speed effects we
# use a LOW_SPEED_FACTOR in the error. Additionally there is # use a LOW_SPEED_FACTOR in the error. Additionally, there is
# friction in the steering wheel that needs to be overcome to # friction in the steering wheel that needs to be overcome to
# move it at all, this is compensated for too. # move it at all, this is compensated for too.
@ -24,12 +25,10 @@ JERK_THRESHOLD = 0.2
class LatControlTorque(LatControl): class LatControlTorque(LatControl):
def __init__(self, CP, CI): def __init__(self, CP, CI):
super().__init__(CP, CI) super().__init__(CP, CI)
self.CP = CP
self.pid = PIDController(CP.lateralTuning.torque.kp, CP.lateralTuning.torque.ki, self.pid = PIDController(CP.lateralTuning.torque.kp, CP.lateralTuning.torque.ki,
k_f=CP.lateralTuning.torque.kf, pos_limit=1.0, neg_limit=-1.0) k_f=CP.lateralTuning.torque.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max)
self.get_steer_feedforward = CI.get_steer_feedforward_function() self.get_steer_feedforward = CI.get_steer_feedforward_function()
self.steer_max = 1.0
self.pid.pos_limit = self.steer_max
self.pid.neg_limit = -self.steer_max
self.use_steering_angle = CP.lateralTuning.torque.useSteeringAngle self.use_steering_angle = CP.lateralTuning.torque.useSteeringAngle
self.friction = CP.lateralTuning.torque.friction self.friction = CP.lateralTuning.torque.friction
@ -37,7 +36,7 @@ class LatControlTorque(LatControl):
super().reset() super().reset()
self.pid.reset() self.pid.reset()
def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk): def update(self, active, CS, VM, params, last_actuators, desired_curvature, desired_curvature_rate, llk):
pid_log = log.ControlsState.LateralTorqueState.new_message() pid_log = log.ControlsState.LateralTorqueState.new_message()
if CS.vEgo < MIN_STEER_SPEED or not active: if CS.vEgo < MIN_STEER_SPEED or not active:
@ -49,9 +48,9 @@ class LatControlTorque(LatControl):
actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll)
else: else:
actual_curvature = llk.angularVelocityCalibrated.value[2] / CS.vEgo actual_curvature = llk.angularVelocityCalibrated.value[2] / CS.vEgo
desired_lateral_accel = desired_curvature * CS.vEgo**2 desired_lateral_accel = desired_curvature * CS.vEgo ** 2
desired_lateral_jerk = desired_curvature_rate * CS.vEgo**2 desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2
actual_lateral_accel = actual_curvature * CS.vEgo**2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2
setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature
measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature
@ -61,7 +60,7 @@ class LatControlTorque(LatControl):
ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY
# convert friction into lateral accel units for feedforward # convert friction into lateral accel units for feedforward
friction_compensation = interp(desired_lateral_jerk, [-JERK_THRESHOLD, JERK_THRESHOLD], [-self.friction, self.friction]) friction_compensation = interp(desired_lateral_jerk, [-JERK_THRESHOLD, JERK_THRESHOLD], [-self.friction, self.friction])
ff += friction_compensation / CP.lateralTuning.torque.kf ff += friction_compensation / self.CP.lateralTuning.torque.kf
output_torque = self.pid.update(error, output_torque = self.pid.update(error,
override=CS.steeringPressed, feedforward=ff, override=CS.steeringPressed, feedforward=ff,
speed=CS.vEgo, speed=CS.vEgo,

@ -1,8 +1,8 @@
from cereal import car from cereal import car
from common.numpy_fast import clip, interp from common.numpy_fast import clip, interp
from common.realtime import DT_CTRL from common.realtime import DT_CTRL
from selfdrive.controls.lib.pid import PIDController
from selfdrive.controls.lib.drive_helpers import CONTROL_N from selfdrive.controls.lib.drive_helpers import CONTROL_N
from selfdrive.controls.lib.pid import PIDController
from selfdrive.modeld.constants import T_IDXS from selfdrive.modeld.constants import T_IDXS
LongCtrlState = car.CarControl.Actuators.LongControlState LongCtrlState = car.CarControl.Actuators.LongControlState
@ -50,12 +50,13 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target,
return long_control_state return long_control_state
class LongControl(): class LongControl:
def __init__(self, CP): def __init__(self, CP):
self.CP = CP
self.long_control_state = LongCtrlState.off # initialized to off self.long_control_state = LongCtrlState.off # initialized to off
self.pid = PIDController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV), self.pid = PIDController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV),
(CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV), (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV),
k_f = CP.longitudinalTuning.kf, rate=1 / DT_CTRL) k_f=CP.longitudinalTuning.kf, rate=1 / DT_CTRL)
self.v_pid = 0.0 self.v_pid = 0.0
self.last_output_accel = 0.0 self.last_output_accel = 0.0
@ -64,7 +65,7 @@ class LongControl():
self.pid.reset() self.pid.reset()
self.v_pid = v_pid self.v_pid = v_pid
def update(self, active, CS, CP, long_plan, accel_limits, t_since_plan): def update(self, active, CS, long_plan, accel_limits, t_since_plan):
"""Update longitudinal control. This updates the state machine and runs a PID loop""" """Update longitudinal control. This updates the state machine and runs a PID loop"""
# Interp control trajectory # Interp control trajectory
speeds = long_plan.speeds speeds = long_plan.speeds
@ -72,11 +73,11 @@ class LongControl():
v_target = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds) v_target = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds)
a_target = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels) a_target = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels)
v_target_lower = interp(CP.longitudinalActuatorDelayLowerBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) v_target_lower = interp(self.CP.longitudinalActuatorDelayLowerBound + t_since_plan, T_IDXS[:CONTROL_N], speeds)
a_target_lower = 2 * (v_target_lower - v_target) / CP.longitudinalActuatorDelayLowerBound - a_target a_target_lower = 2 * (v_target_lower - v_target) / self.CP.longitudinalActuatorDelayLowerBound - a_target
v_target_upper = interp(CP.longitudinalActuatorDelayUpperBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) v_target_upper = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan, T_IDXS[:CONTROL_N], speeds)
a_target_upper = 2 * (v_target_upper - v_target) / CP.longitudinalActuatorDelayUpperBound - a_target a_target_upper = 2 * (v_target_upper - v_target) / self.CP.longitudinalActuatorDelayUpperBound - a_target
a_target = min(a_target_lower, a_target_upper) a_target = min(a_target_lower, a_target_upper)
v_target_future = speeds[-1] v_target_future = speeds[-1]
@ -93,7 +94,7 @@ class LongControl():
# Update state machine # Update state machine
output_accel = self.last_output_accel output_accel = self.last_output_accel
self.long_control_state = long_control_state_trans(CP, active, self.long_control_state, CS.vEgo, self.long_control_state = long_control_state_trans(self.CP, active, self.long_control_state, CS.vEgo,
v_target, v_target_future, CS.brakePressed, v_target, v_target_future, CS.brakePressed,
CS.cruiseState.standstill) CS.cruiseState.standstill)
@ -107,8 +108,8 @@ class LongControl():
# Toyota starts braking more when it thinks you want to stop # Toyota starts braking more when it thinks you want to stop
# Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration
prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < self.v_pid prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < self.v_pid
deadzone = interp(CS.vEgo, CP.longitudinalTuning.deadzoneBP, CP.longitudinalTuning.deadzoneV) deadzone = interp(CS.vEgo, self.CP.longitudinalTuning.deadzoneBP, self.CP.longitudinalTuning.deadzoneV)
freeze_integrator = prevent_overshoot freeze_integrator = prevent_overshoot
error = self.v_pid - CS.vEgo error = self.v_pid - CS.vEgo
@ -121,8 +122,8 @@ class LongControl():
# Intention is to stop, switch to a different brake control until we stop # Intention is to stop, switch to a different brake control until we stop
elif self.long_control_state == LongCtrlState.stopping: elif self.long_control_state == LongCtrlState.stopping:
# Keep applying brakes until the car is stopped # Keep applying brakes until the car is stopped
if not CS.standstill or output_accel > CP.stopAccel: if not CS.standstill or output_accel > self.CP.stopAccel:
output_accel -= CP.stoppingDecelRate * DT_CTRL output_accel -= self.CP.stoppingDecelRate * DT_CTRL
output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) output_accel = clip(output_accel, accel_limits[0], accel_limits[1])
self.reset(CS.vEgo) self.reset(CS.vEgo)

@ -2,19 +2,28 @@
import unittest import unittest
import time import time
import math import math
from collections import OrderedDict from dataclasses import dataclass
from selfdrive.hardware import HARDWARE, TICI from selfdrive.hardware import HARDWARE, TICI
from selfdrive.hardware.tici.power_monitor import get_power from selfdrive.hardware.tici.power_monitor import get_power
from selfdrive.manager.process_config import managed_processes from selfdrive.manager.process_config import managed_processes
from selfdrive.manager.manager import manager_cleanup from selfdrive.manager.manager import manager_cleanup
POWER = OrderedDict(
camerad=2.58, @dataclass
modeld=0.90, class Proc:
dmonitoringmodeld=0.25, name: str
loggerd=0.45, power: float
) rtol: float = 0.05
atol: float = 0.1
warmup: float = 3.
PROCS = [
Proc('camerad', 2.5),
Proc('modeld', 0.95),
Proc('dmonitoringmodeld', 0.25),
Proc('loggerd', 0.45, warmup=10.),
]
class TestPowerDraw(unittest.TestCase): class TestPowerDraw(unittest.TestCase):
@ -36,24 +45,24 @@ class TestPowerDraw(unittest.TestCase):
prev = baseline prev = baseline
used = {} used = {}
for proc in POWER.keys(): for proc in PROCS:
managed_processes[proc].start() managed_processes[proc.name].start()
time.sleep(6) time.sleep(proc.warmup)
now = get_power(8) now = get_power(8)
used[proc] = now - prev used[proc.name] = now - prev
prev = now prev = now
manager_cleanup() manager_cleanup()
print("-"*35) print("-"*35)
print(f"Baseline {baseline:.2f}W\n") print(f"Baseline {baseline:.2f}W\n")
for proc in POWER.keys(): for proc in PROCS:
cur = used[proc] cur = used[proc.name]
expected = POWER[proc] expected = proc.power
print(f"{proc.ljust(20)} {expected:.2f}W {cur:.2f}W") print(f"{proc.name.ljust(20)} {expected:.2f}W {cur:.2f}W")
with self.subTest(proc=proc): with self.subTest(proc=proc.name):
self.assertTrue(math.isclose(cur, expected, rel_tol=0.10, abs_tol=0.1)) self.assertTrue(math.isclose(cur, expected, rel_tol=proc.rtol, abs_tol=proc.atol))
print("-"*35) print("-"*35)

@ -1 +1 @@
8d369bed132b691e1c000a726ab253ce7cbf8e09 d17ecea1f071007193a8a1e1ececf78c96b9deac

@ -33,8 +33,8 @@ original_segments = [
segments = [ segments = [
("BODY", "bd6a637565e91581|2022-04-04--22-05-08--0"), ("BODY", "bd6a637565e91581|2022-04-04--22-05-08--0"),
("HYUNDAI", "fakedata|2022-01-20--17-49-04--0"), ("HYUNDAI", "fakedata|2022-01-20--17-49-04--0"),
("TOYOTA", "fakedata|2022-04-13--18-53-16--0"), ("TOYOTA", "fakedata|2022-04-28--18-59-34--0"),
("TOYOTA2", "fakedata|2022-04-26--22-58-12--0"), ("TOYOTA2", "fakedata|2022-04-28--15-52-38--0"),
("TOYOTA3", "fakedata|2022-04-13--19-09-53--0"), ("TOYOTA3", "fakedata|2022-04-13--19-09-53--0"),
("HONDA", "fakedata|2022-01-20--17-56-40--0"), ("HONDA", "fakedata|2022-01-20--17-56-40--0"),
("HONDA2", "fakedata|2022-04-13--19-23-30--0"), ("HONDA2", "fakedata|2022-04-13--19-23-30--0"),

@ -23,10 +23,10 @@ from tools.lib.logreader import LogReader
PROCS = { PROCS = {
"selfdrive.controls.controlsd": 31.0, "selfdrive.controls.controlsd": 31.0,
"./loggerd": 70.0, "./loggerd": 70.0,
"./camerad": 41.0, "./camerad": 26.0,
"./locationd": 9.1, "./locationd": 9.1,
"selfdrive.controls.plannerd": 11.7, "selfdrive.controls.plannerd": 11.7,
"./_ui": 18.4, "./_ui": 21.0,
"selfdrive.locationd.paramsd": 9.0, "selfdrive.locationd.paramsd": 9.0,
"./_sensord": 6.17, "./_sensord": 6.17,
"selfdrive.controls.radard": 4.5, "selfdrive.controls.radard": 4.5,

@ -131,7 +131,7 @@ void MapWindow::timerUpdate() {
} }
} }
if (sm->updated("navRoute")) { if (sm->updated("navRoute") && (*sm)["navRoute"].getNavRoute().getCoordinates().size()) {
qWarning() << "Got new navRoute from navd. Opening map:" << allow_open; qWarning() << "Got new navRoute from navd. Opening map:" << allow_open;
// Only open the map on setting destination the first time // Only open the map on setting destination the first time

@ -18,18 +18,13 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) {
stacked_layout->setStackingMode(QStackedLayout::StackAll); stacked_layout->setStackingMode(QStackedLayout::StackAll);
main_layout->addLayout(stacked_layout); main_layout->addLayout(stacked_layout);
QStackedLayout *road_view_layout = new QStackedLayout;
road_view_layout->setStackingMode(QStackedLayout::StackAll);
nvg = new NvgWindow(VISION_STREAM_ROAD, this); nvg = new NvgWindow(VISION_STREAM_ROAD, this);
road_view_layout->addWidget(nvg);
hud = new OnroadHud(this);
road_view_layout->addWidget(hud);
QWidget * split_wrapper = new QWidget; QWidget * split_wrapper = new QWidget;
split = new QHBoxLayout(split_wrapper); split = new QHBoxLayout(split_wrapper);
split->setContentsMargins(0, 0, 0, 0); split->setContentsMargins(0, 0, 0, 0);
split->setSpacing(0); split->setSpacing(0);
split->addLayout(road_view_layout); split->addWidget(nvg);
stacked_layout->addWidget(split_wrapper); stacked_layout->addWidget(split_wrapper);
@ -57,7 +52,7 @@ void OnroadWindow::updateState(const UIState &s) {
alerts->updateAlert(alert, bgColor); alerts->updateAlert(alert, bgColor);
} }
hud->updateState(s); nvg->updateState(s);
if (bg != bgColor) { if (bg != bgColor) {
// repaint border // repaint border
@ -167,15 +162,14 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) {
} }
} }
// OnroadHud // NvgWindow
OnroadHud::OnroadHud(QWidget *parent) : QWidget(parent) {
NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraViewWidget("camerad", type, true, parent) {
engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size});
dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size}); dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size});
connect(this, &OnroadHud::valueChanged, [=] { update(); });
} }
void OnroadHud::updateState(const UIState &s) { void NvgWindow::updateState(const UIState &s) {
const int SET_SPEED_NA = 255; const int SET_SPEED_NA = 255;
const SubMaster &sm = *(s.sm); const SubMaster &sm = *(s.sm);
const auto cs = sm["controlsState"].getControlsState(); const auto cs = sm["controlsState"].getControlsState();
@ -202,9 +196,8 @@ void OnroadHud::updateState(const UIState &s) {
} }
} }
void OnroadHud::paintEvent(QPaintEvent *event) { void NvgWindow::drawHud(QPainter &p) {
QPainter p(this); p.save();
p.setRenderHint(QPainter::Antialiasing);
// Header gradient // Header gradient
QLinearGradient bg(0, header_h - (header_h / 2.5), 0, header_h); QLinearGradient bg(0, header_h - (header_h / 2.5), 0, header_h);
@ -246,9 +239,10 @@ void OnroadHud::paintEvent(QPaintEvent *event) {
drawIcon(p, radius / 2 + (bdr_s * 2), rect().bottom() - footer_h / 2, drawIcon(p, radius / 2 + (bdr_s * 2), rect().bottom() - footer_h / 2,
dm_img, QColor(0, 0, 0, 70), dmActive ? 1.0 : 0.2); dm_img, QColor(0, 0, 0, 70), dmActive ? 1.0 : 0.2);
} }
p.restore();
} }
void OnroadHud::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { void NvgWindow::drawText(QPainter &p, int x, int y, const QString &text, int alpha) {
QFontMetrics fm(p.font()); QFontMetrics fm(p.font());
QRect init_rect = fm.boundingRect(text); QRect init_rect = fm.boundingRect(text);
QRect real_rect = fm.boundingRect(init_rect, 0, text); QRect real_rect = fm.boundingRect(init_rect, 0, text);
@ -258,7 +252,7 @@ void OnroadHud::drawText(QPainter &p, int x, int y, const QString &text, int alp
p.drawText(real_rect.x(), real_rect.bottom(), text); p.drawText(real_rect.x(), real_rect.bottom(), text);
} }
void OnroadHud::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity) { void NvgWindow::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity) {
p.setPen(Qt::NoPen); p.setPen(Qt::NoPen);
p.setBrush(bg); p.setBrush(bg);
p.drawEllipse(x - radius / 2, y - radius / 2, radius, radius); p.drawEllipse(x - radius / 2, y - radius / 2, radius, radius);
@ -266,11 +260,6 @@ void OnroadHud::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, flo
p.drawPixmap(x - img_size / 2, y - img_size / 2, img); p.drawPixmap(x - img_size / 2, y - img_size / 2, img);
} }
// NvgWindow
NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraViewWidget("camerad", type, true, parent) {
}
void NvgWindow::initializeGL() { void NvgWindow::initializeGL() {
CameraViewWidget::initializeGL(); CameraViewWidget::initializeGL();
@ -377,11 +366,14 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV
void NvgWindow::paintGL() { void NvgWindow::paintGL() {
CameraViewWidget::paintGL(); CameraViewWidget::paintGL();
QPainter painter(this);
painter.setRenderHint(QPainter::Antialiasing);
painter.setPen(Qt::NoPen);
drawHud(painter);
UIState *s = uiState(); UIState *s = uiState();
if (s->worldObjectsVisible()) { if (s->worldObjectsVisible()) {
QPainter painter(this);
painter.setRenderHint(QPainter::Antialiasing);
painter.setPen(Qt::NoPen);
drawLaneLines(painter, s); drawLaneLines(painter, s);

@ -9,26 +9,40 @@
// ***** onroad widgets ***** // ***** onroad widgets *****
class OnroadAlerts : public QWidget {
Q_OBJECT
public:
OnroadAlerts(QWidget *parent = 0) : QWidget(parent) {};
void updateAlert(const Alert &a, const QColor &color);
class OnroadHud : public QWidget { protected:
void paintEvent(QPaintEvent*) override;
private:
QColor bg;
Alert alert = {};
};
// container window for the NVG UI
class NvgWindow : public CameraViewWidget {
Q_OBJECT Q_OBJECT
Q_PROPERTY(QString speed MEMBER speed NOTIFY valueChanged); Q_PROPERTY(QString speed MEMBER speed);
Q_PROPERTY(QString speedUnit MEMBER speedUnit NOTIFY valueChanged); Q_PROPERTY(QString speedUnit MEMBER speedUnit);
Q_PROPERTY(QString maxSpeed MEMBER maxSpeed NOTIFY valueChanged); Q_PROPERTY(QString maxSpeed MEMBER maxSpeed);
Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set NOTIFY valueChanged); Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set);
Q_PROPERTY(bool engageable MEMBER engageable NOTIFY valueChanged); Q_PROPERTY(bool engageable MEMBER engageable);
Q_PROPERTY(bool dmActive MEMBER dmActive NOTIFY valueChanged); Q_PROPERTY(bool dmActive MEMBER dmActive);
Q_PROPERTY(bool hideDM MEMBER hideDM NOTIFY valueChanged); Q_PROPERTY(bool hideDM MEMBER hideDM);
Q_PROPERTY(int status MEMBER status NOTIFY valueChanged); Q_PROPERTY(int status MEMBER status);
public: public:
explicit OnroadHud(QWidget *parent); explicit NvgWindow(VisionStreamType type, QWidget* parent = 0);
void updateState(const UIState &s); void updateState(const UIState &s);
private: private:
void drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity); void drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity);
void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255);
void paintEvent(QPaintEvent *event) override;
QPixmap engage_img; QPixmap engage_img;
QPixmap dm_img; QPixmap dm_img;
@ -43,32 +57,6 @@ private:
bool hideDM = false; bool hideDM = false;
int status = STATUS_DISENGAGED; int status = STATUS_DISENGAGED;
signals:
void valueChanged();
};
class OnroadAlerts : public QWidget {
Q_OBJECT
public:
OnroadAlerts(QWidget *parent = 0) : QWidget(parent) {};
void updateAlert(const Alert &a, const QColor &color);
protected:
void paintEvent(QPaintEvent*) override;
private:
QColor bg;
Alert alert = {};
};
// container window for the NVG UI
class NvgWindow : public CameraViewWidget {
Q_OBJECT
public:
explicit NvgWindow(VisionStreamType type, QWidget* parent = 0);
protected: protected:
void paintGL() override; void paintGL() override;
void initializeGL() override; void initializeGL() override;
@ -76,6 +64,7 @@ protected:
void updateFrameMat(int w, int h) override; void updateFrameMat(int w, int h) override;
void drawLaneLines(QPainter &painter, const UIState *s); void drawLaneLines(QPainter &painter, const UIState *s);
void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd); void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd);
void drawHud(QPainter &p);
inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); }
inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); } inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); }
@ -94,7 +83,6 @@ public:
private: private:
void paintEvent(QPaintEvent *event); void paintEvent(QPaintEvent *event);
void mousePressEvent(QMouseEvent* e) override; void mousePressEvent(QMouseEvent* e) override;
OnroadHud *hud;
OnroadAlerts *alerts; OnroadAlerts *alerts;
NvgWindow *nvg; NvgWindow *nvg;
QColor bg = bg_colors[STATUS_DISENGAGED]; QColor bg = bg_colors[STATUS_DISENGAGED];

@ -253,7 +253,6 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) {
stream_width = vipc_client->buffers[0].width; stream_width = vipc_client->buffers[0].width;
stream_height = vipc_client->buffers[0].height; stream_height = vipc_client->buffers[0].height;
glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
for (int i = 0; i < 3; ++i) { for (int i = 0; i < 3; ++i) {
glBindTexture(GL_TEXTURE_2D, textures[i]); glBindTexture(GL_TEXTURE_2D, textures[i]);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);

@ -8,7 +8,7 @@ from collections import defaultdict
from tools.lib.logreader import logreader_from_route_or_segment from tools.lib.logreader import logreader_from_route_or_segment
DEMO_ROUTE = "9f583b1d93915c31|2022-04-06--11-34-03" DEMO_ROUTE = "9f583b1d93915c31|2022-04-26--18-49-49"
SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd'] SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd']
# Retrive controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored # Retrive controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored
@ -32,6 +32,7 @@ def read_logs(lr):
data = defaultdict(lambda: defaultdict(lambda: defaultdict(list))) data = defaultdict(lambda: defaultdict(lambda: defaultdict(list)))
mono_to_frame = {} mono_to_frame = {}
frame_mismatches = [] frame_mismatches = []
frame_id_fails = 0
latest_sendcan_monotime = 0 latest_sendcan_monotime = 0
for msg in lr: for msg in lr:
if msg.which() == 'sendcan': if msg.which() == 'sendcan':
@ -56,6 +57,9 @@ def read_logs(lr):
frame_id = mono_to_frame[getattr(msg_obj, key)] frame_id = mono_to_frame[getattr(msg_obj, key)]
if continue_outer: if continue_outer:
continue continue
if frame_id == -1:
frame_id_fails += 1
continue
mono_to_frame[msg.logMonoTime] = frame_id mono_to_frame[msg.logMonoTime] = frame_id
data['timestamp'][frame_id][service].append((msg.which()+" published", msg.logMonoTime)) data['timestamp'][frame_id][service].append((msg.which()+" published", msg.logMonoTime))
@ -79,9 +83,7 @@ def read_logs(lr):
if msg_obj.frameIdExtra != frame_id: if msg_obj.frameIdExtra != frame_id:
frame_mismatches.append(frame_id) frame_mismatches.append(frame_id)
# Failed frameId fetches are stored in -1 assert frame_id_fails < 20, "Too many frameId fetch fails"
assert sum([len(data['timestamp'][-1][service]) for service in data['timestamp'][-1].keys()]) < 20, "Too many frameId fetch fails"
del data['timestamp'][-1]
assert len(frame_mismatches) < 20, "Too many frame mismatches" assert len(frame_mismatches) < 20, "Too many frame mismatches"
return (data, frame_mismatches) return (data, frame_mismatches)
@ -91,9 +93,20 @@ def find_frame_id(time, service, start_times, end_times):
if start_times[frame_id][service] <= time <= end_times[frame_id][service]: if start_times[frame_id][service] <= time <= end_times[frame_id][service]:
yield frame_id yield frame_id
def find_t0(start_times, frame_id=-1):
frame_id = frame_id if frame_id > -1 else min(start_times.keys())
m = max(start_times.keys())
while frame_id <= m:
for service in SERVICES:
if service in start_times[frame_id]:
return start_times[frame_id][service]
frame_id += 1
raise Exception('No start time has been set')
## ASSUMES THAT AT LEAST ONE CLOUDLOG IS MADE IN CONTROLSD ## ASSUMES THAT AT LEAST ONE CLOUDLOG IS MADE IN CONTROLSD
def insert_cloudlogs(lr, timestamps, start_times, end_times): def insert_cloudlogs(lr, timestamps, start_times, end_times):
t0 = start_times[min(start_times.keys())][SERVICES[0]] t0 = find_t0(start_times)
failed_inserts = 0 failed_inserts = 0
latest_controls_frameid = 0 latest_controls_frameid = 0
for msg in lr: for msg in lr:
@ -129,12 +142,13 @@ def insert_cloudlogs(lr, timestamps, start_times, end_times):
assert failed_inserts < len(timestamps), "Too many failed cloudlog inserts" assert failed_inserts < len(timestamps), "Too many failed cloudlog inserts"
def print_timestamps(timestamps, durations, start_times, relative): def print_timestamps(timestamps, durations, start_times, relative):
t0 = start_times[min(start_times.keys())][SERVICES[0]] t0 = find_t0(start_times)
for frame_id in timestamps.keys(): for frame_id in timestamps.keys():
print('='*80) print('='*80)
print("Frame ID:", frame_id) print("Frame ID:", frame_id)
if relative: if relative:
t0 = start_times[frame_id][SERVICES[0]] t0 = find_t0(start_times, frame_id)
for service in SERVICES: for service in SERVICES:
print(" "+service) print(" "+service)
events = timestamps[frame_id][service] events = timestamps[frame_id][service]
@ -144,10 +158,11 @@ def print_timestamps(timestamps, durations, start_times, relative):
print(" "+'%-53s%-53s' %(event, str(time*1000))) print(" "+'%-53s%-53s' %(event, str(time*1000)))
def graph_timestamps(timestamps, start_times, end_times, relative): def graph_timestamps(timestamps, start_times, end_times, relative):
t0 = start_times[min(start_times.keys())][SERVICES[0]] t0 = find_t0(start_times)
y0 = min(start_times.keys())
fig, ax = plt.subplots() fig, ax = plt.subplots()
ax.set_xlim(0, 150 if relative else 750) ax.set_xlim(0, 150 if relative else 750)
ax.set_ylim(0, 15) ax.set_ylim(y0, y0+15)
ax.set_xlabel('milliseconds') ax.set_xlabel('milliseconds')
ax.set_ylabel('Frame ID') ax.set_ylabel('Frame ID')
colors = ['blue', 'green', 'red', 'yellow', 'purple'] colors = ['blue', 'green', 'red', 'yellow', 'purple']
@ -156,7 +171,7 @@ def graph_timestamps(timestamps, start_times, end_times, relative):
points = {"x": [], "y": [], "labels": []} points = {"x": [], "y": [], "labels": []}
for frame_id, services in timestamps.items(): for frame_id, services in timestamps.items():
if relative: if relative:
t0 = start_times[frame_id][SERVICES[0]] t0 = find_t0(start_times, frame_id)
service_bars = [] service_bars = []
for service, events in services.items(): for service, events in services.items():
if start_times[frame_id][service] and end_times[frame_id][service]: if start_times[frame_id][service] and end_times[frame_id][service]:

@ -107,9 +107,9 @@ def logreader_from_route_or_segment(r, sort_by_time=False):
sn = SegmentName(r, allow_route_name=True) sn = SegmentName(r, allow_route_name=True)
route = Route(sn.route_name.canonical_name) route = Route(sn.route_name.canonical_name)
if sn.segment_num < 0: if sn.segment_num < 0:
return MultiLogIterator(route.log_paths(), sort_by_time) return MultiLogIterator(route.log_paths(), sort_by_time=sort_by_time)
else: else:
return LogReader(route.log_paths()[sn.segment_num], sort_by_time) return LogReader(route.log_paths()[sn.segment_num], sort_by_time=sort_by_time)
if __name__ == "__main__": if __name__ == "__main__":

@ -161,12 +161,12 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/liveLocationKalman/angularVelocityCalibrated/value/2</linkedSource> <linked_source>/liveLocationKalman/angularVelocityCalibrated/value/2</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/steeringPressed</v1> <v1>/carState/steeringPressed</v1>
<v2>/carControl/enabled</v2> <v2>/carControl/enabled</v2>
<v3>/liveLocationKalman/velocityCalibrated/value/0</v3> <v3>/liveLocationKalman/velocityCalibrated/value/0</v3>
</additionalSources> </additional_sources>
</snippet> </snippet>
<snippet name="engaged curvature vehicle model"> <snippet name="engaged curvature vehicle model">
<global>engage_delay = 5 <global>engage_delay = 5
@ -184,11 +184,11 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/controlsState/curvature</linkedSource> <linked_source>/controlsState/curvature</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/steeringPressed</v1> <v1>/carState/steeringPressed</v1>
<v2>/carControl/enabled</v2> <v2>/carControl/enabled</v2>
</additionalSources> </additional_sources>
</snippet> </snippet>
<snippet name="engaged curvature plan"> <snippet name="engaged curvature plan">
<global>engage_delay = 5 <global>engage_delay = 5
@ -206,11 +206,11 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/lateralPlan/curvatures/0</linkedSource> <linked_source>/lateralPlan/curvatures/0</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/steeringPressed</v1> <v1>/carState/steeringPressed</v1>
<v2>/carControl/enabled</v2> <v2>/carControl/enabled</v2>
</additionalSources> </additional_sources>
</snippet> </snippet>
<snippet name="engaged_accel_actual"> <snippet name="engaged_accel_actual">
<global>engage_delay = 5 <global>engage_delay = 5
@ -229,12 +229,12 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/carState/aEgo</linkedSource> <linked_source>/carState/aEgo</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/brakePressed</v1> <v1>/carState/brakePressed</v1>
<v2>/carState/gasPressed</v2> <v2>/carState/gasPressed</v2>
<v3>/carControl/enabled</v3> <v3>/carControl/enabled</v3>
</additionalSources> </additional_sources>
</snippet> </snippet>
<snippet name="engaged_accel_plan"> <snippet name="engaged_accel_plan">
<global>engage_delay = 5 <global>engage_delay = 5
@ -253,12 +253,12 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/longitudinalPlan/accels/0</linkedSource> <linked_source>/longitudinalPlan/accels/0</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/brakePressed</v1> <v1>/carState/brakePressed</v1>
<v2>/carState/gasPressed</v2> <v2>/carState/gasPressed</v2>
<v3>/carControl/enabled</v3> <v3>/carControl/enabled</v3>
</additionalSources> </additional_sources>
</snippet> </snippet>
<snippet name="engaged_accel_actuator"> <snippet name="engaged_accel_actuator">
<global>engage_delay = 5 <global>engage_delay = 5
@ -277,12 +277,12 @@ if (time > last_bad_time + engage_delay) then
else else
return 0 return 0
end</function> end</function>
<linkedSource>/carControl/actuators/accel</linkedSource> <linked_source>/carControl/actuators/accel</linked_source>
<additionalSources> <additional_sources>
<v1>/carState/brakePressed</v1> <v1>/carState/brakePressed</v1>
<v2>/carState/gasPressed</v2> <v2>/carState/gasPressed</v2>
<v3>/carControl/enabled</v3> <v3>/carControl/enabled</v3>
</additionalSources> </additional_sources>
</snippet> </snippet>
</customMathEquations> </customMathEquations>
<snippets/> <snippets/>

@ -17,7 +17,7 @@ try:
panda_jungle_imported = True panda_jungle_imported = True
from panda_jungle import PandaJungle # pylint: disable=import-error # type: ignore from panda_jungle import PandaJungle # pylint: disable=import-error # type: ignore
except ImportError: except ImportError:
PandaJugnle = None PandaJungle = None
panda_jungle_imported = False panda_jungle_imported = False
@ -86,7 +86,7 @@ def connect():
if __name__ == "__main__": if __name__ == "__main__":
if panda_jungle_imported: if not panda_jungle_imported:
print("\33[31m", "WARNING: cannot connect to jungles. Clone the jungle library to enable support:", "\033[0m") print("\33[31m", "WARNING: cannot connect to jungles. Clone the jungle library to enable support:", "\033[0m")
print("\033[34m", f"cd {BASEDIR} && git clone https://github.com/commaai/panda_jungle", "\033[0m") print("\033[34m", f"cd {BASEDIR} && git clone https://github.com/commaai/panda_jungle", "\033[0m")

@ -5,40 +5,52 @@ openpilot implements a [bridge](bridge.py) that allows it to run in the [CARLA s
## System Requirements ## System Requirements
openpilot doesn't have any extreme hardware requirements, however CARLA requires an NVIDIA graphics card and is very resource-intensive and may not run smoothly on your system. For this case, we have a low quality mode you can activate by running: openpilot doesn't have any extreme hardware requirements, however CARLA requires an NVIDIA graphics card and is very resource-intensive and may not run smoothly on your system.
``` For this case, we have a the simulator in low quality by default.
./start_openpilot_docker.sh --low_quality
```
You can also check out the [CARLA python documentation](https://carla.readthedocs.io/en/latest/python_api/) to find more parameters to tune that might increase performance on your system. You can also check out the [CARLA python documentation](https://carla.readthedocs.io/en/latest/python_api/) to find more parameters to tune that might increase performance on your system.
## Running the simulator ## Running the simulator
Start Carla simulator, openpilot and bridge processes located in tools/sim:
First, start the CARLA server in one terminal. ``` bash
``` # Terminal 1
./start_carla.sh ./start_carla.sh
# Terminal 2 - Run openpilot and bridge in one Docker:
./start_openpilot_docker.sh
# Running the latest local code execute
# Terminal 2:
./launch_openpilot.sh
# Terminal 3
./bridge.py
``` ```
Then, start the bridge and openpilot in another terminal. ### Bridge usage
_Same commands hold for start_openpilot_docker_
``` ```
./start_openpilot_docker.sh $ ./bridge.py -h
Usage: bridge.py [options]
Bridge between CARLA and openpilot.
Options:
-h, --help show this help message and exit
--joystick Use joystick input to control the car
--high_quality Set simulator to higher quality (requires good GPU)
--town TOWN Select map to drive in
--spawn_point NUM Number of the spawn point to start in
``` ```
To engage openpilot press 1 a few times while focused on bridge.py to increase the cruise speed. To engage openpilot press 1 a few times while focused on bridge.py to increase the cruise speed.
All inputs:
## Controls
| key | functionality |
You can control openpilot driving in the simulation with the following keys |:----:|:-----------------:|
| 1 | Cruise up 5 mph |
| key | functionality | | 2 | Cruise down 5 mph |
| :---: | :---------------: | | 3 | Cruise cancel |
| 1 | Cruise up 5 mph | | q | Exit all |
| 2 | Cruise down 5 mph | | wasd | Control manually |
| 3 | Cruise cancel |
| q | Exit all |
To see the options for changing the environment, such as the town, spawn point or precipitation, you can run `./start_openpilot_docker.sh --help`.
This will print the help output inside the docker container. You need to exit the docker container before running `./start_openpilot_docker.sh` again.
## Further Reading ## Further Reading

@ -32,11 +32,10 @@ STEER_RATIO = 15.
pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'sensorEvents', 'can', "gpsLocationExternal"]) pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'sensorEvents', 'can', "gpsLocationExternal"])
sm = messaging.SubMaster(['carControl', 'controlsState']) sm = messaging.SubMaster(['carControl', 'controlsState'])
def parse_args(add_args=None): def parse_args(add_args=None):
parser = argparse.ArgumentParser(description='Bridge between CARLA and openpilot.') parser = argparse.ArgumentParser(description='Bridge between CARLA and openpilot.')
parser.add_argument('--joystick', action='store_true') parser.add_argument('--joystick', action='store_true')
parser.add_argument('--low_quality', action='store_true') parser.add_argument('--high_quality', action='store_true')
parser.add_argument('--town', type=str, default='Town04_Opt') parser.add_argument('--town', type=str, default='Town04_Opt')
parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16) parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16)
@ -86,10 +85,9 @@ class Camerad:
# TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed
kernel_fn = os.path.join(BASEDIR, "selfdrive", "camerad", "transforms", "rgb_to_yuv.cl") kernel_fn = os.path.join(BASEDIR, "selfdrive", "camerad", "transforms", "rgb_to_yuv.cl")
self._kernel_file = open(kernel_fn) with open(kernel_fn) as f:
prg = cl.Program(self.ctx, f.read()).build(cl_arg)
prg = cl.Program(self.ctx, self._kernel_file.read()).build(cl_arg) self.krnl = prg.rgb_to_yuv
self.krnl = prg.rgb_to_yuv
self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4
self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4
@ -130,10 +128,6 @@ class Camerad:
setattr(dat, pub_type, msg) setattr(dat, pub_type, msg)
pm.send(pub_type, dat) pm.send(pub_type, dat)
def close(self):
self._kernel_file.close()
def imu_callback(imu, vehicle_state): def imu_callback(imu, vehicle_state):
vehicle_state.bearing_deg = math.degrees(imu.compass) vehicle_state.bearing_deg = math.degrees(imu.compass)
dat = messaging.new_message('sensorEvents', 2) dat = messaging.new_message('sensorEvents', 2)
@ -240,13 +234,13 @@ def can_function_runner(vs: VehicleState, exit_event: threading.Event):
def connect_carla_client(): def connect_carla_client():
client = carla.Client("127.0.0.1", 2000) client = carla.Client("127.0.0.1", 2000)
client.set_timeout(10) client.set_timeout(5)
return client return client
class CarlaBridge: class CarlaBridge:
def __init__(self, args): def __init__(self, arguments):
set_params_enabled() set_params_enabled()
msg = messaging.new_message('liveCalibration') msg = messaging.new_message('liveCalibration')
@ -254,32 +248,48 @@ class CarlaBridge:
msg.liveCalibration.rpyCalib = [0.0, 0.0, 0.0] msg.liveCalibration.rpyCalib = [0.0, 0.0, 0.0]
Params().put("CalibrationParams", msg.to_bytes()) Params().put("CalibrationParams", msg.to_bytes())
self._args = args self._args = arguments
self._carla_objects = [] self._carla_objects = []
self._camerad = None self._camerad = None
self._threads_exit_event = threading.Event() self._exit_event = threading.Event()
self._threads = [] self._threads = []
self._shutdown = False self._keep_alive = True
self.started = False self.started = False
signal.signal(signal.SIGTERM, self._on_shutdown) signal.signal(signal.SIGTERM, self._on_shutdown)
self._exit = threading.Event()
def _on_shutdown(self, signal, frame): def _on_shutdown(self, signal, frame):
self._shutdown = True self._keep_alive = False
def bridge_keep_alive(self, q: Queue, retries: int): def bridge_keep_alive(self, q: Queue, retries: int):
while not self._shutdown: try:
try: while self._keep_alive:
self._run(q) try:
break self._run(q)
except RuntimeError as e: break
if retries == 0: except RuntimeError as e:
raise self.close()
retries -= 1 if retries == 0:
print(f"Restarting bridge. Retries left {retries}. Error: {e} ") raise
# Reset for another try
self._carla_objects = []
self._threads = []
self._exit_event = threading.Event()
retries -= 1
if retries <= -1:
print(f"Restarting bridge. Error: {e} ")
else:
print(f"Restarting bridge. Retries left {retries}. Error: {e} ")
finally:
# Clean up resources in the opposite order they were created.
self.close()
def _run(self, q: Queue): def _run(self, q: Queue):
client = connect_carla_client() client = connect_carla_client()
world = client.load_world(self._args.town) world = client.load_world(self._args.town)
settings = world.get_settings() settings = world.get_settings()
settings.synchronous_mode = True # Enables synchronous mode settings.synchronous_mode = True # Enables synchronous mode
settings.fixed_delta_seconds = 0.05 settings.fixed_delta_seconds = 0.05
@ -287,7 +297,7 @@ class CarlaBridge:
world.set_weather(carla.WeatherParameters.ClearSunset) world.set_weather(carla.WeatherParameters.ClearSunset)
if self._args.low_quality: if not self._args.high_quality:
world.unload_map_layer(carla.MapLayer.Foliage) world.unload_map_layer(carla.MapLayer.Foliage)
world.unload_map_layer(carla.MapLayer.Buildings) world.unload_map_layer(carla.MapLayer.Buildings)
world.unload_map_layer(carla.MapLayer.ParkedVehicles) world.unload_map_layer(carla.MapLayer.ParkedVehicles)
@ -324,7 +334,7 @@ class CarlaBridge:
blueprint.set_attribute('image_size_x', str(W)) blueprint.set_attribute('image_size_x', str(W))
blueprint.set_attribute('image_size_y', str(H)) blueprint.set_attribute('image_size_y', str(H))
blueprint.set_attribute('fov', str(fov)) blueprint.set_attribute('fov', str(fov))
if self._args.low_quality: if not self._args.high_quality:
blueprint.set_attribute('enable_postprocess_effects', 'False') blueprint.set_attribute('enable_postprocess_effects', 'False')
camera = world.spawn_actor(blueprint, transform, attach_to=vehicle) camera = world.spawn_actor(blueprint, transform, attach_to=vehicle)
camera.listen(callback) camera.listen(callback)
@ -332,7 +342,7 @@ class CarlaBridge:
self._camerad = Camerad() self._camerad = Camerad()
road_camera = create_camera(fov=40, callback=self._camerad.cam_callback_road) road_camera = create_camera(fov=40, callback=self._camerad.cam_callback_road)
road_wide_camera = create_camera(fov=163, callback=self._camerad.cam_callback_wide_road) # fov bigger than 163 shows unwanted artifacts road_wide_camera = create_camera(fov=120, callback=self._camerad.cam_callback_wide_road) # fov bigger than 120 shows unwanted artifacts
self._carla_objects.extend([road_camera, road_wide_camera]) self._carla_objects.extend([road_camera, road_wide_camera])
@ -349,16 +359,13 @@ class CarlaBridge:
self._carla_objects.extend([imu, gps]) self._carla_objects.extend([imu, gps])
# launch fake car threads # launch fake car threads
self._threads.append(threading.Thread(target=panda_state_function, args=(vehicle_state, self._threads_exit_event,))) self._threads.append(threading.Thread(target=panda_state_function, args=(vehicle_state, self._exit_event,)))
self._threads.append(threading.Thread(target=peripheral_state_function, args=(self._threads_exit_event,))) self._threads.append(threading.Thread(target=peripheral_state_function, args=(self._exit_event,)))
self._threads.append(threading.Thread(target=fake_driver_monitoring, args=(self._threads_exit_event,))) self._threads.append(threading.Thread(target=fake_driver_monitoring, args=(self._exit_event,)))
self._threads.append(threading.Thread(target=can_function_runner, args=(vehicle_state, self._threads_exit_event,))) self._threads.append(threading.Thread(target=can_function_runner, args=(vehicle_state, self._exit_event,)))
for t in self._threads: for t in self._threads:
t.start() t.start()
# can loop
rk = Ratekeeper(100, print_delay_threshold=0.05)
# init # init
throttle_ease_out_counter = REPEAT_COUNTER throttle_ease_out_counter = REPEAT_COUNTER
brake_ease_out_counter = REPEAT_COUNTER brake_ease_out_counter = REPEAT_COUNTER
@ -376,7 +383,14 @@ class CarlaBridge:
brake_manual_multiplier = 0.7 # keyboard signal is always 1 brake_manual_multiplier = 0.7 # keyboard signal is always 1
steer_manual_multiplier = 45 * STEER_RATIO # keyboard signal is always 1 steer_manual_multiplier = 45 * STEER_RATIO # keyboard signal is always 1
while not self._shutdown: # Simulation tends to be slow in the initial steps. This prevents lagging later
for _ in range(20):
world.tick()
# loop
rk = Ratekeeper(100, print_delay_threshold=0.05)
while self._keep_alive:
# 1. Read the throttle, steer and brake from op or manual controls # 1. Read the throttle, steer and brake from op or manual controls
# 2. Set instructions in Carla # 2. Set instructions in Carla
# 3. Send current carstate to op via can # 3. Send current carstate to op via can
@ -495,13 +509,9 @@ class CarlaBridge:
rk.keep_time() rk.keep_time()
self.started = True self.started = True
# Clean up resources in the opposite order they were created.
self.close()
def close(self): def close(self):
self._threads_exit_event.set() self.started = False
if self._camerad is not None: self._exit_event.set()
self._camerad.close()
for s in self._carla_objects: for s in self._carla_objects:
try: try:
s.destroy() s.destroy()

@ -38,7 +38,7 @@ def getch() -> str:
def keyboard_poll_thread(q: 'Queue[str]'): def keyboard_poll_thread(q: 'Queue[str]'):
while True: while True:
c = getch() c = getch()
# print("got %s" % c) print("got %s" % c)
if c == '1': if c == '1':
q.put("cruise_up") q.put("cruise_up")
elif c == '2': elif c == '2':

@ -25,4 +25,4 @@ docker run \
-v /tmp/.X11-unix:/tmp/.X11-unix:rw \ -v /tmp/.X11-unix:/tmp/.X11-unix:rw \
-it \ -it \
carlasim/carla:0.9.12 \ carlasim/carla:0.9.12 \
/bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=High /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=Low

@ -15,27 +15,18 @@ class TestCarlaIntegration(unittest.TestCase):
Tests need Carla simulator to run Tests need Carla simulator to run
""" """
processes = None processes = None
carla_process = None
def setUp(self): def setUp(self):
self.processes = [] self.processes = []
# We want to make sure that carla_sim docker is still running. Skip output shell # We want to make sure that carla_sim docker isn't still running.
subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False) subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False)
self.processes.append(subprocess.Popen(".././start_carla.sh")) self.carla_process = subprocess.Popen(".././start_carla.sh")
# Too many lagging messages in bridge.py can cause a crash. This prevents it. # Too many lagging messages in bridge.py can cause a crash. This prevents it.
unblock_stdout() unblock_stdout()
# Wait 10 seconds to startup carla
def test_run_bridge(self): time.sleep(10)
# Test bridge connect with carla and runs without any errors for 60 seconds
test_duration = 60
carla_bridge = CarlaBridge(bridge.parse_args(['--low_quality']))
p = carla_bridge.run(Queue(), retries=3)
self.processes = [p]
time.sleep(test_duration)
self.assertEqual(p.exitcode, None, f"Bridge process should be running, but exited with code {p.exitcode}")
def test_engage(self): def test_engage(self):
# Startup manager and bridge.py. Check processes are running, then engage and verify. # Startup manager and bridge.py. Check processes are running, then engage and verify.
@ -44,7 +35,7 @@ class TestCarlaIntegration(unittest.TestCase):
sm = messaging.SubMaster(['controlsState', 'carEvents', 'managerState']) sm = messaging.SubMaster(['controlsState', 'carEvents', 'managerState'])
q = Queue() q = Queue()
carla_bridge = CarlaBridge(bridge.parse_args(['--low_quality'])) carla_bridge = CarlaBridge(bridge.parse_args([]))
p_bridge = carla_bridge.run(q, retries=3) p_bridge = carla_bridge.run(q, retries=3)
self.processes.append(p_bridge) self.processes.append(p_bridge)
@ -70,7 +61,7 @@ class TestCarlaIntegration(unittest.TestCase):
no_car_events_issues_once = True no_car_events_issues_once = True
break break
self.assertTrue(no_car_events_issues_once, f"Failed because sm offline, or CarEvents '{car_event_issues}' or processes not running '{not_running}'") self.assertTrue(no_car_events_issues_once, f"Failed because no messages received, or CarEvents '{car_event_issues}' or processes not running '{not_running}'")
start_time = time.monotonic() start_time = time.monotonic()
min_counts_control_active = 100 min_counts_control_active = 100
@ -99,8 +90,11 @@ class TestCarlaIntegration(unittest.TestCase):
p.wait(15) p.wait(15)
else: else:
p.join(15) p.join(15)
subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False)
# Stop carla simulator by removing docker container
subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False)
if self.carla_process is not None:
self.carla_process.wait()
if __name__ == "__main__": if __name__ == "__main__":

Loading…
Cancel
Save