diff --git a/Jenkinsfile b/Jenkinsfile
index 0d624954ea..696446c65f 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -111,7 +111,7 @@ pipeline {
R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}"
}
steps {
- phone_steps("tici", [
+ phone_steps("tici-needs-can", [
["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR EXTRA_FILES='tools/' ./build_devel.sh"],
["build openpilot", "cd selfdrive/manager && ./build.py"],
["check dirty", "release/check-dirty.sh"],
@@ -122,16 +122,24 @@ pipeline {
}
}
+ stage('loopback-tests') {
+ agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
+ steps {
+ phone_steps("tici-loopback", [
+ ["build openpilot", "cd selfdrive/manager && ./build.py"],
+ ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"],
+ ])
+ }
+ }
+
stage('HW + Unit Tests') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
- phone_steps("tici2", [
+ phone_steps("tici-common", [
["build", "cd selfdrive/manager && ./build.py"],
["test power draw", "python system/hardware/tici/test_power_draw.py"],
- ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"],
["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"],
["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"],
- ["test sensord", "python selfdrive/sensord/tests/test_sensord.py"],
["test pigeond", "python selfdrive/sensord/tests/test_pigeond.py"],
])
}
@@ -159,27 +167,32 @@ pipeline {
}
}
- stage('sensord (LSM-C)') {
+ stage('sensord') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici-lsmc", [
["build", "cd selfdrive/manager && ./build.py"],
["test sensord", "cd selfdrive/sensord/tests && python -m unittest test_sensord.py"],
])
+ phone_steps("tici-bmx-lsm", [
+ ["build", "cd selfdrive/manager && ./build.py"],
+ ["test sensord", "cd selfdrive/sensord/tests && python -m unittest test_sensord.py"],
+ ])
}
}
stage('replay') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
- phone_steps("tici3", [
+ phone_steps("tici-common", [
["build", "cd selfdrive/manager && ./build.py"],
["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"],
])
}
}
- }
+ }
}
+
}
}
diff --git a/RELEASES.md b/RELEASES.md
index 18817bda4d..bf89b667fa 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,19 +1,20 @@
-Version 0.8.17 (2022-11-XX)
+Version 0.8.17 (2022-11-21)
========================
* New driving model
- * Internal feature space information content increased tenfold during training (to ~700 bits), this makes the model dramatically more accurate
+ * Internal feature space information content increased tenfold during training (to ~700 bits), which makes the model dramatically more accurate
* Less reliance on previous frames makes model more reactive and snappy
* Trained in new reprojective simulator
- * Model trained in openpilot was trained in 36hrs from scratch, compared to around 1 week of previous releases
- * Model training now simulates lateral and longitudinal behavior, this allows openpilot to slow down for turns, stop at traffic lights, etc,... in experimental mode
-* New driver monitoring model
- * New end-to-end distracted trigger
+ * Trained in 36hrs from scratch, compared to one week for previous releases
+ * Training now simulates both lateral and longitudinal behavior, which allows openpilot to slow down for turns, stop at traffic lights, and more in experimental mode
+* Driver monitoring updates
+ * New bigger model with added end-to-end distracted trigger
+ * Reduced false positives during driver calibration
* Experimental driving mode
* End-to-end longitudinal control
- * Stops for red lights and stop signs
+ * Stops for traffic lights and stop signs
+ * Slows down for turns
* openpilot defaults to chill mode, enable experimental in settings
-* Self-tuning torque lateral controller parameters
- * Parameters learned live for each car
+* Self-tuning torque controller: learns parameters live for each car
* Torque controller used on all Toyota, Lexus, Hyundai, Kia, and Genesis models
* UI updates
* Multi-language in navigation
@@ -21,8 +22,10 @@ Version 0.8.17 (2022-11-XX)
* Improved update experience
* Border turns grey while overriding steering
* Bookmark events while driving; view them in comma connect
+ * New onroad visualization for experimental mode
* AGNOS 6
* tools: new and improved cabana thanks to deanlee!
+* Experimental longitudinal support for Volkswagen, CAN-FD Hyundai, and new GM models
* Genesis GV70 2022-23 support thanks to zunichky and sunnyhaibin!
* Hyundai Santa Cruz 2021-22 support thanks to sunnyhaibin!
* Kia Sportage 2023 support thanks to sunnyhaibin!
diff --git a/cereal b/cereal
index cdba1aafec..afafa0a2a5 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit cdba1aafec5e36505ef6ace675568e1f15003c47
+Subproject commit afafa0a2a537d775842ab2e1bf20cb9a33b34f9a
diff --git a/docs/CARS.md b/docs/CARS.md
index 8c2dc9bff4..0b2b7d9d36 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -107,7 +107,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Kia|Sportage 2023|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
|Kia|Sportage Hybrid 2023|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Kia|Telluride 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
+|Kia|Telluride 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Lexus|ES Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
@@ -150,7 +150,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,8](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,8](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,8](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[9](#footnotes)|
-|Škoda|Superb 2015-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,8](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
+|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,8](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
diff --git a/launch_env.sh b/launch_env.sh
index 88e1f2a9c5..3059ec268e 100755
--- a/launch_env.sh
+++ b/launch_env.sh
@@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1
export VECLIB_MAXIMUM_THREADS=1
if [ -z "$AGNOS_VERSION" ]; then
- export AGNOS_VERSION="6.1"
+ export AGNOS_VERSION="6.2"
fi
if [ -z "$PASSIVE" ]; then
diff --git a/release/files_common b/release/files_common
index 26662f1ef1..a294e1e5b5 100644
--- a/release/files_common
+++ b/release/files_common
@@ -95,6 +95,7 @@ selfdrive/boardd/panda_comms.h
selfdrive/boardd/panda_comms.cc
selfdrive/boardd/set_time.py
selfdrive/boardd/pandad.py
+selfdrive/boardd/tests/test_boardd_loopback.py
selfdrive/car/__init__.py
selfdrive/car/docs_definitions.py
diff --git a/selfdrive/boardd/panda_comms.h b/selfdrive/boardd/panda_comms.h
index 08d0c1a2af..f42eadc5b2 100644
--- a/selfdrive/boardd/panda_comms.h
+++ b/selfdrive/boardd/panda_comms.h
@@ -5,11 +5,16 @@
#include
#include
+#include
+
#include
+
#define TIMEOUT 0
#define SPI_BUF_SIZE 1024
+const bool PANDA_NO_RETRY = getenv("PANDA_NO_RETRY");
+
// comms base class
class PandaCommsHandle {
@@ -29,7 +34,7 @@ public:
virtual int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0;
protected:
- std::mutex hw_lock;
+ std::recursive_mutex hw_lock;
};
class PandaUsbHandle : public PandaCommsHandle {
@@ -65,9 +70,11 @@ public:
private:
int spi_fd = -1;
- int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len);
- int wait_for_ack();
-
uint8_t tx_buf[SPI_BUF_SIZE];
uint8_t rx_buf[SPI_BUF_SIZE];
+
+ int wait_for_ack(spi_ioc_transfer &transfer, uint8_t ack);
+ int bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len);
+ int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len);
+ int spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len);
};
diff --git a/selfdrive/boardd/spi.cc b/selfdrive/boardd/spi.cc
index 1ec5e89c71..2803f58db0 100644
--- a/selfdrive/boardd/spi.cc
+++ b/selfdrive/boardd/spi.cc
@@ -2,10 +2,12 @@
#include
#include
+#include
#include
#include "common/util.h"
#include "common/swaglog.h"
+#include "panda/board/comms_definitions.h"
#include "selfdrive/boardd/panda_comms.h"
@@ -22,13 +24,6 @@ struct __attribute__((packed)) spi_header {
uint16_t max_rx_len;
};
-struct __attribute__((packed)) spi_control_packet {
- uint16_t request;
- uint16_t param1;
- uint16_t param2;
- uint16_t length;
-};
-
PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) {
LOGD("opening SPI panda: %s", serial.c_str());
@@ -40,7 +35,7 @@ PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) {
spi_fd = open(serial.c_str(), O_RDWR);
if (spi_fd < 0) {
- LOGE("failed setting SPI mode %d", err);
+ LOGE("failed opening SPI device %d", err);
goto fail;
}
@@ -85,51 +80,65 @@ void PandaSpiHandle::cleanup() {
int PandaSpiHandle::control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout) {
- int err;
-
- std::lock_guard lk(hw_lock);
- do {
- spi_control_packet packet = {
- .request = request,
- .param1 = param1,
- .param2 = param2,
- .length = 0
- };
-
- // TODO: handle error
- err = spi_transfer(0, (uint8_t *) &packet, sizeof(packet), NULL, 0);
- } while (err < 0 && connected);
-
- return err;
+ ControlPacket_t packet = {
+ .request = request,
+ .param1 = param1,
+ .param2 = param2,
+ .length = 0
+ };
+ return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), NULL, 0);
}
int PandaSpiHandle::control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout) {
- int err;
+ ControlPacket_t packet = {
+ .request = request,
+ .param1 = param1,
+ .param2 = param2,
+ .length = length
+ };
+ return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), data, length);
+}
+
+int PandaSpiHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
+ return bulk_transfer(endpoint, data, length, NULL, 0);
+}
+int PandaSpiHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
+ return bulk_transfer(endpoint, NULL, 0, data, length);
+}
+int PandaSpiHandle::bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len) {
std::lock_guard lk(hw_lock);
- do {
- spi_control_packet packet = {
- .request = request,
- .param1 = param1,
- .param2 = param2,
- .length = length
- };
- // TODO: handle error
- err = spi_transfer(0, (uint8_t *) &packet, sizeof(packet), data, length);
- } while (err < 0 && connected);
+ const int xfer_size = 0x40;
+
+ int ret = 0;
+ uint16_t length = (tx_data != NULL) ? tx_len : rx_len;
+ for (int i = 0; i < (int)std::ceil((float)length / xfer_size); i++) {
+ int d;
+ if (tx_data != NULL) {
+ int len = std::min(xfer_size, tx_len - (xfer_size * i));
+ d = spi_transfer_retry(endpoint, tx_data + (xfer_size * i), len, NULL, 0);
+ } else {
+ d = spi_transfer_retry(endpoint, NULL, 0, rx_data + (xfer_size * i), xfer_size);
+ }
- return err;
-}
+ if (d < 0) {
+ LOGE("SPI: bulk transfer failed with %d", d);
+ comms_healthy = false;
+ return -1;
+ }
-int PandaSpiHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
- return 0;
-}
+ ret += d;
+ if ((rx_data != NULL) && d < xfer_size) {
+ break;
+ }
+ }
-int PandaSpiHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
- return 0;
+ return ret;
}
+
+
std::vector PandaSpiHandle::list() {
// TODO: list all pandas available over SPI
return {};
@@ -144,6 +153,46 @@ void add_checksum(uint8_t *data, int data_len) {
}
}
+bool check_checksum(uint8_t *data, int data_len) {
+ uint8_t checksum = SPI_CHECKSUM_START;
+ for (uint16_t i = 0U; i < data_len; i++) {
+ checksum ^= data[i];
+ }
+ return checksum == 0U;
+}
+
+
+int PandaSpiHandle::spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len) {
+ int ret;
+
+ std::lock_guard lk(hw_lock);
+ do {
+ // TODO: handle error
+ ret = spi_transfer(endpoint, tx_data, tx_len, rx_data, max_rx_len);
+ } while (ret < 0 && connected && !PANDA_NO_RETRY);
+
+ return ret;
+}
+
+int PandaSpiHandle::wait_for_ack(spi_ioc_transfer &transfer, uint8_t ack) {
+ // TODO: add timeout?
+ while (true) {
+ int ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
+ if (ret < 0) {
+ LOGE("SPI: failed to send ACK request");
+ return ret;
+ }
+
+ if (rx_buf[0] == ack) {
+ break;
+ } else if (rx_buf[0] == SPI_NACK) {
+ LOGW("SPI: got NACK");
+ return -1;
+ }
+ }
+
+ return 0;
+}
int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len) {
int ret;
@@ -178,19 +227,9 @@ int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx
// Wait for (N)ACK
tx_buf[0] = 0x12;
transfer.len = 1;
- while (true) {
- ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
- if (ret < 0) {
- LOGE("SPI: failed to send ACK request");
- goto transfer_fail;
- }
-
- if (rx_buf[0] == SPI_HACK) {
- break;
- } else if (rx_buf[0] == SPI_NACK) {
- LOGW("SPI: got header NACK");
- goto transfer_fail;
- }
+ ret = wait_for_ack(transfer, SPI_HACK);
+ if (ret < 0) {
+ goto transfer_fail;
}
// Send data
@@ -208,44 +247,40 @@ int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx
// Wait for (N)ACK
tx_buf[0] = 0xab;
transfer.len = 1;
- while (true) {
- ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
- if (ret < 0) {
- LOGE("SPI: failed to send ACK request");
- goto transfer_fail;
- }
-
- if (rx_buf[0] == SPI_DACK) {
- break;
- } else if (rx_buf[0] == SPI_NACK) {
- LOGE("SPI: got data NACK");
- goto transfer_fail;
- }
+ ret = wait_for_ack(transfer, SPI_DACK);
+ if (ret < 0) {
+ goto transfer_fail;
}
// Read data len
transfer.len = 2;
+ transfer.rx_buf = (uint64_t)(rx_buf + 1);
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to read rx data len");
goto transfer_fail;
}
- rx_data_len = *(uint16_t *)rx_buf;
+ rx_data_len = *(uint16_t *)(rx_buf+1);
assert(rx_data_len < SPI_BUF_SIZE);
// Read data
transfer.len = rx_data_len + 1;
+ transfer.rx_buf = (uint64_t)(rx_buf + 2 + 1);
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to read rx data");
goto transfer_fail;
}
- // TODO: check checksum
+ if (!check_checksum(rx_buf, rx_data_len + 4)) {
+ LOGE("SPI: bad checksum");
+ goto transfer_fail;
+ }
if (rx_data != NULL) {
- memcpy(rx_data, rx_buf, rx_data_len);
+ memcpy(rx_data, rx_buf + 3, rx_data_len);
}
- ret = rx_data_len;
+
+ return rx_data_len;
transfer_fail:
return ret;
diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py
index f4b3f88e99..df1b4b2866 100644
--- a/selfdrive/car/gm/carstate.py
+++ b/selfdrive/car/gm/carstate.py
@@ -63,7 +63,7 @@ class CarState(CarStateBase):
# Regen braking is braking
if self.CP.transmissionType == TransmissionType.direct:
- ret.brakePressed = ret.brakePressed or pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0
+ ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0
ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254.
ret.gasPressed = ret.gas > 1e-5
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index 2420098b4a..eb5ab7329a 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -211,17 +211,20 @@ class CarInterface(CarInterfaceBase):
ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback)
if self.CS.cruise_buttons != self.CS.prev_cruise_buttons and self.CS.prev_cruise_buttons != CruiseButtons.INIT:
- be = create_button_event(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS)
+ buttonEvents = [create_button_event(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS)]
+ # Handle ACCButtons changing buttons mid-press
+ if self.CS.cruise_buttons != CruiseButtons.UNPRESS and self.CS.prev_cruise_buttons != CruiseButtons.UNPRESS:
+ buttonEvents.append(create_button_event(CruiseButtons.UNPRESS, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS))
- # Suppress resume button if we're resuming from stop so we don't adjust speed.
- if be.type == ButtonType.accelCruise and (ret.cruiseState.enabled and ret.standstill):
- be.type = ButtonType.unknown
-
- ret.buttonEvents = [be]
+ ret.buttonEvents = buttonEvents
+ # The ECM allows enabling on falling edge of set, but only rising edge of resume
events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low,
GearShifter.eco, GearShifter.manumatic],
- pcm_enable=self.CP.pcmCruise)
+ pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,))
+ if not self.CP.pcmCruise:
+ if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents):
+ events.add(EventName.buttonEnable)
# Enabling at a standstill with brake is allowed
# TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index b7e28825c3..1dba3a5442 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -142,7 +142,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
],
CAR.PALISADE: [
HyundaiCarInfo("Hyundai Palisade 2020-22", "All", "https://youtu.be/TAnDqjF4fDY?t=456", harness=Harness.hyundai_h),
- HyundaiCarInfo("Kia Telluride 2020", "All", harness=Harness.hyundai_h),
+ HyundaiCarInfo("Kia Telluride 2020-22", "All", harness=Harness.hyundai_h),
],
CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e),
CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a),
diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py
index 982ba40b17..8e8872a539 100644
--- a/selfdrive/car/interfaces.py
+++ b/selfdrive/car/interfaces.py
@@ -250,8 +250,8 @@ class CarInterfaceBase(ABC):
# Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port)
if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed):
events.add(EventName.buttonEnable)
- # Disable on rising edge of cancel for both stock and OP long
- if b.type == ButtonType.cancel and b.pressed:
+ # Disable on rising and falling edge of cancel for both stock and OP long
+ if b.type == ButtonType.cancel:
events.add(EventName.buttonCancel)
# Handle permanent and temporary steering faults
diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py
index ee25b8205f..56530dd738 100755
--- a/selfdrive/car/tests/test_models.py
+++ b/selfdrive/car/tests/test_models.py
@@ -251,8 +251,8 @@ class TestCarModelBase(unittest.TestCase):
if CS.brakePressed and not self.safety.get_brake_pressed_prev():
if self.CP.carFingerprint in (HONDA.PILOT, HONDA.PASSPORT, HONDA.RIDGELINE) and CS.brake > 0.05:
brake_pressed = False
- safety_brake_pressed = self.safety.get_brake_pressed_prev() or self.safety.get_regen_braking_prev()
- checks['brakePressed'] += brake_pressed != safety_brake_pressed
+ checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev()
+ checks['regenBraking'] += CS.regenBraking != self.safety.get_regen_braking_prev()
if self.CP.pcmCruise:
# On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state.
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index babaffbcbe..cb2343e08f 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -233,7 +233,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
CAR.SKODA_KAROQ_MK1: VWCarInfo("Škoda Karoq 2019-21"),
CAR.SKODA_KODIAQ_MK1: VWCarInfo("Škoda Kodiaq 2018-19"),
CAR.SKODA_SCALA_MK1: VWCarInfo("Škoda Scala 2020", footnotes=[Footnote.VW_EXP_LONG, Footnote.VW_MQB_A0]),
- CAR.SKODA_SUPERB_MK3: VWCarInfo("Škoda Superb 2015-18"),
+ CAR.SKODA_SUPERB_MK3: VWCarInfo("Škoda Superb 2015-22"),
CAR.SKODA_OCTAVIA_MK3: [
VWCarInfo("Škoda Octavia 2015, 2018-19"),
VWCarInfo("Škoda Octavia RS 2016"),
@@ -1064,6 +1064,7 @@ FW_VERSIONS = {
},
CAR.SKODA_SUPERB_MK3: {
(Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704L906026ET\xf1\x891343',
b'\xf1\x8704L906026FP\xf1\x891196',
b'\xf1\x8704L906026KB\xf1\x894071',
b'\xf1\x8704L906026KD\xf1\x894798',
@@ -1074,9 +1075,11 @@ FW_VERSIONS = {
b'\xf1\x870CW300042H \xf1\x891601',
b'\xf1\x870D9300011T \xf1\x894801',
b'\xf1\x870D9300012 \xf1\x894940',
+ b'\xf1\x870D9300041H \xf1\x894905',
b'\xf1\x870GC300043 \xf1\x892301',
],
(Ecu.srs, 0x715, None): [
+ b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111',
b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111',
b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\022111200111121001121110012211292221111',
b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\02331310031313100313131013141319331413100',
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 0bdaadf6ef..f69e9e7fd1 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -16,8 +16,7 @@ from system.version import is_tested_branch, get_short_branch
from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can
from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET
-from selfdrive.controls.lib.drive_helpers import V_CRUISE_INITIAL, update_v_cruise, initialize_v_cruise
-from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature
+from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature
from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.longcontrol import LongControl
from selfdrive.controls.lib.latcontrol_pid import LatControlPID
@@ -49,7 +48,6 @@ Desire = log.LateralPlan.Desire
LaneChangeState = log.LateralPlan.LaneChangeState
LaneChangeDirection = log.LateralPlan.LaneChangeDirection
EventName = car.CarEvent.EventName
-ButtonEvent = car.CarState.ButtonEvent
ButtonType = car.CarState.ButtonEvent.Type
SafetyModel = car.CarParams.SafetyModel
@@ -173,9 +171,6 @@ class Controls:
self.active = False
self.can_rcv_timeout = False
self.soft_disable_timer = 0
- self.v_cruise_kph = V_CRUISE_INITIAL
- self.v_cruise_cluster_kph = V_CRUISE_INITIAL
- self.v_cruise_kph_last = 0
self.mismatch_counter = 0
self.cruise_mismatch_counter = 0
self.can_rcv_timeout_counter = 0
@@ -185,11 +180,11 @@ class Controls:
self.events_prev = []
self.current_alert_types = [ET.PERMANENT]
self.logged_comm_issue = None
- self.button_timers = {ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0}
self.last_actuators = car.CarControl.Actuators.new_message()
self.steer_limited = False
self.desired_curvature = 0.0
self.desired_curvature_rate = 0.0
+ self.v_cruise_helper = VCruiseHelper(self.CP)
# TODO: no longer necessary, aside from process replay
self.sm['liveParameters'].valid = True
@@ -219,7 +214,7 @@ class Controls:
controls_state = Params().get("ReplayControlsState")
if controls_state is not None:
controls_state = log.ControlsState.from_bytes(controls_state)
- self.v_cruise_kph = controls_state.vCruise
+ self.v_cruise_helper.v_cruise_kph = controls_state.vCruise
if any(ps.controlsAllowed for ps in self.sm['pandaStates']):
self.state = State.enabled
@@ -245,12 +240,13 @@ class Controls:
# Block resume if cruise never previously enabled
resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents)
- if not self.CP.pcmCruise and self.v_cruise_kph == V_CRUISE_INITIAL and resume_pressed:
+ if not self.CP.pcmCruise and not self.v_cruise_helper.v_cruise_initialized and resume_pressed:
self.events.add(EventName.resumeBlocked)
# Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0
if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \
- (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)):
+ (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \
+ (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)):
self.events.add(EventName.pedalPressed)
if CS.gasPressed:
@@ -477,20 +473,7 @@ class Controls:
def state_transition(self, CS):
"""Compute conditional state transitions and execute actions on state transitions"""
- self.v_cruise_kph_last = self.v_cruise_kph
-
- if CS.cruiseState.available:
- # if stock cruise is completely disabled, then we can use our own set speed logic
- if not self.CP.pcmCruise:
- self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.vEgo, CS.gasPressed, CS.buttonEvents,
- self.button_timers, self.enabled, self.is_metric)
- self.v_cruise_cluster_kph = self.v_cruise_kph
- else:
- self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH
- self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH
- else:
- self.v_cruise_kph = V_CRUISE_INITIAL
- self.v_cruise_cluster_kph = V_CRUISE_INITIAL
+ self.v_cruise_helper.update_v_cruise(CS, self.enabled, self.is_metric)
# decrement the soft disable timer at every step, as it's reset on
# entrance in SOFT_DISABLING state
@@ -568,9 +551,7 @@ class Controls:
else:
self.state = State.enabled
self.current_alert_types.append(ET.ENABLE)
- if not self.CP.pcmCruise:
- self.v_cruise_kph = initialize_v_cruise(CS.vEgo, CS.buttonEvents, self.v_cruise_kph_last)
- self.v_cruise_cluster_kph = self.v_cruise_kph
+ self.v_cruise_helper.initialize_v_cruise(CS)
# Check if openpilot is engaged and actuators are enabled
self.enabled = self.state in ENABLED_STATES
@@ -618,7 +599,7 @@ class Controls:
if not self.joystick_mode:
# 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_helper.v_cruise_kph * CV.KPH_TO_MS)
t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL
actuators.accel = self.LoC.update(CC.longActive, CS, long_plan, pid_accel_limits, t_since_plan)
@@ -682,16 +663,6 @@ class Controls:
return CC, lac_log
- def update_button_timers(self, buttonEvents):
- # increment timer for buttons still pressed
- for k in self.button_timers:
- if self.button_timers[k] > 0:
- self.button_timers[k] += 1
-
- for b in buttonEvents:
- if b.type.raw in self.button_timers:
- self.button_timers[b.type.raw] = 1 if b.pressed else 0
-
def publish_logs(self, CS, start_time, CC, lac_log):
"""Send actuators and hud commands to the car, send controlsstate and MPC logging"""
@@ -714,7 +685,7 @@ class Controls:
CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1
hudControl = CC.hudControl
- hudControl.setSpeed = float(self.v_cruise_cluster_kph * CV.KPH_TO_MS)
+ hudControl.setSpeed = float(self.v_cruise_helper.v_cruise_cluster_kph * CV.KPH_TO_MS)
hudControl.speedVisible = self.enabled
hudControl.lanesVisible = self.enabled
hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead
@@ -797,8 +768,8 @@ class Controls:
controlsState.engageable = not self.events.any(ET.NO_ENTRY)
controlsState.longControlState = self.LoC.long_control_state
controlsState.vPid = float(self.LoC.v_pid)
- controlsState.vCruise = float(self.v_cruise_kph)
- controlsState.vCruiseCluster = float(self.v_cruise_cluster_kph)
+ controlsState.vCruise = float(self.v_cruise_helper.v_cruise_kph)
+ controlsState.vCruiseCluster = float(self.v_cruise_helper.v_cruise_cluster_kph)
controlsState.upAccelCmd = float(self.LoC.pid.p)
controlsState.uiAccelCmd = float(self.LoC.pid.i)
controlsState.ufAccelCmd = float(self.LoC.pid.f)
@@ -879,7 +850,6 @@ class Controls:
self.publish_logs(CS, start_time, CC, lac_log)
self.prof.checkpoint("Sent")
- self.update_button_timers(CS.buttonEvents)
self.CS_prev = CS
def controlsd_thread(self):
@@ -888,6 +858,7 @@ class Controls:
self.rk.monitor_time()
self.prof.display()
+
def main(sm=None, pm=None, logcan=None):
controls = Controls(sm, pm, logcan)
controls.controlsd_thread()
diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py
index e74be7199e..bdbdb7023a 100644
--- a/selfdrive/controls/lib/drive_helpers.py
+++ b/selfdrive/controls/lib/drive_helpers.py
@@ -22,6 +22,7 @@ CAR_ROTATION_RADIUS = 0.0
# EU guidelines
MAX_LATERAL_JERK = 5.0
+ButtonEvent = car.CarState.ButtonEvent
ButtonType = car.CarState.ButtonEvent.Type
CRUISE_LONG_PRESS = 50
CRUISE_NEAREST_FUNC = {
@@ -34,68 +35,122 @@ CRUISE_INTERVAL_SIGN = {
}
-def apply_deadzone(error, deadzone):
- if error > deadzone:
- error -= deadzone
- elif error < - deadzone:
- error += deadzone
- else:
- error = 0.
- return error
-
-
-def rate_limit(new_value, last_value, dw_step, up_step):
- return clip(new_value, last_value + dw_step, last_value + up_step)
-
+class VCruiseHelper:
+ def __init__(self, CP):
+ self.CP = CP
+ self.v_cruise_kph = V_CRUISE_INITIAL
+ self.v_cruise_cluster_kph = V_CRUISE_INITIAL
+ self.v_cruise_kph_last = 0
+ self.button_timers = {ButtonType.decelCruise: 0, ButtonType.accelCruise: 0}
+ self.button_change_states = {btn: {"standstill": False, "enabled": False} for btn in self.button_timers}
+
+ @property
+ def v_cruise_initialized(self):
+ return self.v_cruise_kph != V_CRUISE_INITIAL
+
+ def update_v_cruise(self, CS, enabled, is_metric):
+ self.v_cruise_kph_last = self.v_cruise_kph
+
+ if CS.cruiseState.available:
+ if not self.CP.pcmCruise:
+ # if stock cruise is completely disabled, then we can use our own set speed logic
+ self._update_v_cruise_non_pcm(CS, enabled, is_metric)
+ self.v_cruise_cluster_kph = self.v_cruise_kph
+ self.update_button_timers(CS, enabled)
+ else:
+ self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH
+ self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH
+ else:
+ self.v_cruise_kph = V_CRUISE_INITIAL
+ self.v_cruise_cluster_kph = V_CRUISE_INITIAL
+
+ def _update_v_cruise_non_pcm(self, CS, enabled, is_metric):
+ # handle button presses. TODO: this should be in state_control, but a decelCruise press
+ # would have the effect of both enabling and changing speed is checked after the state transition
+ if not enabled:
+ return
+
+ long_press = False
+ button_type = None
+
+ # should be CV.MPH_TO_KPH, but this causes rounding errors
+ v_cruise_delta = 1. if is_metric else 1.6
+
+ for b in CS.buttonEvents:
+ if b.type.raw in self.button_timers and not b.pressed:
+ if self.button_timers[b.type.raw] > CRUISE_LONG_PRESS:
+ return # end long press
+ button_type = b.type.raw
+ break
+ else:
+ for k in self.button_timers.keys():
+ if self.button_timers[k] and self.button_timers[k] % CRUISE_LONG_PRESS == 0:
+ button_type = k
+ long_press = True
+ break
-def update_v_cruise(v_cruise_kph, v_ego, gas_pressed, buttonEvents, button_timers, enabled, metric):
- # handle button presses. TODO: this should be in state_control, but a decelCruise press
- # would have the effect of both enabling and changing speed is checked after the state transition
- if not enabled:
- return v_cruise_kph
+ if button_type is None:
+ return
- long_press = False
- button_type = None
+ # Don't adjust speed when pressing resume to exit standstill
+ cruise_standstill = self.button_change_states[button_type]["standstill"] or CS.cruiseState.standstill
+ if button_type == ButtonType.accelCruise and cruise_standstill:
+ return
- # should be CV.MPH_TO_KPH, but this causes rounding errors
- v_cruise_delta = 1. if metric else 1.6
+ # Don't adjust speed if we've enabled since the button was depressed (some ports enable on rising edge)
+ if not self.button_change_states[button_type]["enabled"]:
+ return
- for b in buttonEvents:
- if b.type.raw in button_timers and not b.pressed:
- if button_timers[b.type.raw] > CRUISE_LONG_PRESS:
- return v_cruise_kph # end long press
- button_type = b.type.raw
- break
- else:
- for k in button_timers.keys():
- if button_timers[k] and button_timers[k] % CRUISE_LONG_PRESS == 0:
- button_type = k
- long_press = True
- break
-
- if button_type:
v_cruise_delta = v_cruise_delta * (5 if long_press else 1)
- if long_press and v_cruise_kph % v_cruise_delta != 0: # partial interval
- v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](v_cruise_kph / v_cruise_delta) * v_cruise_delta
+ if long_press and self.v_cruise_kph % v_cruise_delta != 0: # partial interval
+ self.v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](self.v_cruise_kph / v_cruise_delta) * v_cruise_delta
else:
- v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type]
+ self.v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type]
# If set is pressed while overriding, clip cruise speed to minimum of vEgo
- if gas_pressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise):
- v_cruise_kph = max(v_cruise_kph, v_ego * CV.MS_TO_KPH)
+ if CS.gasPressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise):
+ self.v_cruise_kph = max(self.v_cruise_kph, CS.vEgo * CV.MS_TO_KPH)
+
+ self.v_cruise_kph = clip(round(self.v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX)
- v_cruise_kph = clip(round(v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX)
+ def update_button_timers(self, CS, enabled):
+ # increment timer for buttons still pressed
+ for k in self.button_timers:
+ if self.button_timers[k] > 0:
+ self.button_timers[k] += 1
- return v_cruise_kph
+ for b in CS.buttonEvents:
+ if b.type.raw in self.button_timers:
+ # Start/end timer and store current state on change of button pressed
+ self.button_timers[b.type.raw] = 1 if b.pressed else 0
+ self.button_change_states[b.type.raw] = {"standstill": CS.cruiseState.standstill, "enabled": enabled}
+ def initialize_v_cruise(self, CS):
+ # initializing is handled by the PCM
+ if self.CP.pcmCruise:
+ return
-def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last):
- for b in buttonEvents:
# 250kph or above probably means we never had a set speed
- if b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) and v_cruise_last < 250:
- return v_cruise_last
+ if any(b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for b in CS.buttonEvents) and self.v_cruise_kph_last < 250:
+ self.v_cruise_kph = self.v_cruise_kph_last
+ else:
+ self.v_cruise_kph = int(round(clip(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX)))
+
+ self.v_cruise_cluster_kph = self.v_cruise_kph
+
- return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX)))
+def apply_deadzone(error, deadzone):
+ if error > deadzone:
+ error -= deadzone
+ elif error < - deadzone:
+ error += deadzone
+ else:
+ error = 0.
+ return error
+
+
+def rate_limit(new_value, last_value, dw_step, up_step):
+ return clip(new_value, last_value + dw_step, last_value + up_step)
def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates):
diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py
index 44426620e9..a761cceecb 100644
--- a/selfdrive/controls/lib/events.py
+++ b/selfdrive/controls/lib/events.py
@@ -597,6 +597,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = {
EventName.buttonCancel: {
ET.USER_DISABLE: EngagementAlert(AudibleAlert.disengage),
+ ET.NO_ENTRY: NoEntryAlert("Cancel Pressed"),
},
EventName.brakeHold: {
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
index 080782ad0f..6b79813117 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
@@ -301,8 +301,10 @@ class LongitudinalMpc:
return lead_xv
def set_accel_limits(self, min_a, max_a):
+ # TODO this sets a max accel limit, but the minimum limit is only for cruise decel
+ # needs refactor
self.cruise_min_a = min_a
- self.cruise_max_a = max_a
+ self.max_a = max_a
def update(self, carstate, radarstate, v_cruise, x, v, a, j):
v_ego = self.x0[1]
@@ -317,16 +319,17 @@ class LongitudinalMpc:
lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1])
lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1])
+ self.params[:,0] = MIN_ACCEL
+ self.params[:,1] = self.max_a
+
# Update in ACC mode or ACC/e2e blend
if self.mode == 'acc':
- self.params[:,0] = MIN_ACCEL
- self.params[:,1] = self.cruise_max_a
self.params[:,5] = LEAD_DANGER_FACTOR
# Fake an obstacle for cruise, this ensures smooth acceleration to set speed
# when the leads are no factor.
v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05)
- v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05)
+ v_upper = v_ego + (T_IDXS * self.max_a * 1.05)
v_cruise_clipped = np.clip(v_cruise * np.ones(N+1),
v_lower,
v_upper)
@@ -338,9 +341,6 @@ class LongitudinalMpc:
x[:], v[:], a[:], j[:] = 0.0, 0.0, 0.0, 0.0
elif self.mode == 'blended':
- self.params[:,0] = MIN_ACCEL
- self.params[:,1] = MAX_ACCEL
-
self.params[:,5] = 1.0
x_obstacles = np.column_stack([lead_0_obstacle,
diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py
index 2fa13bfb15..def0a1208a 100755
--- a/selfdrive/controls/lib/longitudinal_planner.py
+++ b/selfdrive/controls/lib/longitudinal_planner.py
@@ -10,7 +10,7 @@ from common.params import Params
from common.realtime import DT_MDL
from selfdrive.modeld.constants import T_IDXS
from selfdrive.controls.lib.longcontrol import LongCtrlState
-from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc
+from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc, MIN_ACCEL, MAX_ACCEL
from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC
from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N
from system.swaglog import cloudlog
@@ -69,7 +69,8 @@ class LongitudinalPlanner:
e2e = self.params.get_bool('ExperimentalMode') and self.CP.openpilotLongitudinalControl
self.mpc.mode = 'blended' if e2e else 'acc'
- def parse_model(self, model_msg, model_error):
+ @staticmethod
+ def parse_model(model_msg, model_error):
if (len(model_msg.position.x) == 33 and
len(model_msg.velocity.x) == 33 and
len(model_msg.acceleration.x) == 33):
@@ -103,8 +104,12 @@ class LongitudinalPlanner:
# No change cost when user is controlling the speed, or when standstill
prev_accel_constraint = not (reset_state or sm['carState'].standstill)
- accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)]
- accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP)
+ if self.mpc.mode == 'acc':
+ accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)]
+ accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP)
+ else:
+ accel_limits = [MIN_ACCEL, MAX_ACCEL]
+ accel_limits_turns = [MIN_ACCEL, MAX_ACCEL]
if reset_state:
self.v_desired_filter.x = v_ego
diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/controls/tests/test_cruise_speed.py
old mode 100644
new mode 100755
index ca070f1c3f..3d6f55931e
--- a/selfdrive/controls/tests/test_cruise_speed.py
+++ b/selfdrive/controls/tests/test_cruise_speed.py
@@ -1,10 +1,17 @@
#!/usr/bin/env python3
-import unittest
import numpy as np
+from parameterized import parameterized_class
+import unittest
+
+from selfdrive.controls.lib.drive_helpers import VCruiseHelper, V_CRUISE_MAX, V_CRUISE_ENABLE_MIN
+from cereal import car
+from common.conversions import Conversions as CV
from common.params import Params
+from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
+ButtonEvent = car.CarState.ButtonEvent
+ButtonType = car.CarState.ButtonEvent.Type
-from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
def run_cruise_simulation(cruise, t_end=20.):
man = Maneuver(
@@ -19,7 +26,7 @@ def run_cruise_simulation(cruise, t_end=20.):
)
valid, output = man.evaluate()
assert valid
- return output[-1,3]
+ return output[-1, 3]
class TestCruiseSpeed(unittest.TestCase):
@@ -35,5 +42,87 @@ class TestCruiseSpeed(unittest.TestCase):
self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s')
+# TODO: test pcmCruise
+@parameterized_class(('pcm_cruise',), [(False,)])
+class TestVCruiseHelper(unittest.TestCase):
+ def setUp(self):
+ self.CP = car.CarParams(pcmCruise=self.pcm_cruise) # pylint: disable=E1101
+ self.v_cruise_helper = VCruiseHelper(self.CP)
+ self.reset_cruise_speed_state()
+
+ def reset_cruise_speed_state(self):
+ # Two resets previous cruise speed
+ for _ in range(2):
+ self.v_cruise_helper.update_v_cruise(car.CarState(cruiseState={"available": False}), enabled=False, is_metric=False)
+
+ def enable(self, v_ego):
+ # Simulates user pressing set with a current speed
+ self.v_cruise_helper.initialize_v_cruise(car.CarState(vEgo=v_ego))
+
+ def test_adjust_speed(self):
+ """
+ Asserts speed changes on falling edges of buttons.
+ """
+
+ self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
+
+ for btn in (ButtonType.accelCruise, ButtonType.decelCruise):
+ for pressed in (True, False):
+ CS = car.CarState(cruiseState={"available": True})
+ CS.buttonEvents = [ButtonEvent(type=btn, pressed=pressed)]
+
+ self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False)
+ self.assertEqual(pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
+
+ def test_rising_edge_enable(self):
+ """
+ Some car interfaces may enable on rising edge of a button,
+ ensure we don't adjust speed if enabled changes mid-press.
+ """
+
+ # NOTE: enabled is always one frame behind the result from button press in controlsd
+ for enabled, pressed in ((False, False),
+ (False, True),
+ (True, False)):
+ CS = car.CarState(cruiseState={"available": True})
+ CS.buttonEvents = [ButtonEvent(type=ButtonType.decelCruise, pressed=pressed)]
+ self.v_cruise_helper.update_v_cruise(CS, enabled=enabled, is_metric=False)
+ if pressed:
+ self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
+
+ # Expected diff on enabling. Speed should not change on falling edge of pressed
+ self.assertEqual(not pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
+
+ def test_resume_in_standstill(self):
+ """
+ Asserts we don't increment set speed if user presses resume/accel to exit cruise standstill.
+ """
+
+ self.enable(0)
+
+ for standstill in (True, False):
+ for pressed in (True, False):
+ CS = car.CarState(cruiseState={"available": True, "standstill": standstill})
+ CS.buttonEvents = [ButtonEvent(type=ButtonType.accelCruise, pressed=pressed)]
+ self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False)
+
+ # speed should only update if not at standstill and button falling edge
+ should_equal = standstill or pressed
+ self.assertEqual(should_equal, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
+
+ def test_initialize_v_cruise(self):
+ """
+ Asserts allowed cruise speeds on enabling with SET.
+ """
+
+ for v_ego in np.linspace(0, 100, 101):
+ self.reset_cruise_speed_state()
+ self.assertFalse(self.v_cruise_helper.v_cruise_initialized)
+
+ self.enable(float(v_ego))
+ self.assertTrue(V_CRUISE_ENABLE_MIN <= self.v_cruise_helper.v_cruise_kph <= V_CRUISE_MAX)
+ self.assertTrue(self.v_cruise_helper.v_cruise_initialized)
+
+
if __name__ == "__main__":
unittest.main()
diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py
index 7ac2c5f506..6d4df0423a 100755
--- a/selfdrive/manager/test/test_manager.py
+++ b/selfdrive/manager/test/test_manager.py
@@ -4,6 +4,7 @@ import signal
import time
import unittest
+from common.params import Params
import selfdrive.manager.manager as manager
from selfdrive.manager.process import DaemonProcess
from selfdrive.manager.process_config import managed_processes
@@ -20,6 +21,10 @@ class TestManager(unittest.TestCase):
os.environ['PASSIVE'] = '0'
HARDWARE.set_power_save(False)
+ # ensure clean CarParams
+ params = Params()
+ params.clear_all()
+
def tearDown(self):
manager.manager_cleanup()
@@ -40,6 +45,7 @@ class TestManager(unittest.TestCase):
Ensure all processes exit cleanly when stopped.
"""
HARDWARE.set_power_save(False)
+ manager.manager_init()
manager.manager_prepare()
for p in ALL_PROCESSES:
managed_processes[p].start()
diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py
index dad5d89844..071eaada12 100644
--- a/selfdrive/test/longitudinal_maneuvers/maneuver.py
+++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py
@@ -17,6 +17,7 @@ class Maneuver():
self.only_lead2 = kwargs.get("only_lead2", False)
self.only_radar = kwargs.get("only_radar", False)
self.ensure_start = kwargs.get("ensure_start", False)
+ self.enabled = kwargs.get("enabled", True)
self.duration = duration
self.title = title
@@ -26,23 +27,24 @@ class Maneuver():
lead_relevancy=self.lead_relevancy,
speed=self.speed,
distance_lead=self.distance_lead,
+ enabled=self.enabled,
only_lead2=self.only_lead2,
only_radar=self.only_radar,
)
valid = True
logs = []
- while plant.current_time() < self.duration:
- speed_lead = np.interp(plant.current_time(), self.breakpoints, self.speed_lead_values)
- prob = np.interp(plant.current_time(), self.breakpoints, self.prob_lead_values)
- cruise = np.interp(plant.current_time(), self.breakpoints, self.cruise_values)
+ while plant.current_time < self.duration:
+ speed_lead = np.interp(plant.current_time, self.breakpoints, self.speed_lead_values)
+ prob = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values)
+ cruise = np.interp(plant.current_time, self.breakpoints, self.cruise_values)
log = plant.step(speed_lead, prob, cruise)
d_rel = log['distance_lead'] - log['distance'] if self.lead_relevancy else 200.
v_rel = speed_lead - log['speed'] if self.lead_relevancy else 0.
log['d_rel'] = d_rel
log['v_rel'] = v_rel
- logs.append(np.array([plant.current_time(),
+ logs.append(np.array([plant.current_time,
log['distance'],
log['distance_lead'],
log['speed'],
diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py
index e81510e9ba..c3af1eee03 100755
--- a/selfdrive/test/longitudinal_maneuvers/plant.py
+++ b/selfdrive/test/longitudinal_maneuvers/plant.py
@@ -10,11 +10,12 @@ from selfdrive.modeld.constants import T_IDXS
from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU
-class Plant():
+
+class Plant:
messaging_initialized = False
def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0,
- only_lead2=False, only_radar=False):
+ enabled=True, only_lead2=False, only_radar=False):
self.rate = 1. / DT_MDL
if not Plant.messaging_initialized:
@@ -32,10 +33,11 @@ class Plant():
self.speeds = []
# lead car
- self.distance_lead = distance_lead
self.lead_relevancy = lead_relevancy
- self.only_lead2=only_lead2
- self.only_radar=only_radar
+ self.distance_lead = distance_lead
+ self.enabled = enabled
+ self.only_lead2 = only_lead2
+ self.only_radar = only_radar
self.rk = Ratekeeper(self.rate, print_delay_threshold=100.0)
self.ts = 1. / self.rate
@@ -47,6 +49,7 @@ class Plant():
self.planner = LongitudinalPlanner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed)
+ @property
def current_time(self):
return float(self.rk.frame) / self.rate
@@ -104,9 +107,7 @@ class Plant():
acceleration.x = [float(x) for x in np.zeros_like(T_IDXS)]
model.modelV2.acceleration = acceleration
-
-
- control.controlsState.longControlState = LongCtrlState.pid
+ control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off
control.controlsState.vCruise = float(v_cruise * 3.6)
car_state.carState.vEgo = float(self.speed)
car_state.carState.standstill = self.speed < 0.01
@@ -141,7 +142,7 @@ class Plant():
# print at 5hz
if (self.rk.frame % (self.rate // 5)) == 0:
print("%2.2f sec %6.2f m %6.2f m/s %6.2f m/s2 lead_rel: %6.2f m %6.2f m/s"
- % (self.current_time(), self.distance, self.speed, self.acceleration, d_rel, v_rel))
+ % (self.current_time, self.distance, self.speed, self.acceleration, d_rel, v_rel))
# ******** update prevs ********
diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
index 7cc95b104a..e859952445 100755
--- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
+++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
@@ -10,7 +10,7 @@ from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
# TODO: make new FCW tests
maneuvers = [
Maneuver(
- 'approach stopped car at 20m/s, initial distance: 120m',
+ 'approach stopped car at 25m/s, initial distance: 120m',
duration=20.,
initial_speed=25.,
lead_relevancy=True,
@@ -118,6 +118,13 @@ maneuvers = [
breakpoints=[1., 10., 15.],
ensure_start=True,
),
+ Maneuver(
+ 'cruising at 25 m/s while disabled',
+ duration=20.,
+ initial_speed=25.,
+ lead_relevancy=False,
+ enabled=False,
+ ),
]
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index cac678ca1f..f35e23d45f 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-a36f7e2fd922fcadca6f8a3d777f4db787cba016
+aa2d370836588fd80b648dbed8d156765ec804d5
diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts
index 0bbae22517..31c910a910 100644
--- a/selfdrive/ui/translations/main_ko.ts
+++ b/selfdrive/ui/translations/main_ko.ts
@@ -1004,11 +1004,11 @@ location set
Experimental Mode
- 실험 모드
+ 실험적 모드
openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: <br> <h4>🌮 End-to-End Longitudinal Control 🌮</h4> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides which speed to drive, the set speed will only act as an upper bound.
-
+ openpilot은 기본적으로 <b>안정적 모드</b>로 주행합니다. 실험적 모드는 안정적 모드에 준비되지 않은 <b>알파 수준 기능</b>을 활성화 합니다. 실험 모드의 특징은 아래에 나열되어 있습니다 <br> <h4>🌮 E2E 롱컨트롤 🌮</h4> 주행모델이 가속과 감속을 제어하도록 합니다. openpilot은 신호등과 정지표지판을 보고 멈추는 것을 포함하여 운전자가 생각하는것처럼 주행합니다. 주행 모델이 주행할 속도를 결정하므로 설정된 속도는 상한선으로만 작용합니다.
openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control on this car. Enable this to switch to openpilot longitudinal control.
@@ -1016,7 +1016,7 @@ location set
WARNING: openpilot longitudinal control is experimental for this car and will disable Automatic Emergency Braking (AEB).
-
+ 경고: openpilot 롱컨트롤은 실험적인 기능으로 차량의 자동긴급제동(AEB)를 비활성화합니다.
diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts
index 702702a8be..6a1d32f87a 100644
--- a/selfdrive/ui/translations/main_pt-BR.ts
+++ b/selfdrive/ui/translations/main_pt-BR.ts
@@ -1012,7 +1012,7 @@ trabalho definido
openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: <br> <h4>🌮 End-to-End Longitudinal Control 🌮</h4> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides which speed to drive, the set speed will only act as an upper bound.
-
+ openpilot por padrão funciona em <b>modo chill</b>. modo Experimental ativa <b>recursos de nível-alfa</b> que não estão prontos para o modo chill. Recursos experimentais estão listados abaixo: <br> <h4>🌮 Controle Longitudinal de Ponta a Ponta 🌮</h4> Deixe o modelo de condução controlar o acelerador e os freios. Uma vez que o modelo de condução decide qual velocidade dirigir, a velocidade definida só funcionará como um limite superior.
openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control on this car. Enable this to switch to openpilot longitudinal control.
@@ -1020,7 +1020,7 @@ trabalho definido
WARNING: openpilot longitudinal control is experimental for this car and will disable Automatic Emergency Braking (AEB).
-
+ ATENÇÃO: o controle longitudinal do openpilot é experimental para este carro e desativará a Frenagem Automática de Emergência (AEB).
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 0f6bc981cf..c9810597b5 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -60,11 +60,11 @@
Cellular Metered
-
+ 行動網路
Prevent large data uploads when on a metered connection
-
+ 防止使用行動網路上傳大量的數據
@@ -240,11 +240,11 @@
Reset
-
+ 重設
Review
-
+ 回顧
@@ -864,7 +864,7 @@ location set
Uninstall
-
+ 卸載
@@ -1004,19 +1004,19 @@ location set
Experimental Mode
-
+ 實驗模式
openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: <br> <h4>🌮 End-to-End Longitudinal Control 🌮</h4> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides which speed to drive, the set speed will only act as an upper bound.
-
+ openpilot 默認以 <b>輕鬆模式</b> 駕駛。 實驗模式啟用了尚未準備好進入輕鬆模式的 <b>alpha 級功能</b>。 實驗功能如下: <br> <h4>🌮端到端縱向控制🌮</h4> 讓駕駛模型控制油門和剎車。 openpilot 將像人類一樣駕駛,包括紅燈和停車標誌時停車,因為是由駕駛模型來決定車速,所以定速的設定值只會作為上限。
openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control on this car. Enable this to switch to openpilot longitudinal control.
-
+ openpilot 默認使用汽車內置的主動巡航控制 (ACC),而不是使用 openpilot 縱向控制。啟用此選項可切換到 openpilot 縱向控制。
WARNING: openpilot longitudinal control is experimental for this car and will disable Automatic Emergency Braking (AEB).
-
+ 警告:openpilot 縱向控制在這輛車上仍屬實驗性質,啟用後會喪失自動緊急煞車 (AEB) 功能。
@@ -1074,7 +1074,7 @@ location set
Forget
-
+ 清除
diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json
index 8534c8a978..7876b1af1f 100644
--- a/system/hardware/tici/agnos.json
+++ b/system/hardware/tici/agnos.json
@@ -1,9 +1,9 @@
[
{
"name": "boot",
- "url": "https://commadist.azureedge.net/agnosupdate/boot-57626d7737ab2fa1318e8707a202b1295b5da79ad2fa0a36377cc9481ad0d136.img.xz",
- "hash": "57626d7737ab2fa1318e8707a202b1295b5da79ad2fa0a36377cc9481ad0d136",
- "hash_raw": "57626d7737ab2fa1318e8707a202b1295b5da79ad2fa0a36377cc9481ad0d136",
+ "url": "https://commadist.azureedge.net/agnosupdate/boot-72662ec5d586c7a22659a1c8b140932d5472914176020fe76ba4204edbbb214a.img.xz",
+ "hash": "72662ec5d586c7a22659a1c8b140932d5472914176020fe76ba4204edbbb214a",
+ "hash_raw": "72662ec5d586c7a22659a1c8b140932d5472914176020fe76ba4204edbbb214a",
"size": 14780416,
"sparse": false,
"full_check": true,
@@ -41,9 +41,9 @@
},
{
"name": "system",
- "url": "https://commadist.azureedge.net/agnosupdate/system-b40b08912576bb972907acba7c201c1399395cbc0cba06ce6e5e3f70ab565cb5.img.xz",
- "hash": "6e8fbcc21a265f7f58062abce7675dc05540e2b60cee2df56992a151ba64936f",
- "hash_raw": "b40b08912576bb972907acba7c201c1399395cbc0cba06ce6e5e3f70ab565cb5",
+ "url": "https://commadist.azureedge.net/agnosupdate/system-9efdc9368f05e06008a7a1dbbee21b564e89988dc94d6ddee3a3a88e42268f0e.img.xz",
+ "hash": "48209ce7e8cc2fff4ec024f0cd82fc2e3e097b5c0629be2b292acf64e6701449",
+ "hash_raw": "9efdc9368f05e06008a7a1dbbee21b564e89988dc94d6ddee3a3a88e42268f0e",
"size": 10737418240,
"sparse": true,
"full_check": false,
diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py
index c5b931ddae..e2fd20c1be 100644
--- a/system/hardware/tici/hardware.py
+++ b/system/hardware/tici/hardware.py
@@ -431,9 +431,6 @@ class Tici(HardwareBase):
def initialize_hardware(self):
self.amplifier.initialize_configuration()
- # TODO: this should go in AGNOS
- os.system("sudo chmod 666 /dev/spidev0.0")
-
# Allow thermald to write engagement status to kmsg
os.system("sudo chmod a+w /dev/kmsg")
diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript
index b7321e1f8d..3ff4862800 100644
--- a/tools/cabana/SConscript
+++ b/tools/cabana/SConscript
@@ -19,7 +19,7 @@ prev_moc_path = cabana_env['QT_MOCHPREFIX']
cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_'
cabana_env.Execute('./generate_dbc_json.py --out car_fingerprint_to_dbc.json')
cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc',
- 'canmessages.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
+ 'canmessages.cc', 'commands.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
cabana_env.Program('_cabana', ['cabana.cc', cabana_lib], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
if GetOption('test'):
diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc
index 678fe5f876..bcd2b88a81 100644
--- a/tools/cabana/binaryview.cc
+++ b/tools/cabana/binaryview.cc
@@ -165,14 +165,14 @@ void BinaryViewModel::setMessage(const QString &message_id) {
if ((dbc_msg = dbc()->msg(msg_id))) {
row_count = dbc_msg->size;
items.resize(row_count * column_count);
- for (int i = 0; i < dbc_msg->sigs.size(); ++i) {
- const auto &sig = dbc_msg->sigs[i];
+ int i = 0;
+ for (auto &[name, sig] : dbc_msg->sigs) {
auto [start, end] = getSignalRange(&sig);
for (int j = start; j <= end; ++j) {
int bit_index = sig.is_little_endian ? bigEndianBitIndex(j) : j;
int idx = column_count * (bit_index / 8) + bit_index % 8;
if (idx >= items.size()) {
- qWarning() << "signal " << sig.name.c_str() << "out of bounds.start_bit:" << sig.start_bit << "size:" << sig.size;
+ qWarning() << "signal " << name << "out of bounds.start_bit:" << sig.start_bit << "size:" << sig.size;
break;
}
if (j == start) sig.is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true;
@@ -180,6 +180,7 @@ void BinaryViewModel::setMessage(const QString &message_id) {
items[idx].bg_color = getColor(i);
items[idx].sigs.push_back(&sig);
}
+ ++i;
}
} else {
row_count = can->lastMessage(msg_id).dat.size();
diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h
index 05bfe7e79f..2d6fc5c18b 100644
--- a/tools/cabana/binaryview.h
+++ b/tools/cabana/binaryview.h
@@ -50,7 +50,7 @@ public:
private:
QString msg_id;
- const Msg *dbc_msg;
+ const DBCMsg *dbc_msg;
int row_count = 0;
const int column_count = 9;
};
diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc
index e670ee8c94..3bcaae4bbd 100644
--- a/tools/cabana/canmessages.cc
+++ b/tools/cabana/canmessages.cc
@@ -44,7 +44,7 @@ QList CANMessages::findSignalValues(const QString &id, const Signal *si
for (auto &evt : *evts) {
if (evt->which != cereal::Event::Which::CAN) continue;
- for (auto c : evt->event.getCan()) {
+ for (const auto &c : evt->event.getCan()) {
if (bus == c.getSrc() && address == c.getAddress()) {
double val = get_raw_value((uint8_t *)c.getDat().begin(), c.getDat().size(), *signal);
if ((flag == EQ && val == value) || (flag == LT && val < value) || (flag == GT && val > value)) {
@@ -65,6 +65,7 @@ void CANMessages::process(QHash *messages) {
emit updated();
emit msgsReceived(messages);
delete messages;
+ processing = false;
}
bool CANMessages::eventFilter(const Event *event) {
@@ -78,7 +79,7 @@ bool CANMessages::eventFilter(const Event *event) {
}
double current_sec = replay->currentSeconds();
- if (counters_begin_sec == 0) {
+ if (counters_begin_sec == 0 || counters_begin_sec >= current_sec) {
counters.clear();
counters_begin_sec = current_sec;
}
@@ -94,7 +95,6 @@ bool CANMessages::eventFilter(const Event *event) {
}
CanData &data = list.emplace_front();
data.ts = current_sec;
- data.bus_time = c.getBusTime();
data.dat.append((char *)c.getDat().begin(), c.getDat().size());
data.count = ++counters[id];
@@ -105,7 +105,9 @@ bool CANMessages::eventFilter(const Event *event) {
}
double ts = millis_since_boot();
- if ((ts - prev_update_ts) > (1000.0 / settings.fps)) {
+ if ((ts - prev_update_ts) > (1000.0 / settings.fps) && !processing) {
+ // delay posting CAN message if UI thread is busy
+ processing = true;
prev_update_ts = ts;
// use pointer to avoid data copy in queued connection.
emit received(new_msgs.release());
@@ -120,7 +122,7 @@ const std::deque CANMessages::messages(const QString &id) {
}
void CANMessages::seekTo(double ts) {
- replay->seekTo(ts, false);
+ replay->seekTo(std::max(double(0), ts), false);
counters_begin_sec = 0;
}
diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h
index 5ee33bce0d..ff41edad54 100644
--- a/tools/cabana/canmessages.h
+++ b/tools/cabana/canmessages.h
@@ -16,7 +16,6 @@ struct CanData {
double ts = 0.;
uint32_t count = 0;
uint32_t freq = 0;
- uint16_t bus_time = 0;
QByteArray dat;
};
@@ -63,6 +62,7 @@ protected:
Replay *replay = nullptr;
std::mutex lock;
std::atomic counters_begin_sec = 0;
+ std::atomic processing = false;
QHash counters;
QHash> received_msgs;
};
diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc
index 3a170bccdc..06387b3585 100644
--- a/tools/cabana/chartswidget.cc
+++ b/tools/cabana/chartswidget.cc
@@ -192,6 +192,8 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent)
chart->createDefaultAxes();
chart->legend()->hide();
chart->layout()->setContentsMargins(0, 0, 0, 0);
+ // top margin for title
+ chart->setMargins({0, 11, 0, 0});
line_marker = new QGraphicsLineItem(chart);
line_marker->setZValue(chart->zValue() + 10);
@@ -205,7 +207,6 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent)
item_group->setZValue(chart->zValue() + 10);
// title
- msg_title = new QGraphicsTextItem(chart);
QToolButton *remove_btn = new QToolButton();
remove_btn->setText("X");
remove_btn->setAutoRaise(true);
@@ -234,13 +235,11 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent)
void ChartView::resizeEvent(QResizeEvent *event) {
QChartView::resizeEvent(event);
- msg_title->setPos(11, 6);
close_btn_proxy->setPos(event->size().width() - close_btn_proxy->size().width() - 11, 8);
}
void ChartView::updateTitle() {
- chart()->setTitle(signal->name.c_str());
- msg_title->setHtml(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id));
+ chart()->setTitle(tr("%1 %2 %3").arg(dbc()->msg(id)->name).arg(id).arg(signal->name.c_str()));
}
void ChartView::updateFromSettings() {
@@ -248,7 +247,6 @@ void ChartView::updateFromSettings() {
chart()->setTheme(settings.chart_theme == 0 ? QChart::ChartThemeLight : QChart::QChart::ChartThemeDark);
auto color = chart()->titleBrush().color();
line_marker->setPen(QPen(color, 2));
- msg_title->setDefaultTextColor(color);
}
void ChartView::setRange(double min, double max, bool force_update) {
@@ -265,6 +263,7 @@ void ChartView::adjustChartMargins() {
if (chart()->plotArea().left() != aligned_pos) {
const float left_margin = chart()->margins().left() + aligned_pos - chart()->plotArea().left();
chart()->setMargins(QMargins(left_margin, 11, 0, 0));
+ updateLineMarker(can->currentSec());
}
}
@@ -290,7 +289,7 @@ void ChartView::updateSeries(const std::pair range) {
double end_ns = (route_start_time + range.second) * 1e9;
for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) {
if ((*it)->which == cereal::Event::Which::CAN) {
- for (auto c : (*it)->event.getCan()) {
+ for (const auto &c : (*it)->event.getCan()) {
if (bus == c.getSrc() && address == c.getAddress()) {
auto dat = c.getDat();
double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *signal);
diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h
index e32a6697ce..20c673a757 100644
--- a/tools/cabana/chartswidget.h
+++ b/tools/cabana/chartswidget.h
@@ -44,7 +44,7 @@ private:
QGraphicsItemGroup *item_group;
QGraphicsLineItem *line_marker, *track_line;
QGraphicsEllipseItem *track_ellipse;
- QGraphicsTextItem *value_text, *msg_title;
+ QGraphicsTextItem *value_text;
QGraphicsProxyWidget *close_btn_proxy;
QVector vals;
};
diff --git a/tools/cabana/commands.cc b/tools/cabana/commands.cc
new file mode 100644
index 0000000000..b3f5cb1c66
--- /dev/null
+++ b/tools/cabana/commands.cc
@@ -0,0 +1,75 @@
+#include "tools/cabana/commands.h"
+
+// EditMsgCommand
+
+EditMsgCommand::EditMsgCommand(const QString &id, const QString &title, int size, QUndoCommand *parent)
+ : id(id), new_title(title), new_size(size), QUndoCommand(parent) {
+ if (auto msg = dbc()->msg(id)) {
+ old_title = msg->name;
+ old_size = msg->size;
+ }
+ setText(QObject::tr("Edit message %1:%2").arg(DBCManager::parseId(id).second).arg(title));
+}
+
+void EditMsgCommand::undo() {
+ if (old_title.isEmpty())
+ dbc()->removeMsg(id);
+ else
+ dbc()->updateMsg(id, old_title, old_size);
+}
+
+void EditMsgCommand::redo() {
+ dbc()->updateMsg(id, new_title, new_size);
+}
+
+// RemoveMsgCommand
+
+RemoveMsgCommand::RemoveMsgCommand(const QString &id, QUndoCommand *parent) : id(id), QUndoCommand(parent) {
+ if (auto msg = dbc()->msg(id)) {
+ message = *msg;
+ setText(QObject::tr("Remove message %1:%2").arg(DBCManager::parseId(id).second).arg(message.name));
+ }
+}
+
+void RemoveMsgCommand::undo() {
+ if (!message.name.isEmpty()) {
+ dbc()->updateMsg(id, message.name, message.size);
+ for (auto &[name, s] : message.sigs)
+ dbc()->addSignal(id, s);
+ }
+}
+
+void RemoveMsgCommand::redo() {
+ if (!message.name.isEmpty())
+ dbc()->removeMsg(id);
+}
+
+// AddSigCommand
+
+AddSigCommand::AddSigCommand(const QString &id, const Signal &sig, QUndoCommand *parent)
+ : id(id), signal(sig), QUndoCommand(parent) {
+ setText(QObject::tr("Add signal %1 to %2").arg(sig.name.c_str()).arg(DBCManager::parseId(id).second));
+}
+
+void AddSigCommand::undo() { dbc()->removeSignal(id, signal.name.c_str()); }
+void AddSigCommand::redo() { dbc()->addSignal(id, signal); }
+
+// RemoveSigCommand
+
+RemoveSigCommand::RemoveSigCommand(const QString &id, const Signal *sig, QUndoCommand *parent)
+ : id(id), signal(*sig), QUndoCommand(parent) {
+ setText(QObject::tr("Remove signal %1 from %2").arg(signal.name.c_str()).arg(DBCManager::parseId(id).second));
+}
+
+void RemoveSigCommand::undo() { dbc()->addSignal(id, signal); }
+void RemoveSigCommand::redo() { dbc()->removeSignal(id, signal.name.c_str()); }
+
+// EditSignalCommand
+
+EditSignalCommand::EditSignalCommand(const QString &id, const Signal *sig, const Signal &new_sig, QUndoCommand *parent)
+ : id(id), old_signal(*sig), new_signal(new_sig), QUndoCommand(parent) {
+ setText(QObject::tr("Edit signal %1").arg(old_signal.name.c_str()));
+}
+
+void EditSignalCommand::undo() { dbc()->updateSignal(id, new_signal.name.c_str(), old_signal); }
+void EditSignalCommand::redo() { dbc()->updateSignal(id, old_signal.name.c_str(), new_signal); }
diff --git a/tools/cabana/commands.h b/tools/cabana/commands.h
new file mode 100644
index 0000000000..7ea1f66653
--- /dev/null
+++ b/tools/cabana/commands.h
@@ -0,0 +1,63 @@
+#pragma once
+
+#include
+
+#include "tools/cabana/canmessages.h"
+#include "tools/cabana/dbcmanager.h"
+
+class EditMsgCommand : public QUndoCommand {
+public:
+ EditMsgCommand(const QString &id, const QString &title, int size, QUndoCommand *parent = nullptr);
+ void undo() override;
+ void redo() override;
+
+private:
+ const QString id;
+ QString old_title, new_title;
+ int old_size = 0, new_size = 0;
+};
+
+class RemoveMsgCommand : public QUndoCommand {
+public:
+ RemoveMsgCommand(const QString &id, QUndoCommand *parent = nullptr);
+ void undo() override;
+ void redo() override;
+
+private:
+ const QString id;
+ DBCMsg message;
+};
+
+class AddSigCommand : public QUndoCommand {
+public:
+ AddSigCommand(const QString &id, const Signal &sig, QUndoCommand *parent = nullptr);
+ void undo() override;
+ void redo() override;
+
+private:
+ const QString id;
+ Signal signal = {};
+};
+
+class RemoveSigCommand : public QUndoCommand {
+public:
+ RemoveSigCommand(const QString &id, const Signal *sig, QUndoCommand *parent = nullptr);
+ void undo() override;
+ void redo() override;
+
+private:
+ const QString id;
+ Signal signal = {};
+};
+
+class EditSignalCommand : public QUndoCommand {
+public:
+ EditSignalCommand(const QString &id, const Signal *sig, const Signal &new_sig, QUndoCommand *parent = nullptr);
+ void undo() override;
+ void redo() override;
+
+private:
+ const QString id;
+ Signal old_signal = {};
+ Signal new_signal = {};
+};
diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc
index abdd9a08df..18f103d34c 100644
--- a/tools/cabana/dbcmanager.cc
+++ b/tools/cabana/dbcmanager.cc
@@ -10,32 +10,36 @@ DBCManager::~DBCManager() {}
void DBCManager::open(const QString &dbc_file_name) {
dbc = const_cast(dbc_lookup(dbc_file_name.toStdString()));
- updateMsgMap();
- emit DBCFileChanged();
+ initMsgMap();
}
void DBCManager::open(const QString &name, const QString &content) {
std::istringstream stream(content.toStdString());
dbc = const_cast(dbc_parse_from_stream(name.toStdString(), stream));
- updateMsgMap();
- emit DBCFileChanged();
+ initMsgMap();
}
-void DBCManager::updateMsgMap() {
- msg_map.clear();
- for (auto &msg : dbc->msgs)
- msg_map[msg.address] = &msg;
+void DBCManager::initMsgMap() {
+ msgs.clear();
+ for (auto &msg : dbc->msgs) {
+ auto &m = msgs[msg.address];
+ m.name = msg.name.c_str();
+ m.size = msg.size;
+ for (auto &s : msg.sigs)
+ m.sigs[QString::fromStdString(s.name)] = s;
+ }
+ emit DBCFileChanged();
}
QString DBCManager::generateDBC() {
if (!dbc) return {};
QString dbc_string;
- for (auto &m : dbc->msgs) {
- dbc_string += QString("BO_ %1 %2: %3 XXX\n").arg(m.address).arg(m.name.c_str()).arg(m.size);
- for (auto &sig : m.sigs) {
+ for (auto &[address, m] : msgs) {
+ dbc_string += QString("BO_ %1 %2: %3 XXX\n").arg(address).arg(m.name).arg(m.size);
+ for (auto &[name, sig] : m.sigs) {
dbc_string += QString(" SG_ %1 : %2|%3@%4%5 (%6,%7) [0|0] \"\" XXX\n")
- .arg(sig.name.c_str())
+ .arg(name)
.arg(sig.start_bit)
.arg(sig.size)
.arg(sig.is_little_endian ? '1' : '0')
@@ -49,48 +53,45 @@ QString DBCManager::generateDBC() {
}
void DBCManager::updateMsg(const QString &id, const QString &name, uint32_t size) {
- auto [bus, address] = parseId(id);
- if (auto m = const_cast(msg(address))) {
- m->name = name.toStdString();
- m->size = size;
- } else {
- m = &dbc->msgs.emplace_back(Msg{.address = address, .name = name.toStdString(), .size = size});
- msg_map[address] = m;
- }
+ auto [_, address] = parseId(id);
+ auto &m = msgs[address];
+ m.name = name;
+ m.size = size;
emit msgUpdated(address);
}
void DBCManager::removeMsg(const QString &id) {
uint32_t address = parseId(id).second;
- auto it = std::find_if(dbc->msgs.begin(), dbc->msgs.end(), [address](auto &m) { return m.address == address; });
- if (it != dbc->msgs.end()) {
- dbc->msgs.erase(it);
- updateMsgMap();
- emit msgRemoved(address);
- }
+ msgs.erase(address);
+ emit msgRemoved(address);
}
void DBCManager::addSignal(const QString &id, const Signal &sig) {
- if (Msg *m = const_cast(msg(id))) {
- emit signalAdded(&m->sigs.emplace_back(sig));
+ if (auto m = const_cast(msg(id))) {
+ auto &s = m->sigs[sig.name.c_str()];
+ s = sig;
+ emit signalAdded(&s);
}
}
void DBCManager::updateSignal(const QString &id, const QString &sig_name, const Signal &sig) {
- if (Msg *m = const_cast(msg(id))) {
- auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); });
- if (it != m->sigs.end()) {
- *it = sig;
- emit signalUpdated(&(*it));
- }
+ if (auto m = const_cast(msg(id))) {
+ // change key name
+ QString new_name = QString::fromStdString(sig.name);
+ auto node = m->sigs.extract(sig_name);
+ node.key() = new_name;
+ auto it = m->sigs.insert(std::move(node));
+ auto &s = m->sigs[new_name];
+ s = sig;
+ emit signalUpdated(&s);
}
}
void DBCManager::removeSignal(const QString &id, const QString &sig_name) {
- if (Msg *m = const_cast(msg(id))) {
- auto it = std::find_if(m->sigs.begin(), m->sigs.end(), [=](auto &sig) { return sig_name == sig.name.c_str(); });
+ if (auto m = const_cast(msg(id))) {
+ auto it = m->sigs.find(sig_name);
if (it != m->sigs.end()) {
- emit signalRemoved(&(*it));
+ emit signalRemoved(&(it->second));
m->sigs.erase(it);
}
}
@@ -164,3 +165,11 @@ std::pair getSignalRange(const Signal *s) {
int to = from + s->size - 1;
return {from, to};
}
+
+bool operator==(const Signal &l, const Signal &r) {
+ return l.name == r.name && l.size == r.size &&
+ l.start_bit == r.start_bit &&
+ l.msb == r.msb && l.lsb == r.lsb &&
+ l.is_signed == r.is_signed && l.is_little_endian == r.is_little_endian &&
+ l.factor == r.factor && l.offset == r.offset;
+}
diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h
index 81c723a20d..b1d2082969 100644
--- a/tools/cabana/dbcmanager.h
+++ b/tools/cabana/dbcmanager.h
@@ -1,9 +1,16 @@
#pragma once
+#include