Release 260111
This commit is contained in:
4
selfdrive/pandad/__init__.py
Normal file
4
selfdrive/pandad/__init__.py
Normal file
@@ -0,0 +1,4 @@
|
||||
# Cython, now uses scons to build
|
||||
from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp, can_capnp_to_list
|
||||
assert can_list_to_can_capnp
|
||||
assert can_capnp_to_list
|
||||
15
selfdrive/pandad/can_types.h
Normal file
15
selfdrive/pandad/can_types.h
Normal file
@@ -0,0 +1,15 @@
|
||||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <cstdint>
|
||||
|
||||
struct CanFrame {
|
||||
long src;
|
||||
uint32_t address;
|
||||
std::vector<uint8_t> dat;
|
||||
};
|
||||
|
||||
struct CanData {
|
||||
uint64_t nanos;
|
||||
std::vector<CanFrame> frames;
|
||||
};
|
||||
99
selfdrive/pandad/panda.h
Normal file
99
selfdrive/pandad/panda.h
Normal file
@@ -0,0 +1,99 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
#include <ctime>
|
||||
#include <functional>
|
||||
#include <list>
|
||||
#include <memory>
|
||||
#include <optional>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "cereal/gen/cpp/car.capnp.h"
|
||||
#include "cereal/gen/cpp/log.capnp.h"
|
||||
#include "panda/board/health.h"
|
||||
#include "panda/board/can.h"
|
||||
#include "selfdrive/pandad/panda_comms.h"
|
||||
|
||||
#define USB_TX_SOFT_LIMIT (0x100U)
|
||||
#define USBPACKET_MAX_SIZE (0x40)
|
||||
|
||||
#define RECV_SIZE (0x4000U)
|
||||
|
||||
#define CAN_REJECTED_BUS_OFFSET 0xC0U
|
||||
#define CAN_RETURNED_BUS_OFFSET 0x80U
|
||||
|
||||
#define PANDA_BUS_OFFSET 4
|
||||
|
||||
struct __attribute__((packed)) can_header {
|
||||
uint8_t reserved : 1;
|
||||
uint8_t bus : 3;
|
||||
uint8_t data_len_code : 4;
|
||||
uint8_t rejected : 1;
|
||||
uint8_t returned : 1;
|
||||
uint8_t extended : 1;
|
||||
uint32_t addr : 29;
|
||||
uint8_t checksum : 8;
|
||||
};
|
||||
|
||||
struct can_frame {
|
||||
long address;
|
||||
std::string dat;
|
||||
long src;
|
||||
};
|
||||
|
||||
|
||||
class Panda {
|
||||
private:
|
||||
std::unique_ptr<PandaCommsHandle> handle;
|
||||
|
||||
public:
|
||||
Panda(std::string serial="", uint32_t bus_offset=0);
|
||||
|
||||
cereal::PandaState::PandaType hw_type = cereal::PandaState::PandaType::UNKNOWN;
|
||||
const uint32_t bus_offset;
|
||||
|
||||
bool connected();
|
||||
bool comms_healthy();
|
||||
std::string hw_serial();
|
||||
|
||||
// Static functions
|
||||
static std::vector<std::string> list(bool usb_only=false);
|
||||
|
||||
// Panda functionality
|
||||
cereal::PandaState::PandaType get_hw_type();
|
||||
void set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param=0U);
|
||||
void set_alternative_experience(uint16_t alternative_experience);
|
||||
std::string serial_read(int port_number = 0);
|
||||
void set_uart_baud(int uart, int rate);
|
||||
void set_fan_speed(uint16_t fan_speed);
|
||||
uint16_t get_fan_speed();
|
||||
void set_ir_pwr(uint16_t ir_pwr);
|
||||
std::optional<health_t> get_state();
|
||||
std::optional<can_health_t> get_can_state(uint16_t can_number);
|
||||
void set_loopback(bool loopback);
|
||||
std::optional<std::vector<uint8_t>> get_firmware_version();
|
||||
bool up_to_date();
|
||||
std::optional<std::string> get_serial();
|
||||
void set_power_saving(bool power_saving);
|
||||
void enable_deepsleep();
|
||||
void send_heartbeat(bool engaged);
|
||||
void set_can_speed_kbps(uint16_t bus, uint16_t speed);
|
||||
void set_can_fd_auto(uint16_t bus, bool enabled);
|
||||
void set_data_speed_kbps(uint16_t bus, uint16_t speed);
|
||||
void set_canfd_non_iso(uint16_t bus, bool non_iso);
|
||||
void can_send(const capnp::List<cereal::CanData>::Reader &can_data_list);
|
||||
bool can_receive(std::vector<can_frame>& out_vec);
|
||||
void can_reset_communications();
|
||||
|
||||
protected:
|
||||
// for unit tests
|
||||
uint8_t receive_buffer[RECV_SIZE + sizeof(can_header) + 64];
|
||||
uint32_t receive_buffer_size = 0;
|
||||
|
||||
Panda(uint32_t bus_offset) : bus_offset(bus_offset) {}
|
||||
void pack_can_buffer(const capnp::List<cereal::CanData>::Reader &can_data_list,
|
||||
std::function<void(uint8_t *, size_t)> write_func);
|
||||
bool unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector<can_frame> &out_vec);
|
||||
uint8_t calculate_checksum(uint8_t *data, uint32_t len);
|
||||
};
|
||||
93
selfdrive/pandad/panda_comms.h
Normal file
93
selfdrive/pandad/panda_comms.h
Normal file
@@ -0,0 +1,93 @@
|
||||
#pragma once
|
||||
|
||||
#include <atomic>
|
||||
#include <cstdint>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#ifndef __APPLE__
|
||||
#include <linux/spi/spidev.h>
|
||||
#endif
|
||||
|
||||
#include <libusb-1.0/libusb.h>
|
||||
|
||||
|
||||
#define TIMEOUT 0
|
||||
#define SPI_BUF_SIZE 2048
|
||||
|
||||
|
||||
// comms base class
|
||||
class PandaCommsHandle {
|
||||
public:
|
||||
PandaCommsHandle(std::string serial) {}
|
||||
virtual ~PandaCommsHandle() {}
|
||||
virtual void cleanup() = 0;
|
||||
|
||||
std::string hw_serial;
|
||||
std::atomic<bool> connected = true;
|
||||
std::atomic<bool> comms_healthy = true;
|
||||
static std::vector<std::string> list();
|
||||
|
||||
// HW communication
|
||||
virtual int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT) = 0;
|
||||
virtual int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT) = 0;
|
||||
virtual int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0;
|
||||
virtual int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0;
|
||||
};
|
||||
|
||||
class PandaUsbHandle : public PandaCommsHandle {
|
||||
public:
|
||||
PandaUsbHandle(std::string serial);
|
||||
~PandaUsbHandle();
|
||||
int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT);
|
||||
int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT);
|
||||
int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
|
||||
int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
|
||||
void cleanup();
|
||||
|
||||
static std::vector<std::string> list();
|
||||
|
||||
private:
|
||||
libusb_context *ctx = NULL;
|
||||
libusb_device_handle *dev_handle = NULL;
|
||||
std::recursive_mutex hw_lock;
|
||||
void handle_usb_issue(int err, const char func[]);
|
||||
};
|
||||
|
||||
#ifndef __APPLE__
|
||||
struct __attribute__((packed)) spi_header {
|
||||
uint8_t sync;
|
||||
uint8_t endpoint;
|
||||
uint16_t tx_len;
|
||||
uint16_t max_rx_len;
|
||||
};
|
||||
|
||||
class PandaSpiHandle : public PandaCommsHandle {
|
||||
public:
|
||||
PandaSpiHandle(std::string serial);
|
||||
~PandaSpiHandle();
|
||||
int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT);
|
||||
int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT);
|
||||
int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
|
||||
int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
|
||||
void cleanup();
|
||||
|
||||
static std::vector<std::string> list();
|
||||
|
||||
private:
|
||||
int spi_fd = -1;
|
||||
uint8_t tx_buf[SPI_BUF_SIZE];
|
||||
uint8_t rx_buf[SPI_BUF_SIZE];
|
||||
inline static std::recursive_mutex hw_lock;
|
||||
|
||||
int wait_for_ack(uint8_t ack, uint8_t tx, unsigned int timeout, unsigned int length);
|
||||
int bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len, unsigned int timeout);
|
||||
int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout);
|
||||
int spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout);
|
||||
int lltransfer(spi_ioc_transfer &t);
|
||||
|
||||
spi_header header;
|
||||
uint32_t xfer_count = 0;
|
||||
};
|
||||
#endif
|
||||
BIN
selfdrive/pandad/pandad
Executable file
BIN
selfdrive/pandad/pandad
Executable file
Binary file not shown.
27
selfdrive/pandad/pandad.h
Normal file
27
selfdrive/pandad/pandad.h
Normal file
@@ -0,0 +1,27 @@
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "common/params.h"
|
||||
#include "selfdrive/pandad/panda.h"
|
||||
|
||||
void pandad_main_thread(std::vector<std::string> serials);
|
||||
|
||||
class PandaSafety {
|
||||
public:
|
||||
PandaSafety(const std::vector<Panda *> &pandas) : pandas_(pandas) {}
|
||||
void configureSafetyMode();
|
||||
|
||||
private:
|
||||
void updateMultiplexingMode();
|
||||
std::string fetchCarParams();
|
||||
void setSafetyMode(const std::string ¶ms_string);
|
||||
|
||||
bool initialized_ = false;
|
||||
bool log_once_ = false;
|
||||
bool safety_configured_ = false;
|
||||
bool prev_obd_multiplexing_ = false;
|
||||
std::vector<Panda *> pandas_;
|
||||
Params params_;
|
||||
};
|
||||
179
selfdrive/pandad/pandad.py
Executable file
179
selfdrive/pandad/pandad.py
Executable file
@@ -0,0 +1,179 @@
|
||||
#!/usr/bin/env python3
|
||||
# simple pandad wrapper that updates the panda first
|
||||
import os
|
||||
import usb1
|
||||
import time
|
||||
import signal
|
||||
import subprocess
|
||||
|
||||
from panda import Panda, PandaDFU, PandaProtocolMismatch, FW_PATH
|
||||
from openpilot.common.basedir import BASEDIR
|
||||
from openpilot.common.params import Params
|
||||
from openpilot.system.hardware import HARDWARE
|
||||
from openpilot.common.swaglog import cloudlog
|
||||
|
||||
|
||||
def get_expected_signature(panda: Panda) -> bytes:
|
||||
try:
|
||||
fn = os.path.join(FW_PATH, panda.get_mcu_type().config.app_fn)
|
||||
return Panda.get_signature_from_firmware(fn)
|
||||
except Exception:
|
||||
cloudlog.exception("Error computing expected signature")
|
||||
return b""
|
||||
|
||||
def flash_panda(panda_serial: str) -> Panda:
|
||||
try:
|
||||
panda = Panda(panda_serial)
|
||||
except PandaProtocolMismatch:
|
||||
cloudlog.warning("detected protocol mismatch, reflashing panda")
|
||||
HARDWARE.recover_internal_panda()
|
||||
raise
|
||||
|
||||
fw_signature = get_expected_signature(panda)
|
||||
internal_panda = panda.is_internal()
|
||||
|
||||
panda_version = "bootstub" if panda.bootstub else panda.get_version()
|
||||
panda_signature = b"" if panda.bootstub else panda.get_signature()
|
||||
cloudlog.warning(f"Panda {panda_serial} connected, version: {panda_version}, signature {panda_signature.hex()[:16]}, expected {fw_signature.hex()[:16]}")
|
||||
|
||||
if panda.bootstub or panda_signature != fw_signature:
|
||||
cloudlog.info("Panda firmware out of date, update required")
|
||||
panda.flash()
|
||||
cloudlog.info("Done flashing")
|
||||
|
||||
if panda.bootstub:
|
||||
bootstub_version = panda.get_version()
|
||||
cloudlog.info(f"Flashed firmware not booting, flashing development bootloader. {bootstub_version=}, {internal_panda=}")
|
||||
if internal_panda:
|
||||
HARDWARE.recover_internal_panda()
|
||||
panda.recover(reset=(not internal_panda))
|
||||
cloudlog.info("Done flashing bootstub")
|
||||
|
||||
if panda.bootstub:
|
||||
cloudlog.info("Panda still not booting, exiting")
|
||||
raise AssertionError
|
||||
|
||||
panda_signature = panda.get_signature()
|
||||
if panda_signature != fw_signature:
|
||||
cloudlog.info("Version mismatch after flashing, exiting")
|
||||
raise AssertionError
|
||||
|
||||
return panda
|
||||
|
||||
|
||||
def main() -> None:
|
||||
# signal pandad to close the relay and exit
|
||||
def signal_handler(signum, frame):
|
||||
cloudlog.info(f"Caught signal {signum}, exiting")
|
||||
nonlocal do_exit
|
||||
do_exit = True
|
||||
if process is not None:
|
||||
process.send_signal(signal.SIGINT)
|
||||
|
||||
process = None
|
||||
do_exit = False
|
||||
signal.signal(signal.SIGINT, signal_handler)
|
||||
|
||||
count = 0
|
||||
first_run = True
|
||||
params = Params()
|
||||
no_internal_panda_count = 0
|
||||
|
||||
while not do_exit:
|
||||
try:
|
||||
count += 1
|
||||
cloudlog.event("pandad.flash_and_connect", count=count)
|
||||
params.remove("PandaSignatures")
|
||||
|
||||
# TODO: remove this in the next AGNOS
|
||||
# wait until USB is up before counting
|
||||
if time.monotonic() < 25.:
|
||||
no_internal_panda_count = 0
|
||||
|
||||
# Handle missing internal panda
|
||||
if no_internal_panda_count > 0:
|
||||
if no_internal_panda_count == 3:
|
||||
cloudlog.info("No pandas found, putting internal panda into DFU")
|
||||
HARDWARE.recover_internal_panda()
|
||||
else:
|
||||
cloudlog.info("No pandas found, resetting internal panda")
|
||||
HARDWARE.reset_internal_panda()
|
||||
time.sleep(3) # wait to come back up
|
||||
|
||||
# Flash all Pandas in DFU mode
|
||||
dfu_serials = PandaDFU.list()
|
||||
if len(dfu_serials) > 0:
|
||||
for serial in dfu_serials:
|
||||
cloudlog.info(f"Panda in DFU mode found, flashing recovery {serial}")
|
||||
PandaDFU(serial).recover()
|
||||
time.sleep(1)
|
||||
|
||||
panda_serials = Panda.list()
|
||||
if len(panda_serials) == 0:
|
||||
no_internal_panda_count += 1
|
||||
continue
|
||||
|
||||
cloudlog.info(f"{len(panda_serials)} panda(s) found, connecting - {panda_serials}")
|
||||
|
||||
# Flash pandas
|
||||
pandas: list[Panda] = []
|
||||
for serial in panda_serials:
|
||||
pandas.append(flash_panda(serial))
|
||||
|
||||
# Ensure internal panda is present if expected
|
||||
internal_pandas = [panda for panda in pandas if panda.is_internal()]
|
||||
if HARDWARE.has_internal_panda() and len(internal_pandas) == 0:
|
||||
cloudlog.error("Internal panda is missing, trying again")
|
||||
no_internal_panda_count += 1
|
||||
continue
|
||||
no_internal_panda_count = 0
|
||||
|
||||
# sort pandas to have deterministic order
|
||||
# * the internal one is always first
|
||||
# * then sort by hardware type
|
||||
# * as a last resort, sort by serial number
|
||||
pandas.sort(key=lambda x: (not x.is_internal(), x.get_type(), x.get_usb_serial()))
|
||||
panda_serials = [p.get_usb_serial() for p in pandas]
|
||||
|
||||
# log panda fw versions
|
||||
params.put("PandaSignatures", b','.join(p.get_signature() for p in pandas))
|
||||
|
||||
for panda in pandas:
|
||||
# check health for lost heartbeat
|
||||
health = panda.health()
|
||||
if health["heartbeat_lost"]:
|
||||
params.put_bool("PandaHeartbeatLost", True)
|
||||
cloudlog.event("heartbeat lost", deviceState=health, serial=panda.get_usb_serial())
|
||||
if health["som_reset_triggered"]:
|
||||
params.put_bool("PandaSomResetTriggered", True)
|
||||
cloudlog.event("panda.som_reset_triggered", health=health, serial=panda.get_usb_serial())
|
||||
|
||||
if first_run:
|
||||
# reset panda to ensure we're in a good state
|
||||
cloudlog.info(f"Resetting panda {panda.get_usb_serial()}")
|
||||
panda.reset(reconnect=True)
|
||||
|
||||
for p in pandas:
|
||||
p.close()
|
||||
# TODO: wrap all panda exceptions in a base panda exception
|
||||
except (usb1.USBErrorNoDevice, usb1.USBErrorPipe):
|
||||
# a panda was disconnected while setting everything up. let's try again
|
||||
cloudlog.exception("Panda USB exception while setting up")
|
||||
continue
|
||||
except PandaProtocolMismatch:
|
||||
cloudlog.exception("pandad.protocol_mismatch")
|
||||
continue
|
||||
except Exception:
|
||||
cloudlog.exception("pandad.uncaught_exception")
|
||||
continue
|
||||
|
||||
first_run = False
|
||||
|
||||
# run pandad with all connected serials as arguments
|
||||
os.environ['MANAGER_DAEMON'] = 'pandad'
|
||||
process = subprocess.Popen(["./pandad", *panda_serials], cwd=os.path.join(BASEDIR, "selfdrive/pandad"))
|
||||
process.wait()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
56
selfdrive/pandad/pandad_api_impl.pyx
Normal file
56
selfdrive/pandad/pandad_api_impl.pyx
Normal file
@@ -0,0 +1,56 @@
|
||||
# distutils: language = c++
|
||||
# cython: language_level=3
|
||||
from cython.operator cimport dereference as deref, preincrement as preinc
|
||||
from libcpp.vector cimport vector
|
||||
from libcpp.string cimport string
|
||||
from libcpp cimport bool
|
||||
from libc.stdint cimport uint8_t, uint32_t, uint64_t
|
||||
|
||||
cdef extern from "selfdrive/pandad/can_types.h":
|
||||
cdef struct CanFrame:
|
||||
long src
|
||||
uint32_t address
|
||||
vector[uint8_t] dat
|
||||
|
||||
cdef struct CanData:
|
||||
uint64_t nanos
|
||||
vector[CanFrame] frames
|
||||
|
||||
cdef extern from "can_list_to_can_capnp.cc":
|
||||
void can_list_to_can_capnp_cpp(const vector[CanFrame] &can_list, string &out, bool sendcan, bool valid) nogil
|
||||
void can_capnp_to_can_list_cpp(const vector[string] &strings, vector[CanData] &can_data, bool sendcan)
|
||||
|
||||
def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True):
|
||||
cdef CanFrame *f
|
||||
cdef vector[CanFrame] can_list
|
||||
cdef uint32_t cpp_can_msgs_len = len(can_msgs)
|
||||
|
||||
with nogil:
|
||||
can_list.reserve(cpp_can_msgs_len)
|
||||
|
||||
for can_msg in can_msgs:
|
||||
f = &(can_list.emplace_back())
|
||||
f.address = can_msg[0]
|
||||
f.dat = can_msg[1]
|
||||
f.src = can_msg[2]
|
||||
|
||||
cdef string out
|
||||
cdef bool is_sendcan = (msgtype == 'sendcan')
|
||||
cdef bool is_valid = valid
|
||||
with nogil:
|
||||
can_list_to_can_capnp_cpp(can_list, out, is_sendcan, is_valid)
|
||||
return out
|
||||
|
||||
def can_capnp_to_list(strings, msgtype='can'):
|
||||
cdef vector[CanData] data
|
||||
can_capnp_to_can_list_cpp(strings, data, msgtype == 'sendcan')
|
||||
|
||||
result = []
|
||||
cdef CanData *d
|
||||
cdef vector[CanData].iterator it = data.begin()
|
||||
while it != data.end():
|
||||
d = &deref(it)
|
||||
frames = [(f.address, (<char *>&f.dat[0])[:f.dat.size()], f.src) for f in d.frames]
|
||||
result.append((d.nanos, frames))
|
||||
preinc(it)
|
||||
return result
|
||||
BIN
selfdrive/pandad/pandad_api_impl.so
Executable file
BIN
selfdrive/pandad/pandad_api_impl.so
Executable file
Binary file not shown.
0
selfdrive/pandad/tests/__init__.py
Normal file
0
selfdrive/pandad/tests/__init__.py
Normal file
BIN
selfdrive/pandad/tests/bootstub.panda.bin
Executable file
BIN
selfdrive/pandad/tests/bootstub.panda.bin
Executable file
Binary file not shown.
BIN
selfdrive/pandad/tests/bootstub.panda_h7.bin
Executable file
BIN
selfdrive/pandad/tests/bootstub.panda_h7.bin
Executable file
Binary file not shown.
BIN
selfdrive/pandad/tests/bootstub.panda_h7_spiv0.bin
Executable file
BIN
selfdrive/pandad/tests/bootstub.panda_h7_spiv0.bin
Executable file
Binary file not shown.
129
selfdrive/pandad/tests/test_pandad.py
Normal file
129
selfdrive/pandad/tests/test_pandad.py
Normal file
@@ -0,0 +1,129 @@
|
||||
import os
|
||||
import pytest
|
||||
import time
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from cereal import log
|
||||
from openpilot.common.gpio import gpio_set, gpio_init
|
||||
from panda import Panda, PandaDFU, PandaProtocolMismatch
|
||||
from openpilot.common.retry import retry
|
||||
from openpilot.system.manager.process_config import managed_processes
|
||||
from openpilot.system.hardware import HARDWARE
|
||||
from openpilot.system.hardware.tici.pins import GPIO
|
||||
|
||||
HERE = os.path.dirname(os.path.realpath(__file__))
|
||||
|
||||
|
||||
@pytest.mark.tici
|
||||
class TestPandad:
|
||||
|
||||
def setup_method(self):
|
||||
# ensure panda is up
|
||||
if len(Panda.list()) == 0:
|
||||
self._run_test(60)
|
||||
|
||||
self.spi = HARDWARE.get_device_type() != 'tici'
|
||||
|
||||
def teardown_method(self):
|
||||
managed_processes['pandad'].stop()
|
||||
|
||||
def _run_test(self, timeout=30) -> float:
|
||||
st = time.monotonic()
|
||||
sm = messaging.SubMaster(['pandaStates'])
|
||||
|
||||
managed_processes['pandad'].start()
|
||||
while (time.monotonic() - st) < timeout:
|
||||
sm.update(100)
|
||||
if len(sm['pandaStates']) and sm['pandaStates'][0].pandaType != log.PandaState.PandaType.unknown:
|
||||
break
|
||||
dt = time.monotonic() - st
|
||||
managed_processes['pandad'].stop()
|
||||
|
||||
if len(sm['pandaStates']) == 0 or sm['pandaStates'][0].pandaType == log.PandaState.PandaType.unknown:
|
||||
raise Exception("pandad failed to start")
|
||||
|
||||
return dt
|
||||
|
||||
def _go_to_dfu(self):
|
||||
HARDWARE.recover_internal_panda()
|
||||
assert Panda.wait_for_dfu(None, 10)
|
||||
|
||||
def _assert_no_panda(self):
|
||||
assert not Panda.wait_for_dfu(None, 3)
|
||||
assert not Panda.wait_for_panda(None, 3)
|
||||
|
||||
@retry(attempts=3)
|
||||
def _flash_bootstub_and_test(self, fn, expect_mismatch=False):
|
||||
self._go_to_dfu()
|
||||
pd = PandaDFU(None)
|
||||
if fn is None:
|
||||
fn = os.path.join(HERE, pd.get_mcu_type().config.bootstub_fn)
|
||||
with open(fn, "rb") as f:
|
||||
pd.program_bootstub(f.read())
|
||||
pd.reset()
|
||||
HARDWARE.reset_internal_panda()
|
||||
|
||||
assert Panda.wait_for_panda(None, 10)
|
||||
if expect_mismatch:
|
||||
with pytest.raises(PandaProtocolMismatch):
|
||||
Panda()
|
||||
else:
|
||||
with Panda() as p:
|
||||
assert p.bootstub
|
||||
|
||||
self._run_test(45)
|
||||
|
||||
def test_in_dfu(self):
|
||||
HARDWARE.recover_internal_panda()
|
||||
self._run_test(60)
|
||||
|
||||
def test_in_bootstub(self):
|
||||
with Panda() as p:
|
||||
p.reset(enter_bootstub=True)
|
||||
assert p.bootstub
|
||||
self._run_test()
|
||||
|
||||
def test_internal_panda_reset(self):
|
||||
gpio_init(GPIO.STM_RST_N, True)
|
||||
gpio_set(GPIO.STM_RST_N, 1)
|
||||
time.sleep(0.5)
|
||||
assert all(not Panda(s).is_internal() for s in Panda.list())
|
||||
self._run_test()
|
||||
|
||||
assert any(Panda(s).is_internal() for s in Panda.list())
|
||||
|
||||
def test_best_case_startup_time(self):
|
||||
# run once so we're up to date
|
||||
self._run_test(60)
|
||||
|
||||
ts = []
|
||||
for _ in range(10):
|
||||
# should be nearly instant this time
|
||||
dt = self._run_test(5)
|
||||
ts.append(dt)
|
||||
|
||||
# 5s for USB (due to enumeration)
|
||||
# - 0.2s pandad -> pandad
|
||||
# - plus some buffer
|
||||
print("startup times", ts, sum(ts) / len(ts))
|
||||
assert 0.1 < (sum(ts)/len(ts)) < (0.7 if self.spi else 5.0)
|
||||
|
||||
def test_protocol_version_check(self):
|
||||
if not self.spi:
|
||||
pytest.skip("SPI test")
|
||||
# flash old fw
|
||||
fn = os.path.join(HERE, "bootstub.panda_h7_spiv0.bin")
|
||||
self._flash_bootstub_and_test(fn, expect_mismatch=True)
|
||||
|
||||
def test_release_to_devel_bootstub(self):
|
||||
self._flash_bootstub_and_test(None)
|
||||
|
||||
def test_recover_from_bad_bootstub(self):
|
||||
self._go_to_dfu()
|
||||
with PandaDFU(None) as pd:
|
||||
pd.program_bootstub(b"\x00"*1024)
|
||||
pd.reset()
|
||||
HARDWARE.reset_internal_panda()
|
||||
self._assert_no_panda()
|
||||
|
||||
self._run_test(60)
|
||||
113
selfdrive/pandad/tests/test_pandad_loopback.py
Normal file
113
selfdrive/pandad/tests/test_pandad_loopback.py
Normal file
@@ -0,0 +1,113 @@
|
||||
import os
|
||||
import copy
|
||||
import random
|
||||
import time
|
||||
import pytest
|
||||
from collections import defaultdict
|
||||
from pprint import pprint
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from cereal import car, log
|
||||
from opendbc.car.can_definitions import CanData
|
||||
from openpilot.common.retry import retry
|
||||
from openpilot.common.params import Params
|
||||
from openpilot.common.timeout import Timeout
|
||||
from openpilot.selfdrive.pandad import can_list_to_can_capnp
|
||||
from openpilot.system.hardware import TICI
|
||||
from openpilot.selfdrive.test.helpers import with_processes
|
||||
|
||||
|
||||
@retry(attempts=3)
|
||||
def setup_pandad(num_pandas):
|
||||
params = Params()
|
||||
params.clear_all()
|
||||
params.put_bool("IsOnroad", False)
|
||||
|
||||
sm = messaging.SubMaster(['pandaStates'])
|
||||
with Timeout(90, "pandad didn't start"):
|
||||
while sm.recv_frame['pandaStates'] < 1 or len(sm['pandaStates']) == 0 or \
|
||||
any(ps.pandaType == log.PandaState.PandaType.unknown for ps in sm['pandaStates']):
|
||||
sm.update(1000)
|
||||
|
||||
found_pandas = len(sm['pandaStates'])
|
||||
assert num_pandas == found_pandas, "connected pandas ({found_pandas}) doesn't match expected panda count ({num_pandas}). \
|
||||
connect another panda for multipanda tests."
|
||||
|
||||
# pandad safety setting relies on these params
|
||||
cp = car.CarParams.new_message()
|
||||
|
||||
safety_config = car.CarParams.SafetyConfig.new_message()
|
||||
safety_config.safetyModel = car.CarParams.SafetyModel.allOutput
|
||||
cp.safetyConfigs = [safety_config]*num_pandas
|
||||
|
||||
params.put_bool("IsOnroad", True)
|
||||
params.put_bool("FirmwareQueryDone", True)
|
||||
params.put_bool("ControlsReady", True)
|
||||
params.put("CarParams", cp.to_bytes())
|
||||
|
||||
with Timeout(90, "pandad didn't set safety mode"):
|
||||
while any(ps.safetyModel != car.CarParams.SafetyModel.allOutput for ps in sm['pandaStates']):
|
||||
sm.update(1000)
|
||||
|
||||
def send_random_can_messages(sendcan, count, num_pandas=1):
|
||||
sent_msgs = defaultdict(set)
|
||||
for _ in range(count):
|
||||
to_send = []
|
||||
for __ in range(random.randrange(20)):
|
||||
bus = random.choice([b for b in range(3*num_pandas) if b % 4 != 3])
|
||||
addr = random.randrange(1, 1<<29)
|
||||
dat = bytes(random.getrandbits(8) for _ in range(random.randrange(1, 9)))
|
||||
if (addr, dat) in sent_msgs[bus]:
|
||||
continue
|
||||
sent_msgs[bus].add((addr, dat))
|
||||
to_send.append(CanData(addr, dat, bus))
|
||||
sendcan.send(can_list_to_can_capnp(to_send, msgtype='sendcan'))
|
||||
return sent_msgs
|
||||
|
||||
|
||||
@pytest.mark.tici
|
||||
class TestBoarddLoopback:
|
||||
@classmethod
|
||||
def setup_class(cls):
|
||||
os.environ['STARTED'] = '1'
|
||||
os.environ['BOARDD_LOOPBACK'] = '1'
|
||||
|
||||
@with_processes(['pandad'])
|
||||
def test_loopback(self):
|
||||
num_pandas = 2 if TICI and "SINGLE_PANDA" not in os.environ else 1
|
||||
setup_pandad(num_pandas)
|
||||
|
||||
sendcan = messaging.pub_sock('sendcan')
|
||||
can = messaging.sub_sock('can', conflate=False, timeout=100)
|
||||
sm = messaging.SubMaster(['pandaStates'])
|
||||
time.sleep(1)
|
||||
|
||||
n = 200
|
||||
for i in range(n):
|
||||
print(f"pandad loopback {i}/{n}")
|
||||
|
||||
sent_msgs = send_random_can_messages(sendcan, random.randrange(20, 100), num_pandas)
|
||||
|
||||
sent_loopback = copy.deepcopy(sent_msgs)
|
||||
sent_loopback.update({k+128: copy.deepcopy(v) for k, v in sent_msgs.items()})
|
||||
sent_total = {k: len(v) for k, v in sent_loopback.items()}
|
||||
for _ in range(100 * 5):
|
||||
sm.update(0)
|
||||
recvd = messaging.drain_sock(can, wait_for_one=True)
|
||||
for msg in recvd:
|
||||
for m in msg.can:
|
||||
key = (m.address, m.dat)
|
||||
assert key in sent_loopback[m.src], f"got unexpected msg: {m.src=} {m.address=} {m.dat=}"
|
||||
sent_loopback[m.src].discard(key)
|
||||
|
||||
if all(len(v) == 0 for v in sent_loopback.values()):
|
||||
break
|
||||
|
||||
# if a set isn't empty, messages got dropped
|
||||
pprint(sent_msgs)
|
||||
pprint(sent_loopback)
|
||||
print({k: len(x) for k, x in sent_loopback.items()})
|
||||
print(sum([len(x) for x in sent_loopback.values()]))
|
||||
pprint(sm['pandaStates']) # may drop messages due to RX buffer overflow
|
||||
for bus in sent_loopback.keys():
|
||||
assert not len(sent_loopback[bus]), f"loop {i}: bus {bus} missing {len(sent_loopback[bus])} out of {sent_total[bus]} messages"
|
||||
105
selfdrive/pandad/tests/test_pandad_spi.py
Normal file
105
selfdrive/pandad/tests/test_pandad_spi.py
Normal file
@@ -0,0 +1,105 @@
|
||||
import os
|
||||
import time
|
||||
import numpy as np
|
||||
import pytest
|
||||
import random
|
||||
|
||||
import cereal.messaging as messaging
|
||||
from cereal.services import SERVICE_LIST
|
||||
from openpilot.system.hardware import HARDWARE
|
||||
from openpilot.selfdrive.test.helpers import with_processes
|
||||
from openpilot.selfdrive.pandad.tests.test_pandad_loopback import setup_pandad, send_random_can_messages
|
||||
|
||||
JUNGLE_SPAM = "JUNGLE_SPAM" in os.environ
|
||||
|
||||
@pytest.mark.tici
|
||||
class TestBoarddSpi:
|
||||
@classmethod
|
||||
def setup_class(cls):
|
||||
if HARDWARE.get_device_type() == 'tici':
|
||||
pytest.skip("only for spi pandas")
|
||||
os.environ['STARTED'] = '1'
|
||||
os.environ['SPI_ERR_PROB'] = '0.001'
|
||||
if not JUNGLE_SPAM:
|
||||
os.environ['BOARDD_LOOPBACK'] = '1'
|
||||
|
||||
@with_processes(['pandad'])
|
||||
def test_spi_corruption(self, subtests):
|
||||
setup_pandad(1)
|
||||
|
||||
sendcan = messaging.pub_sock('sendcan')
|
||||
socks = {s: messaging.sub_sock(s, conflate=False, timeout=100) for s in ('can', 'pandaStates', 'peripheralState')}
|
||||
time.sleep(2)
|
||||
for s in socks.values():
|
||||
messaging.drain_sock_raw(s)
|
||||
|
||||
total_recv_count = 0
|
||||
total_sent_count = 0
|
||||
sent_msgs = {bus: list() for bus in range(3)}
|
||||
|
||||
st = time.monotonic()
|
||||
ts = {s: list() for s in socks.keys()}
|
||||
for _ in range(int(os.getenv("TEST_TIME", "20"))):
|
||||
# send some CAN messages
|
||||
if not JUNGLE_SPAM:
|
||||
sent = send_random_can_messages(sendcan, random.randrange(2, 20))
|
||||
for k, v in sent.items():
|
||||
sent_msgs[k].extend(list(v))
|
||||
total_sent_count += len(v)
|
||||
|
||||
for service, sock in socks.items():
|
||||
for m in messaging.drain_sock(sock):
|
||||
ts[service].append(m.logMonoTime)
|
||||
|
||||
# sanity check for corruption
|
||||
assert m.valid or (service == "can")
|
||||
if service == "can":
|
||||
for msg in m.can:
|
||||
if JUNGLE_SPAM:
|
||||
# PandaJungle.set_generated_can(True)
|
||||
i = msg.address - 0x200
|
||||
assert msg.address >= 0x200
|
||||
assert msg.src == (i%3)
|
||||
assert msg.dat == b"\xff"*(i%8)
|
||||
total_recv_count += 1
|
||||
continue
|
||||
|
||||
if msg.src > 4:
|
||||
continue
|
||||
key = (msg.address, msg.dat)
|
||||
assert key in sent_msgs[msg.src], f"got unexpected msg: {msg.src=} {msg.address=} {msg.dat=}"
|
||||
# TODO: enable this
|
||||
#sent_msgs[msg.src].remove(key)
|
||||
total_recv_count += 1
|
||||
elif service == "pandaStates":
|
||||
assert len(m.pandaStates) == 1
|
||||
ps = m.pandaStates[0]
|
||||
assert ps.uptime < 1000
|
||||
assert ps.pandaType == "tres"
|
||||
assert ps.ignitionLine
|
||||
assert not ps.ignitionCan
|
||||
assert 4000 < ps.voltage < 14000
|
||||
elif service == "peripheralState":
|
||||
ps = m.peripheralState
|
||||
assert ps.pandaType == "tres"
|
||||
assert 4000 < ps.voltage < 14000
|
||||
assert 50 < ps.current < 1000
|
||||
assert ps.fanSpeedRpm < 10000
|
||||
|
||||
time.sleep(0.5)
|
||||
et = time.monotonic() - st
|
||||
|
||||
print("\n======== timing report ========")
|
||||
for service, times in ts.items():
|
||||
dts = np.diff(times)/1e6
|
||||
print(service.ljust(17), f"{np.mean(dts):7.2f} {np.min(dts):7.2f} {np.max(dts):7.2f}")
|
||||
with subtests.test(msg="timing check", service=service):
|
||||
edt = 1e3 / SERVICE_LIST[service].frequency
|
||||
assert edt*0.9 < np.mean(dts) < edt*1.1
|
||||
assert np.max(dts) < edt*8
|
||||
assert np.min(dts) < edt
|
||||
assert len(dts) >= ((et-0.5)*SERVICE_LIST[service].frequency*0.8)
|
||||
|
||||
with subtests.test(msg="CAN traffic"):
|
||||
print(f"Sent {total_sent_count} CAN messages, got {total_recv_count} back. {total_recv_count/(total_sent_count+1e-4):.2%} received")
|
||||
assert total_recv_count > 20
|
||||
Reference in New Issue
Block a user