Compare commits
18 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 7742b517b6 | |||
| fa5e1dcdf4 | |||
| ade1497457 | |||
| f1d3bff4fe | |||
| 791b2e7374 | |||
| df875bdf4d | |||
| 15a9cde274 | |||
| ae7643975d | |||
| 8609e455a0 | |||
| 029df375f5 | |||
| a9ceb3c851 | |||
| 425c349184 | |||
| bcbbfabbdb | |||
| b9c36dcca5 | |||
| db4e73577e | |||
| 35539ea934 | |||
| 8187771ab0 | |||
| b0e5b298fe |
@@ -46,7 +46,9 @@ extern "C" {
|
||||
#include <vector>
|
||||
#include "stm32_spi.h"
|
||||
#include "stm32_delay.h"
|
||||
#include "TinyGPSPlus.h"
|
||||
extern "C" {
|
||||
#include "um982_gps.h"
|
||||
}
|
||||
extern "C" {
|
||||
#include "GY_85_HAL.h"
|
||||
}
|
||||
@@ -121,8 +123,8 @@ UART_HandleTypeDef huart5;
|
||||
UART_HandleTypeDef huart3;
|
||||
|
||||
/* USER CODE BEGIN PV */
|
||||
// The TinyGPSPlus object
|
||||
TinyGPSPlus gps;
|
||||
// UM982 dual-antenna GPS receiver
|
||||
UM982_GPS_t um982;
|
||||
|
||||
// Global data structures
|
||||
GPS_Data_t current_gps_data = {0};
|
||||
@@ -173,7 +175,7 @@ float RADAR_Altitude;
|
||||
double RADAR_Longitude = 0;
|
||||
double RADAR_Latitude = 0;
|
||||
|
||||
extern uint8_t GUI_start_flag_received;
|
||||
extern uint8_t GUI_start_flag_received; // [STM32-006] Legacy, unused -- kept for linker compat
|
||||
|
||||
|
||||
//RADAR
|
||||
@@ -620,7 +622,8 @@ typedef enum {
|
||||
ERROR_POWER_SUPPLY,
|
||||
ERROR_TEMPERATURE_HIGH,
|
||||
ERROR_MEMORY_ALLOC,
|
||||
ERROR_WATCHDOG_TIMEOUT
|
||||
ERROR_WATCHDOG_TIMEOUT,
|
||||
ERROR_COUNT // must be last — used for bounds checking error_strings[]
|
||||
} SystemError_t;
|
||||
|
||||
static SystemError_t last_error = ERROR_NONE;
|
||||
@@ -631,21 +634,42 @@ static bool system_emergency_state = false;
|
||||
SystemError_t checkSystemHealth(void) {
|
||||
SystemError_t current_error = ERROR_NONE;
|
||||
|
||||
// 1. Check AD9523 Clock Generator
|
||||
static uint32_t last_clock_check = 0;
|
||||
if (HAL_GetTick() - last_clock_check > 5000) {
|
||||
GPIO_PinState s0 = HAL_GPIO_ReadPin(AD9523_STATUS0_GPIO_Port, AD9523_STATUS0_Pin);
|
||||
GPIO_PinState s1 = HAL_GPIO_ReadPin(AD9523_STATUS1_GPIO_Port, AD9523_STATUS1_Pin);
|
||||
DIAG_GPIO("CLK", "AD9523 STATUS0", s0);
|
||||
DIAG_GPIO("CLK", "AD9523 STATUS1", s1);
|
||||
if (s0 == GPIO_PIN_RESET || s1 == GPIO_PIN_RESET) {
|
||||
current_error = ERROR_AD9523_CLOCK;
|
||||
DIAG_ERR("CLK", "AD9523 clock health check FAILED (STATUS0=%d STATUS1=%d)", s0, s1);
|
||||
// 0. Watchdog: detect main-loop stall (checkSystemHealth not called for >60 s).
|
||||
// Timestamp is captured at function ENTRY and updated unconditionally, so
|
||||
// any early return from a sub-check below cannot leave a stale value that
|
||||
// would later trip a spurious ERROR_WATCHDOG_TIMEOUT. A dedicated cold-start
|
||||
// branch ensures the first call after boot never trips (last_health_check==0
|
||||
// would otherwise make `HAL_GetTick() - 0 > 60000` true forever after the
|
||||
// 60-s mark of the init sequence).
|
||||
static uint32_t last_health_check = 0;
|
||||
uint32_t now_tick = HAL_GetTick();
|
||||
if (last_health_check == 0) {
|
||||
last_health_check = now_tick; // cold start: seed only
|
||||
} else {
|
||||
uint32_t elapsed = now_tick - last_health_check;
|
||||
last_health_check = now_tick; // update BEFORE any early return
|
||||
if (elapsed > 60000) {
|
||||
current_error = ERROR_WATCHDOG_TIMEOUT;
|
||||
DIAG_ERR("SYS", "Health check: Watchdog timeout (>60s since last check)");
|
||||
return current_error;
|
||||
}
|
||||
last_clock_check = HAL_GetTick();
|
||||
}
|
||||
|
||||
// 1. Check AD9523 Clock Generator
|
||||
static uint32_t last_clock_check = 0;
|
||||
if (HAL_GetTick() - last_clock_check > 5000) {
|
||||
GPIO_PinState s0 = HAL_GPIO_ReadPin(AD9523_STATUS0_GPIO_Port, AD9523_STATUS0_Pin);
|
||||
GPIO_PinState s1 = HAL_GPIO_ReadPin(AD9523_STATUS1_GPIO_Port, AD9523_STATUS1_Pin);
|
||||
DIAG_GPIO("CLK", "AD9523 STATUS0", s0);
|
||||
DIAG_GPIO("CLK", "AD9523 STATUS1", s1);
|
||||
if (s0 == GPIO_PIN_RESET || s1 == GPIO_PIN_RESET) {
|
||||
current_error = ERROR_AD9523_CLOCK;
|
||||
DIAG_ERR("CLK", "AD9523 clock health check FAILED (STATUS0=%d STATUS1=%d)", s0, s1);
|
||||
return current_error;
|
||||
}
|
||||
last_clock_check = HAL_GetTick();
|
||||
}
|
||||
|
||||
// 2. Check ADF4382 Lock Status
|
||||
bool tx_locked, rx_locked;
|
||||
if (ADF4382A_CheckLockStatus(&lo_manager, &tx_locked, &rx_locked) == ADF4382A_MANAGER_OK) {
|
||||
@@ -679,37 +703,34 @@ SystemError_t checkSystemHealth(void) {
|
||||
|
||||
// 4. Check IMU Communication
|
||||
static uint32_t last_imu_check = 0;
|
||||
if (HAL_GetTick() - last_imu_check > 10000) {
|
||||
if (!GY85_Update(&imu)) {
|
||||
current_error = ERROR_IMU_COMM;
|
||||
DIAG_ERR("IMU", "Health check: GY85_Update() FAILED");
|
||||
return current_error;
|
||||
}
|
||||
last_imu_check = HAL_GetTick();
|
||||
}
|
||||
if (HAL_GetTick() - last_imu_check > 10000) {
|
||||
if (!GY85_Update(&imu)) {
|
||||
current_error = ERROR_IMU_COMM;
|
||||
DIAG_ERR("IMU", "Health check: GY85_Update() FAILED");
|
||||
return current_error;
|
||||
}
|
||||
last_imu_check = HAL_GetTick();
|
||||
}
|
||||
|
||||
// 5. Check BMP180 Communication
|
||||
static uint32_t last_bmp_check = 0;
|
||||
if (HAL_GetTick() - last_bmp_check > 15000) {
|
||||
double pressure = myBMP.getPressure();
|
||||
if (pressure < 30000.0 || pressure > 110000.0 || isnan(pressure)) {
|
||||
current_error = ERROR_BMP180_COMM;
|
||||
DIAG_ERR("SYS", "Health check: BMP180 pressure out of range: %.0f", pressure);
|
||||
return current_error;
|
||||
}
|
||||
last_bmp_check = HAL_GetTick();
|
||||
}
|
||||
if (HAL_GetTick() - last_bmp_check > 15000) {
|
||||
double pressure = myBMP.getPressure();
|
||||
if (pressure < 30000.0 || pressure > 110000.0 || isnan(pressure)) {
|
||||
current_error = ERROR_BMP180_COMM;
|
||||
DIAG_ERR("SYS", "Health check: BMP180 pressure out of range: %.0f", pressure);
|
||||
return current_error;
|
||||
}
|
||||
last_bmp_check = HAL_GetTick();
|
||||
}
|
||||
|
||||
// 6. Check GPS Communication
|
||||
static uint32_t last_gps_fix = 0;
|
||||
if (gps.location.isUpdated()) {
|
||||
last_gps_fix = HAL_GetTick();
|
||||
}
|
||||
if (HAL_GetTick() - last_gps_fix > 30000) {
|
||||
current_error = ERROR_GPS_COMM;
|
||||
DIAG_WARN("SYS", "Health check: GPS no fix for >30s");
|
||||
return current_error;
|
||||
}
|
||||
// 6. Check GPS Communication (30s grace period from boot / last valid fix)
|
||||
uint32_t gps_fix_age = um982_position_age(&um982);
|
||||
if (gps_fix_age > 30000) {
|
||||
current_error = ERROR_GPS_COMM;
|
||||
DIAG_WARN("SYS", "Health check: GPS no fix for >30s (age=%lu ms)", (unsigned long)gps_fix_age);
|
||||
return current_error;
|
||||
}
|
||||
|
||||
// 7. Check RF Power Amplifier Current
|
||||
if (PowerAmplifier) {
|
||||
@@ -734,14 +755,7 @@ SystemError_t checkSystemHealth(void) {
|
||||
return current_error;
|
||||
}
|
||||
|
||||
// 9. Simple watchdog check
|
||||
static uint32_t last_health_check = 0;
|
||||
if (HAL_GetTick() - last_health_check > 60000) {
|
||||
current_error = ERROR_WATCHDOG_TIMEOUT;
|
||||
DIAG_ERR("SYS", "Health check: Watchdog timeout (>60s since last check)");
|
||||
return current_error;
|
||||
}
|
||||
last_health_check = HAL_GetTick();
|
||||
// 9. Watchdog check is performed at function entry (see step 0).
|
||||
|
||||
if (current_error != ERROR_NONE) {
|
||||
DIAG_ERR("SYS", "checkSystemHealth returning error code %d", current_error);
|
||||
@@ -853,7 +867,7 @@ void handleSystemError(SystemError_t error) {
|
||||
DIAG_ERR("SYS", "handleSystemError: error=%d error_count=%lu", error, error_count);
|
||||
|
||||
char error_msg[100];
|
||||
const char* error_strings[] = {
|
||||
static const char* const error_strings[] = {
|
||||
"No error",
|
||||
"AD9523 Clock failure",
|
||||
"ADF4382 TX LO unlocked",
|
||||
@@ -873,9 +887,16 @@ void handleSystemError(SystemError_t error) {
|
||||
"Watchdog timeout"
|
||||
};
|
||||
|
||||
static_assert(sizeof(error_strings) / sizeof(error_strings[0]) == ERROR_COUNT,
|
||||
"error_strings[] and SystemError_t enum are out of sync");
|
||||
|
||||
const char* err_name = (error >= 0 && error < (int)(sizeof(error_strings) / sizeof(error_strings[0])))
|
||||
? error_strings[error]
|
||||
: "Unknown error";
|
||||
|
||||
snprintf(error_msg, sizeof(error_msg),
|
||||
"ERROR #%d: %s (Count: %lu)\r\n",
|
||||
error, error_strings[error], error_count);
|
||||
error, err_name, error_count);
|
||||
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
||||
|
||||
// Blink LED pattern based on error code
|
||||
@@ -901,7 +922,7 @@ void handleSystemError(SystemError_t error) {
|
||||
if ((error >= ERROR_RF_PA_OVERCURRENT && error <= ERROR_POWER_SUPPLY) ||
|
||||
error == ERROR_TEMPERATURE_HIGH ||
|
||||
error == ERROR_WATCHDOG_TIMEOUT) {
|
||||
DIAG_ERR("SYS", "CRITICAL ERROR (code %d: %s) -- initiating Emergency_Stop()", error, error_strings[error]);
|
||||
DIAG_ERR("SYS", "CRITICAL ERROR (code %d: %s) -- initiating Emergency_Stop()", error, err_name);
|
||||
snprintf(error_msg, sizeof(error_msg),
|
||||
"CRITICAL ERROR! Initiating emergency shutdown.\r\n");
|
||||
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
||||
@@ -1034,20 +1055,7 @@ static inline void delay_ms(uint32_t ms) { HAL_Delay(ms); }
|
||||
|
||||
|
||||
|
||||
// This custom version of delay() ensures that the gps object
|
||||
// is being "fed".
|
||||
static void smartDelay(unsigned long ms)
|
||||
{
|
||||
uint32_t start = HAL_GetTick();
|
||||
uint8_t ch;
|
||||
|
||||
do {
|
||||
// While there is new data available in UART (non-blocking)
|
||||
if (HAL_UART_Receive(&huart5, &ch, 1, 0) == HAL_OK) {
|
||||
gps.encode(ch); // Pass received byte to TinyGPS++ equivalent parser
|
||||
}
|
||||
} while (HAL_GetTick() - start < ms);
|
||||
}
|
||||
// smartDelay removed -- replaced by non-blocking um982_process() in main loop
|
||||
|
||||
// Small helper to enable DWT cycle counter for microdelay
|
||||
static void DWT_Init(void)
|
||||
@@ -1191,7 +1199,14 @@ static int configure_ad9523(void)
|
||||
|
||||
// init ad9523 defaults (fills any missing pdata defaults)
|
||||
DIAG("CLK", "Calling ad9523_init() -- fills pdata defaults");
|
||||
ad9523_init(&init_param);
|
||||
{
|
||||
int32_t init_ret = ad9523_init(&init_param);
|
||||
DIAG("CLK", "ad9523_init() returned %ld", (long)init_ret);
|
||||
if (init_ret != 0) {
|
||||
DIAG_ERR("CLK", "ad9523_init() FAILED (ret=%ld)", (long)init_ret);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/* [Bug #2 FIXED] Removed first ad9523_setup() call that was here.
|
||||
* It wrote to the chip while still in reset — writes were lost.
|
||||
@@ -1580,6 +1595,12 @@ int main(void)
|
||||
Yaw_Sensor = (180*atan2(magRawY,magRawX)/PI) - Mag_Declination;
|
||||
|
||||
if(Yaw_Sensor<0)Yaw_Sensor+=360;
|
||||
|
||||
// Override magnetometer heading with UM982 dual-antenna heading when available
|
||||
if (um982_is_heading_valid(&um982)) {
|
||||
Yaw_Sensor = um982_get_heading(&um982);
|
||||
}
|
||||
|
||||
RxEst_0 = RxEst_1;
|
||||
RyEst_0 = RyEst_1;
|
||||
RzEst_0 = RzEst_1;
|
||||
@@ -1755,14 +1776,38 @@ int main(void)
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////GPS/////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
for(int i=0; i<10;i++){
|
||||
smartDelay(1000);
|
||||
RADAR_Longitude = gps.location.lng();
|
||||
RADAR_Latitude = gps.location.lat();
|
||||
DIAG_SECTION("GPS INIT (UM982)");
|
||||
DIAG("GPS", "Initializing UM982 on UART5 @ 115200 (baseline=50cm, tol=3cm)");
|
||||
if (!um982_init(&um982, &huart5, 50.0f, 3.0f)) {
|
||||
DIAG_WARN("GPS", "UM982 init: no VERSIONA response -- module may need more time");
|
||||
// Not fatal: module may still start sending NMEA data after boot
|
||||
} else {
|
||||
DIAG("GPS", "UM982 init OK -- VERSIONA received");
|
||||
}
|
||||
|
||||
//move Stepper to position 1 = 0°
|
||||
HAL_GPIO_WritePin(STEPPER_CW_P_GPIO_Port, STEPPER_CW_P_Pin, GPIO_PIN_RESET);//Set stepper motor spinning direction to CCW
|
||||
// Collect GPS data for a few seconds (non-blocking pump)
|
||||
DIAG("GPS", "Pumping GPS for 5 seconds to acquire initial fix...");
|
||||
{
|
||||
uint32_t gps_start = HAL_GetTick();
|
||||
while (HAL_GetTick() - gps_start < 5000) {
|
||||
um982_process(&um982);
|
||||
HAL_Delay(10);
|
||||
}
|
||||
}
|
||||
RADAR_Longitude = um982_get_longitude(&um982);
|
||||
RADAR_Latitude = um982_get_latitude(&um982);
|
||||
DIAG("GPS", "Initial position: lat=%.6f lon=%.6f fix=%d sats=%d",
|
||||
RADAR_Latitude, RADAR_Longitude,
|
||||
um982_get_fix_quality(&um982), um982_get_num_sats(&um982));
|
||||
|
||||
// Re-apply heading after GPS init so the north-alignment stepper move uses
|
||||
// UM982 dual-antenna heading when available.
|
||||
if (um982_is_heading_valid(&um982)) {
|
||||
Yaw_Sensor = um982_get_heading(&um982);
|
||||
}
|
||||
|
||||
//move Stepper to position 1 = 0°
|
||||
HAL_GPIO_WritePin(STEPPER_CW_P_GPIO_Port, STEPPER_CW_P_Pin, GPIO_PIN_RESET);//Set stepper motor spinning direction to CCW
|
||||
//Point Stepper to North
|
||||
for(int i= 0;i<(int)(Yaw_Sensor*Stepper_steps/360);i++){
|
||||
HAL_GPIO_WritePin(STEPPER_CLK_P_GPIO_Port, STEPPER_CLK_P_Pin, GPIO_PIN_SET);
|
||||
@@ -1784,29 +1829,11 @@ int main(void)
|
||||
HAL_UART_Transmit(&huart3, (uint8_t*)gps_send_error, sizeof(gps_send_error) - 1, 1000);
|
||||
}
|
||||
|
||||
// Check if start flag was received and settings are ready
|
||||
do{
|
||||
if (usbHandler.isStartFlagReceived() &&
|
||||
usbHandler.getState() == USBHandler::USBState::READY_FOR_DATA) {
|
||||
|
||||
const RadarSettings& settings = usbHandler.getSettings();
|
||||
|
||||
// Use the settings to configure your radar system
|
||||
/*
|
||||
settings.getSystemFrequency();
|
||||
settings.getChirpDuration1();
|
||||
settings.getChirpDuration2();
|
||||
settings.getChirpsPerPosition();
|
||||
settings.getFreqMin();
|
||||
settings.getFreqMax();
|
||||
settings.getPRF1();
|
||||
settings.getPRF2();
|
||||
settings.getMaxDistance();
|
||||
*/
|
||||
|
||||
|
||||
}
|
||||
}while(!usbHandler.isStartFlagReceived());
|
||||
/* [STM32-006 FIXED] Removed blocking do-while loop that waited for
|
||||
* usbHandler.isStartFlagReceived(). The production V7 PyQt GUI does not
|
||||
* send the legacy 4-byte start flag [23,46,158,237], so this loop hung
|
||||
* the MCU at boot indefinitely. The USB settings handshake (if ever
|
||||
* re-enabled) should be handled non-blocking in the main loop. */
|
||||
|
||||
/***************************************************************/
|
||||
/************RF Power Amplifier Powering up sequence************/
|
||||
@@ -2031,6 +2058,18 @@ int main(void)
|
||||
}
|
||||
DIAG("SYS", "Exited safe mode blink loop -- system_emergency_state cleared");
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
////////////////////////// GPS: Non-blocking NMEA processing ////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
um982_process(&um982);
|
||||
|
||||
// Update position globals continuously
|
||||
if (um982_is_position_valid(&um982)) {
|
||||
RADAR_Latitude = um982_get_latitude(&um982);
|
||||
RADAR_Longitude = um982_get_longitude(&um982);
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
////////////////////////// Monitor ADF4382A lock status periodically//////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
@@ -2581,7 +2620,7 @@ static void MX_UART5_Init(void)
|
||||
|
||||
/* USER CODE END UART5_Init 1 */
|
||||
huart5.Instance = UART5;
|
||||
huart5.Init.BaudRate = 9600;
|
||||
huart5.Init.BaudRate = 115200;
|
||||
huart5.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart5.Init.StopBits = UART_STOPBITS_1;
|
||||
huart5.Init.Parity = UART_PARITY_NONE;
|
||||
|
||||
@@ -0,0 +1,586 @@
|
||||
/*******************************************************************************
|
||||
* um982_gps.c -- UM982 dual-antenna GNSS receiver driver implementation
|
||||
*
|
||||
* See um982_gps.h for API documentation.
|
||||
* Command syntax per Unicore N4 Command Reference EN R1.14.
|
||||
******************************************************************************/
|
||||
#include "um982_gps.h"
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
||||
/* ========================= Internal helpers ========================== */
|
||||
|
||||
/**
|
||||
* Advance to the next comma-delimited field in an NMEA sentence.
|
||||
* Returns pointer to the start of the next field (after the comma),
|
||||
* or NULL if no more commas found before end-of-string or '*'.
|
||||
*
|
||||
* Handles empty fields (consecutive commas) correctly by returning
|
||||
* a pointer to the character after the comma (which may be another comma).
|
||||
*/
|
||||
static const char *next_field(const char *p)
|
||||
{
|
||||
if (p == NULL) return NULL;
|
||||
while (*p != '\0' && *p != ',' && *p != '*') {
|
||||
p++;
|
||||
}
|
||||
if (*p == ',') return p + 1;
|
||||
return NULL; /* End of sentence or checksum marker */
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the length of the current field (up to next comma, '*', or '\0').
|
||||
*/
|
||||
static int field_len(const char *p)
|
||||
{
|
||||
int len = 0;
|
||||
if (p == NULL) return 0;
|
||||
while (p[len] != '\0' && p[len] != ',' && p[len] != '*') {
|
||||
len++;
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if a field is non-empty (has at least one character before delimiter).
|
||||
*/
|
||||
static bool field_valid(const char *p)
|
||||
{
|
||||
return p != NULL && field_len(p) > 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse a floating-point value from a field, returning 0.0 if empty.
|
||||
*/
|
||||
static double field_to_double(const char *p)
|
||||
{
|
||||
if (!field_valid(p)) return 0.0;
|
||||
return strtod(p, NULL);
|
||||
}
|
||||
|
||||
static float field_to_float(const char *p)
|
||||
{
|
||||
return (float)field_to_double(p);
|
||||
}
|
||||
|
||||
static int field_to_int(const char *p)
|
||||
{
|
||||
if (!field_valid(p)) return 0;
|
||||
return (int)strtol(p, NULL, 10);
|
||||
}
|
||||
|
||||
/* ========================= Checksum ================================== */
|
||||
|
||||
bool um982_verify_checksum(const char *sentence)
|
||||
{
|
||||
if (sentence == NULL || sentence[0] != '$') return false;
|
||||
|
||||
const char *p = sentence + 1; /* Skip '$' */
|
||||
uint8_t computed = 0;
|
||||
|
||||
while (*p != '\0' && *p != '*') {
|
||||
computed ^= (uint8_t)*p;
|
||||
p++;
|
||||
}
|
||||
|
||||
if (*p != '*') return false; /* No checksum marker found */
|
||||
p++; /* Skip '*' */
|
||||
|
||||
/* Parse 2-char hex checksum */
|
||||
if (p[0] == '\0' || p[1] == '\0') return false;
|
||||
|
||||
char hex_str[3] = { p[0], p[1], '\0' };
|
||||
unsigned long expected = strtoul(hex_str, NULL, 16);
|
||||
|
||||
return computed == (uint8_t)expected;
|
||||
}
|
||||
|
||||
/* ========================= Coordinate parsing ======================== */
|
||||
|
||||
double um982_parse_coord(const char *field, char hemisphere)
|
||||
{
|
||||
if (field == NULL || field[0] == '\0') return NAN;
|
||||
|
||||
/* Find the decimal point to determine degree digit count.
|
||||
* Latitude: ddmm.mmmm (dot at index 4, degrees = 2)
|
||||
* Longitude: dddmm.mmmm (dot at index 5, degrees = 3)
|
||||
* General: degree_digits = dot_position - 2
|
||||
*/
|
||||
const char *dot = strchr(field, '.');
|
||||
if (dot == NULL) return NAN;
|
||||
|
||||
int dot_pos = (int)(dot - field);
|
||||
int deg_digits = dot_pos - 2;
|
||||
|
||||
if (deg_digits < 1 || deg_digits > 3) return NAN;
|
||||
|
||||
/* Extract degree portion */
|
||||
double degrees = 0.0;
|
||||
for (int i = 0; i < deg_digits; i++) {
|
||||
if (field[i] < '0' || field[i] > '9') return NAN;
|
||||
degrees = degrees * 10.0 + (field[i] - '0');
|
||||
}
|
||||
|
||||
/* Extract minutes portion (everything from deg_digits onward) */
|
||||
double minutes = strtod(field + deg_digits, NULL);
|
||||
if (minutes < 0.0 || minutes >= 60.0) return NAN;
|
||||
|
||||
double result = degrees + minutes / 60.0;
|
||||
|
||||
/* Apply hemisphere sign */
|
||||
if (hemisphere == 'S' || hemisphere == 'W') {
|
||||
result = -result;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ========================= Sentence parsers ========================== */
|
||||
|
||||
/**
|
||||
* Identify the NMEA sentence type by skipping the 2-char talker ID
|
||||
* and comparing the 3-letter formatter.
|
||||
*
|
||||
* "$GNGGA,..." -> talker="GN", formatter="GGA"
|
||||
* "$GPTHS,..." -> talker="GP", formatter="THS"
|
||||
*
|
||||
* Returns pointer to the formatter (3 chars at sentence+3), or NULL
|
||||
* if sentence is too short.
|
||||
*/
|
||||
static const char *get_formatter(const char *sentence)
|
||||
{
|
||||
/* sentence starts with '$', followed by 2-char talker + 3-char formatter */
|
||||
if (sentence == NULL || strlen(sentence) < 6) return NULL;
|
||||
return sentence + 3; /* Skip "$XX" -> points to formatter */
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse GGA sentence — position and fix quality.
|
||||
*
|
||||
* Format: $--GGA,time,lat,N/S,lon,E/W,quality,numSat,hdop,alt,M,geoidSep,M,dgpsAge,refID*XX
|
||||
* field: 1 2 3 4 5 6 7 8 9 10 11 12 13 14
|
||||
*/
|
||||
static void parse_gga(UM982_GPS_t *gps, const char *sentence)
|
||||
{
|
||||
/* Skip to first field (after "$XXGGA,") */
|
||||
const char *f = strchr(sentence, ',');
|
||||
if (f == NULL) return;
|
||||
f++; /* f -> field 1 (time) */
|
||||
|
||||
/* Field 1: UTC time — skip for now */
|
||||
const char *f2 = next_field(f); /* lat */
|
||||
const char *f3 = next_field(f2); /* N/S */
|
||||
const char *f4 = next_field(f3); /* lon */
|
||||
const char *f5 = next_field(f4); /* E/W */
|
||||
const char *f6 = next_field(f5); /* quality */
|
||||
const char *f7 = next_field(f6); /* numSat */
|
||||
const char *f8 = next_field(f7); /* hdop */
|
||||
const char *f9 = next_field(f8); /* altitude */
|
||||
const char *f10 = next_field(f9); /* M */
|
||||
const char *f11 = next_field(f10); /* geoid sep */
|
||||
|
||||
uint32_t now = HAL_GetTick();
|
||||
|
||||
/* Parse fix quality first — if 0, position is meaningless */
|
||||
gps->fix_quality = (uint8_t)field_to_int(f6);
|
||||
|
||||
/* Parse coordinates */
|
||||
if (field_valid(f2) && field_valid(f3)) {
|
||||
char hem = field_valid(f3) ? *f3 : 'N';
|
||||
double lat = um982_parse_coord(f2, hem);
|
||||
if (!isnan(lat)) gps->latitude = lat;
|
||||
}
|
||||
|
||||
if (field_valid(f4) && field_valid(f5)) {
|
||||
char hem = field_valid(f5) ? *f5 : 'E';
|
||||
double lon = um982_parse_coord(f4, hem);
|
||||
if (!isnan(lon)) gps->longitude = lon;
|
||||
}
|
||||
|
||||
/* Number of satellites */
|
||||
gps->num_satellites = (uint8_t)field_to_int(f7);
|
||||
|
||||
/* HDOP */
|
||||
if (field_valid(f8)) {
|
||||
gps->hdop = field_to_float(f8);
|
||||
}
|
||||
|
||||
/* Altitude */
|
||||
if (field_valid(f9)) {
|
||||
gps->altitude = field_to_float(f9);
|
||||
}
|
||||
|
||||
/* Geoid separation */
|
||||
if (field_valid(f11)) {
|
||||
gps->geoid_sep = field_to_float(f11);
|
||||
}
|
||||
|
||||
gps->last_gga_tick = now;
|
||||
if (gps->fix_quality != UM982_FIX_NONE) {
|
||||
gps->last_fix_tick = now;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse RMC sentence — recommended minimum (position, speed, date).
|
||||
*
|
||||
* Format: $--RMC,time,status,lat,N/S,lon,E/W,speed,course,date,magVar,E/W,mode*XX
|
||||
* field: 1 2 3 4 5 6 7 8 9 10 11 12
|
||||
*/
|
||||
static void parse_rmc(UM982_GPS_t *gps, const char *sentence)
|
||||
{
|
||||
const char *f = strchr(sentence, ',');
|
||||
if (f == NULL) return;
|
||||
f++; /* f -> field 1 (time) */
|
||||
|
||||
const char *f2 = next_field(f); /* status */
|
||||
const char *f3 = next_field(f2); /* lat */
|
||||
const char *f4 = next_field(f3); /* N/S */
|
||||
const char *f5 = next_field(f4); /* lon */
|
||||
const char *f6 = next_field(f5); /* E/W */
|
||||
const char *f7 = next_field(f6); /* speed knots */
|
||||
const char *f8 = next_field(f7); /* course true */
|
||||
|
||||
/* Status */
|
||||
if (field_valid(f2)) {
|
||||
gps->rmc_status = *f2;
|
||||
}
|
||||
|
||||
/* Position (only if status = A for valid) */
|
||||
if (field_valid(f2) && *f2 == 'A') {
|
||||
if (field_valid(f3) && field_valid(f4)) {
|
||||
double lat = um982_parse_coord(f3, *f4);
|
||||
if (!isnan(lat)) gps->latitude = lat;
|
||||
}
|
||||
if (field_valid(f5) && field_valid(f6)) {
|
||||
double lon = um982_parse_coord(f5, *f6);
|
||||
if (!isnan(lon)) gps->longitude = lon;
|
||||
}
|
||||
}
|
||||
|
||||
/* Speed (knots) */
|
||||
if (field_valid(f7)) {
|
||||
gps->speed_knots = field_to_float(f7);
|
||||
}
|
||||
|
||||
/* Course */
|
||||
if (field_valid(f8)) {
|
||||
gps->course_true = field_to_float(f8);
|
||||
}
|
||||
|
||||
gps->last_rmc_tick = HAL_GetTick();
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse THS sentence — true heading and status (UM982-specific).
|
||||
*
|
||||
* Format: $--THS,heading,mode*XX
|
||||
* field: 1 2
|
||||
*/
|
||||
static void parse_ths(UM982_GPS_t *gps, const char *sentence)
|
||||
{
|
||||
const char *f = strchr(sentence, ',');
|
||||
if (f == NULL) return;
|
||||
f++; /* f -> field 1 (heading) */
|
||||
|
||||
const char *f2 = next_field(f); /* mode */
|
||||
|
||||
/* Heading */
|
||||
if (field_valid(f)) {
|
||||
gps->heading = field_to_float(f);
|
||||
} else {
|
||||
gps->heading = NAN;
|
||||
}
|
||||
|
||||
/* Mode */
|
||||
if (field_valid(f2)) {
|
||||
gps->heading_mode = *f2;
|
||||
} else {
|
||||
gps->heading_mode = 'V'; /* Not valid if missing */
|
||||
}
|
||||
|
||||
gps->last_ths_tick = HAL_GetTick();
|
||||
}
|
||||
|
||||
/**
|
||||
* Parse VTG sentence — course and speed over ground.
|
||||
*
|
||||
* Format: $--VTG,courseTrue,T,courseMag,M,speedKnots,N,speedKmh,K,mode*XX
|
||||
* field: 1 2 3 4 5 6 7 8 9
|
||||
*/
|
||||
static void parse_vtg(UM982_GPS_t *gps, const char *sentence)
|
||||
{
|
||||
const char *f = strchr(sentence, ',');
|
||||
if (f == NULL) return;
|
||||
f++; /* f -> field 1 (course true) */
|
||||
|
||||
const char *f2 = next_field(f); /* T */
|
||||
const char *f3 = next_field(f2); /* course mag */
|
||||
const char *f4 = next_field(f3); /* M */
|
||||
const char *f5 = next_field(f4); /* speed knots */
|
||||
const char *f6 = next_field(f5); /* N */
|
||||
const char *f7 = next_field(f6); /* speed km/h */
|
||||
|
||||
/* Course true */
|
||||
if (field_valid(f)) {
|
||||
gps->course_true = field_to_float(f);
|
||||
}
|
||||
|
||||
/* Speed knots */
|
||||
if (field_valid(f5)) {
|
||||
gps->speed_knots = field_to_float(f5);
|
||||
}
|
||||
|
||||
/* Speed km/h */
|
||||
if (field_valid(f7)) {
|
||||
gps->speed_kmh = field_to_float(f7);
|
||||
}
|
||||
|
||||
gps->last_vtg_tick = HAL_GetTick();
|
||||
}
|
||||
|
||||
/* ========================= Sentence dispatch ========================= */
|
||||
|
||||
void um982_parse_sentence(UM982_GPS_t *gps, const char *sentence)
|
||||
{
|
||||
if (sentence == NULL || sentence[0] != '$') return;
|
||||
|
||||
/* Verify checksum before parsing */
|
||||
if (!um982_verify_checksum(sentence)) return;
|
||||
|
||||
/* Check for VERSIONA response (starts with '#', not '$') -- handled separately */
|
||||
/* Actually VERSIONA starts with '#', so it won't enter here. We check in feed(). */
|
||||
|
||||
/* Identify sentence type */
|
||||
const char *fmt = get_formatter(sentence);
|
||||
if (fmt == NULL) return;
|
||||
|
||||
if (strncmp(fmt, "GGA", 3) == 0) {
|
||||
gps->initialized = true;
|
||||
parse_gga(gps, sentence);
|
||||
} else if (strncmp(fmt, "RMC", 3) == 0) {
|
||||
gps->initialized = true;
|
||||
parse_rmc(gps, sentence);
|
||||
} else if (strncmp(fmt, "THS", 3) == 0) {
|
||||
gps->initialized = true;
|
||||
parse_ths(gps, sentence);
|
||||
} else if (strncmp(fmt, "VTG", 3) == 0) {
|
||||
gps->initialized = true;
|
||||
parse_vtg(gps, sentence);
|
||||
}
|
||||
/* Other sentences silently ignored */
|
||||
}
|
||||
|
||||
/* ========================= Command interface ========================= */
|
||||
|
||||
bool um982_send_command(UM982_GPS_t *gps, const char *cmd)
|
||||
{
|
||||
if (gps == NULL || gps->huart == NULL || cmd == NULL) return false;
|
||||
|
||||
/* Build command with \r\n termination */
|
||||
char buf[UM982_CMD_BUF_SIZE];
|
||||
int len = snprintf(buf, sizeof(buf), "%s\r\n", cmd);
|
||||
if (len <= 0 || (size_t)len >= sizeof(buf)) return false;
|
||||
|
||||
HAL_StatusTypeDef status = HAL_UART_Transmit(
|
||||
gps->huart, (const uint8_t *)buf, (uint16_t)len, 100);
|
||||
|
||||
return status == HAL_OK;
|
||||
}
|
||||
|
||||
/* ========================= Line assembly + feed ====================== */
|
||||
|
||||
/**
|
||||
* Process a completed line from the line buffer.
|
||||
*/
|
||||
static void process_line(UM982_GPS_t *gps, const char *line)
|
||||
{
|
||||
if (line == NULL || line[0] == '\0') return;
|
||||
|
||||
/* NMEA sentence starts with '$' */
|
||||
if (line[0] == '$') {
|
||||
um982_parse_sentence(gps, line);
|
||||
return;
|
||||
}
|
||||
|
||||
/* Unicore proprietary response starts with '#' (e.g. #VERSIONA) */
|
||||
if (line[0] == '#') {
|
||||
if (strncmp(line + 1, "VERSIONA", 8) == 0) {
|
||||
gps->version_received = true;
|
||||
gps->initialized = true;
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void um982_feed(UM982_GPS_t *gps, const uint8_t *data, uint16_t len)
|
||||
{
|
||||
if (gps == NULL || data == NULL || len == 0) return;
|
||||
|
||||
for (uint16_t i = 0; i < len; i++) {
|
||||
uint8_t ch = data[i];
|
||||
|
||||
/* End of line: process if we have content */
|
||||
if (ch == '\n' || ch == '\r') {
|
||||
if (gps->line_len > 0 && !gps->line_overflow) {
|
||||
gps->line_buf[gps->line_len] = '\0';
|
||||
process_line(gps, gps->line_buf);
|
||||
}
|
||||
gps->line_len = 0;
|
||||
gps->line_overflow = false;
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Accumulate into line buffer */
|
||||
if (gps->line_len < UM982_LINE_BUF_SIZE - 1) {
|
||||
gps->line_buf[gps->line_len++] = (char)ch;
|
||||
} else {
|
||||
gps->line_overflow = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* ========================= UART process (production) ================= */
|
||||
|
||||
void um982_process(UM982_GPS_t *gps)
|
||||
{
|
||||
if (gps == NULL || gps->huart == NULL) return;
|
||||
|
||||
/* Read all available bytes from the UART one at a time.
|
||||
* At 115200 baud (~11.5 KB/s) and a typical main-loop period of ~10 ms,
|
||||
* we expect ~115 bytes per call — negligible overhead on a 168 MHz STM32.
|
||||
*
|
||||
* Note: batch reads (HAL_UART_Receive with Size > 1 and Timeout = 0) are
|
||||
* NOT safe here because the HAL consumes bytes from the data register as
|
||||
* it reads them. If fewer than Size bytes are available, the consumed
|
||||
* bytes are lost (HAL_TIMEOUT is returned and the caller has no way to
|
||||
* know how many bytes were actually placed into the buffer). */
|
||||
uint8_t ch;
|
||||
while (HAL_UART_Receive(gps->huart, &ch, 1, 0) == HAL_OK) {
|
||||
um982_feed(gps, &ch, 1);
|
||||
}
|
||||
}
|
||||
|
||||
/* ========================= Validity checks =========================== */
|
||||
|
||||
bool um982_is_heading_valid(const UM982_GPS_t *gps)
|
||||
{
|
||||
if (gps == NULL) return false;
|
||||
if (isnan(gps->heading)) return false;
|
||||
|
||||
/* Mode must be Autonomous or Differential */
|
||||
if (gps->heading_mode != 'A' && gps->heading_mode != 'D') return false;
|
||||
|
||||
/* Check age */
|
||||
uint32_t age = HAL_GetTick() - gps->last_ths_tick;
|
||||
return age < UM982_HEADING_TIMEOUT_MS;
|
||||
}
|
||||
|
||||
bool um982_is_position_valid(const UM982_GPS_t *gps)
|
||||
{
|
||||
if (gps == NULL) return false;
|
||||
if (gps->fix_quality == UM982_FIX_NONE) return false;
|
||||
|
||||
/* Check age of the last valid fix */
|
||||
uint32_t age = HAL_GetTick() - gps->last_fix_tick;
|
||||
return age < UM982_POSITION_TIMEOUT_MS;
|
||||
}
|
||||
|
||||
uint32_t um982_heading_age(const UM982_GPS_t *gps)
|
||||
{
|
||||
if (gps == NULL) return UINT32_MAX;
|
||||
return HAL_GetTick() - gps->last_ths_tick;
|
||||
}
|
||||
|
||||
uint32_t um982_position_age(const UM982_GPS_t *gps)
|
||||
{
|
||||
if (gps == NULL) return UINT32_MAX;
|
||||
return HAL_GetTick() - gps->last_fix_tick;
|
||||
}
|
||||
|
||||
/* ========================= Initialization ============================ */
|
||||
|
||||
bool um982_init(UM982_GPS_t *gps, UART_HandleTypeDef *huart,
|
||||
float baseline_cm, float tolerance_cm)
|
||||
{
|
||||
if (gps == NULL || huart == NULL) return false;
|
||||
|
||||
/* Zero-init entire structure */
|
||||
memset(gps, 0, sizeof(UM982_GPS_t));
|
||||
|
||||
gps->huart = huart;
|
||||
gps->heading = NAN;
|
||||
gps->heading_mode = 'V';
|
||||
gps->rmc_status = 'V';
|
||||
gps->speed_knots = 0.0f;
|
||||
|
||||
/* Seed fix timestamp so position_age() returns ~0 instead of uptime.
|
||||
* Gives the module a full 30s grace window from init to acquire a fix
|
||||
* before the health check fires ERROR_GPS_COMM. */
|
||||
gps->last_fix_tick = HAL_GetTick();
|
||||
gps->speed_kmh = 0.0f;
|
||||
gps->course_true = 0.0f;
|
||||
|
||||
/* Step 1: Stop all current output to get a clean slate */
|
||||
um982_send_command(gps, "UNLOG");
|
||||
HAL_Delay(100);
|
||||
|
||||
/* Step 2: Configure heading mode
|
||||
* Per N4 Reference 4.18: CONFIG HEADING FIXLENGTH (default mode)
|
||||
* "The distance between ANT1 and ANT2 is fixed. They move synchronously." */
|
||||
um982_send_command(gps, "CONFIG HEADING FIXLENGTH");
|
||||
HAL_Delay(50);
|
||||
|
||||
/* Step 3: Set baseline length if specified
|
||||
* Per N4 Reference: CONFIG HEADING LENGTH <cm> <tolerance_cm>
|
||||
* "parameter1: Fixed baseline length (cm), valid range >= 0"
|
||||
* "parameter2: Tolerable error margin (cm), valid range > 0" */
|
||||
if (baseline_cm > 0.0f) {
|
||||
char cmd[64];
|
||||
if (tolerance_cm > 0.0f) {
|
||||
snprintf(cmd, sizeof(cmd), "CONFIG HEADING LENGTH %.0f %.0f",
|
||||
baseline_cm, tolerance_cm);
|
||||
} else {
|
||||
snprintf(cmd, sizeof(cmd), "CONFIG HEADING LENGTH %.0f",
|
||||
baseline_cm);
|
||||
}
|
||||
um982_send_command(gps, cmd);
|
||||
HAL_Delay(50);
|
||||
}
|
||||
|
||||
/* Step 4: Enable NMEA output sentences on COM2.
|
||||
* Per N4 Reference: "When requesting NMEA messages, users should add GP
|
||||
* before each command name"
|
||||
*
|
||||
* We target COM2 because the ELT0213 board (GNSS.STORE) exposes COM2
|
||||
* (RXD2/TXD2) on its 12-pin JST connector (pins 5 & 6). The STM32
|
||||
* UART5 (PC12-TX, PD2-RX) connects to these pins via JP8.
|
||||
* COM2 defaults to 115200 baud — matching our UART5 config. */
|
||||
um982_send_command(gps, "GPGGA COM2 1"); /* GGA at 1 Hz */
|
||||
HAL_Delay(50);
|
||||
um982_send_command(gps, "GPRMC COM2 1"); /* RMC at 1 Hz */
|
||||
HAL_Delay(50);
|
||||
um982_send_command(gps, "GPTHS COM2 0.2"); /* THS at 5 Hz (heading primary) */
|
||||
HAL_Delay(50);
|
||||
|
||||
/* Step 5: Skip SAVECONFIG -- NMEA config is re-sent every boot anyway.
|
||||
* Saving to NVM on every power cycle would wear flash. If persistent
|
||||
* config is needed, call um982_send_command(gps, "SAVECONFIG") once
|
||||
* during commissioning. */
|
||||
|
||||
/* Step 6: Query version to verify communication */
|
||||
gps->version_received = false;
|
||||
um982_send_command(gps, "VERSIONA");
|
||||
|
||||
/* Wait for VERSIONA response (non-blocking poll) */
|
||||
uint32_t start = HAL_GetTick();
|
||||
while (!gps->version_received &&
|
||||
(HAL_GetTick() - start) < UM982_INIT_TIMEOUT_MS) {
|
||||
um982_process(gps);
|
||||
HAL_Delay(10);
|
||||
}
|
||||
|
||||
gps->initialized = gps->version_received;
|
||||
return gps->initialized;
|
||||
}
|
||||
@@ -0,0 +1,213 @@
|
||||
/*******************************************************************************
|
||||
* um982_gps.h -- UM982 dual-antenna GNSS receiver driver
|
||||
*
|
||||
* Parses NMEA sentences (GGA, RMC, THS, VTG) from the Unicore UM982 module
|
||||
* and provides position, heading, and velocity data.
|
||||
*
|
||||
* Design principles:
|
||||
* - Non-blocking: process() reads available UART bytes without waiting
|
||||
* - Correct NMEA parsing: proper tokenizer handles empty fields
|
||||
* - Longitude handles 3-digit degrees (dddmm.mmmm) via decimal-point detection
|
||||
* - Checksum verified on every sentence
|
||||
* - Command syntax verified against Unicore N4 Command Reference EN R1.14
|
||||
*
|
||||
* Hardware: UM982 on UART5 @ 115200 baud, dual-antenna heading mode
|
||||
******************************************************************************/
|
||||
#ifndef UM982_GPS_H
|
||||
#define UM982_GPS_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <math.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Forward-declare the HAL UART handle type. The real definition comes from
|
||||
* stm32f7xx_hal.h (production) or stm32_hal_mock.h (tests). */
|
||||
#ifndef STM32_HAL_MOCK_H
|
||||
#include "stm32f7xx_hal.h"
|
||||
#else
|
||||
/* Already included via mock -- nothing to do */
|
||||
#endif
|
||||
|
||||
/* ========================= Constants ================================= */
|
||||
|
||||
#define UM982_RX_BUF_SIZE 512 /* Ring buffer for incoming UART bytes */
|
||||
#define UM982_LINE_BUF_SIZE 96 /* Max NMEA sentence (82 chars + margin) */
|
||||
#define UM982_CMD_BUF_SIZE 128 /* Outgoing command buffer */
|
||||
#define UM982_INIT_TIMEOUT_MS 3000 /* Timeout waiting for VERSIONA response */
|
||||
|
||||
/* Fix quality values (from GGA field 6) */
|
||||
#define UM982_FIX_NONE 0
|
||||
#define UM982_FIX_GPS 1
|
||||
#define UM982_FIX_DGPS 2
|
||||
#define UM982_FIX_RTK_FIXED 4
|
||||
#define UM982_FIX_RTK_FLOAT 5
|
||||
|
||||
/* Validity timeout defaults (ms) */
|
||||
#define UM982_HEADING_TIMEOUT_MS 2000
|
||||
#define UM982_POSITION_TIMEOUT_MS 5000
|
||||
|
||||
/* ========================= Data Types ================================ */
|
||||
|
||||
typedef struct {
|
||||
/* Position */
|
||||
double latitude; /* Decimal degrees, positive = North */
|
||||
double longitude; /* Decimal degrees, positive = East */
|
||||
float altitude; /* Meters above MSL */
|
||||
float geoid_sep; /* Geoid separation (meters) */
|
||||
|
||||
/* Heading (from dual-antenna THS) */
|
||||
float heading; /* True heading 0-360 degrees, NAN if invalid */
|
||||
char heading_mode; /* A=autonomous, D=diff, E=est, M=manual, S=sim, V=invalid */
|
||||
|
||||
/* Velocity */
|
||||
float speed_knots; /* Speed over ground (knots) */
|
||||
float speed_kmh; /* Speed over ground (km/h) */
|
||||
float course_true; /* Course over ground (degrees true) */
|
||||
|
||||
/* Quality */
|
||||
uint8_t fix_quality; /* 0=none, 1=GPS, 2=DGPS, 4=RTK fixed, 5=RTK float */
|
||||
uint8_t num_satellites; /* Satellites used in fix */
|
||||
float hdop; /* Horizontal dilution of precision */
|
||||
|
||||
/* RMC status */
|
||||
char rmc_status; /* A=valid, V=warning */
|
||||
|
||||
/* Timestamps (HAL_GetTick() at last update) */
|
||||
uint32_t last_fix_tick; /* Last valid GGA fix (fix_quality > 0) */
|
||||
uint32_t last_gga_tick;
|
||||
uint32_t last_rmc_tick;
|
||||
uint32_t last_ths_tick;
|
||||
uint32_t last_vtg_tick;
|
||||
|
||||
/* Communication state */
|
||||
bool initialized; /* VERSIONA or supported NMEA traffic seen */
|
||||
bool version_received; /* VERSIONA response seen */
|
||||
|
||||
/* ---- Internal parser state (not for external use) ---- */
|
||||
|
||||
/* Ring buffer */
|
||||
uint8_t rx_buf[UM982_RX_BUF_SIZE];
|
||||
uint16_t rx_head; /* Write index */
|
||||
uint16_t rx_tail; /* Read index */
|
||||
|
||||
/* Line assembler */
|
||||
char line_buf[UM982_LINE_BUF_SIZE];
|
||||
uint8_t line_len;
|
||||
bool line_overflow; /* Current line exceeded buffer */
|
||||
|
||||
/* UART handle */
|
||||
UART_HandleTypeDef *huart;
|
||||
|
||||
} UM982_GPS_t;
|
||||
|
||||
/* ========================= Public API ================================ */
|
||||
|
||||
/**
|
||||
* Initialize the UM982_GPS_t structure and configure the module.
|
||||
*
|
||||
* Sends: UNLOG, CONFIG HEADING, optional CONFIG HEADING LENGTH,
|
||||
* GPGGA, GPRMC, GPTHS
|
||||
* Queries VERSIONA to verify communication.
|
||||
*
|
||||
* @param gps Pointer to UM982_GPS_t instance
|
||||
* @param huart UART handle (e.g. &huart5)
|
||||
* @param baseline_cm Distance between antennas in cm (0 = use module default)
|
||||
* @param tolerance_cm Baseline tolerance in cm (0 = use module default)
|
||||
* @return true if VERSIONA response received within timeout
|
||||
*/
|
||||
bool um982_init(UM982_GPS_t *gps, UART_HandleTypeDef *huart,
|
||||
float baseline_cm, float tolerance_cm);
|
||||
|
||||
/**
|
||||
* Process available UART data. Call from main loop — non-blocking.
|
||||
*
|
||||
* Reads all available bytes from UART, assembles lines, and dispatches
|
||||
* complete NMEA sentences to the appropriate parser.
|
||||
*
|
||||
* @param gps Pointer to UM982_GPS_t instance
|
||||
*/
|
||||
void um982_process(UM982_GPS_t *gps);
|
||||
|
||||
/**
|
||||
* Feed raw bytes directly into the parser (useful for testing).
|
||||
* In production, um982_process() calls this internally after UART read.
|
||||
*
|
||||
* @param gps Pointer to UM982_GPS_t instance
|
||||
* @param data Pointer to byte array
|
||||
* @param len Number of bytes
|
||||
*/
|
||||
void um982_feed(UM982_GPS_t *gps, const uint8_t *data, uint16_t len);
|
||||
|
||||
/* ---- Getters ---- */
|
||||
|
||||
static inline float um982_get_heading(const UM982_GPS_t *gps) { return gps->heading; }
|
||||
static inline double um982_get_latitude(const UM982_GPS_t *gps) { return gps->latitude; }
|
||||
static inline double um982_get_longitude(const UM982_GPS_t *gps) { return gps->longitude; }
|
||||
static inline float um982_get_altitude(const UM982_GPS_t *gps) { return gps->altitude; }
|
||||
static inline uint8_t um982_get_fix_quality(const UM982_GPS_t *gps) { return gps->fix_quality; }
|
||||
static inline uint8_t um982_get_num_sats(const UM982_GPS_t *gps) { return gps->num_satellites; }
|
||||
static inline float um982_get_hdop(const UM982_GPS_t *gps) { return gps->hdop; }
|
||||
static inline float um982_get_speed_knots(const UM982_GPS_t *gps) { return gps->speed_knots; }
|
||||
static inline float um982_get_speed_kmh(const UM982_GPS_t *gps) { return gps->speed_kmh; }
|
||||
static inline float um982_get_course(const UM982_GPS_t *gps) { return gps->course_true; }
|
||||
|
||||
/**
|
||||
* Check if heading is valid (mode A or D, and within timeout).
|
||||
*/
|
||||
bool um982_is_heading_valid(const UM982_GPS_t *gps);
|
||||
|
||||
/**
|
||||
* Check if position is valid (fix_quality > 0, and within timeout).
|
||||
*/
|
||||
bool um982_is_position_valid(const UM982_GPS_t *gps);
|
||||
|
||||
/**
|
||||
* Get age of last heading update in milliseconds.
|
||||
*/
|
||||
uint32_t um982_heading_age(const UM982_GPS_t *gps);
|
||||
|
||||
/**
|
||||
* Get age of the last valid position fix in milliseconds.
|
||||
*/
|
||||
uint32_t um982_position_age(const UM982_GPS_t *gps);
|
||||
|
||||
/* ========================= Internal (exposed for testing) ============ */
|
||||
|
||||
/**
|
||||
* Verify NMEA checksum. Returns true if valid.
|
||||
* Sentence must start with '$' and contain '*XX' before termination.
|
||||
*/
|
||||
bool um982_verify_checksum(const char *sentence);
|
||||
|
||||
/**
|
||||
* Parse a complete NMEA line (with $ prefix and *XX checksum).
|
||||
* Dispatches to GGA/RMC/THS/VTG parsers as appropriate.
|
||||
*/
|
||||
void um982_parse_sentence(UM982_GPS_t *gps, const char *sentence);
|
||||
|
||||
/**
|
||||
* Parse NMEA coordinate string to decimal degrees.
|
||||
* Works for both latitude (ddmm.mmmm) and longitude (dddmm.mmmm)
|
||||
* by detecting the decimal point position.
|
||||
*
|
||||
* @param field NMEA coordinate field (e.g. "4404.14036" or "12118.85961")
|
||||
* @param hemisphere 'N', 'S', 'E', or 'W'
|
||||
* @return Decimal degrees (negative for S/W), or NAN on parse error
|
||||
*/
|
||||
double um982_parse_coord(const char *field, char hemisphere);
|
||||
|
||||
/**
|
||||
* Send a command to the UM982. Appends \r\n automatically.
|
||||
* @return true if UART transmit succeeded
|
||||
*/
|
||||
bool um982_send_command(UM982_GPS_t *gps, const char *cmd);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* UM982_GPS_H */
|
||||
@@ -3,18 +3,38 @@
|
||||
*.dSYM/
|
||||
|
||||
# Test binaries (built by Makefile)
|
||||
# TESTS_WITH_REAL
|
||||
test_bug1_timed_sync_init_ordering
|
||||
test_bug2_ad9523_double_setup
|
||||
test_bug3_timed_sync_noop
|
||||
test_bug4_phase_shift_before_check
|
||||
test_bug5_fine_phase_gpio_only
|
||||
test_bug9_platform_ops_null
|
||||
test_bug10_spi_cs_not_toggled
|
||||
test_bug15_htim3_dangling_extern
|
||||
|
||||
# TESTS_MOCK_ONLY
|
||||
test_bug2_ad9523_double_setup
|
||||
test_bug6_timer_variable_collision
|
||||
test_bug7_gpio_pin_conflict
|
||||
test_bug8_uart_commented_out
|
||||
test_bug9_platform_ops_null
|
||||
test_bug10_spi_cs_not_toggled
|
||||
test_bug11_platform_spi_transmit_only
|
||||
test_bug14_diag_section_args
|
||||
test_gap3_emergency_stop_rails
|
||||
|
||||
# TESTS_STANDALONE
|
||||
test_bug12_pa_cal_loop_inverted
|
||||
test_bug13_dac2_adc_buffer_mismatch
|
||||
test_bug14_diag_section_args
|
||||
test_bug15_htim3_dangling_extern
|
||||
test_gap3_iwdg_config
|
||||
test_gap3_temperature_max
|
||||
test_gap3_idq_periodic_reread
|
||||
test_gap3_emergency_state_ordering
|
||||
test_gap3_overtemp_emergency_stop
|
||||
test_gap3_health_watchdog_cold_start
|
||||
|
||||
# TESTS_WITH_PLATFORM
|
||||
test_bug11_platform_spi_transmit_only
|
||||
|
||||
# TESTS_WITH_CXX
|
||||
test_agc_outer_loop
|
||||
|
||||
# Manual / one-off test builds
|
||||
test_um982_gps
|
||||
|
||||
@@ -27,6 +27,10 @@ CXX_LIB_DIR := ../9_1_1_C_Cpp_Libraries
|
||||
CXX_SRCS := $(CXX_LIB_DIR)/ADAR1000_AGC.cpp $(CXX_LIB_DIR)/ADAR1000_Manager.cpp
|
||||
CXX_OBJS := ADAR1000_AGC.o ADAR1000_Manager.o
|
||||
|
||||
# GPS driver source
|
||||
GPS_SRC := ../9_1_3_C_Cpp_Code/um982_gps.c
|
||||
GPS_OBJ := um982_gps.o
|
||||
|
||||
# Real source files compiled against mock headers
|
||||
REAL_SRC := ../9_1_1_C_Cpp_Libraries/adf4382a_manager.c
|
||||
|
||||
@@ -65,7 +69,8 @@ TESTS_STANDALONE := test_bug12_pa_cal_loop_inverted \
|
||||
test_gap3_temperature_max \
|
||||
test_gap3_idq_periodic_reread \
|
||||
test_gap3_emergency_state_ordering \
|
||||
test_gap3_overtemp_emergency_stop
|
||||
test_gap3_overtemp_emergency_stop \
|
||||
test_gap3_health_watchdog_cold_start
|
||||
|
||||
# Tests that need platform_noos_stm32.o + mocks
|
||||
TESTS_WITH_PLATFORM := test_bug11_platform_spi_transmit_only
|
||||
@@ -73,12 +78,15 @@ TESTS_WITH_PLATFORM := test_bug11_platform_spi_transmit_only
|
||||
# C++ tests (AGC outer loop)
|
||||
TESTS_WITH_CXX := test_agc_outer_loop
|
||||
|
||||
ALL_TESTS := $(TESTS_WITH_REAL) $(TESTS_MOCK_ONLY) $(TESTS_STANDALONE) $(TESTS_WITH_PLATFORM) $(TESTS_WITH_CXX)
|
||||
# GPS driver tests (need mocks + GPS source + -lm)
|
||||
TESTS_GPS := test_um982_gps
|
||||
|
||||
ALL_TESTS := $(TESTS_WITH_REAL) $(TESTS_MOCK_ONLY) $(TESTS_STANDALONE) $(TESTS_WITH_PLATFORM) $(TESTS_WITH_CXX) $(TESTS_GPS)
|
||||
|
||||
.PHONY: all build test clean \
|
||||
$(addprefix test_,bug1 bug2 bug3 bug4 bug5 bug6 bug7 bug8 bug9 bug10 bug11 bug12 bug13 bug14 bug15) \
|
||||
test_gap3_estop test_gap3_iwdg test_gap3_temp test_gap3_idq test_gap3_order \
|
||||
test_gap3_overtemp
|
||||
test_gap3_overtemp test_gap3_wdog
|
||||
|
||||
all: build test
|
||||
|
||||
@@ -167,6 +175,9 @@ test_gap3_emergency_state_ordering: test_gap3_emergency_state_ordering.c
|
||||
test_gap3_overtemp_emergency_stop: test_gap3_overtemp_emergency_stop.c
|
||||
$(CC) $(CFLAGS) $< -o $@
|
||||
|
||||
test_gap3_health_watchdog_cold_start: test_gap3_health_watchdog_cold_start.c
|
||||
$(CC) $(CFLAGS) $< -o $@
|
||||
|
||||
# Tests that need platform_noos_stm32.o + mocks
|
||||
$(TESTS_WITH_PLATFORM): %: %.c $(MOCK_OBJS) $(PLATFORM_OBJ)
|
||||
$(CC) $(CFLAGS) $(INCLUDES) $< $(MOCK_OBJS) $(PLATFORM_OBJ) -o $@
|
||||
@@ -189,6 +200,20 @@ test_agc_outer_loop: test_agc_outer_loop.cpp $(CXX_OBJS) $(MOCK_OBJS)
|
||||
test_agc: test_agc_outer_loop
|
||||
./test_agc_outer_loop
|
||||
|
||||
# --- GPS driver rules ---
|
||||
|
||||
$(GPS_OBJ): $(GPS_SRC)
|
||||
$(CC) $(CFLAGS) $(INCLUDES) -I../9_1_3_C_Cpp_Code -c $< -o $@
|
||||
|
||||
# Note: test includes um982_gps.c directly for white-box testing (static fn access)
|
||||
test_um982_gps: test_um982_gps.c $(MOCK_OBJS)
|
||||
$(CC) $(CFLAGS) $(INCLUDES) -I../9_1_3_C_Cpp_Code $< $(MOCK_OBJS) -lm -o $@
|
||||
|
||||
# Convenience target
|
||||
.PHONY: test_gps
|
||||
test_gps: test_um982_gps
|
||||
./test_um982_gps
|
||||
|
||||
# --- Individual test targets ---
|
||||
|
||||
test_bug1: test_bug1_timed_sync_init_ordering
|
||||
@@ -254,6 +279,9 @@ test_gap3_order: test_gap3_emergency_state_ordering
|
||||
test_gap3_overtemp: test_gap3_overtemp_emergency_stop
|
||||
./test_gap3_overtemp_emergency_stop
|
||||
|
||||
test_gap3_wdog: test_gap3_health_watchdog_cold_start
|
||||
./test_gap3_health_watchdog_cold_start
|
||||
|
||||
# --- Clean ---
|
||||
|
||||
clean:
|
||||
|
||||
@@ -21,6 +21,7 @@ SPI_HandleTypeDef hspi4 = { .id = 4 };
|
||||
I2C_HandleTypeDef hi2c1 = { .id = 1 };
|
||||
I2C_HandleTypeDef hi2c2 = { .id = 2 };
|
||||
UART_HandleTypeDef huart3 = { .id = 3 };
|
||||
UART_HandleTypeDef huart5 = { .id = 5 }; /* GPS UART */
|
||||
ADC_HandleTypeDef hadc3 = { .id = 3 };
|
||||
TIM_HandleTypeDef htim3 = { .id = 3 };
|
||||
|
||||
@@ -34,6 +35,26 @@ uint32_t mock_tick = 0;
|
||||
/* ========================= Printf control ========================= */
|
||||
int mock_printf_enabled = 0;
|
||||
|
||||
/* ========================= Mock UART TX capture =================== */
|
||||
uint8_t mock_uart_tx_buf[MOCK_UART_TX_BUF_SIZE];
|
||||
uint16_t mock_uart_tx_len = 0;
|
||||
|
||||
/* ========================= Mock UART RX buffer ==================== */
|
||||
#define MOCK_UART_RX_SLOTS 8
|
||||
|
||||
static struct {
|
||||
uint32_t uart_id;
|
||||
uint8_t buf[MOCK_UART_RX_BUF_SIZE];
|
||||
uint16_t head;
|
||||
uint16_t tail;
|
||||
} mock_uart_rx[MOCK_UART_RX_SLOTS];
|
||||
|
||||
void mock_uart_tx_clear(void)
|
||||
{
|
||||
mock_uart_tx_len = 0;
|
||||
memset(mock_uart_tx_buf, 0, sizeof(mock_uart_tx_buf));
|
||||
}
|
||||
|
||||
/* ========================= Mock GPIO read ========================= */
|
||||
#define GPIO_READ_TABLE_SIZE 32
|
||||
static struct {
|
||||
@@ -49,6 +70,9 @@ void spy_reset(void)
|
||||
mock_tick = 0;
|
||||
mock_printf_enabled = 0;
|
||||
memset(gpio_read_table, 0, sizeof(gpio_read_table));
|
||||
memset(mock_uart_rx, 0, sizeof(mock_uart_rx));
|
||||
mock_uart_tx_len = 0;
|
||||
memset(mock_uart_tx_buf, 0, sizeof(mock_uart_tx_buf));
|
||||
}
|
||||
|
||||
const SpyRecord *spy_get(int index)
|
||||
@@ -185,6 +209,83 @@ HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pD
|
||||
.value = Timeout,
|
||||
.extra = huart
|
||||
});
|
||||
/* Capture TX data for test inspection */
|
||||
for (uint16_t i = 0; i < Size && mock_uart_tx_len < MOCK_UART_TX_BUF_SIZE; i++) {
|
||||
mock_uart_tx_buf[mock_uart_tx_len++] = pData[i];
|
||||
}
|
||||
return HAL_OK;
|
||||
}
|
||||
|
||||
/* ========================= Mock UART RX helpers ====================== */
|
||||
|
||||
/* find_rx_slot, mock_uart_rx_load, etc. use the mock_uart_rx declared above */
|
||||
|
||||
static int find_rx_slot(UART_HandleTypeDef *huart)
|
||||
{
|
||||
if (huart == NULL) return -1;
|
||||
/* Find existing slot */
|
||||
for (int i = 0; i < MOCK_UART_RX_SLOTS; i++) {
|
||||
if (mock_uart_rx[i].uart_id == huart->id && mock_uart_rx[i].head != mock_uart_rx[i].tail) {
|
||||
return i;
|
||||
}
|
||||
if (mock_uart_rx[i].uart_id == huart->id) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
/* Find empty slot */
|
||||
for (int i = 0; i < MOCK_UART_RX_SLOTS; i++) {
|
||||
if (mock_uart_rx[i].uart_id == 0) {
|
||||
mock_uart_rx[i].uart_id = huart->id;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
void mock_uart_rx_load(UART_HandleTypeDef *huart, const uint8_t *data, uint16_t len)
|
||||
{
|
||||
int slot = find_rx_slot(huart);
|
||||
if (slot < 0) return;
|
||||
mock_uart_rx[slot].uart_id = huart->id;
|
||||
for (uint16_t i = 0; i < len; i++) {
|
||||
uint16_t next = (mock_uart_rx[slot].head + 1) % MOCK_UART_RX_BUF_SIZE;
|
||||
if (next == mock_uart_rx[slot].tail) break; /* Buffer full */
|
||||
mock_uart_rx[slot].buf[mock_uart_rx[slot].head] = data[i];
|
||||
mock_uart_rx[slot].head = next;
|
||||
}
|
||||
}
|
||||
|
||||
void mock_uart_rx_clear(UART_HandleTypeDef *huart)
|
||||
{
|
||||
int slot = find_rx_slot(huart);
|
||||
if (slot < 0) return;
|
||||
mock_uart_rx[slot].head = 0;
|
||||
mock_uart_rx[slot].tail = 0;
|
||||
}
|
||||
|
||||
HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData,
|
||||
uint16_t Size, uint32_t Timeout)
|
||||
{
|
||||
(void)Timeout;
|
||||
int slot = find_rx_slot(huart);
|
||||
if (slot < 0) return HAL_TIMEOUT;
|
||||
|
||||
for (uint16_t i = 0; i < Size; i++) {
|
||||
if (mock_uart_rx[slot].head == mock_uart_rx[slot].tail) {
|
||||
return HAL_TIMEOUT; /* No more data */
|
||||
}
|
||||
pData[i] = mock_uart_rx[slot].buf[mock_uart_rx[slot].tail];
|
||||
mock_uart_rx[slot].tail = (mock_uart_rx[slot].tail + 1) % MOCK_UART_RX_BUF_SIZE;
|
||||
}
|
||||
|
||||
spy_push((SpyRecord){
|
||||
.type = SPY_UART_RX,
|
||||
.port = NULL,
|
||||
.pin = Size,
|
||||
.value = Timeout,
|
||||
.extra = huart
|
||||
});
|
||||
|
||||
return HAL_OK;
|
||||
}
|
||||
|
||||
|
||||
@@ -105,6 +105,7 @@ typedef struct {
|
||||
extern SPI_HandleTypeDef hspi1, hspi4;
|
||||
extern I2C_HandleTypeDef hi2c1, hi2c2;
|
||||
extern UART_HandleTypeDef huart3;
|
||||
extern UART_HandleTypeDef huart5; /* GPS UART */
|
||||
extern ADC_HandleTypeDef hadc3;
|
||||
extern TIM_HandleTypeDef htim3; /* Timer for DELADJ PWM */
|
||||
|
||||
@@ -139,6 +140,7 @@ typedef enum {
|
||||
SPY_TIM_SET_COMPARE,
|
||||
SPY_SPI_TRANSMIT_RECEIVE,
|
||||
SPY_SPI_TRANSMIT,
|
||||
SPY_UART_RX,
|
||||
} SpyCallType;
|
||||
|
||||
typedef struct {
|
||||
@@ -187,6 +189,23 @@ void HAL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
|
||||
uint32_t HAL_GetTick(void);
|
||||
void HAL_Delay(uint32_t Delay);
|
||||
HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||
HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||
|
||||
/* ========================= Mock UART RX buffer ======================= */
|
||||
|
||||
/* Inject bytes into the mock UART RX buffer for a specific UART handle.
|
||||
* HAL_UART_Receive will return these bytes one at a time. */
|
||||
#define MOCK_UART_RX_BUF_SIZE 2048
|
||||
|
||||
void mock_uart_rx_load(UART_HandleTypeDef *huart, const uint8_t *data, uint16_t len);
|
||||
void mock_uart_rx_clear(UART_HandleTypeDef *huart);
|
||||
|
||||
/* Capture buffer for UART TX data (to verify commands sent to GPS module) */
|
||||
#define MOCK_UART_TX_BUF_SIZE 2048
|
||||
|
||||
extern uint8_t mock_uart_tx_buf[MOCK_UART_TX_BUF_SIZE];
|
||||
extern uint16_t mock_uart_tx_len;
|
||||
void mock_uart_tx_clear(void);
|
||||
|
||||
/* ========================= SPI stubs ============================== */
|
||||
|
||||
|
||||
@@ -0,0 +1,132 @@
|
||||
/*******************************************************************************
|
||||
* test_gap3_health_watchdog_cold_start.c
|
||||
*
|
||||
* Safety bug: checkSystemHealth()'s internal watchdog (step 9, pre-fix) had two
|
||||
* linked defects that, once ERROR_WATCHDOG_TIMEOUT was escalated to
|
||||
* Emergency_Stop() by the overtemp/watchdog PR, would false-latch the radar:
|
||||
*
|
||||
* (1) Cold-start false trip:
|
||||
* static uint32_t last_health_check = 0;
|
||||
* if (HAL_GetTick() - last_health_check > 60000) { ... }
|
||||
* On the very first call, last_health_check == 0, so once the MCU has
|
||||
* been up >60 s (which is typical after the ADAR1000 / AD9523 / ADF4382
|
||||
* init sequence) the subtraction `now - 0` exceeds 60 000 ms and the
|
||||
* watchdog trips spuriously.
|
||||
*
|
||||
* (2) Stale-timestamp after early returns:
|
||||
* last_health_check = HAL_GetTick(); // at END of function
|
||||
* Every earlier sub-check (IMU, BMP180, GPS, PA Idq, temperature) has an
|
||||
* `if (fault) return current_error;` path that skips the update. After a
|
||||
* cumulative 60 s of transient faults, the next clean call compares
|
||||
* `now` against the long-stale `last_health_check` and trips.
|
||||
*
|
||||
* After fix: Watchdog logic moved to function ENTRY. A dedicated cold-start
|
||||
* branch seeds the timestamp on the first call without checking.
|
||||
* On every subsequent call, the elapsed delta is captured FIRST
|
||||
* and last_health_check is updated BEFORE any sub-check runs, so
|
||||
* early returns no longer leave a stale value.
|
||||
*
|
||||
* Test strategy:
|
||||
* Extract the post-fix watchdog predicate into a standalone function that
|
||||
* takes a simulated HAL_GetTick() value and returns whether the watchdog
|
||||
* should trip. Walk through boot + fault sequences that would have tripped
|
||||
* the pre-fix code and assert the post-fix code does NOT trip.
|
||||
******************************************************************************/
|
||||
#include <assert.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
/* --- Post-fix watchdog state + predicate, extracted verbatim --- */
|
||||
static uint32_t last_health_check = 0;
|
||||
|
||||
/* Returns 1 iff this call should raise ERROR_WATCHDOG_TIMEOUT.
|
||||
Updates last_health_check BEFORE returning (matches post-fix behaviour). */
|
||||
static int health_watchdog_step(uint32_t now_tick)
|
||||
{
|
||||
if (last_health_check == 0) {
|
||||
last_health_check = now_tick; /* cold start: seed only, never trip */
|
||||
return 0;
|
||||
}
|
||||
uint32_t elapsed = now_tick - last_health_check;
|
||||
last_health_check = now_tick; /* update BEFORE any early return */
|
||||
return (elapsed > 60000) ? 1 : 0;
|
||||
}
|
||||
|
||||
/* Test helper: reset the static state between scenarios. */
|
||||
static void reset_state(void) { last_health_check = 0; }
|
||||
|
||||
int main(void)
|
||||
{
|
||||
printf("=== Safety fix: checkSystemHealth() watchdog cold-start + stale-ts ===\n");
|
||||
|
||||
/* ---------- Scenario 1: cold-start after 60 s of init must NOT trip ---- */
|
||||
printf(" Test 1: first call at t=75000 ms (post-init) does not trip... ");
|
||||
reset_state();
|
||||
assert(health_watchdog_step(75000) == 0);
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 2: first call far beyond 60 s (PRE-FIX BUG) ------- */
|
||||
printf(" Test 2: first call at t=600000 ms still does not trip... ");
|
||||
reset_state();
|
||||
assert(health_watchdog_step(600000) == 0);
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 3: healthy main-loop pacing (10 ms period) -------- */
|
||||
printf(" Test 3: 1000 calls at 10 ms intervals never trip... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(1000); /* seed */
|
||||
for (int i = 1; i <= 1000; i++) {
|
||||
assert(health_watchdog_step(1000 + i * 10) == 0);
|
||||
}
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 4: stale-timestamp after a burst of early returns -
|
||||
Pre-fix bug: many early returns skipped the timestamp update, so a
|
||||
later clean call would compare `now` against a 60+ s old value. Post-fix,
|
||||
every call (including ones that would have early-returned in the real
|
||||
function) updates the timestamp at the top, so this scenario is modelled
|
||||
by calling health_watchdog_step() on every iteration of the main loop. */
|
||||
printf(" Test 4: 70 s of 100 ms-spaced calls after seed do not trip... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(50000); /* seed mid-run */
|
||||
for (int i = 1; i <= 700; i++) { /* 70 s @ 100 ms */
|
||||
int tripped = health_watchdog_step(50000 + i * 100);
|
||||
assert(tripped == 0);
|
||||
}
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 5: genuine stall MUST trip ------------------------ */
|
||||
printf(" Test 5: real 60+ s gap between calls does trip... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(10000); /* seed */
|
||||
assert(health_watchdog_step(10000 + 60001) == 1);
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 6: exactly 60 s gap is the boundary -- do NOT trip
|
||||
Post-fix predicate uses strict >60000, matching the pre-fix comparator. */
|
||||
printf(" Test 6: exactly 60000 ms gap does not trip (boundary)... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(10000);
|
||||
assert(health_watchdog_step(10000 + 60000) == 0);
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 7: trip, then recover on next paced call ---------- */
|
||||
printf(" Test 7: after a genuine stall+trip, next paced call does not re-trip... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(5000); /* seed */
|
||||
assert(health_watchdog_step(5000 + 70000) == 1); /* stall -> trip */
|
||||
assert(health_watchdog_step(5000 + 70000 + 10) == 0); /* resume paced */
|
||||
printf("PASS\n");
|
||||
|
||||
/* ---------- Scenario 8: HAL_GetTick() 32-bit wrap (~49.7 days) ---------
|
||||
Because we subtract unsigned 32-bit values, wrap is handled correctly as
|
||||
long as the true elapsed time is < 2^32 ms. */
|
||||
printf(" Test 8: tick wrap from 0xFFFFFF00 -> 0x00000064 (200 ms span) does not trip... ");
|
||||
reset_state();
|
||||
(void)health_watchdog_step(0xFFFFFF00u);
|
||||
assert(health_watchdog_step(0x00000064u) == 0); /* elapsed = 0x164 = 356 ms */
|
||||
printf("PASS\n");
|
||||
|
||||
printf("\n=== Safety fix: ALL TESTS PASSED ===\n\n");
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,853 @@
|
||||
/*******************************************************************************
|
||||
* test_um982_gps.c -- Unit tests for UM982 GPS driver
|
||||
*
|
||||
* Tests NMEA parsing, checksum validation, coordinate parsing, init sequence,
|
||||
* and validity tracking. Uses the mock HAL infrastructure for UART.
|
||||
*
|
||||
* Build: see Makefile target test_um982_gps
|
||||
* Run: ./test_um982_gps
|
||||
******************************************************************************/
|
||||
#include "stm32_hal_mock.h"
|
||||
#include "../9_1_3_C_Cpp_Code/um982_gps.h"
|
||||
#include "../9_1_3_C_Cpp_Code/um982_gps.c" /* Include .c directly for white-box testing */
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <math.h>
|
||||
|
||||
/* ========================= Test helpers ============================== */
|
||||
|
||||
static int tests_passed = 0;
|
||||
static int tests_failed = 0;
|
||||
|
||||
#define TEST(name) \
|
||||
do { printf(" [TEST] %-55s ", name); } while(0)
|
||||
|
||||
#define PASS() \
|
||||
do { printf("PASS\n"); tests_passed++; } while(0)
|
||||
|
||||
#define FAIL(msg) \
|
||||
do { printf("FAIL: %s\n", msg); tests_failed++; } while(0)
|
||||
|
||||
#define ASSERT_TRUE(expr, msg) \
|
||||
do { if (!(expr)) { FAIL(msg); return; } } while(0)
|
||||
|
||||
#define ASSERT_FALSE(expr, msg) \
|
||||
do { if (expr) { FAIL(msg); return; } } while(0)
|
||||
|
||||
#define ASSERT_EQ_INT(a, b, msg) \
|
||||
do { if ((a) != (b)) { \
|
||||
char _buf[256]; \
|
||||
snprintf(_buf, sizeof(_buf), "%s (got %d, expected %d)", msg, (int)(a), (int)(b)); \
|
||||
FAIL(_buf); return; \
|
||||
} } while(0)
|
||||
|
||||
#define ASSERT_NEAR(a, b, tol, msg) \
|
||||
do { if (fabs((double)(a) - (double)(b)) > (tol)) { \
|
||||
char _buf[256]; \
|
||||
snprintf(_buf, sizeof(_buf), "%s (got %.8f, expected %.8f)", msg, (double)(a), (double)(b)); \
|
||||
FAIL(_buf); return; \
|
||||
} } while(0)
|
||||
|
||||
#define ASSERT_NAN(val, msg) \
|
||||
do { if (!isnan(val)) { FAIL(msg); return; } } while(0)
|
||||
|
||||
static UM982_GPS_t gps;
|
||||
|
||||
static void reset_gps(void)
|
||||
{
|
||||
spy_reset();
|
||||
memset(&gps, 0, sizeof(gps));
|
||||
gps.huart = &huart5;
|
||||
gps.heading = NAN;
|
||||
gps.heading_mode = 'V';
|
||||
gps.rmc_status = 'V';
|
||||
}
|
||||
|
||||
/* ========================= Checksum tests ============================ */
|
||||
|
||||
static void test_checksum_valid(void)
|
||||
{
|
||||
TEST("checksum: valid GGA");
|
||||
ASSERT_TRUE(um982_verify_checksum(
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47"),
|
||||
"should be valid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_checksum_valid_ths(void)
|
||||
{
|
||||
TEST("checksum: valid THS");
|
||||
ASSERT_TRUE(um982_verify_checksum("$GNTHS,341.3344,A*1F"),
|
||||
"should be valid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_checksum_invalid(void)
|
||||
{
|
||||
TEST("checksum: invalid (wrong value)");
|
||||
ASSERT_FALSE(um982_verify_checksum("$GNTHS,341.3344,A*FF"),
|
||||
"should be invalid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_checksum_missing_star(void)
|
||||
{
|
||||
TEST("checksum: missing * marker");
|
||||
ASSERT_FALSE(um982_verify_checksum("$GNTHS,341.3344,A"),
|
||||
"should be invalid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_checksum_null(void)
|
||||
{
|
||||
TEST("checksum: NULL input");
|
||||
ASSERT_FALSE(um982_verify_checksum(NULL), "should be false");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_checksum_no_dollar(void)
|
||||
{
|
||||
TEST("checksum: missing $ prefix");
|
||||
ASSERT_FALSE(um982_verify_checksum("GNTHS,341.3344,A*1F"),
|
||||
"should be invalid without $");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Coordinate parsing tests ================== */
|
||||
|
||||
static void test_coord_latitude_north(void)
|
||||
{
|
||||
TEST("coord: latitude 4404.14036 N");
|
||||
double lat = um982_parse_coord("4404.14036", 'N');
|
||||
/* 44 + 04.14036/60 = 44.069006 */
|
||||
ASSERT_NEAR(lat, 44.069006, 0.000001, "latitude");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_latitude_south(void)
|
||||
{
|
||||
TEST("coord: latitude 3358.92500 S (negative)");
|
||||
double lat = um982_parse_coord("3358.92500", 'S');
|
||||
ASSERT_TRUE(lat < 0.0, "should be negative for S");
|
||||
ASSERT_NEAR(lat, -(33.0 + 58.925/60.0), 0.000001, "latitude");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_longitude_3digit(void)
|
||||
{
|
||||
TEST("coord: longitude 12118.85961 W (3-digit degrees)");
|
||||
double lon = um982_parse_coord("12118.85961", 'W');
|
||||
/* 121 + 18.85961/60 = 121.314327 */
|
||||
ASSERT_TRUE(lon < 0.0, "should be negative for W");
|
||||
ASSERT_NEAR(lon, -(121.0 + 18.85961/60.0), 0.000001, "longitude");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_longitude_east(void)
|
||||
{
|
||||
TEST("coord: longitude 11614.19729 E");
|
||||
double lon = um982_parse_coord("11614.19729", 'E');
|
||||
ASSERT_TRUE(lon > 0.0, "should be positive for E");
|
||||
ASSERT_NEAR(lon, 116.0 + 14.19729/60.0, 0.000001, "longitude");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_empty(void)
|
||||
{
|
||||
TEST("coord: empty string returns NAN");
|
||||
ASSERT_NAN(um982_parse_coord("", 'N'), "should be NAN");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_null(void)
|
||||
{
|
||||
TEST("coord: NULL returns NAN");
|
||||
ASSERT_NAN(um982_parse_coord(NULL, 'N'), "should be NAN");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_coord_no_dot(void)
|
||||
{
|
||||
TEST("coord: no decimal point returns NAN");
|
||||
ASSERT_NAN(um982_parse_coord("440414036", 'N'), "should be NAN");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= GGA parsing tests ========================= */
|
||||
|
||||
static void test_parse_gga_full(void)
|
||||
{
|
||||
TEST("GGA: full sentence with all fields");
|
||||
reset_gps();
|
||||
mock_set_tick(1000);
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
ASSERT_NEAR(gps.latitude, 44.069006, 0.0001, "latitude");
|
||||
ASSERT_NEAR(gps.longitude, -(121.0 + 18.85961/60.0), 0.0001, "longitude");
|
||||
ASSERT_EQ_INT(gps.fix_quality, 1, "fix quality");
|
||||
ASSERT_EQ_INT(gps.num_satellites, 12, "num sats");
|
||||
ASSERT_NEAR(gps.hdop, 0.98, 0.01, "hdop");
|
||||
ASSERT_NEAR(gps.altitude, 1113.0, 0.1, "altitude");
|
||||
ASSERT_NEAR(gps.geoid_sep, -21.3, 0.1, "geoid sep");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_gga_rtk_fixed(void)
|
||||
{
|
||||
TEST("GGA: RTK fixed (quality=4)");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,023634.00,4004.73871635,N,11614.19729418,E,4,28,0.7,61.0988,M,-8.4923,M,,*5D");
|
||||
|
||||
ASSERT_EQ_INT(gps.fix_quality, 4, "RTK fixed");
|
||||
ASSERT_EQ_INT(gps.num_satellites, 28, "num sats");
|
||||
ASSERT_NEAR(gps.latitude, 40.0 + 4.73871635/60.0, 0.0000001, "latitude");
|
||||
ASSERT_NEAR(gps.longitude, 116.0 + 14.19729418/60.0, 0.0000001, "longitude");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_gga_no_fix(void)
|
||||
{
|
||||
TEST("GGA: no fix (quality=0)");
|
||||
reset_gps();
|
||||
|
||||
/* Compute checksum for this sentence */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||
|
||||
ASSERT_EQ_INT(gps.fix_quality, 0, "no fix");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= RMC parsing tests ========================= */
|
||||
|
||||
static void test_parse_rmc_valid(void)
|
||||
{
|
||||
TEST("RMC: valid position and speed");
|
||||
reset_gps();
|
||||
mock_set_tick(2000);
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNRMC,001031.00,A,4404.13993,N,12118.86023,W,0.146,,100117,,,A*7B");
|
||||
|
||||
ASSERT_EQ_INT(gps.rmc_status, 'A', "status");
|
||||
ASSERT_NEAR(gps.latitude, 44.0 + 4.13993/60.0, 0.0001, "latitude");
|
||||
ASSERT_NEAR(gps.longitude, -(121.0 + 18.86023/60.0), 0.0001, "longitude");
|
||||
ASSERT_NEAR(gps.speed_knots, 0.146, 0.001, "speed");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_rmc_void(void)
|
||||
{
|
||||
TEST("RMC: void status (no valid fix)");
|
||||
reset_gps();
|
||||
gps.latitude = 12.34; /* Pre-set to check it doesn't get overwritten */
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNRMC,235959.00,V,,,,,,,100117,,,N*64");
|
||||
|
||||
ASSERT_EQ_INT(gps.rmc_status, 'V', "void status");
|
||||
ASSERT_NEAR(gps.latitude, 12.34, 0.001, "lat should not change on void");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= THS parsing tests ========================= */
|
||||
|
||||
static void test_parse_ths_autonomous(void)
|
||||
{
|
||||
TEST("THS: autonomous heading 341.3344");
|
||||
reset_gps();
|
||||
mock_set_tick(3000);
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||
|
||||
ASSERT_NEAR(gps.heading, 341.3344, 0.001, "heading");
|
||||
ASSERT_EQ_INT(gps.heading_mode, 'A', "mode");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_ths_not_valid(void)
|
||||
{
|
||||
TEST("THS: not valid mode");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,,V*10");
|
||||
|
||||
ASSERT_NAN(gps.heading, "heading should be NAN when empty");
|
||||
ASSERT_EQ_INT(gps.heading_mode, 'V', "mode V");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_ths_zero(void)
|
||||
{
|
||||
TEST("THS: heading exactly 0.0000");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,0.0000,A*19");
|
||||
|
||||
ASSERT_NEAR(gps.heading, 0.0, 0.001, "heading zero");
|
||||
ASSERT_EQ_INT(gps.heading_mode, 'A', "mode A");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_parse_ths_360_boundary(void)
|
||||
{
|
||||
TEST("THS: heading near 360");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,359.9999,D*13");
|
||||
|
||||
ASSERT_NEAR(gps.heading, 359.9999, 0.001, "heading near 360");
|
||||
ASSERT_EQ_INT(gps.heading_mode, 'D', "mode D");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= VTG parsing tests ========================= */
|
||||
|
||||
static void test_parse_vtg(void)
|
||||
{
|
||||
TEST("VTG: course and speed");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GPVTG,220.86,T,,M,2.550,N,4.724,K,A*34");
|
||||
|
||||
ASSERT_NEAR(gps.course_true, 220.86, 0.01, "course");
|
||||
ASSERT_NEAR(gps.speed_knots, 2.550, 0.001, "speed knots");
|
||||
ASSERT_NEAR(gps.speed_kmh, 4.724, 0.001, "speed kmh");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Talker ID tests =========================== */
|
||||
|
||||
static void test_talker_gp(void)
|
||||
{
|
||||
TEST("talker: GP prefix parses correctly");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps, "$GPTHS,123.4567,A*07");
|
||||
|
||||
ASSERT_NEAR(gps.heading, 123.4567, 0.001, "heading with GP");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_talker_gl(void)
|
||||
{
|
||||
TEST("talker: GL prefix parses correctly");
|
||||
reset_gps();
|
||||
|
||||
um982_parse_sentence(&gps, "$GLTHS,123.4567,A*1B");
|
||||
|
||||
ASSERT_NEAR(gps.heading, 123.4567, 0.001, "heading with GL");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Feed / line assembly tests ================ */
|
||||
|
||||
static void test_feed_single_sentence(void)
|
||||
{
|
||||
TEST("feed: single complete sentence with CRLF");
|
||||
reset_gps();
|
||||
mock_set_tick(5000);
|
||||
|
||||
const char *data = "$GNTHS,341.3344,A*1F\r\n";
|
||||
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||
|
||||
ASSERT_NEAR(gps.heading, 341.3344, 0.001, "heading");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_feed_multiple_sentences(void)
|
||||
{
|
||||
TEST("feed: multiple sentences in one chunk");
|
||||
reset_gps();
|
||||
mock_set_tick(5000);
|
||||
|
||||
const char *data =
|
||||
"$GNTHS,100.0000,A*18\r\n"
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47\r\n";
|
||||
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||
|
||||
ASSERT_NEAR(gps.heading, 100.0, 0.01, "heading from THS");
|
||||
ASSERT_EQ_INT(gps.fix_quality, 1, "fix from GGA");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_feed_partial_then_complete(void)
|
||||
{
|
||||
TEST("feed: partial bytes then complete");
|
||||
reset_gps();
|
||||
mock_set_tick(5000);
|
||||
|
||||
const char *part1 = "$GNTHS,200.";
|
||||
const char *part2 = "5000,A*1E\r\n";
|
||||
um982_feed(&gps, (const uint8_t *)part1, (uint16_t)strlen(part1));
|
||||
/* Heading should not be set yet */
|
||||
ASSERT_NAN(gps.heading, "should be NAN before complete");
|
||||
|
||||
um982_feed(&gps, (const uint8_t *)part2, (uint16_t)strlen(part2));
|
||||
ASSERT_NEAR(gps.heading, 200.5, 0.01, "heading after complete");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_feed_bad_checksum_rejected(void)
|
||||
{
|
||||
TEST("feed: bad checksum sentence is rejected");
|
||||
reset_gps();
|
||||
mock_set_tick(5000);
|
||||
|
||||
const char *data = "$GNTHS,999.0000,A*FF\r\n";
|
||||
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||
|
||||
ASSERT_NAN(gps.heading, "heading should remain NAN");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_feed_versiona_response(void)
|
||||
{
|
||||
TEST("feed: VERSIONA response sets flag");
|
||||
reset_gps();
|
||||
|
||||
const char *data = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||
|
||||
ASSERT_TRUE(gps.version_received, "version_received should be true");
|
||||
ASSERT_TRUE(gps.initialized, "VERSIONA should mark communication alive");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Validity / age tests ====================== */
|
||||
|
||||
static void test_heading_valid_within_timeout(void)
|
||||
{
|
||||
TEST("validity: heading valid within timeout");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||
|
||||
/* Still at tick 10000 */
|
||||
ASSERT_TRUE(um982_is_heading_valid(&gps), "should be valid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_heading_invalid_after_timeout(void)
|
||||
{
|
||||
TEST("validity: heading invalid after 2s timeout");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||
|
||||
/* Advance past timeout */
|
||||
mock_set_tick(12500);
|
||||
ASSERT_FALSE(um982_is_heading_valid(&gps), "should be invalid after 2.5s");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_heading_invalid_mode_v(void)
|
||||
{
|
||||
TEST("validity: heading invalid with mode V");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,,V*10");
|
||||
|
||||
ASSERT_FALSE(um982_is_heading_valid(&gps), "mode V is invalid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_position_valid(void)
|
||||
{
|
||||
TEST("validity: position valid with fix quality 1");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
ASSERT_TRUE(um982_is_position_valid(&gps), "should be valid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_position_invalid_no_fix(void)
|
||||
{
|
||||
TEST("validity: position invalid with no fix");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||
|
||||
ASSERT_FALSE(um982_is_position_valid(&gps), "no fix = invalid");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_position_age_uses_last_valid_fix(void)
|
||||
{
|
||||
TEST("age: position age uses last valid fix, not no-fix GGA");
|
||||
reset_gps();
|
||||
|
||||
mock_set_tick(10000);
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
mock_set_tick(12000);
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||
|
||||
mock_set_tick(12500);
|
||||
ASSERT_EQ_INT(um982_position_age(&gps), 2500, "age should still be from last valid fix");
|
||||
ASSERT_FALSE(um982_is_position_valid(&gps), "latest no-fix GGA should invalidate position");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_heading_age(void)
|
||||
{
|
||||
TEST("age: heading age computed correctly");
|
||||
reset_gps();
|
||||
mock_set_tick(10000);
|
||||
|
||||
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||
|
||||
mock_set_tick(10500);
|
||||
uint32_t age = um982_heading_age(&gps);
|
||||
ASSERT_EQ_INT(age, 500, "age should be 500ms");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Send command tests ======================== */
|
||||
|
||||
static void test_send_command_appends_crlf(void)
|
||||
{
|
||||
TEST("send_command: appends \\r\\n");
|
||||
reset_gps();
|
||||
|
||||
um982_send_command(&gps, "GPGGA COM2 1");
|
||||
|
||||
/* Check that TX buffer contains "GPGGA COM2 1\r\n" */
|
||||
const char *expected = "GPGGA COM2 1\r\n";
|
||||
ASSERT_TRUE(mock_uart_tx_len == strlen(expected), "TX length");
|
||||
ASSERT_TRUE(memcmp(mock_uart_tx_buf, expected, strlen(expected)) == 0,
|
||||
"TX content should be 'GPGGA COM2 1\\r\\n'");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_send_command_null_safety(void)
|
||||
{
|
||||
TEST("send_command: NULL gps returns false");
|
||||
ASSERT_FALSE(um982_send_command(NULL, "RESET"), "should return false");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Init sequence tests ======================= */
|
||||
|
||||
static void test_init_sends_correct_commands(void)
|
||||
{
|
||||
TEST("init: sends correct command sequence");
|
||||
spy_reset();
|
||||
mock_uart_tx_clear();
|
||||
|
||||
/* Pre-load VERSIONA response so init succeeds */
|
||||
const char *ver_resp = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||
mock_uart_rx_load(&huart5, (const uint8_t *)ver_resp, (uint16_t)strlen(ver_resp));
|
||||
|
||||
UM982_GPS_t init_gps;
|
||||
bool ok = um982_init(&init_gps, &huart5, 50.0f, 3.0f);
|
||||
|
||||
ASSERT_TRUE(ok, "init should succeed");
|
||||
ASSERT_TRUE(init_gps.initialized, "should be initialized");
|
||||
|
||||
/* Verify TX buffer contains expected commands */
|
||||
const char *tx = (const char *)mock_uart_tx_buf;
|
||||
ASSERT_TRUE(strstr(tx, "UNLOG\r\n") != NULL, "should send UNLOG");
|
||||
ASSERT_TRUE(strstr(tx, "CONFIG HEADING FIXLENGTH\r\n") != NULL, "should send CONFIG HEADING");
|
||||
ASSERT_TRUE(strstr(tx, "CONFIG HEADING LENGTH 50 3\r\n") != NULL, "should send LENGTH");
|
||||
ASSERT_TRUE(strstr(tx, "GPGGA COM2 1\r\n") != NULL, "should enable GGA");
|
||||
ASSERT_TRUE(strstr(tx, "GPRMC COM2 1\r\n") != NULL, "should enable RMC");
|
||||
ASSERT_TRUE(strstr(tx, "GPTHS COM2 0.2\r\n") != NULL, "should enable THS at 5Hz");
|
||||
ASSERT_TRUE(strstr(tx, "SAVECONFIG\r\n") == NULL, "should NOT save config (NVM wear)");
|
||||
ASSERT_TRUE(strstr(tx, "VERSIONA\r\n") != NULL, "should query version");
|
||||
|
||||
/* Verify command order: UNLOG should come before GPGGA */
|
||||
const char *unlog_pos = strstr(tx, "UNLOG\r\n");
|
||||
const char *gpgga_pos = strstr(tx, "GPGGA COM2 1\r\n");
|
||||
ASSERT_TRUE(unlog_pos < gpgga_pos, "UNLOG should precede GPGGA");
|
||||
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_init_no_baseline(void)
|
||||
{
|
||||
TEST("init: baseline=0 skips LENGTH command");
|
||||
spy_reset();
|
||||
mock_uart_tx_clear();
|
||||
|
||||
const char *ver_resp = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||
mock_uart_rx_load(&huart5, (const uint8_t *)ver_resp, (uint16_t)strlen(ver_resp));
|
||||
|
||||
UM982_GPS_t init_gps;
|
||||
um982_init(&init_gps, &huart5, 0.0f, 0.0f);
|
||||
|
||||
const char *tx = (const char *)mock_uart_tx_buf;
|
||||
ASSERT_TRUE(strstr(tx, "CONFIG HEADING LENGTH") == NULL, "should NOT send LENGTH");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_init_fails_no_version(void)
|
||||
{
|
||||
TEST("init: fails if no VERSIONA response");
|
||||
spy_reset();
|
||||
mock_uart_tx_clear();
|
||||
|
||||
/* Don't load any RX data — init should timeout */
|
||||
UM982_GPS_t init_gps;
|
||||
bool ok = um982_init(&init_gps, &huart5, 50.0f, 3.0f);
|
||||
|
||||
ASSERT_FALSE(ok, "init should fail without version response");
|
||||
ASSERT_FALSE(init_gps.initialized, "should not be initialized");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_nmea_traffic_sets_initialized_without_versiona(void)
|
||||
{
|
||||
TEST("init state: supported NMEA traffic sets initialized");
|
||||
reset_gps();
|
||||
|
||||
ASSERT_FALSE(gps.initialized, "should start uninitialized");
|
||||
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||
ASSERT_TRUE(gps.initialized, "supported NMEA should mark communication alive");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Edge case tests =========================== */
|
||||
|
||||
static void test_empty_fields_handled(void)
|
||||
{
|
||||
TEST("edge: GGA with empty lat/lon fields");
|
||||
reset_gps();
|
||||
gps.latitude = 99.99;
|
||||
gps.longitude = 99.99;
|
||||
|
||||
/* GGA with empty position fields (no fix) */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||
|
||||
ASSERT_EQ_INT(gps.fix_quality, 0, "no fix");
|
||||
/* Latitude/longitude should not be updated (fields are empty) */
|
||||
ASSERT_NEAR(gps.latitude, 99.99, 0.01, "lat unchanged");
|
||||
ASSERT_NEAR(gps.longitude, 99.99, 0.01, "lon unchanged");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_sentence_too_short(void)
|
||||
{
|
||||
TEST("edge: sentence too short to have formatter");
|
||||
reset_gps();
|
||||
/* Should not crash */
|
||||
um982_parse_sentence(&gps, "$GN");
|
||||
um982_parse_sentence(&gps, "$");
|
||||
um982_parse_sentence(&gps, "");
|
||||
um982_parse_sentence(&gps, NULL);
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_line_overflow(void)
|
||||
{
|
||||
TEST("edge: oversized line is dropped");
|
||||
reset_gps();
|
||||
|
||||
/* Create a line longer than UM982_LINE_BUF_SIZE */
|
||||
char big[200];
|
||||
memset(big, 'X', sizeof(big));
|
||||
big[0] = '$';
|
||||
big[198] = '\n';
|
||||
big[199] = '\0';
|
||||
|
||||
um982_feed(&gps, (const uint8_t *)big, 199);
|
||||
/* Should not crash, heading should still be NAN */
|
||||
ASSERT_NAN(gps.heading, "no valid data from overflow");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_process_via_mock_uart(void)
|
||||
{
|
||||
TEST("process: reads from mock UART RX buffer");
|
||||
reset_gps();
|
||||
mock_set_tick(5000);
|
||||
|
||||
/* Load data into mock UART RX */
|
||||
const char *data = "$GNTHS,275.1234,D*18\r\n";
|
||||
mock_uart_rx_load(&huart5, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||
|
||||
/* Call process() which reads from UART */
|
||||
um982_process(&gps);
|
||||
|
||||
ASSERT_NEAR(gps.heading, 275.1234, 0.001, "heading via process()");
|
||||
ASSERT_EQ_INT(gps.heading_mode, 'D', "mode D");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= PR #68 bug regression tests =============== */
|
||||
|
||||
/* These tests specifically verify the bugs found in the reverted PR #68 */
|
||||
|
||||
static void test_regression_sentence_id_with_gn_prefix(void)
|
||||
{
|
||||
TEST("regression: GN-prefixed GGA is correctly identified");
|
||||
reset_gps();
|
||||
|
||||
/* PR #68 bug: strncmp(sentence, "GGA", 3) compared "GNG" vs "GGA" — never matched.
|
||||
* Our fix: skip 2-char talker ID, compare at sentence+3. */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
ASSERT_EQ_INT(gps.fix_quality, 1, "GGA should parse with GN prefix");
|
||||
ASSERT_NEAR(gps.latitude, 44.069006, 0.001, "latitude should be parsed");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_regression_longitude_3digit_degrees(void)
|
||||
{
|
||||
TEST("regression: 3-digit longitude degrees parsed correctly");
|
||||
reset_gps();
|
||||
|
||||
/* PR #68 bug: hardcoded 2-digit degrees for longitude.
|
||||
* 12118.85961 should be 121° 18.85961' = 121.314327° */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
ASSERT_NEAR(gps.longitude, -(121.0 + 18.85961/60.0), 0.0001,
|
||||
"longitude 121° should not be parsed as 12°");
|
||||
ASSERT_TRUE(gps.longitude < -100.0, "longitude should be > 100 degrees");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_regression_hemisphere_no_ptr_corrupt(void)
|
||||
{
|
||||
TEST("regression: hemisphere parsing doesn't corrupt field pointer");
|
||||
reset_gps();
|
||||
|
||||
/* PR #68 bug: GGA/RMC hemisphere cases manually advanced ptr,
|
||||
* desynchronizing from field counter. Our parser uses proper tokenizer. */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||
|
||||
/* After lat/lon, remaining fields should be correct */
|
||||
ASSERT_EQ_INT(gps.num_satellites, 12, "sats after hemisphere");
|
||||
ASSERT_NEAR(gps.hdop, 0.98, 0.01, "hdop after hemisphere");
|
||||
ASSERT_NEAR(gps.altitude, 1113.0, 0.1, "altitude after hemisphere");
|
||||
PASS();
|
||||
}
|
||||
|
||||
static void test_regression_rmc_also_parsed(void)
|
||||
{
|
||||
TEST("regression: RMC sentence is actually parsed (not dead code)");
|
||||
reset_gps();
|
||||
|
||||
/* PR #68 bug: identifySentence never matched GGA/RMC, so position
|
||||
* parsing was dead code. */
|
||||
um982_parse_sentence(&gps,
|
||||
"$GNRMC,001031.00,A,4404.13993,N,12118.86023,W,0.146,,100117,,,A*7B");
|
||||
|
||||
ASSERT_TRUE(gps.latitude > 44.0, "RMC lat should be parsed");
|
||||
ASSERT_TRUE(gps.longitude < -121.0, "RMC lon should be parsed");
|
||||
ASSERT_NEAR(gps.speed_knots, 0.146, 0.001, "RMC speed");
|
||||
PASS();
|
||||
}
|
||||
|
||||
/* ========================= Main ====================================== */
|
||||
|
||||
int main(void)
|
||||
{
|
||||
printf("=== UM982 GPS Driver Tests ===\n\n");
|
||||
|
||||
printf("--- Checksum ---\n");
|
||||
test_checksum_valid();
|
||||
test_checksum_valid_ths();
|
||||
test_checksum_invalid();
|
||||
test_checksum_missing_star();
|
||||
test_checksum_null();
|
||||
test_checksum_no_dollar();
|
||||
|
||||
printf("\n--- Coordinate Parsing ---\n");
|
||||
test_coord_latitude_north();
|
||||
test_coord_latitude_south();
|
||||
test_coord_longitude_3digit();
|
||||
test_coord_longitude_east();
|
||||
test_coord_empty();
|
||||
test_coord_null();
|
||||
test_coord_no_dot();
|
||||
|
||||
printf("\n--- GGA Parsing ---\n");
|
||||
test_parse_gga_full();
|
||||
test_parse_gga_rtk_fixed();
|
||||
test_parse_gga_no_fix();
|
||||
|
||||
printf("\n--- RMC Parsing ---\n");
|
||||
test_parse_rmc_valid();
|
||||
test_parse_rmc_void();
|
||||
|
||||
printf("\n--- THS Parsing ---\n");
|
||||
test_parse_ths_autonomous();
|
||||
test_parse_ths_not_valid();
|
||||
test_parse_ths_zero();
|
||||
test_parse_ths_360_boundary();
|
||||
|
||||
printf("\n--- VTG Parsing ---\n");
|
||||
test_parse_vtg();
|
||||
|
||||
printf("\n--- Talker IDs ---\n");
|
||||
test_talker_gp();
|
||||
test_talker_gl();
|
||||
|
||||
printf("\n--- Feed / Line Assembly ---\n");
|
||||
test_feed_single_sentence();
|
||||
test_feed_multiple_sentences();
|
||||
test_feed_partial_then_complete();
|
||||
test_feed_bad_checksum_rejected();
|
||||
test_feed_versiona_response();
|
||||
|
||||
printf("\n--- Validity / Age ---\n");
|
||||
test_heading_valid_within_timeout();
|
||||
test_heading_invalid_after_timeout();
|
||||
test_heading_invalid_mode_v();
|
||||
test_position_valid();
|
||||
test_position_invalid_no_fix();
|
||||
test_position_age_uses_last_valid_fix();
|
||||
test_heading_age();
|
||||
|
||||
printf("\n--- Send Command ---\n");
|
||||
test_send_command_appends_crlf();
|
||||
test_send_command_null_safety();
|
||||
|
||||
printf("\n--- Init Sequence ---\n");
|
||||
test_init_sends_correct_commands();
|
||||
test_init_no_baseline();
|
||||
test_init_fails_no_version();
|
||||
test_nmea_traffic_sets_initialized_without_versiona();
|
||||
|
||||
printf("\n--- Edge Cases ---\n");
|
||||
test_empty_fields_handled();
|
||||
test_sentence_too_short();
|
||||
test_line_overflow();
|
||||
test_process_via_mock_uart();
|
||||
|
||||
printf("\n--- PR #68 Regression ---\n");
|
||||
test_regression_sentence_id_with_gn_prefix();
|
||||
test_regression_longitude_3digit_degrees();
|
||||
test_regression_hemisphere_no_ptr_corrupt();
|
||||
test_regression_rmc_also_parsed();
|
||||
|
||||
printf("\n===============================================\n");
|
||||
printf(" Results: %d passed, %d failed (of %d total)\n",
|
||||
tests_passed, tests_failed, tests_passed + tests_failed);
|
||||
printf("===============================================\n");
|
||||
|
||||
return tests_failed > 0 ? 1 : 0;
|
||||
}
|
||||
@@ -137,6 +137,145 @@ module cdc_adc_to_processing #(
|
||||
|
||||
endmodule
|
||||
|
||||
// ============================================================================
|
||||
// ASYNC FIFO FOR CONTINUOUS SAMPLE STREAMS
|
||||
// ============================================================================
|
||||
// Replaces cdc_adc_to_processing for the DDC path where the CIC decimator
|
||||
// produces samples at ~100 MSPS from a 400 MHz clock and the consumer runs
|
||||
// at 100 MHz. Gray-coded read/write pointers (the only valid use of Gray
|
||||
// encoding across clock domains) ensure no data corruption or loss.
|
||||
//
|
||||
// Depth must be a power of 2. Default 8 entries gives comfortable margin
|
||||
// for the 4:1 decimated stream (1 sample per 4 src clocks, 1 consumer
|
||||
// clock per sample).
|
||||
// ============================================================================
|
||||
module cdc_async_fifo #(
|
||||
parameter WIDTH = 18,
|
||||
parameter DEPTH = 8, // Must be power of 2
|
||||
parameter ADDR_BITS = 3 // log2(DEPTH)
|
||||
)(
|
||||
// Write (source) domain
|
||||
input wire wr_clk,
|
||||
input wire wr_reset_n,
|
||||
input wire [WIDTH-1:0] wr_data,
|
||||
input wire wr_en,
|
||||
output wire wr_full,
|
||||
|
||||
// Read (destination) domain
|
||||
input wire rd_clk,
|
||||
input wire rd_reset_n,
|
||||
output wire [WIDTH-1:0] rd_data,
|
||||
output wire rd_valid,
|
||||
input wire rd_ack // Consumer asserts to pop
|
||||
);
|
||||
|
||||
// Gray code conversion functions
|
||||
function [ADDR_BITS:0] bin2gray;
|
||||
input [ADDR_BITS:0] bin;
|
||||
bin2gray = bin ^ (bin >> 1);
|
||||
endfunction
|
||||
|
||||
function [ADDR_BITS:0] gray2bin;
|
||||
input [ADDR_BITS:0] gray;
|
||||
reg [ADDR_BITS:0] bin;
|
||||
integer k;
|
||||
begin
|
||||
bin[ADDR_BITS] = gray[ADDR_BITS];
|
||||
for (k = ADDR_BITS-1; k >= 0; k = k - 1)
|
||||
bin[k] = bin[k+1] ^ gray[k];
|
||||
gray2bin = bin;
|
||||
end
|
||||
endfunction
|
||||
|
||||
// ------- Pointer declarations (both domains, before use) -------
|
||||
// Write domain pointers
|
||||
reg [ADDR_BITS:0] wr_ptr_bin = 0; // Extra bit for full/empty
|
||||
reg [ADDR_BITS:0] wr_ptr_gray = 0;
|
||||
|
||||
// Read domain pointers (declared here so write domain can synchronize them)
|
||||
reg [ADDR_BITS:0] rd_ptr_bin = 0;
|
||||
reg [ADDR_BITS:0] rd_ptr_gray = 0;
|
||||
|
||||
// ------- Write domain -------
|
||||
|
||||
// Synchronized read pointer in write domain (scalar regs, not memory
|
||||
// arrays — avoids iverilog sensitivity/NBA bugs on array elements and
|
||||
// gives synthesis explicit flop names for ASYNC_REG constraints)
|
||||
(* ASYNC_REG = "TRUE" *) reg [ADDR_BITS:0] rd_ptr_gray_sync0 = 0;
|
||||
(* ASYNC_REG = "TRUE" *) reg [ADDR_BITS:0] rd_ptr_gray_sync1 = 0;
|
||||
|
||||
// FIFO memory (inferred as distributed RAM — small depth)
|
||||
reg [WIDTH-1:0] mem [0:DEPTH-1];
|
||||
|
||||
wire wr_addr_match = (wr_ptr_gray == rd_ptr_gray_sync1);
|
||||
wire wr_wrap_match = (wr_ptr_gray[ADDR_BITS] != rd_ptr_gray_sync1[ADDR_BITS]) &&
|
||||
(wr_ptr_gray[ADDR_BITS-1] != rd_ptr_gray_sync1[ADDR_BITS-1]) &&
|
||||
(wr_ptr_gray[ADDR_BITS-2:0] == rd_ptr_gray_sync1[ADDR_BITS-2:0]);
|
||||
assign wr_full = wr_wrap_match;
|
||||
|
||||
always @(posedge wr_clk) begin
|
||||
if (!wr_reset_n) begin
|
||||
wr_ptr_bin <= 0;
|
||||
wr_ptr_gray <= 0;
|
||||
rd_ptr_gray_sync0 <= 0;
|
||||
rd_ptr_gray_sync1 <= 0;
|
||||
end else begin
|
||||
// Synchronize read pointer into write domain
|
||||
rd_ptr_gray_sync0 <= rd_ptr_gray;
|
||||
rd_ptr_gray_sync1 <= rd_ptr_gray_sync0;
|
||||
|
||||
// Write
|
||||
if (wr_en && !wr_full) begin
|
||||
mem[wr_ptr_bin[ADDR_BITS-1:0]] <= wr_data;
|
||||
wr_ptr_bin <= wr_ptr_bin + 1;
|
||||
wr_ptr_gray <= bin2gray(wr_ptr_bin + 1);
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
// ------- Read domain -------
|
||||
|
||||
// Synchronized write pointer in read domain (scalar regs — see above)
|
||||
(* ASYNC_REG = "TRUE" *) reg [ADDR_BITS:0] wr_ptr_gray_sync0 = 0;
|
||||
(* ASYNC_REG = "TRUE" *) reg [ADDR_BITS:0] wr_ptr_gray_sync1 = 0;
|
||||
|
||||
wire rd_empty = (rd_ptr_gray == wr_ptr_gray_sync1);
|
||||
|
||||
// Output register — holds data until consumed
|
||||
reg [WIDTH-1:0] rd_data_reg = 0;
|
||||
reg rd_valid_reg = 0;
|
||||
|
||||
always @(posedge rd_clk) begin
|
||||
if (!rd_reset_n) begin
|
||||
rd_ptr_bin <= 0;
|
||||
rd_ptr_gray <= 0;
|
||||
wr_ptr_gray_sync0 <= 0;
|
||||
wr_ptr_gray_sync1 <= 0;
|
||||
rd_data_reg <= 0;
|
||||
rd_valid_reg <= 0;
|
||||
end else begin
|
||||
// Synchronize write pointer into read domain
|
||||
wr_ptr_gray_sync0 <= wr_ptr_gray;
|
||||
wr_ptr_gray_sync1 <= wr_ptr_gray_sync0;
|
||||
|
||||
// Pop logic: present data when FIFO not empty
|
||||
if (!rd_empty && (!rd_valid_reg || rd_ack)) begin
|
||||
rd_data_reg <= mem[rd_ptr_bin[ADDR_BITS-1:0]];
|
||||
rd_valid_reg <= 1'b1;
|
||||
rd_ptr_bin <= rd_ptr_bin + 1;
|
||||
rd_ptr_gray <= bin2gray(rd_ptr_bin + 1);
|
||||
end else if (rd_valid_reg && rd_ack) begin
|
||||
// Consumer took data but FIFO is empty now
|
||||
rd_valid_reg <= 1'b0;
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
assign rd_data = rd_data_reg;
|
||||
assign rd_valid = rd_valid_reg;
|
||||
|
||||
endmodule
|
||||
|
||||
// ============================================================================
|
||||
// CDC FOR SINGLE BIT SIGNALS
|
||||
// Uses synchronous reset on sync chain to avoid metastability on reset
|
||||
|
||||
@@ -584,41 +584,59 @@ cic_decimator_4x_enhanced cic_q_inst (
|
||||
assign cic_valid = cic_valid_i & cic_valid_q;
|
||||
|
||||
// ============================================================================
|
||||
// Enhanced FIR Filters with FIXED valid signal handling
|
||||
// NOTE: Wire declarations moved BEFORE CDC instances to fix forward-reference
|
||||
// error in Icarus Verilog (was originally after CDC instantiation)
|
||||
// Clock Domain Crossing: 400 MHz CIC output → 100 MHz FIR input
|
||||
// ============================================================================
|
||||
// The CIC decimates 4:1, producing one sample per 4 clk_400m cycles (~100 MSPS).
|
||||
// The FIR runs at clk_100m (100 MHz). The two clocks have unknown phase
|
||||
// relationship, so a proper asynchronous FIFO with Gray-coded pointers is
|
||||
// required. The old cdc_adc_to_processing module Gray-encoded the sample
|
||||
// DATA which is invalid (Gray encoding only guarantees single-bit transitions
|
||||
// for monotonically incrementing counters, not arbitrary sample values).
|
||||
//
|
||||
// Depth 8 provides margin: worst case, 2 samples can be in flight before
|
||||
// the read side pops, well within a depth-8 budget.
|
||||
// ============================================================================
|
||||
wire fir_in_valid_i, fir_in_valid_q;
|
||||
wire fir_valid_i, fir_valid_q;
|
||||
wire fir_i_ready, fir_q_ready;
|
||||
wire [17:0] fir_d_in_i, fir_d_in_q;
|
||||
wire [17:0] fir_d_in_i, fir_d_in_q;
|
||||
|
||||
cdc_adc_to_processing #(
|
||||
.WIDTH(18),
|
||||
.STAGES(3)
|
||||
)CDC_FIR_i(
|
||||
.src_clk(clk_400m),
|
||||
.dst_clk(clk_100m),
|
||||
.src_reset_n(reset_n_400m),
|
||||
.dst_reset_n(reset_n),
|
||||
.src_data(cic_i_out),
|
||||
.src_valid(cic_valid_i),
|
||||
.dst_data(fir_d_in_i),
|
||||
.dst_valid(fir_in_valid_i)
|
||||
// I-channel CDC: async FIFO, 400 MHz write → 100 MHz read
|
||||
cdc_async_fifo #(
|
||||
.WIDTH(18),
|
||||
.DEPTH(8),
|
||||
.ADDR_BITS(3)
|
||||
) CDC_FIR_i (
|
||||
.wr_clk(clk_400m),
|
||||
.wr_reset_n(reset_n_400m),
|
||||
.wr_data(cic_i_out),
|
||||
.wr_en(cic_valid_i),
|
||||
.wr_full(), // At 1:1 data rate, overflow should not occur
|
||||
|
||||
.rd_clk(clk_100m),
|
||||
.rd_reset_n(reset_n),
|
||||
.rd_data(fir_d_in_i),
|
||||
.rd_valid(fir_in_valid_i),
|
||||
.rd_ack(fir_in_valid_i) // Auto-pop: consume every valid sample
|
||||
);
|
||||
|
||||
cdc_adc_to_processing #(
|
||||
.WIDTH(18),
|
||||
.STAGES(3)
|
||||
)CDC_FIR_q(
|
||||
.src_clk(clk_400m),
|
||||
.dst_clk(clk_100m),
|
||||
.src_reset_n(reset_n_400m),
|
||||
.dst_reset_n(reset_n),
|
||||
.src_data(cic_q_out),
|
||||
.src_valid(cic_valid_q),
|
||||
.dst_data(fir_d_in_q),
|
||||
.dst_valid(fir_in_valid_q)
|
||||
// Q-channel CDC: async FIFO, 400 MHz write → 100 MHz read
|
||||
cdc_async_fifo #(
|
||||
.WIDTH(18),
|
||||
.DEPTH(8),
|
||||
.ADDR_BITS(3)
|
||||
) CDC_FIR_q (
|
||||
.wr_clk(clk_400m),
|
||||
.wr_reset_n(reset_n_400m),
|
||||
.wr_data(cic_q_out),
|
||||
.wr_en(cic_valid_q),
|
||||
.wr_full(),
|
||||
|
||||
.rd_clk(clk_100m),
|
||||
.rd_reset_n(reset_n),
|
||||
.rd_data(fir_d_in_q),
|
||||
.rd_valid(fir_in_valid_q),
|
||||
.rd_ack(fir_in_valid_q)
|
||||
);
|
||||
|
||||
// ============================================================================
|
||||
|
||||
@@ -531,6 +531,23 @@ xfft_16 fft_inst (
|
||||
// Status Outputs
|
||||
// ==============================================
|
||||
assign processing_active = (state != S_IDLE);
|
||||
assign frame_complete = (state == S_IDLE && frame_buffer_full == 0);
|
||||
|
||||
// frame_complete must be a single-cycle pulse, not a level.
|
||||
// The AGC (rx_gain_control) uses this as frame_boundary to snapshot
|
||||
// per-frame metrics and update gain. If held high continuously,
|
||||
// the AGC would re-evaluate every clock with zeroed accumulators,
|
||||
// collapsing saturation_count/peak_magnitude to zero.
|
||||
//
|
||||
// Detect the falling edge of processing_active: the exact clock
|
||||
// when the Doppler processor finishes all sub-frame FFTs and
|
||||
// returns to S_IDLE with the frame buffer drained.
|
||||
reg processing_active_prev;
|
||||
always @(posedge clk or negedge reset_n) begin
|
||||
if (!reset_n)
|
||||
processing_active_prev <= 1'b0;
|
||||
else
|
||||
processing_active_prev <= processing_active;
|
||||
end
|
||||
assign frame_complete = (~processing_active & processing_active_prev);
|
||||
|
||||
endmodule
|
||||
|
||||
@@ -77,6 +77,7 @@ reg signed [15:0] buf_rdata_i, buf_rdata_q;
|
||||
// State machine
|
||||
reg [3:0] state;
|
||||
localparam ST_IDLE = 0;
|
||||
localparam ST_WAIT_LISTEN = 9; // Wait for TX chirp to end before collecting
|
||||
localparam ST_COLLECT_DATA = 1;
|
||||
localparam ST_ZERO_PAD = 2;
|
||||
localparam ST_WAIT_REF = 3;
|
||||
@@ -98,11 +99,22 @@ reg signed [15:0] overlap_cache_i [0:OVERLAP_SAMPLES-1];
|
||||
reg signed [15:0] overlap_cache_q [0:OVERLAP_SAMPLES-1];
|
||||
reg [7:0] overlap_copy_count;
|
||||
|
||||
// Listen-window delay counter: skip TX chirp duration before collecting echoes.
|
||||
// The chirp_start_pulse fires at the beginning of TX, but the matched filter
|
||||
// must collect receive-window samples (echoes), not TX leakage.
|
||||
// For long chirp: skip LONG_CHIRP_SAMPLES (3000) ddc_valid counts
|
||||
// For short chirp: skip SHORT_CHIRP_SAMPLES (50) ddc_valid counts
|
||||
reg [15:0] listen_delay_count;
|
||||
reg [15:0] listen_delay_target;
|
||||
|
||||
// Microcontroller sync detection
|
||||
// mc_new_chirp/elevation/azimuth are TOGGLE signals from radar_mode_controller:
|
||||
// they invert on every event. Detect ANY transition (XOR with previous value),
|
||||
// not just rising edge, otherwise every other chirp/elevation/azimuth is missed.
|
||||
reg mc_new_chirp_prev, mc_new_elevation_prev, mc_new_azimuth_prev;
|
||||
wire chirp_start_pulse = mc_new_chirp && !mc_new_chirp_prev;
|
||||
wire elevation_change_pulse = mc_new_elevation && !mc_new_elevation_prev;
|
||||
wire azimuth_change_pulse = mc_new_azimuth && !mc_new_azimuth_prev;
|
||||
wire chirp_start_pulse = mc_new_chirp ^ mc_new_chirp_prev;
|
||||
wire elevation_change_pulse = mc_new_elevation ^ mc_new_elevation_prev;
|
||||
wire azimuth_change_pulse = mc_new_azimuth ^ mc_new_azimuth_prev;
|
||||
|
||||
// Processing chain signals
|
||||
wire [15:0] fft_pc_i, fft_pc_q;
|
||||
@@ -184,6 +196,8 @@ always @(posedge clk or negedge reset_n) begin
|
||||
buf_wdata_q <= 0;
|
||||
buf_raddr <= 0;
|
||||
overlap_copy_count <= 0;
|
||||
listen_delay_count <= 0;
|
||||
listen_delay_target <= 0;
|
||||
end else begin
|
||||
pc_valid <= 0;
|
||||
mem_request <= 0;
|
||||
@@ -205,19 +219,45 @@ always @(posedge clk or negedge reset_n) begin
|
||||
|
||||
// Wait for chirp start from microcontroller
|
||||
if (chirp_start_pulse) begin
|
||||
state <= ST_COLLECT_DATA;
|
||||
total_segments <= use_long_chirp ? LONG_SEGMENTS[2:0] : SHORT_SEGMENTS[2:0];
|
||||
|
||||
// Delay collection until the listen window opens.
|
||||
// chirp_start_pulse fires at TX start; echoes only arrive
|
||||
// after the chirp finishes. Skip the TX duration by
|
||||
// counting ddc_valid pulses before entering ST_COLLECT_DATA.
|
||||
listen_delay_count <= 0;
|
||||
listen_delay_target <= use_long_chirp ? LONG_CHIRP_SAMPLES[15:0]
|
||||
: SHORT_CHIRP_SAMPLES[15:0];
|
||||
state <= ST_WAIT_LISTEN;
|
||||
|
||||
`ifdef SIMULATION
|
||||
$display("[MULTI_SEG_FIXED] Starting %s chirp, segments: %d",
|
||||
use_long_chirp ? "LONG" : "SHORT",
|
||||
use_long_chirp ? LONG_SEGMENTS : SHORT_SEGMENTS);
|
||||
$display("[MULTI_SEG_FIXED] Overlap: %d samples, Advance: %d samples",
|
||||
OVERLAP_SAMPLES, SEGMENT_ADVANCE);
|
||||
$display("[MULTI_SEG_FIXED] Chirp start detected, waiting for listen window (%0d samples)",
|
||||
use_long_chirp ? LONG_CHIRP_SAMPLES : SHORT_CHIRP_SAMPLES);
|
||||
`endif
|
||||
end
|
||||
end
|
||||
|
||||
ST_WAIT_LISTEN: begin
|
||||
// Skip TX chirp duration — count ddc_valid pulses until the
|
||||
// listen window opens. This ensures we only collect echo data,
|
||||
// not TX leakage or dead time.
|
||||
if (ddc_valid) begin
|
||||
if (listen_delay_count >= listen_delay_target - 1) begin
|
||||
// Listen window is now open — begin data collection
|
||||
state <= ST_COLLECT_DATA;
|
||||
`ifdef SIMULATION
|
||||
$display("[MULTI_SEG_FIXED] Listen window open after %0d TX samples, starting %s chirp collection",
|
||||
listen_delay_count + 1,
|
||||
use_long_chirp ? "LONG" : "SHORT");
|
||||
$display("[MULTI_SEG_FIXED] Overlap: %d samples, Advance: %d samples",
|
||||
OVERLAP_SAMPLES, SEGMENT_ADVANCE);
|
||||
`endif
|
||||
end else begin
|
||||
listen_delay_count <= listen_delay_count + 1;
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
ST_COLLECT_DATA: begin
|
||||
// Collect samples for current segment with overlap-save
|
||||
if (ddc_valid && buffer_write_ptr < BUFFER_SIZE) begin
|
||||
@@ -534,9 +574,36 @@ always @(posedge clk or negedge reset_n) begin
|
||||
end
|
||||
`endif
|
||||
|
||||
// ========== OUTPUT CONNECTIONS ==========
|
||||
// ========== OUTPUT CONNECTIONS — OVERLAP-SAVE TRIM ==========
|
||||
// In overlap-save processing, the first OVERLAP_SAMPLES (128) output bins
|
||||
// of each segment after segment 0 are corrupted by circular convolution
|
||||
// wrap-around. These must be discarded. Only the SEGMENT_ADVANCE (896)
|
||||
// valid bins per segment are forwarded downstream.
|
||||
//
|
||||
// For segment 0: all 1024 output bins are valid (no prior overlap).
|
||||
// For segments 1+: bins [0..127] are artifacts, bins [128..1023] are valid.
|
||||
//
|
||||
// We count fft_pc_valid pulses per segment and suppress output during
|
||||
// the overlap region.
|
||||
reg [10:0] output_bin_count;
|
||||
wire output_in_overlap = (current_segment != 0) &&
|
||||
(output_bin_count < OVERLAP_SAMPLES);
|
||||
|
||||
always @(posedge clk or negedge reset_n) begin
|
||||
if (!reset_n) begin
|
||||
output_bin_count <= 0;
|
||||
end else begin
|
||||
if (state == ST_PROCESSING && buffer_read_ptr == 0) begin
|
||||
// Reset counter at start of each segment's processing
|
||||
output_bin_count <= 0;
|
||||
end else if (fft_pc_valid) begin
|
||||
output_bin_count <= output_bin_count + 1;
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
assign pc_i_w = fft_pc_i;
|
||||
assign pc_q_w = fft_pc_q;
|
||||
assign pc_valid_w = fft_pc_valid;
|
||||
assign pc_valid_w = fft_pc_valid & ~output_in_overlap;
|
||||
|
||||
endmodule
|
||||
@@ -11,8 +11,10 @@ module radar_receiver_final (
|
||||
input wire adc_dco_n, // Data Clock Output N (400MHz LVDS)
|
||||
output wire adc_pwdn,
|
||||
|
||||
// Chirp counter from transmitter (for frame sync and matched filter)
|
||||
// Chirp counter from transmitter (for matched filter indexing)
|
||||
input wire [5:0] chirp_counter,
|
||||
// Frame-start pulse from transmitter (CDC-synchronized, 1 clk_100m cycle)
|
||||
input wire tx_frame_start,
|
||||
|
||||
output wire [31:0] doppler_output,
|
||||
output wire doppler_valid,
|
||||
@@ -392,32 +394,31 @@ mti_canceller #(
|
||||
.mti_first_chirp(mti_first_chirp)
|
||||
);
|
||||
|
||||
// ========== FRAME SYNC USING chirp_counter ==========
|
||||
reg [5:0] chirp_counter_prev;
|
||||
// ========== FRAME SYNC FROM TRANSMITTER ==========
|
||||
// [FPGA-001 FIXED] Use the authoritative new_chirp_frame signal from the
|
||||
// transmitter (via plfm_chirp_controller_enhanced), CDC-synchronized to
|
||||
// clk_100m in radar_system_top. Previous code tried to derive frame
|
||||
// boundaries from chirp_counter == 0, but that counter comes from the
|
||||
// transmitter path (plfm_chirp_controller_enhanced) which does NOT wrap
|
||||
// at chirps_per_elev — it overflows to N and only wraps at 6-bit rollover
|
||||
// (64). This caused frame pulses at half the expected rate for N=32.
|
||||
reg tx_frame_start_prev;
|
||||
reg new_frame_pulse;
|
||||
|
||||
always @(posedge clk or negedge reset_n) begin
|
||||
if (!reset_n) begin
|
||||
chirp_counter_prev <= 6'd0;
|
||||
tx_frame_start_prev <= 1'b0;
|
||||
new_frame_pulse <= 1'b0;
|
||||
end else begin
|
||||
// Default: no pulse
|
||||
new_frame_pulse <= 1'b0;
|
||||
|
||||
// Dynamic frame detection using host_chirps_per_elev.
|
||||
// Detect frame boundary when chirp_counter changes AND is a
|
||||
// multiple of host_chirps_per_elev (0, N, 2N, 3N, ...).
|
||||
// Uses a modulo counter that resets at host_chirps_per_elev.
|
||||
if (chirp_counter != chirp_counter_prev) begin
|
||||
if (chirp_counter == 6'd0 ||
|
||||
chirp_counter == host_chirps_per_elev ||
|
||||
chirp_counter == {host_chirps_per_elev, 1'b0}) begin
|
||||
new_frame_pulse <= 1'b1;
|
||||
end
|
||||
// Edge detect: tx_frame_start is a toggle-CDC derived pulse that
|
||||
// may be 1 clock wide. Capture rising edge for clean 1-cycle pulse.
|
||||
if (tx_frame_start && !tx_frame_start_prev) begin
|
||||
new_frame_pulse <= 1'b1;
|
||||
end
|
||||
|
||||
// Store previous value
|
||||
chirp_counter_prev <= chirp_counter;
|
||||
tx_frame_start_prev <= tx_frame_start;
|
||||
end
|
||||
end
|
||||
|
||||
@@ -483,14 +484,6 @@ always @(posedge clk or negedge reset_n) begin
|
||||
`endif
|
||||
chirps_in_current_frame <= 0;
|
||||
end
|
||||
|
||||
// Monitor chirp counter pattern
|
||||
if (chirp_counter != chirp_counter_prev) begin
|
||||
`ifdef SIMULATION
|
||||
$display("[TOP] chirp_counter: %0d ? %0d",
|
||||
chirp_counter_prev, chirp_counter);
|
||||
`endif
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
|
||||
@@ -505,6 +505,8 @@ radar_receiver_final rx_inst (
|
||||
|
||||
// Chirp counter from transmitter (CDC-synchronized from 120 MHz domain)
|
||||
.chirp_counter(tx_current_chirp_sync),
|
||||
// Frame-start pulse from transmitter (CDC-synchronized toggle→pulse)
|
||||
.tx_frame_start(tx_new_chirp_frame_sync),
|
||||
|
||||
// ADC Physical Interface
|
||||
.adc_d_p(adc_d_p),
|
||||
|
||||
@@ -526,6 +526,25 @@ run_test "Radar Mode Controller" \
|
||||
|
||||
echo ""
|
||||
|
||||
# ===========================================================================
|
||||
# PHASE 5: P0 ADVERSARIAL TESTS — Invariant Violation Fixes
|
||||
# ===========================================================================
|
||||
echo "--- PHASE 5: P0 Adversarial Tests ---"
|
||||
|
||||
run_test "P0 Fix #1: Async FIFO CDC (show-ahead, overflow, reset)" \
|
||||
tb/tb_p0_async_fifo.vvp \
|
||||
tb/tb_p0_async_fifo.v cdc_modules.v
|
||||
|
||||
run_test "P0 Fixes #2/#3/#4: Matched Filter (toggle, listen, overlap)" \
|
||||
tb/tb_p0_mf_adversarial.vvp \
|
||||
tb/tb_p0_mf_adversarial.v matched_filter_multi_segment.v
|
||||
|
||||
run_test "P0 Fix #7: Frame Complete Pulse (falling-edge)" \
|
||||
tb/tb_p0_frame_pulse.vvp \
|
||||
tb/tb_p0_frame_pulse.v
|
||||
|
||||
echo ""
|
||||
|
||||
# ===========================================================================
|
||||
# SUMMARY
|
||||
# ===========================================================================
|
||||
|
||||
@@ -291,9 +291,12 @@ class Mixer:
|
||||
Convert 8-bit unsigned ADC to 18-bit signed.
|
||||
RTL: adc_signed_w = {1'b0, adc_data, {9{1'b0}}} -
|
||||
{1'b0, {8{1'b1}}, {9{1'b0}}} / 2
|
||||
= (adc_data << 9) - (0xFF << 9) / 2
|
||||
= (adc_data << 9) - (0xFF << 8) [integer division]
|
||||
= (adc_data << 9) - 0x7F80
|
||||
|
||||
Verilog '/' binds tighter than '-', so the division applies
|
||||
only to the second concatenation:
|
||||
{1'b0, 8'hFF, 9'b0} = 0x1FE00
|
||||
0x1FE00 / 2 = 0xFF00 = 65280
|
||||
Result: (adc_data << 9) - 0xFF00
|
||||
"""
|
||||
adc_data_8bit = adc_data_8bit & 0xFF
|
||||
# {1'b0, adc_data, 9'b0} = adc_data << 9, zero-padded to 18 bits
|
||||
|
||||
@@ -290,9 +290,9 @@ def run_ddc(adc_samples):
|
||||
for n in range(n_samples):
|
||||
# ADC sign conversion: RTL does offset binary → signed 18-bit
|
||||
# adc_signed_w = {1'b0, adc_data, 9'b0} - {1'b0, 8'hFF, 9'b0}/2
|
||||
# Simplified: center around zero, scale to 18-bit
|
||||
# Exact: (adc_val << 9) - 0xFF00, where 0xFF00 = {1'b0,8'hFF,9'b0}/2
|
||||
adc_val = int(adc_samples[n])
|
||||
adc_signed = (adc_val - 128) << 9 # Approximate RTL sign conversion to 18-bit
|
||||
adc_signed = (adc_val << 9) - 0xFF00 # Exact RTL: {1'b0,adc,9'b0} - {1'b0,8'hFF,9'b0}/2
|
||||
adc_signed = saturate(adc_signed, 18)
|
||||
|
||||
# NCO lookup (ignoring dithering for golden reference)
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,558 @@
|
||||
`timescale 1ns / 1ps
|
||||
|
||||
// ============================================================================
|
||||
// ADVERSARIAL TESTBENCH: cdc_async_fifo (P0 Fix #1)
|
||||
// ============================================================================
|
||||
// Actively tries to BREAK the async FIFO that replaced the flawed
|
||||
// Gray-encoded CDC for the DDC 400→100 MHz sample path.
|
||||
//
|
||||
// Attack vectors:
|
||||
// 1. Read on empty FIFO — no spurious rd_valid
|
||||
// 2. Single write/read — basic data integrity
|
||||
// 3. Fill to capacity — wr_full asserts correctly
|
||||
// 4. Overflow — write-when-full must be rejected, no corruption
|
||||
// 5. Ordered streaming — FIFO order preserved under sustained load
|
||||
// 6. Reset mid-transfer — clean recovery, no stale data
|
||||
// 7. Burst writes at max wr_clk rate — stress back-pressure
|
||||
// 8. wr_full deasserts promptly after read
|
||||
// 9. Alternating single-entry traffic — throughput = 1
|
||||
// 10. Pathological data patterns — all-ones, alternating bits
|
||||
// ============================================================================
|
||||
|
||||
module tb_p0_async_fifo;
|
||||
|
||||
localparam WR_PERIOD = 2.5; // 400 MHz source clock
|
||||
localparam RD_PERIOD = 10.0; // 100 MHz destination clock
|
||||
localparam WIDTH = 18;
|
||||
localparam DEPTH = 8;
|
||||
|
||||
// ── Test bookkeeping ─────────────────────────────────────
|
||||
integer pass_count = 0;
|
||||
integer fail_count = 0;
|
||||
integer test_num = 0;
|
||||
integer i, j;
|
||||
|
||||
task check;
|
||||
input cond;
|
||||
input [511:0] label;
|
||||
begin
|
||||
test_num = test_num + 1;
|
||||
if (cond) begin
|
||||
$display("[PASS] Test %0d: %0s", test_num, label);
|
||||
pass_count = pass_count + 1;
|
||||
end else begin
|
||||
$display("[FAIL] Test %0d: %0s", test_num, label);
|
||||
fail_count = fail_count + 1;
|
||||
end
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── DUT signals ──────────────────────────────────────────
|
||||
reg wr_clk = 0;
|
||||
reg rd_clk = 0;
|
||||
reg wr_reset_n = 0;
|
||||
reg rd_reset_n = 0;
|
||||
reg [WIDTH-1:0] wr_data = 0;
|
||||
reg wr_en = 0;
|
||||
wire wr_full;
|
||||
wire [WIDTH-1:0] rd_data;
|
||||
wire rd_valid;
|
||||
reg rd_ack = 0;
|
||||
|
||||
always #(WR_PERIOD/2) wr_clk = ~wr_clk;
|
||||
always #(RD_PERIOD/2) rd_clk = ~rd_clk;
|
||||
|
||||
cdc_async_fifo #(
|
||||
.WIDTH(WIDTH), .DEPTH(DEPTH), .ADDR_BITS(3)
|
||||
) dut (
|
||||
.wr_clk(wr_clk), .wr_reset_n(wr_reset_n),
|
||||
.wr_data(wr_data), .wr_en(wr_en), .wr_full(wr_full),
|
||||
.rd_clk(rd_clk), .rd_reset_n(rd_reset_n),
|
||||
.rd_data(rd_data), .rd_valid(rd_valid), .rd_ack(rd_ack)
|
||||
);
|
||||
|
||||
// ── Helper tasks ─────────────────────────────────────────
|
||||
task do_reset;
|
||||
begin
|
||||
wr_en = 0; rd_ack = 0; wr_data = 0;
|
||||
wr_reset_n = 0; rd_reset_n = 0;
|
||||
#100;
|
||||
wr_reset_n = 1; rd_reset_n = 1;
|
||||
#50;
|
||||
end
|
||||
endtask
|
||||
|
||||
task wait_wr_n;
|
||||
input integer n;
|
||||
integer k;
|
||||
begin
|
||||
for (k = 0; k < n; k = k + 1) @(posedge wr_clk);
|
||||
end
|
||||
endtask
|
||||
|
||||
task wait_rd_n;
|
||||
input integer n;
|
||||
integer k;
|
||||
begin
|
||||
for (k = 0; k < n; k = k + 1) @(posedge rd_clk);
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── Read one entry with timeout ──────────────────────────
|
||||
reg [WIDTH-1:0] read_result;
|
||||
reg read_ok;
|
||||
|
||||
task read_one;
|
||||
output [WIDTH-1:0] data_out;
|
||||
output valid_out;
|
||||
integer timeout;
|
||||
begin
|
||||
rd_ack = 1;
|
||||
valid_out = 0;
|
||||
data_out = {WIDTH{1'bx}};
|
||||
for (timeout = 0; timeout < 20; timeout = timeout + 1) begin
|
||||
@(posedge rd_clk);
|
||||
if (rd_valid) begin
|
||||
data_out = rd_data;
|
||||
valid_out = 1;
|
||||
timeout = 999; // break
|
||||
end
|
||||
end
|
||||
@(posedge rd_clk);
|
||||
rd_ack = 0;
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── Drain FIFO, return count of entries read ─────────────
|
||||
integer drain_count;
|
||||
reg [WIDTH-1:0] drain_buf [0:15];
|
||||
|
||||
task drain_fifo;
|
||||
output integer count;
|
||||
integer t;
|
||||
begin
|
||||
count = 0;
|
||||
rd_ack = 1;
|
||||
for (t = 0; t < 60; t = t + 1) begin
|
||||
@(posedge rd_clk);
|
||||
if (rd_valid && count < 16) begin
|
||||
drain_buf[count] = rd_data;
|
||||
count = count + 1;
|
||||
end
|
||||
end
|
||||
rd_ack = 0;
|
||||
wait_rd_n(3);
|
||||
end
|
||||
endtask
|
||||
|
||||
// ══════════════════════════════════════════════════════════
|
||||
// MAIN TEST SEQUENCE
|
||||
// ══════════════════════════════════════════════════════════
|
||||
initial begin
|
||||
$dumpfile("tb_p0_async_fifo.vcd");
|
||||
$dumpvars(0, tb_p0_async_fifo);
|
||||
|
||||
do_reset;
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 1: Empty FIFO — no spurious rd_valid
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 1: Empty FIFO behavior ===");
|
||||
|
||||
// 1a: rd_valid must be 0 when nothing written
|
||||
wait_rd_n(10);
|
||||
check(rd_valid == 0, "Empty FIFO: rd_valid is 0 (no writes)");
|
||||
|
||||
// 1b: rd_ack on empty must not produce spurious valid
|
||||
rd_ack = 1;
|
||||
wait_rd_n(10);
|
||||
check(rd_valid == 0, "Empty FIFO: rd_ack on empty produces no valid");
|
||||
rd_ack = 0;
|
||||
wait_rd_n(3);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 2: Single write/read
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 2: Single write/read ===");
|
||||
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = 18'h2ABCD;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Wait for CDC propagation
|
||||
wait_rd_n(6);
|
||||
check(rd_valid == 1, "Single write: rd_valid asserted");
|
||||
check(rd_data == 18'h2ABCD, "Single write: data integrity");
|
||||
|
||||
// ACK and verify deassert
|
||||
#1; rd_ack = 1;
|
||||
@(posedge rd_clk); #1;
|
||||
rd_ack = 0;
|
||||
wait_rd_n(6);
|
||||
check(rd_valid == 0, "Single write: rd_valid deasserts after ack+empty");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 3: Fill to capacity
|
||||
// ──────────────────────────────────────────────────────
|
||||
// NOTE: This FIFO uses a pre-fetch show-ahead architecture.
|
||||
// When the FIFO goes from empty to non-empty, the read domain
|
||||
// auto-presents the first entry into rd_data_reg, advancing
|
||||
// rd_ptr by 1. This frees one slot in the underlying memory,
|
||||
// so wr_full requires DEPTH+1 writes (DEPTH in mem + 1 in the
|
||||
// output register). This is necessary because a combinational
|
||||
// read from mem across clock domains would be CDC-unsafe.
|
||||
$display("\n=== GROUP 3: Fill to capacity ===");
|
||||
do_reset;
|
||||
|
||||
// Write DEPTH entries
|
||||
for (i = 0; i < DEPTH; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = i[17:0] + 18'h100;
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Wait for auto-present round-trip through both synchronizers
|
||||
wait_wr_n(12);
|
||||
|
||||
// After auto-present, rd_ptr advanced by 1 → 1 slot freed → not full yet
|
||||
check(wr_full == 0, "Pre-fetch show-ahead: DEPTH writes, 1 auto-present frees slot");
|
||||
|
||||
// Write one more entry into the freed slot → now truly full
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = 18'hFACE;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
wait_wr_n(6);
|
||||
check(wr_full == 1, "Fill-to-full: wr_full asserted after DEPTH+1 writes");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 4: Overflow — write when full
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 4: Overflow protection ===");
|
||||
|
||||
// Attempt to write 3 more entries while full
|
||||
for (i = 0; i < 3; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = 18'h3DEAD + i[17:0];
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Drain and verify DEPTH+1 entries (DEPTH mem + 1 output register)
|
||||
drain_fifo(drain_count);
|
||||
check(drain_count == DEPTH + 1, "Overflow: exactly DEPTH+1 entries (overflow rejected)");
|
||||
|
||||
// Verify data integrity — check first DEPTH entries + the extra FACE entry
|
||||
begin : overflow_data_check
|
||||
reg data_ok;
|
||||
data_ok = 1;
|
||||
// First entry is the auto-presented one (index 0 from Group 3)
|
||||
if (drain_buf[0] !== 18'h100) begin
|
||||
$display(" overflow corruption at [0]: expected %h, got %h",
|
||||
18'h100, drain_buf[0]);
|
||||
data_ok = 0;
|
||||
end
|
||||
// Next DEPTH-1 entries are indices 1..DEPTH-1
|
||||
for (i = 1; i < DEPTH; i = i + 1) begin
|
||||
if (drain_buf[i] !== i[17:0] + 18'h100) begin
|
||||
$display(" overflow corruption at [%0d]: expected %h, got %h",
|
||||
i, i[17:0] + 18'h100, drain_buf[i]);
|
||||
data_ok = 0;
|
||||
end
|
||||
end
|
||||
// Last entry is the FACE entry from the +1 write
|
||||
if (drain_buf[DEPTH] !== 18'hFACE) begin
|
||||
$display(" overflow corruption at [%0d]: expected %h, got %h",
|
||||
DEPTH, 18'hFACE, drain_buf[DEPTH]);
|
||||
data_ok = 0;
|
||||
end
|
||||
check(data_ok, "Overflow: all DEPTH+1 entries data intact (no corruption)");
|
||||
end
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 5: Data ordering under sustained streaming
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 5: Sustained streaming order ===");
|
||||
do_reset;
|
||||
|
||||
// Simulate CIC-decimated DDC output: 1 sample per 4 wr_clks
|
||||
// Reader continuously ACKs (rate-matched at 100 MHz)
|
||||
begin : stream_test
|
||||
reg [WIDTH-1:0] expected_val;
|
||||
integer read_idx;
|
||||
reg ordering_ok;
|
||||
|
||||
ordering_ok = 1;
|
||||
read_idx = 0;
|
||||
|
||||
fork
|
||||
// Writer: 32 samples, 1 per 4 wr_clks (rate-matched to rd_clk)
|
||||
begin : stream_writer
|
||||
integer w;
|
||||
for (w = 0; w < 32; w = w + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = w[17:0] + 18'h1000;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
wait_wr_n(2); // 4 wr_clks total per sample
|
||||
end
|
||||
end
|
||||
|
||||
// Reader: continuously consume at rd_clk rate
|
||||
begin : stream_reader
|
||||
integer rd_t;
|
||||
rd_ack = 1;
|
||||
for (rd_t = 0; rd_t < 500 && read_idx < 32; rd_t = rd_t + 1) begin
|
||||
@(posedge rd_clk);
|
||||
if (rd_valid) begin
|
||||
expected_val = read_idx[17:0] + 18'h1000;
|
||||
if (rd_data !== expected_val) begin
|
||||
$display(" stream order error at [%0d]: expected %h, got %h",
|
||||
read_idx, expected_val, rd_data);
|
||||
ordering_ok = 0;
|
||||
end
|
||||
read_idx = read_idx + 1;
|
||||
end
|
||||
end
|
||||
#1; rd_ack = 0;
|
||||
end
|
||||
join
|
||||
|
||||
check(read_idx == 32, "Streaming: all 32 samples received");
|
||||
check(ordering_ok, "Streaming: FIFO order preserved");
|
||||
end
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 6: Reset mid-transfer
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 6: Reset mid-transfer ===");
|
||||
do_reset;
|
||||
|
||||
// Write 4 entries
|
||||
for (i = 0; i < 4; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = i[17:0] + 18'hAA00;
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
wait_wr_n(3);
|
||||
|
||||
// Assert reset while data is in FIFO
|
||||
wr_reset_n = 0; rd_reset_n = 0;
|
||||
#50;
|
||||
wr_reset_n = 1; rd_reset_n = 1;
|
||||
#50;
|
||||
|
||||
// 6a: FIFO must be empty after reset
|
||||
wait_rd_n(10);
|
||||
check(rd_valid == 0, "Reset mid-xfer: FIFO empty (no stale data)");
|
||||
check(wr_full == 0, "Reset mid-xfer: wr_full deasserted");
|
||||
|
||||
// 6b: New write after reset must work
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = 18'h3CAFE;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
wait_rd_n(6);
|
||||
check(rd_valid == 1, "Reset recovery: rd_valid for new write");
|
||||
check(rd_data == 18'h3CAFE, "Reset recovery: correct data");
|
||||
#1; rd_ack = 1; @(posedge rd_clk); #1; rd_ack = 0;
|
||||
wait_rd_n(5);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 7: Burst writes at max wr_clk rate
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 7: Max-rate burst ===");
|
||||
do_reset;
|
||||
|
||||
// Write 7 entries back-to-back (1 per wr_clk, no decimation)
|
||||
for (i = 0; i < 7; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = i[17:0] + 18'hB000;
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Drain and count
|
||||
drain_fifo(drain_count);
|
||||
check(drain_count == 7, "Burst: all 7 entries received (no drops)");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 8: wr_full deasserts after read
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 8: wr_full release ===");
|
||||
do_reset;
|
||||
|
||||
// Fill FIFO: DEPTH entries first
|
||||
for (i = 0; i < DEPTH; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = i[17:0];
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Wait for auto-present round-trip
|
||||
wait_wr_n(12);
|
||||
|
||||
// Write the +1 entry (into the slot freed by auto-present)
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = 18'h3BEEF;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
wait_wr_n(6);
|
||||
check(wr_full == 1, "wr_full release: initially full (DEPTH+1 writes)");
|
||||
|
||||
// Read one entry (ACK the auto-presented data)
|
||||
#1; rd_ack = 1;
|
||||
wait_rd_n(2);
|
||||
#1; rd_ack = 0;
|
||||
|
||||
// Wait for rd_ptr sync back to wr domain (2 wr_clk cycles + margin)
|
||||
wait_wr_n(10);
|
||||
check(wr_full == 0, "wr_full release: deasserts after 1 read");
|
||||
|
||||
// Drain rest
|
||||
drain_fifo(drain_count);
|
||||
wait_rd_n(5);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 9: Alternating single-entry throughput
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 9: Alternating single-entry ===");
|
||||
do_reset;
|
||||
|
||||
begin : alt_test
|
||||
reg alt_ok;
|
||||
reg alt_got_valid;
|
||||
integer rd_w;
|
||||
alt_ok = 1;
|
||||
for (i = 0; i < 12; i = i + 1) begin
|
||||
// Write 1
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = i[17:0] + 18'hC000;
|
||||
wr_en = 1;
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Read 1 — wait for auto-present with rd_ack=0, then pulse ack
|
||||
rd_ack = 0;
|
||||
alt_got_valid = 0;
|
||||
for (rd_w = 0; rd_w < 20; rd_w = rd_w + 1) begin
|
||||
@(posedge rd_clk);
|
||||
if (rd_valid && !alt_got_valid) begin
|
||||
alt_got_valid = 1;
|
||||
if (rd_data !== i[17:0] + 18'hC000) begin
|
||||
$display(" alt[%0d]: data mismatch", i);
|
||||
alt_ok = 0;
|
||||
end
|
||||
rd_w = 999; // break
|
||||
end
|
||||
end
|
||||
if (!alt_got_valid) begin
|
||||
$display(" alt[%0d]: no rd_valid after write", i);
|
||||
alt_ok = 0;
|
||||
end
|
||||
// Consume the entry
|
||||
#1; rd_ack = 1;
|
||||
@(posedge rd_clk); #1;
|
||||
rd_ack = 0;
|
||||
wait_rd_n(2);
|
||||
end
|
||||
check(alt_ok, "Alternating: 12 single-entry cycles all correct");
|
||||
end
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP 10: Pathological data patterns
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP 10: Pathological data patterns ===");
|
||||
do_reset;
|
||||
|
||||
begin : patho_test
|
||||
reg patho_ok;
|
||||
reg patho_seen;
|
||||
reg [WIDTH-1:0] patterns [0:4];
|
||||
integer rd_w;
|
||||
patterns[0] = 18'h3FFFF; // all ones
|
||||
patterns[1] = 18'h00000; // all zeros
|
||||
patterns[2] = 18'h2AAAA; // alternating 10...
|
||||
patterns[3] = 18'h15555; // alternating 01...
|
||||
patterns[4] = 18'h20001; // MSB + LSB set
|
||||
|
||||
patho_ok = 1;
|
||||
// Write all 5 patterns
|
||||
for (i = 0; i < 5; i = i + 1) begin
|
||||
@(posedge wr_clk); #1;
|
||||
wr_data = patterns[i];
|
||||
wr_en = 1;
|
||||
end
|
||||
@(posedge wr_clk); #1;
|
||||
wr_en = 0;
|
||||
|
||||
// Read one at a time: wait for auto-present, check, ack
|
||||
rd_ack = 0;
|
||||
for (i = 0; i < 5; i = i + 1) begin
|
||||
patho_seen = 0;
|
||||
for (rd_w = 0; rd_w < 30; rd_w = rd_w + 1) begin
|
||||
@(posedge rd_clk);
|
||||
if (rd_valid && !patho_seen) begin
|
||||
patho_seen = 1;
|
||||
if (rd_data !== patterns[i]) begin
|
||||
$display(" pattern[%0d]: expected %h got %h",
|
||||
i, patterns[i], rd_data);
|
||||
patho_ok = 0;
|
||||
end
|
||||
rd_w = 999; // break
|
||||
end
|
||||
end
|
||||
if (!patho_seen) begin
|
||||
$display(" pattern[%0d]: no valid", i);
|
||||
patho_ok = 0;
|
||||
end
|
||||
// Consume the entry
|
||||
#1; rd_ack = 1;
|
||||
@(posedge rd_clk); #1;
|
||||
rd_ack = 0;
|
||||
end
|
||||
check(patho_ok, "Pathological: all 5 bit-patterns survive CDC");
|
||||
end
|
||||
|
||||
// ══════════════════════════════════════════════════════
|
||||
// SUMMARY
|
||||
// ══════════════════════════════════════════════════════
|
||||
$display("\n============================================");
|
||||
$display(" P0 Fix #1: Async FIFO Adversarial Tests");
|
||||
$display("============================================");
|
||||
$display(" PASSED: %0d", pass_count);
|
||||
$display(" FAILED: %0d", fail_count);
|
||||
$display("============================================");
|
||||
|
||||
if (fail_count > 0)
|
||||
$display("RESULT: FAIL");
|
||||
else
|
||||
$display("RESULT: PASS");
|
||||
|
||||
$finish;
|
||||
end
|
||||
|
||||
// Timeout watchdog
|
||||
initial begin
|
||||
#1000000;
|
||||
$display("[FAIL] TIMEOUT: simulation exceeded 1ms");
|
||||
$finish;
|
||||
end
|
||||
|
||||
endmodule
|
||||
@@ -0,0 +1,361 @@
|
||||
`timescale 1ns / 1ps
|
||||
|
||||
// ============================================================================
|
||||
// ADVERSARIAL TESTBENCH: frame_complete Pulse Width (P0 Fix #7)
|
||||
// ============================================================================
|
||||
// Tests the falling-edge pulse detection pattern used in doppler_processor.v
|
||||
// (lines 533-551) for the frame_complete signal.
|
||||
//
|
||||
// The OLD code held frame_complete as a continuous level whenever the
|
||||
// Doppler processor was idle. This caused the AGC (rx_gain_control) to
|
||||
// re-evaluate every clock with zeroed accumulators, collapsing gain control.
|
||||
//
|
||||
// The FIX detects the falling edge of processing_active:
|
||||
// assign processing_active = (state != S_IDLE);
|
||||
// reg processing_active_prev;
|
||||
// always @(posedge clk or negedge reset_n)
|
||||
// processing_active_prev <= processing_active;
|
||||
// assign frame_complete = (~processing_active & processing_active_prev);
|
||||
//
|
||||
// This DUT wrapper replicates the EXACT pattern from doppler_processor.v.
|
||||
// The adversarial tests drive the state input and verify:
|
||||
// - Pulse width is EXACTLY 1 clock cycle
|
||||
// - No pulse during extended idle
|
||||
// - No pulse on reset deassertion
|
||||
// - Back-to-back frame completions produce distinct pulses
|
||||
// - State transitions not touching S_IDLE produce no pulse
|
||||
// - OLD behavior (continuous level) is regressed
|
||||
// ============================================================================
|
||||
|
||||
// ── DUT: Exact replica of doppler_processor.v frame_complete logic ──
|
||||
module frame_complete_dut (
|
||||
input wire clk,
|
||||
input wire reset_n,
|
||||
input wire [3:0] state, // Mimic doppler FSM state input
|
||||
output wire processing_active,
|
||||
output wire frame_complete
|
||||
);
|
||||
// S_IDLE encoding from doppler_processor_optimized
|
||||
localparam [3:0] S_IDLE = 4'd0;
|
||||
|
||||
assign processing_active = (state != S_IDLE);
|
||||
|
||||
reg processing_active_prev;
|
||||
always @(posedge clk or negedge reset_n) begin
|
||||
if (!reset_n)
|
||||
processing_active_prev <= 1'b0;
|
||||
else
|
||||
processing_active_prev <= processing_active;
|
||||
end
|
||||
|
||||
assign frame_complete = (~processing_active & processing_active_prev);
|
||||
endmodule
|
||||
|
||||
|
||||
// ── TESTBENCH ────────────────────────────────────────────────
|
||||
module tb_p0_frame_pulse;
|
||||
|
||||
localparam CLK_PERIOD = 10.0; // 100 MHz
|
||||
|
||||
// Doppler FSM state encodings (from doppler_processor_optimized)
|
||||
localparam [3:0] S_IDLE = 4'd0;
|
||||
localparam [3:0] S_ACCUMULATE = 4'd1;
|
||||
localparam [3:0] S_WINDOW = 4'd2;
|
||||
localparam [3:0] S_FFT = 4'd3;
|
||||
localparam [3:0] S_OUTPUT = 4'd4;
|
||||
localparam [3:0] S_NEXT_BIN = 4'd5;
|
||||
|
||||
// ── Test bookkeeping ─────────────────────────────────────
|
||||
integer pass_count = 0;
|
||||
integer fail_count = 0;
|
||||
integer test_num = 0;
|
||||
integer i;
|
||||
|
||||
task check;
|
||||
input cond;
|
||||
input [511:0] label;
|
||||
begin
|
||||
test_num = test_num + 1;
|
||||
if (cond) begin
|
||||
$display("[PASS] Test %0d: %0s", test_num, label);
|
||||
pass_count = pass_count + 1;
|
||||
end else begin
|
||||
$display("[FAIL] Test %0d: %0s", test_num, label);
|
||||
fail_count = fail_count + 1;
|
||||
end
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── DUT signals ──────────────────────────────────────────
|
||||
reg clk = 0;
|
||||
reg reset_n = 0;
|
||||
reg [3:0] state = S_IDLE;
|
||||
wire processing_active;
|
||||
wire frame_complete;
|
||||
|
||||
always #(CLK_PERIOD/2) clk = ~clk;
|
||||
|
||||
frame_complete_dut dut (
|
||||
.clk(clk),
|
||||
.reset_n(reset_n),
|
||||
.state(state),
|
||||
.processing_active(processing_active),
|
||||
.frame_complete(frame_complete)
|
||||
);
|
||||
|
||||
// ── Helper ───────────────────────────────────────────────
|
||||
task wait_n;
|
||||
input integer n;
|
||||
integer k;
|
||||
begin
|
||||
for (k = 0; k < n; k = k + 1) @(posedge clk);
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── Count frame_complete pulses over N clocks ────────────
|
||||
integer pulse_count;
|
||||
|
||||
task count_pulses;
|
||||
input integer n_clocks;
|
||||
output integer count;
|
||||
integer c;
|
||||
begin
|
||||
count = 0;
|
||||
for (c = 0; c < n_clocks; c = c + 1) begin
|
||||
@(posedge clk);
|
||||
if (frame_complete) count = count + 1;
|
||||
end
|
||||
end
|
||||
endtask
|
||||
|
||||
// ══════════════════════════════════════════════════════════
|
||||
// MAIN TEST SEQUENCE
|
||||
// ══════════════════════════════════════════════════════════
|
||||
initial begin
|
||||
$dumpfile("tb_p0_frame_pulse.vcd");
|
||||
$dumpvars(0, tb_p0_frame_pulse);
|
||||
|
||||
// ── RESET ────────────────────────────────────────────
|
||||
state = S_IDLE;
|
||||
reset_n = 0;
|
||||
#100;
|
||||
reset_n = 1;
|
||||
@(posedge clk);
|
||||
@(posedge clk);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 1: No pulse on reset deassertion
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 1: Reset deassertion ===");
|
||||
// processing_active = 0 (state = S_IDLE)
|
||||
// processing_active_prev was reset to 0
|
||||
// frame_complete = ~0 & 0 = 0
|
||||
check(frame_complete == 0, "No pulse on reset deassertion (both 0)");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 2: No pulse during extended idle
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 2: Extended idle ===");
|
||||
count_pulses(200, pulse_count);
|
||||
check(pulse_count == 0, "No pulse during 200 clocks of continuous idle");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 3: Single frame completion — pulse width = 1
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 3: Single frame completion ===");
|
||||
|
||||
// Enter active state
|
||||
@(posedge clk); #1;
|
||||
state = S_ACCUMULATE;
|
||||
wait_n(5);
|
||||
check(processing_active == 1, "Active: processing_active = 1");
|
||||
check(frame_complete == 0, "Active: no frame_complete while active");
|
||||
|
||||
// Stay active for 50 clocks (various states)
|
||||
#1; state = S_WINDOW; wait_n(10);
|
||||
#1; state = S_FFT; wait_n(10);
|
||||
#1; state = S_OUTPUT; wait_n(10);
|
||||
#1; state = S_NEXT_BIN; wait_n(10);
|
||||
check(frame_complete == 0, "Active (multi-state): no frame_complete");
|
||||
|
||||
// Return to idle — should produce exactly 1 pulse
|
||||
#1; state = S_IDLE;
|
||||
@(posedge clk);
|
||||
// On this edge: processing_active = 0, processing_active_prev = 1
|
||||
// frame_complete = ~0 & 1 = 1
|
||||
check(frame_complete == 1, "Completion: frame_complete fires");
|
||||
|
||||
@(posedge clk);
|
||||
// Now: processing_active_prev catches up to 0
|
||||
// frame_complete = ~0 & 0 = 0
|
||||
check(frame_complete == 0, "Completion: pulse is EXACTLY 1 cycle wide");
|
||||
|
||||
// Verify no more pulses
|
||||
count_pulses(100, pulse_count);
|
||||
check(pulse_count == 0, "Post-completion: no re-fire during idle");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 4: Back-to-back frame completions
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 4: Back-to-back completions ===");
|
||||
|
||||
begin : backtoback_test
|
||||
integer total_pulses;
|
||||
total_pulses = 0;
|
||||
|
||||
// Do 5 rapid frame cycles
|
||||
for (i = 0; i < 5; i = i + 1) begin
|
||||
// Go active
|
||||
@(posedge clk); #1;
|
||||
state = S_ACCUMULATE;
|
||||
wait_n(3);
|
||||
|
||||
// Return to idle
|
||||
#1; state = S_IDLE;
|
||||
@(posedge clk);
|
||||
if (frame_complete) total_pulses = total_pulses + 1;
|
||||
@(posedge clk); // pulse should be gone
|
||||
if (frame_complete) begin
|
||||
$display(" [WARN] frame %0d: pulse persisted > 1 cycle", i);
|
||||
end
|
||||
end
|
||||
|
||||
check(total_pulses == 5, "Back-to-back: exactly 5 pulses for 5 completions");
|
||||
end
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 5: State transitions not touching S_IDLE
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 5: Non-idle transitions ===");
|
||||
|
||||
@(posedge clk); #1;
|
||||
state = S_ACCUMULATE;
|
||||
wait_n(3);
|
||||
|
||||
// Cycle through active states without returning to idle
|
||||
begin : nonidle_test
|
||||
integer nonidle_pulses;
|
||||
nonidle_pulses = 0;
|
||||
|
||||
#1; state = S_WINDOW;
|
||||
@(posedge clk);
|
||||
if (frame_complete) nonidle_pulses = nonidle_pulses + 1;
|
||||
|
||||
#1; state = S_FFT;
|
||||
@(posedge clk);
|
||||
if (frame_complete) nonidle_pulses = nonidle_pulses + 1;
|
||||
|
||||
#1; state = S_OUTPUT;
|
||||
@(posedge clk);
|
||||
if (frame_complete) nonidle_pulses = nonidle_pulses + 1;
|
||||
|
||||
#1; state = S_NEXT_BIN;
|
||||
@(posedge clk);
|
||||
if (frame_complete) nonidle_pulses = nonidle_pulses + 1;
|
||||
|
||||
#1; state = S_ACCUMULATE;
|
||||
wait_n(10);
|
||||
count_pulses(10, pulse_count);
|
||||
nonidle_pulses = nonidle_pulses + pulse_count;
|
||||
|
||||
check(nonidle_pulses == 0,
|
||||
"Non-idle transitions: zero pulses (all states active)");
|
||||
end
|
||||
|
||||
// Return to idle (one pulse expected)
|
||||
#1; state = S_IDLE;
|
||||
@(posedge clk);
|
||||
check(frame_complete == 1, "Cleanup: pulse on final idle transition");
|
||||
@(posedge clk);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 6: Long active period — no premature pulse
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 6: Long active period ===");
|
||||
|
||||
@(posedge clk); #1;
|
||||
state = S_FFT;
|
||||
|
||||
count_pulses(500, pulse_count);
|
||||
check(pulse_count == 0, "Long active (500 clocks): no premature pulse");
|
||||
|
||||
#1; state = S_IDLE;
|
||||
@(posedge clk);
|
||||
check(frame_complete == 1, "Long active → idle: pulse fires");
|
||||
@(posedge clk);
|
||||
check(frame_complete == 0, "Long active → idle: single cycle only");
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 7: Reset during active state
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 7: Reset during active ===");
|
||||
|
||||
@(posedge clk); #1;
|
||||
state = S_ACCUMULATE;
|
||||
wait_n(5);
|
||||
|
||||
// Assert reset while active
|
||||
reset_n = 0;
|
||||
#50;
|
||||
// During reset: processing_active_prev forced to 0
|
||||
// state still = S_ACCUMULATE, processing_active = 1
|
||||
reset_n = 1;
|
||||
@(posedge clk);
|
||||
@(posedge clk);
|
||||
// After reset release: prev = 0, active = 1
|
||||
// frame_complete = ~1 & 0 = 0 (no spurious pulse)
|
||||
check(frame_complete == 0, "Reset during active: no spurious pulse");
|
||||
|
||||
// Now go idle — should pulse
|
||||
#1; state = S_IDLE;
|
||||
@(posedge clk);
|
||||
check(frame_complete == 1, "Reset recovery: pulse on idle after active");
|
||||
@(posedge clk);
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// TEST 8: REGRESSION — old continuous-level behavior
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== TEST 8: REGRESSION ===");
|
||||
// OLD code: frame_complete = (state == S_IDLE && frame_buffer_full == 0)
|
||||
// This held frame_complete HIGH for the entire idle period.
|
||||
// With AGC sampling frame_complete, this caused re-evaluation every clock.
|
||||
//
|
||||
// The FIX produces a 1-cycle pulse. We've proven:
|
||||
// - Pulse width = 1 cycle (Test 3)
|
||||
// - No re-fire during idle (Test 2, 3)
|
||||
// - Old behavior would have frame_complete = 1 for 200+ clocks (Test 2)
|
||||
//
|
||||
// Quantify: old code would produce 200 "events" over 200 idle clocks.
|
||||
// New code produces 0. This is the fix.
|
||||
|
||||
state = S_IDLE;
|
||||
count_pulses(200, pulse_count);
|
||||
check(pulse_count == 0,
|
||||
"REGRESSION: 0 pulses in 200 idle clocks (old code: 200)");
|
||||
|
||||
// ══════════════════════════════════════════════════════
|
||||
// SUMMARY
|
||||
// ══════════════════════════════════════════════════════
|
||||
$display("\n============================================");
|
||||
$display(" P0 Fix #7: frame_complete Pulse Tests");
|
||||
$display("============================================");
|
||||
$display(" PASSED: %0d", pass_count);
|
||||
$display(" FAILED: %0d", fail_count);
|
||||
$display("============================================");
|
||||
|
||||
if (fail_count > 0)
|
||||
$display("RESULT: FAIL");
|
||||
else
|
||||
$display("RESULT: PASS");
|
||||
|
||||
$finish;
|
||||
end
|
||||
|
||||
// Timeout watchdog
|
||||
initial begin
|
||||
#500000;
|
||||
$display("[FAIL] TIMEOUT: simulation exceeded 500us");
|
||||
$finish;
|
||||
end
|
||||
|
||||
endmodule
|
||||
@@ -0,0 +1,602 @@
|
||||
`timescale 1ns / 1ps
|
||||
|
||||
// ============================================================================
|
||||
// ADVERSARIAL TESTBENCH: Matched Filter Fixes (P0 Fixes #2, #3, #4)
|
||||
// ============================================================================
|
||||
// Tests three critical signal-processing invariant fixes in
|
||||
// matched_filter_multi_segment.v:
|
||||
//
|
||||
// Fix #2 — Toggle detection: XOR replaces AND+NOT so both edges of
|
||||
// mc_new_chirp generate chirp_start_pulse (not just 0→1).
|
||||
//
|
||||
// Fix #3 — Listen delay: ST_WAIT_LISTEN state skips TX chirp duration
|
||||
// (counting ddc_valid pulses) before collecting echo samples.
|
||||
//
|
||||
// Fix #4 — Overlap-save trim: First 128 output bins of segments 1+
|
||||
// are suppressed (circular convolution artifacts).
|
||||
//
|
||||
// A STUB processing chain replaces the real FFT pipeline, providing
|
||||
// controlled timing for state machine verification.
|
||||
// ============================================================================
|
||||
|
||||
// ============================================================================
|
||||
// STUB: matched_filter_processing_chain
|
||||
// ============================================================================
|
||||
// Same port signature as the real module. Accepts 1024 adc_valid samples,
|
||||
// simulates a short processing delay, then outputs 1024 range_profile_valid
|
||||
// pulses with incrementing data. chain_state reports 0 when idle.
|
||||
// ============================================================================
|
||||
module matched_filter_processing_chain (
|
||||
input wire clk,
|
||||
input wire reset_n,
|
||||
|
||||
input wire [15:0] adc_data_i,
|
||||
input wire [15:0] adc_data_q,
|
||||
input wire adc_valid,
|
||||
|
||||
input wire [5:0] chirp_counter,
|
||||
|
||||
input wire [15:0] long_chirp_real,
|
||||
input wire [15:0] long_chirp_imag,
|
||||
input wire [15:0] short_chirp_real,
|
||||
input wire [15:0] short_chirp_imag,
|
||||
|
||||
output reg signed [15:0] range_profile_i,
|
||||
output reg signed [15:0] range_profile_q,
|
||||
output reg range_profile_valid,
|
||||
|
||||
output wire [3:0] chain_state
|
||||
);
|
||||
|
||||
localparam [3:0] ST_IDLE = 4'd0;
|
||||
localparam [3:0] ST_COLLECTING = 4'd1;
|
||||
localparam [3:0] ST_DELAY = 4'd2;
|
||||
localparam [3:0] ST_OUTPUTTING = 4'd3;
|
||||
localparam [3:0] ST_DONE = 4'd9;
|
||||
|
||||
reg [3:0] state = ST_IDLE;
|
||||
reg [10:0] count = 0;
|
||||
|
||||
assign chain_state = state;
|
||||
|
||||
always @(posedge clk or negedge reset_n) begin
|
||||
if (!reset_n) begin
|
||||
state <= ST_IDLE;
|
||||
count <= 0;
|
||||
range_profile_valid <= 0;
|
||||
range_profile_i <= 0;
|
||||
range_profile_q <= 0;
|
||||
end else begin
|
||||
range_profile_valid <= 0;
|
||||
|
||||
case (state)
|
||||
ST_IDLE: begin
|
||||
count <= 0;
|
||||
if (adc_valid) begin
|
||||
state <= ST_COLLECTING;
|
||||
count <= 1;
|
||||
end
|
||||
end
|
||||
|
||||
ST_COLLECTING: begin
|
||||
if (adc_valid) begin
|
||||
count <= count + 1;
|
||||
if (count >= 11'd1023) begin
|
||||
state <= ST_DELAY;
|
||||
count <= 0;
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
ST_DELAY: begin
|
||||
// Simulate processing latency (8 clocks)
|
||||
count <= count + 1;
|
||||
if (count >= 11'd7) begin
|
||||
state <= ST_OUTPUTTING;
|
||||
count <= 0;
|
||||
end
|
||||
end
|
||||
|
||||
ST_OUTPUTTING: begin
|
||||
range_profile_valid <= 1;
|
||||
range_profile_i <= count[15:0];
|
||||
range_profile_q <= ~count[15:0];
|
||||
count <= count + 1;
|
||||
if (count >= 11'd1023) begin
|
||||
state <= ST_DONE;
|
||||
end
|
||||
end
|
||||
|
||||
ST_DONE: begin
|
||||
state <= ST_IDLE;
|
||||
end
|
||||
|
||||
default: state <= ST_IDLE;
|
||||
endcase
|
||||
end
|
||||
end
|
||||
|
||||
endmodule
|
||||
|
||||
|
||||
// ============================================================================
|
||||
// TESTBENCH
|
||||
// ============================================================================
|
||||
module tb_p0_mf_adversarial;
|
||||
|
||||
localparam CLK_PERIOD = 10.0; // 100 MHz
|
||||
|
||||
// Override matched_filter parameters for fast simulation
|
||||
localparam TB_LONG_CHIRP = 2000; // echo samples + listen delay target
|
||||
localparam TB_SHORT_CHIRP = 10;
|
||||
localparam TB_LONG_SEGS = 3;
|
||||
localparam TB_SHORT_SEGS = 1;
|
||||
localparam TB_OVERLAP = 128;
|
||||
localparam TB_BUF_SIZE = 1024;
|
||||
localparam TB_SEG_ADVANCE = TB_BUF_SIZE - TB_OVERLAP; // 896
|
||||
|
||||
// ── Test bookkeeping ─────────────────────────────────────
|
||||
integer pass_count = 0;
|
||||
integer fail_count = 0;
|
||||
integer test_num = 0;
|
||||
integer i;
|
||||
|
||||
task check;
|
||||
input cond;
|
||||
input [511:0] label;
|
||||
begin
|
||||
test_num = test_num + 1;
|
||||
if (cond) begin
|
||||
$display("[PASS] Test %0d: %0s", test_num, label);
|
||||
pass_count = pass_count + 1;
|
||||
end else begin
|
||||
$display("[FAIL] Test %0d: %0s", test_num, label);
|
||||
fail_count = fail_count + 1;
|
||||
end
|
||||
end
|
||||
endtask
|
||||
|
||||
// ── DUT signals ──────────────────────────────────────────
|
||||
reg clk = 0;
|
||||
reg reset_n = 0;
|
||||
reg signed [17:0] ddc_i = 0;
|
||||
reg signed [17:0] ddc_q = 0;
|
||||
reg ddc_valid = 0;
|
||||
reg use_long_chirp = 0;
|
||||
reg [5:0] chirp_counter = 0;
|
||||
reg mc_new_chirp = 0;
|
||||
reg mc_new_elevation = 0;
|
||||
reg mc_new_azimuth = 0;
|
||||
reg [15:0] long_chirp_real = 0;
|
||||
reg [15:0] long_chirp_imag = 0;
|
||||
reg [15:0] short_chirp_real = 0;
|
||||
reg [15:0] short_chirp_imag = 0;
|
||||
reg mem_ready = 1; // Always ready (stub memory)
|
||||
|
||||
wire [1:0] segment_request;
|
||||
wire [9:0] sample_addr_out;
|
||||
wire mem_request_w;
|
||||
wire signed [15:0] pc_i_w;
|
||||
wire signed [15:0] pc_q_w;
|
||||
wire pc_valid_w;
|
||||
wire [3:0] status;
|
||||
|
||||
always #(CLK_PERIOD/2) clk = ~clk;
|
||||
|
||||
matched_filter_multi_segment #(
|
||||
.BUFFER_SIZE(TB_BUF_SIZE),
|
||||
.LONG_CHIRP_SAMPLES(TB_LONG_CHIRP),
|
||||
.SHORT_CHIRP_SAMPLES(TB_SHORT_CHIRP),
|
||||
.OVERLAP_SAMPLES(TB_OVERLAP),
|
||||
.SEGMENT_ADVANCE(TB_SEG_ADVANCE),
|
||||
.LONG_SEGMENTS(TB_LONG_SEGS),
|
||||
.SHORT_SEGMENTS(TB_SHORT_SEGS),
|
||||
.DEBUG(0)
|
||||
) dut (
|
||||
.clk(clk),
|
||||
.reset_n(reset_n),
|
||||
.ddc_i(ddc_i),
|
||||
.ddc_q(ddc_q),
|
||||
.ddc_valid(ddc_valid),
|
||||
.use_long_chirp(use_long_chirp),
|
||||
.chirp_counter(chirp_counter),
|
||||
.mc_new_chirp(mc_new_chirp),
|
||||
.mc_new_elevation(mc_new_elevation),
|
||||
.mc_new_azimuth(mc_new_azimuth),
|
||||
.long_chirp_real(long_chirp_real),
|
||||
.long_chirp_imag(long_chirp_imag),
|
||||
.short_chirp_real(short_chirp_real),
|
||||
.short_chirp_imag(short_chirp_imag),
|
||||
.segment_request(segment_request),
|
||||
.sample_addr_out(sample_addr_out),
|
||||
.mem_request(mem_request_w),
|
||||
.mem_ready(mem_ready),
|
||||
.pc_i_w(pc_i_w),
|
||||
.pc_q_w(pc_q_w),
|
||||
.pc_valid_w(pc_valid_w),
|
||||
.status(status)
|
||||
);
|
||||
|
||||
// ── Hierarchical refs for observability ──────────────────
|
||||
wire [3:0] dut_state = dut.state;
|
||||
wire dut_chirp_pulse = dut.chirp_start_pulse;
|
||||
wire dut_elev_pulse = dut.elevation_change_pulse;
|
||||
wire dut_azim_pulse = dut.azimuth_change_pulse;
|
||||
wire [15:0] dut_listen_count = dut.listen_delay_count;
|
||||
wire [15:0] dut_listen_target = dut.listen_delay_target;
|
||||
wire [2:0] dut_segment = dut.current_segment;
|
||||
wire [10:0] dut_out_bin_count = dut.output_bin_count;
|
||||
wire dut_overlap_gate = dut.output_in_overlap;
|
||||
|
||||
// State constants (mirror matched_filter_multi_segment localparams)
|
||||
localparam [3:0] ST_IDLE = 4'd0;
|
||||
localparam [3:0] ST_COLLECT_DATA = 4'd1;
|
||||
localparam [3:0] ST_ZERO_PAD = 4'd2;
|
||||
localparam [3:0] ST_WAIT_REF = 4'd3;
|
||||
localparam [3:0] ST_PROCESSING = 4'd4;
|
||||
localparam [3:0] ST_WAIT_FFT = 4'd5;
|
||||
localparam [3:0] ST_OUTPUT = 4'd6;
|
||||
localparam [3:0] ST_NEXT_SEG = 4'd7;
|
||||
localparam [3:0] ST_OVERLAP_COPY = 4'd8;
|
||||
localparam [3:0] ST_WAIT_LISTEN = 4'd9;
|
||||
|
||||
// ── Helper tasks ─────────────────────────────────────────
|
||||
task do_reset;
|
||||
begin
|
||||
reset_n = 0;
|
||||
mc_new_chirp = 0;
|
||||
mc_new_elevation = 0;
|
||||
mc_new_azimuth = 0;
|
||||
ddc_valid = 0;
|
||||
ddc_i = 0;
|
||||
ddc_q = 0;
|
||||
use_long_chirp = 0;
|
||||
#100;
|
||||
reset_n = 1;
|
||||
@(posedge clk);
|
||||
@(posedge clk); // Let mc_new_chirp_prev settle to 0
|
||||
end
|
||||
endtask
|
||||
|
||||
task wait_n;
|
||||
input integer n;
|
||||
integer k;
|
||||
begin
|
||||
for (k = 0; k < n; k = k + 1) @(posedge clk);
|
||||
end
|
||||
endtask
|
||||
|
||||
// Provide N ddc_valid pulses (continuous, every clock)
|
||||
task provide_samples;
|
||||
input integer n;
|
||||
integer k;
|
||||
begin
|
||||
for (k = 0; k < n; k = k + 1) begin
|
||||
@(posedge clk);
|
||||
ddc_i <= k[17:0];
|
||||
ddc_q <= ~k[17:0];
|
||||
ddc_valid <= 1;
|
||||
end
|
||||
@(posedge clk);
|
||||
ddc_valid <= 0;
|
||||
end
|
||||
endtask
|
||||
|
||||
// Wait for DUT to reach a specific state (with timeout)
|
||||
task wait_for_state;
|
||||
input [3:0] target;
|
||||
input integer timeout_clks;
|
||||
integer t;
|
||||
begin
|
||||
for (t = 0; t < timeout_clks; t = t + 1) begin
|
||||
@(posedge clk);
|
||||
if (dut_state == target) t = timeout_clks + 1; // break
|
||||
end
|
||||
end
|
||||
endtask
|
||||
|
||||
// ══════════════════════════════════════════════════════════
|
||||
// MAIN TEST SEQUENCE
|
||||
// ══════════════════════════════════════════════════════════
|
||||
// Counters for overlap trim verification
|
||||
integer seg0_valid_count;
|
||||
integer seg1_valid_count;
|
||||
reg seg0_counting, seg1_counting;
|
||||
reg bin127_suppressed, bin128_passed;
|
||||
|
||||
initial begin
|
||||
$dumpfile("tb_p0_mf_adversarial.vcd");
|
||||
$dumpvars(0, tb_p0_mf_adversarial);
|
||||
|
||||
seg0_valid_count = 0;
|
||||
seg1_valid_count = 0;
|
||||
seg0_counting = 0;
|
||||
seg1_counting = 0;
|
||||
bin127_suppressed = 0;
|
||||
bin128_passed = 0;
|
||||
|
||||
do_reset;
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP A: TOGGLE DETECTION (Fix #2)
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP A: Toggle Detection (Fix #2) ===");
|
||||
|
||||
// A1: Rising edge (0→1) generates chirp_start_pulse
|
||||
@(posedge clk);
|
||||
check(dut_chirp_pulse == 0, "A1 pre: no pulse before toggle");
|
||||
#1; mc_new_chirp = 1; // 0→1
|
||||
@(posedge clk); // pulse should fire (combinational on new vs prev)
|
||||
check(dut_chirp_pulse == 1, "A1: rising edge (0->1) generates pulse");
|
||||
|
||||
// Pulse must be 1 cycle wide
|
||||
@(posedge clk); // mc_new_chirp_prev updates to 1
|
||||
check(dut_chirp_pulse == 0, "A1: pulse is single-cycle (gone on next clock)");
|
||||
|
||||
// Let state machine settle (it entered ST_WAIT_LISTEN)
|
||||
do_reset;
|
||||
|
||||
// A2: Falling edge (1→0) generates pulse — THIS IS THE FIX
|
||||
#1; mc_new_chirp = 1;
|
||||
@(posedge clk); // prev catches up to 1
|
||||
@(posedge clk); // prev = 1, mc_new_chirp = 1, XOR = 0
|
||||
check(dut_chirp_pulse == 0, "A2 pre: no pulse when stable high");
|
||||
|
||||
#1; mc_new_chirp = 0; // 1→0
|
||||
@(posedge clk); // XOR: 0 ^ 1 = 1
|
||||
check(dut_chirp_pulse == 1, "A2: falling edge (1->0) generates pulse (FIX!)");
|
||||
@(posedge clk);
|
||||
check(dut_chirp_pulse == 0, "A2: pulse ends after 1 cycle");
|
||||
|
||||
do_reset;
|
||||
|
||||
// A3: Stable low — no spurious pulses over 50 clocks
|
||||
begin : stable_low_test
|
||||
reg any_pulse;
|
||||
any_pulse = 0;
|
||||
for (i = 0; i < 50; i = i + 1) begin
|
||||
@(posedge clk);
|
||||
if (dut_chirp_pulse) any_pulse = 1;
|
||||
end
|
||||
check(!any_pulse, "A3: stable low for 50 clocks — no spurious pulse");
|
||||
end
|
||||
|
||||
// A4: Elevation and azimuth toggles also detected
|
||||
#1; mc_new_elevation = 1; // 0→1
|
||||
@(posedge clk);
|
||||
check(dut_elev_pulse == 1, "A4a: elevation toggle 0->1 detected");
|
||||
@(posedge clk);
|
||||
#1; mc_new_elevation = 0; // 1→0
|
||||
@(posedge clk);
|
||||
check(dut_elev_pulse == 1, "A4b: elevation toggle 1->0 detected");
|
||||
|
||||
#1; mc_new_azimuth = 1;
|
||||
@(posedge clk);
|
||||
check(dut_azim_pulse == 1, "A4c: azimuth toggle 0->1 detected");
|
||||
@(posedge clk);
|
||||
#1; mc_new_azimuth = 0;
|
||||
@(posedge clk);
|
||||
check(dut_azim_pulse == 1, "A4d: azimuth toggle 1->0 detected");
|
||||
|
||||
// A5: REGRESSION — verify OLD behavior would have failed
|
||||
// Old code: chirp_start_pulse = mc_new_chirp && !mc_new_chirp_prev
|
||||
// This is a rising-edge detector. On 1→0: 0 && !1 = 0 (missed!)
|
||||
// The NEW XOR code: 0 ^ 1 = 1 (detected!)
|
||||
// We already proved this works in A2. Document the regression:
|
||||
$display(" [INFO] A5 REGRESSION: old AND+NOT code produced 0 for 1->0 transition");
|
||||
$display(" [INFO] old: mc_new_chirp(0) && !mc_new_chirp_prev(1) = 0 && 0 = 0 MISSED");
|
||||
$display(" [INFO] new: mc_new_chirp(0) ^ mc_new_chirp_prev(1) = 0 ^ 1 = 1 DETECTED");
|
||||
check(1, "A5: REGRESSION documented — falling edge was missed by old code");
|
||||
|
||||
do_reset;
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP B: LISTEN DELAY (Fix #3)
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP B: Listen Delay (Fix #3) ===");
|
||||
|
||||
// Use SHORT chirp: listen_delay_target = TB_SHORT_CHIRP = 10
|
||||
#1; use_long_chirp = 0;
|
||||
|
||||
// B1: Chirp start → enters ST_WAIT_LISTEN (not ST_COLLECT_DATA)
|
||||
mc_new_chirp = 1; // toggle 0→1
|
||||
@(posedge clk); // pulse fires, state machine acts
|
||||
@(posedge clk); // non-blocking assignment settles
|
||||
check(dut_state == ST_WAIT_LISTEN, "B1: enters ST_WAIT_LISTEN (not COLLECT_DATA)");
|
||||
check(dut_listen_target == TB_SHORT_CHIRP,
|
||||
"B1: listen_delay_target = SHORT_CHIRP_SAMPLES");
|
||||
|
||||
// B2: Counter increments only on ddc_valid
|
||||
// Provide 5 valid pulses, then 5 clocks without valid, then 5 more valid
|
||||
for (i = 0; i < 5; i = i + 1) begin
|
||||
@(posedge clk);
|
||||
ddc_valid <= 1;
|
||||
ddc_i <= i[17:0];
|
||||
ddc_q <= 0;
|
||||
end
|
||||
@(posedge clk);
|
||||
ddc_valid <= 0;
|
||||
|
||||
// Counter should be 5 after 5 valid pulses
|
||||
@(posedge clk);
|
||||
check(dut_listen_count == 5, "B2a: counter = 5 after 5 valid pulses");
|
||||
check(dut_state == ST_WAIT_LISTEN, "B2a: still in ST_WAIT_LISTEN");
|
||||
|
||||
// B3: 5 clocks with no valid — counter must NOT advance
|
||||
wait_n(5);
|
||||
check(dut_listen_count == 5, "B3: counter stays 5 during ddc_valid gaps");
|
||||
check(dut_state == ST_WAIT_LISTEN, "B3: still in ST_WAIT_LISTEN");
|
||||
|
||||
// B4: Provide remaining pulses to hit boundary
|
||||
// Need 5 more valid pulses (total 10 = TB_SHORT_CHIRP)
|
||||
// Counter transitions at >= target-1 = 9, so pulse 10 triggers
|
||||
for (i = 0; i < 4; i = i + 1) begin
|
||||
@(posedge clk);
|
||||
ddc_valid <= 1;
|
||||
ddc_i <= (i + 5);
|
||||
ddc_q <= 0;
|
||||
end
|
||||
// After 4 more: count = 9 = target-1 → transition happens on THIS valid
|
||||
@(posedge clk);
|
||||
ddc_valid <= 1; // 10th pulse
|
||||
@(posedge clk);
|
||||
ddc_valid <= 0;
|
||||
@(posedge clk); // Let non-blocking assignments settle
|
||||
|
||||
check(dut_state == ST_COLLECT_DATA,
|
||||
"B4: transitions to ST_COLLECT_DATA after exact delay count");
|
||||
|
||||
// B5: First sample collected is the one AFTER the delay
|
||||
// The module is now in ST_COLLECT_DATA. Provide a sample and verify
|
||||
// it gets written to the buffer (buffer_write_ptr should advance)
|
||||
begin : first_sample_check
|
||||
reg [10:0] ptr_before;
|
||||
ptr_before = dut.buffer_write_ptr;
|
||||
@(posedge clk);
|
||||
ddc_valid <= 1;
|
||||
ddc_i <= 18'h1FACE;
|
||||
ddc_q <= 18'h1BEEF;
|
||||
@(posedge clk);
|
||||
ddc_valid <= 0;
|
||||
@(posedge clk);
|
||||
check(dut.buffer_write_ptr == ptr_before + 1,
|
||||
"B5: first echo sample collected (write_ptr advanced)");
|
||||
end
|
||||
|
||||
do_reset;
|
||||
|
||||
// ──────────────────────────────────────────────────────
|
||||
// GROUP C: OVERLAP-SAVE OUTPUT TRIM (Fix #4)
|
||||
// ──────────────────────────────────────────────────────
|
||||
$display("\n=== GROUP C: Overlap-Save Output Trim (Fix #4) ===");
|
||||
|
||||
// Use LONG chirp with 2+ segments for overlap trim testing
|
||||
#1; use_long_chirp = 1;
|
||||
seg0_valid_count = 0;
|
||||
seg1_valid_count = 0;
|
||||
|
||||
// C-SETUP: Trigger chirp, pass through listen delay, process 2 segments
|
||||
mc_new_chirp = 1; // toggle 0→1
|
||||
@(posedge clk);
|
||||
@(posedge clk);
|
||||
check(dut_state == ST_WAIT_LISTEN, "C-setup: entered ST_WAIT_LISTEN");
|
||||
check(dut_listen_target == TB_LONG_CHIRP,
|
||||
"C-setup: listen target = LONG_CHIRP_SAMPLES");
|
||||
|
||||
// Pass through listen delay: provide TB_LONG_CHIRP (2000) ddc_valid pulses
|
||||
$display(" [INFO] Providing %0d listen-delay samples...", TB_LONG_CHIRP);
|
||||
provide_samples(TB_LONG_CHIRP);
|
||||
|
||||
// Should now be in ST_COLLECT_DATA
|
||||
@(posedge clk);
|
||||
check(dut_state == ST_COLLECT_DATA,
|
||||
"C-setup: in ST_COLLECT_DATA after listen delay");
|
||||
|
||||
// ── SEGMENT 0: Collect 1024 samples ──
|
||||
$display(" [INFO] Providing 1024 echo samples for segment 0...");
|
||||
provide_samples(TB_BUF_SIZE);
|
||||
|
||||
// Should transition through WAIT_REF → PROCESSING → WAIT_FFT
|
||||
// mem_ready is always 1, so WAIT_REF passes immediately
|
||||
wait_for_state(ST_WAIT_FFT, 2000);
|
||||
check(dut_state == ST_WAIT_FFT, "C-setup: seg0 reached ST_WAIT_FFT");
|
||||
check(dut_segment == 0, "C-setup: processing segment 0");
|
||||
|
||||
// During ST_WAIT_FFT, the stub chain outputs 1024 fft_pc_valid pulses.
|
||||
// Count pc_valid_w (the gated output) for segment 0.
|
||||
seg0_counting = 1;
|
||||
wait_for_state(ST_OUTPUT, 2000);
|
||||
seg0_counting = 0;
|
||||
|
||||
// C1: Segment 0 — ALL output bins should pass (no trim)
|
||||
check(seg0_valid_count == TB_BUF_SIZE,
|
||||
"C1: segment 0 — all 1024 output bins pass (no trim)");
|
||||
|
||||
// Let state machine proceed to next segment
|
||||
wait_for_state(ST_COLLECT_DATA, 500);
|
||||
check(dut_segment == 1, "C-setup: advanced to segment 1");
|
||||
|
||||
// ── SEGMENT 1: Collect 896 samples (buffer starts at 128 from overlap) ──
|
||||
$display(" [INFO] Providing %0d echo samples for segment 1...", TB_SEG_ADVANCE);
|
||||
provide_samples(TB_SEG_ADVANCE);
|
||||
|
||||
// Wait for seg 1 processing
|
||||
wait_for_state(ST_WAIT_FFT, 2000);
|
||||
check(dut_state == ST_WAIT_FFT, "C-setup: seg1 reached ST_WAIT_FFT");
|
||||
|
||||
// Count pc_valid_w during segment 1 output
|
||||
seg1_counting = 1;
|
||||
bin127_suppressed = 0;
|
||||
bin128_passed = 0;
|
||||
|
||||
// Monitor specific boundary bins during chain output
|
||||
begin : seg1_output_monitor
|
||||
integer wait_count;
|
||||
for (wait_count = 0; wait_count < 2000; wait_count = wait_count + 1) begin
|
||||
@(posedge clk);
|
||||
|
||||
// Check boundary: bin 127 should be suppressed
|
||||
if (dut_out_bin_count == 127 && dut.fft_pc_valid) begin
|
||||
if (pc_valid_w == 0) bin127_suppressed = 1;
|
||||
end
|
||||
|
||||
// Check boundary: bin 128 should pass
|
||||
if (dut_out_bin_count == 128 && dut.fft_pc_valid) begin
|
||||
if (pc_valid_w == 1) bin128_passed = 1;
|
||||
end
|
||||
|
||||
if (dut_state == ST_OUTPUT) begin
|
||||
wait_count = 9999; // break
|
||||
end
|
||||
end
|
||||
end
|
||||
seg1_counting = 0;
|
||||
|
||||
// C2: Segment 1 — first 128 bins suppressed, 896 pass
|
||||
check(seg1_valid_count == TB_SEG_ADVANCE,
|
||||
"C2: segment 1 — exactly 896 output bins pass (128 trimmed)");
|
||||
|
||||
// C3: Boundary bin accuracy
|
||||
check(bin127_suppressed, "C3a: bin 127 suppressed (overlap artifact)");
|
||||
check(bin128_passed, "C3b: bin 128 passes (first valid bin)");
|
||||
|
||||
// C4: Overlap gate signal logic
|
||||
// For segment != 0, output_in_overlap should be true when bin_count < 128
|
||||
check(dut_segment == 1, "C4 pre: still on segment 1");
|
||||
// (Gate was already verified implicitly by C2/C3 counts)
|
||||
check(1, "C4: overlap gate correctly suppresses bins [0..127] on seg 1+");
|
||||
|
||||
// ══════════════════════════════════════════════════════
|
||||
// SUMMARY
|
||||
// ══════════════════════════════════════════════════════
|
||||
$display("\n============================================");
|
||||
$display(" P0 Fixes #2/#3/#4: MF Adversarial Tests");
|
||||
$display("============================================");
|
||||
$display(" PASSED: %0d", pass_count);
|
||||
$display(" FAILED: %0d", fail_count);
|
||||
$display("============================================");
|
||||
|
||||
if (fail_count > 0)
|
||||
$display("RESULT: FAIL");
|
||||
else
|
||||
$display("RESULT: PASS");
|
||||
|
||||
$finish;
|
||||
end
|
||||
|
||||
// ── Continuous counters for overlap trim verification ────
|
||||
always @(posedge clk) begin
|
||||
if (seg0_counting && pc_valid_w)
|
||||
seg0_valid_count <= seg0_valid_count + 1;
|
||||
if (seg1_counting && pc_valid_w)
|
||||
seg1_valid_count <= seg1_valid_count + 1;
|
||||
end
|
||||
|
||||
// Timeout watchdog (generous for 2000-sample listen delay + 2 segments)
|
||||
initial begin
|
||||
#5000000;
|
||||
$display("[FAIL] TIMEOUT: simulation exceeded 5ms");
|
||||
$finish;
|
||||
end
|
||||
|
||||
endmodule
|
||||
@@ -96,15 +96,31 @@ end
|
||||
reg [5:0] chirp_counter;
|
||||
reg mc_new_chirp_prev;
|
||||
|
||||
// Frame-start pulse: mirrors the real transmitter's new_chirp_frame signal.
|
||||
// In the real system this fires on IDLE→LONG_CHIRP transitions in the chirp
|
||||
// controller. Here we derive it from the mode controller's chirp_count
|
||||
// wrapping back to 0 (which wraps correctly at cfg_chirps_per_elev).
|
||||
reg tx_frame_start;
|
||||
reg [5:0] rmc_chirp_prev;
|
||||
|
||||
always @(posedge clk_100m or negedge reset_n) begin
|
||||
if (!reset_n) begin
|
||||
chirp_counter <= 6'd0;
|
||||
mc_new_chirp_prev <= 1'b0;
|
||||
tx_frame_start <= 1'b0;
|
||||
rmc_chirp_prev <= 6'd0;
|
||||
end else begin
|
||||
mc_new_chirp_prev <= dut.mc_new_chirp;
|
||||
if (dut.mc_new_chirp != mc_new_chirp_prev) begin
|
||||
chirp_counter <= chirp_counter + 1;
|
||||
end
|
||||
|
||||
// Detect when the internal mode controller's chirp_count wraps to 0
|
||||
tx_frame_start <= 1'b0;
|
||||
if (dut.rmc_chirp_count == 6'd0 && rmc_chirp_prev != 6'd0) begin
|
||||
tx_frame_start <= 1'b1;
|
||||
end
|
||||
rmc_chirp_prev <= dut.rmc_chirp_count;
|
||||
end
|
||||
end
|
||||
|
||||
@@ -128,6 +144,7 @@ radar_receiver_final dut (
|
||||
.adc_pwdn(),
|
||||
|
||||
.chirp_counter(chirp_counter),
|
||||
.tx_frame_start(tx_frame_start),
|
||||
|
||||
.doppler_output(doppler_output),
|
||||
.doppler_valid(doppler_valid),
|
||||
|
||||
@@ -497,6 +497,7 @@ def count_concat_bits(concat_expr: str, port_widths: dict[str, int]) -> ConcatWi
|
||||
# Unknown width — flag it
|
||||
fragments.append((part, -1))
|
||||
total = -1 # Can't compute
|
||||
break
|
||||
|
||||
return ConcatWidth(
|
||||
total_bits=total,
|
||||
|
||||
@@ -49,8 +49,8 @@ sys.path.insert(0, str(cp.GUI_DIR))
|
||||
# Helpers
|
||||
# ===================================================================
|
||||
|
||||
IVERILOG = os.environ.get("IVERILOG", "/opt/homebrew/bin/iverilog")
|
||||
VVP = os.environ.get("VVP", "/opt/homebrew/bin/vvp")
|
||||
IVERILOG = os.environ.get("IVERILOG", "iverilog")
|
||||
VVP = os.environ.get("VVP", "vvp")
|
||||
CXX = os.environ.get("CXX", "c++")
|
||||
|
||||
# Check tool availability for conditional skipping
|
||||
@@ -61,6 +61,20 @@ _has_cxx = subprocess.run(
|
||||
[CXX, "--version"], capture_output=True
|
||||
).returncode == 0
|
||||
|
||||
# In CI, missing tools must be a hard failure — never silently skip.
|
||||
_in_ci = os.environ.get("GITHUB_ACTIONS") == "true"
|
||||
if _in_ci:
|
||||
if not _has_iverilog:
|
||||
raise RuntimeError(
|
||||
"iverilog is required in CI but was not found. "
|
||||
"Ensure 'apt-get install iverilog' ran and IVERILOG/VVP are on PATH."
|
||||
)
|
||||
if not _has_cxx:
|
||||
raise RuntimeError(
|
||||
"C++ compiler is required in CI but was not found. "
|
||||
"Ensure build-essential is installed."
|
||||
)
|
||||
|
||||
|
||||
def _parse_hex_results(text: str) -> list[dict[str, str]]:
|
||||
"""Parse space-separated hex lines from TB output files."""
|
||||
|
||||
Reference in New Issue
Block a user