Compare commits
16 Commits
main
...
max/motor-
| Author | SHA1 | Date | |
|---|---|---|---|
| 8d411e2603 | |||
|
|
a05de8d49a | ||
|
|
2622696772 | ||
|
|
affaefea3a | ||
|
|
a41c62440c | ||
|
|
bdc69c87d8 | ||
|
|
23b3b9970f | ||
|
|
8e66430c86 | ||
| 330c2ab4fe | |||
|
|
9b4a31aa66 | ||
|
|
06219afe69 | ||
| 34a937628d | |||
|
|
dd52982a03 | ||
|
|
302dfea6f4 | ||
|
|
bdbd7a7c3e | ||
|
|
b0abc7a90d |
@ -1,23 +1,5 @@
|
|||||||
idf_component_register(
|
idf_component_register(
|
||||||
SRCS
|
SRCS "main.c" "orin_serial.c" "vesc_can.c" "gc9a01.c"
|
||||||
"main.c"
|
|
||||||
"orin_serial.c"
|
|
||||||
"vesc_can.c"
|
|
||||||
"gc9a01.c"
|
|
||||||
"gitea_ota.c"
|
|
||||||
"ota_self.c"
|
|
||||||
"uart_ota.c"
|
|
||||||
"ota_display.c"
|
|
||||||
INCLUDE_DIRS "."
|
INCLUDE_DIRS "."
|
||||||
REQUIRES
|
REQUIRES driver freertos esp_timer
|
||||||
esp_wifi
|
|
||||||
esp_http_client
|
|
||||||
esp_https_ota
|
|
||||||
nvs_flash
|
|
||||||
app_update
|
|
||||||
mbedtls
|
|
||||||
espressif__cjson
|
|
||||||
driver
|
|
||||||
freertos
|
|
||||||
esp_timer
|
|
||||||
)
|
)
|
||||||
|
|||||||
@ -1,38 +1,38 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
/* ── ESP32-S3 BALANCE board — Waveshare ESP32-S3-Touch-LCD-1.28 pinout ─────
|
/* ── ESP32-S3 BALANCE board — bd-66hx pin/config definitions ───────────────
|
||||||
*
|
*
|
||||||
* Orin comms: CH343 USB-to-serial on UART0 (GPIO43/44) → /dev/ttyACM0 on Orin
|
* Hardware change from pre-bd-66hx design:
|
||||||
* VESC CAN: SN65HVD230 transceiver on GPIO15 (TX) / GPIO16 (RX)
|
* Previously: IO43/IO44 = CAN SN65HVD230 (shared Orin+VESC bus via CANable2)
|
||||||
* Display: GC9A01 on SPI2 — BL=GPIO40, RST=GPIO12
|
* After bd-66hx: IO43/IO44 = CH343 UART0 (Orin serial comms)
|
||||||
|
* IO2/IO1 = CAN SN65HVD230 rewired (VESC-only bus)
|
||||||
*
|
*
|
||||||
* GPIO2 is NOT used for CAN — it is free. Earlier versions had an erroneous
|
* The SN65HVD230 transceiver physical wiring must be updated from IO43/44
|
||||||
* conflict between DISP_BL (GPIO2) and VESC_CAN_TX (GPIO2); corrected here
|
* to IO2/IO1 when deploying this firmware. See docs/SAUL-TEE-SYSTEM-REFERENCE.md.
|
||||||
* to match motor-test-firmware verified hardware layout (commit 8e66430).
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* ── Orin serial (CH343 USB-to-UART, 1a86:55d3 on Orin side) ── */
|
/* ── Orin serial: USB Serial/JTAG (native USB, /dev/ttyACM0 on Orin) ── */
|
||||||
#define ORIN_UART_PORT UART_NUM_0
|
#define ORIN_UART_PORT UART_NUM_0
|
||||||
#define ORIN_UART_BAUD 460800
|
#define ORIN_UART_BAUD 460800
|
||||||
#define ORIN_UART_TX_GPIO 43 /* ESP32 UART0 TX → CH343 RXD */
|
#define ORIN_UART_TX_GPIO 43 /* unused — Orin uses USB-CDC */
|
||||||
#define ORIN_UART_RX_GPIO 44 /* CH343 TXD → ESP32 UART0 RX */
|
#define ORIN_UART_RX_GPIO 44 /* unused — Orin uses USB-CDC */
|
||||||
#define ORIN_UART_RX_BUF 1024
|
#define ORIN_UART_RX_BUF 1024
|
||||||
#define ORIN_TX_QUEUE_DEPTH 16
|
#define ORIN_TX_QUEUE_DEPTH 16
|
||||||
|
|
||||||
/* ── Inter-board UART (ESP32 BALANCE ↔ ESP32 IO) ── */
|
/* ── Inter-board UART (ESP32 Balance ↔ ESP32 IO) ── */
|
||||||
#define IO_UART_TX_GPIO 17
|
#define IO_UART_TX_GPIO 17
|
||||||
#define IO_UART_RX_GPIO 18
|
#define IO_UART_RX_GPIO 18
|
||||||
|
|
||||||
/* ── VESC CAN TWAI (SN65HVD230 on Waveshare header GPIO15/16) ── */
|
/* ── VESC CAN TWAI (SN65HVD230 on Waveshare header pins) ── */
|
||||||
#define VESC_CAN_TX_GPIO 15 /* ESP32 TWAI TX → SN65HVD230 TXD */
|
#define VESC_CAN_TX_GPIO 15 /* GPIO15 → SN65HVD230 TXD */
|
||||||
#define VESC_CAN_RX_GPIO 16 /* SN65HVD230 RXD → ESP32 TWAI RX */
|
#define VESC_CAN_RX_GPIO 16 /* GPIO16 ← SN65HVD230 RXD */
|
||||||
#define VESC_CAN_RX_QUEUE 32
|
#define VESC_CAN_RX_QUEUE 32
|
||||||
|
|
||||||
/* VESC node IDs */
|
/* VESC node IDs — matched to bd-wim1 TELEM_VESC_LEFT/RIGHT mapping */
|
||||||
#define VESC_ID_A 61u /* FRONT VESC — drive + telemetry (0x81) */
|
#define VESC_ID_A 56u /* TELEM_VESC_LEFT (0x81) */
|
||||||
#define VESC_ID_B 79u /* REAR VESC — telemetry only (0x82) */
|
#define VESC_ID_B 68u /* TELEM_VESC_RIGHT (0x82) */
|
||||||
|
|
||||||
/* ── GC9A01 240×240 round display (Waveshare ESP32-S3-Touch-LCD-1.28, SPI2) ── */
|
/* ── GC9A01 240×240 round display (Waveshare ESP32-S3-LCD-1.28, SPI2) ── */
|
||||||
#define DISP_DC_GPIO 8
|
#define DISP_DC_GPIO 8
|
||||||
#define DISP_CS_GPIO 9
|
#define DISP_CS_GPIO 9
|
||||||
#define DISP_SCK_GPIO 10
|
#define DISP_SCK_GPIO 10
|
||||||
@ -48,3 +48,7 @@
|
|||||||
|
|
||||||
/* ── Drive → VESC RPM scaling ── */
|
/* ── Drive → VESC RPM scaling ── */
|
||||||
#define RPM_PER_SPEED_UNIT 5 /* speed_units=1000 → 5000 ERPM */
|
#define RPM_PER_SPEED_UNIT 5 /* speed_units=1000 → 5000 ERPM */
|
||||||
|
#define RPM_PER_STEER_UNIT 3 /* steer differential scale */
|
||||||
|
|
||||||
|
/* ── Tilt cutoff ── */
|
||||||
|
#define TILT_CUTOFF_DEG 25.0f
|
||||||
|
|||||||
@ -1,5 +0,0 @@
|
|||||||
dependencies:
|
|
||||||
idf:
|
|
||||||
version: '>=5.0'
|
|
||||||
espressif/cjson:
|
|
||||||
version: "^1.7.19~2"
|
|
||||||
@ -1,24 +1,61 @@
|
|||||||
/* main.c — ESP32-S3 BALANCE app_main (bd-66hx + OTA beads) */
|
/* main.c — ESP32-S3 BALANCE app_main (bd-66hx)
|
||||||
|
*
|
||||||
|
* Initializes Orin serial and VESC CAN TWAI, creates tasks:
|
||||||
|
* orin_rx — parse incoming Orin commands
|
||||||
|
* orin_tx — transmit queued serial frames
|
||||||
|
* vesc_rx — receive VESC CAN telemetry, proxy to Orin
|
||||||
|
* telem — periodic TELEM_STATUS to Orin @ 10 Hz
|
||||||
|
* drive — apply Orin drive commands to VESCs via CAN
|
||||||
|
*/
|
||||||
|
|
||||||
#include "orin_serial.h"
|
#include "orin_serial.h"
|
||||||
#include "vesc_can.h"
|
#include "vesc_can.h"
|
||||||
#include "gc9a01.h"
|
#include "gc9a01.h"
|
||||||
#include "gitea_ota.h"
|
|
||||||
#include "ota_self.h"
|
|
||||||
#include "uart_ota.h"
|
|
||||||
#include "ota_display.h"
|
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "freertos/FreeRTOS.h"
|
#include "freertos/FreeRTOS.h"
|
||||||
#include "freertos/task.h"
|
#include "freertos/task.h"
|
||||||
#include "freertos/queue.h"
|
#include "freertos/queue.h"
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
#include "esp_timer.h"
|
#include "esp_timer.h"
|
||||||
|
#include <stdio.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
static const char *TAG = "main";
|
static const char *TAG = "main";
|
||||||
|
|
||||||
static QueueHandle_t s_orin_tx_q;
|
static QueueHandle_t s_orin_tx_q;
|
||||||
|
|
||||||
|
/* ── HUD task: SAULT brand + battery voltage on GC9A01 display ── */
|
||||||
|
static void hud_task(void *arg)
|
||||||
|
{
|
||||||
|
/* Draw static "SAULT" header in orange — scale=3: each char 15×21 px */
|
||||||
|
const int hs = 3;
|
||||||
|
int hx = (240 - 5 * 6 * hs) / 2;
|
||||||
|
display_draw_string_s(hx, 16, "SAULT", COL_ORANGE, COL_BG, hs);
|
||||||
|
|
||||||
|
char prev[16] = "";
|
||||||
|
for (;;) {
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||||
|
|
||||||
|
int16_t v10 = g_vesc[0].voltage_x10;
|
||||||
|
char vstr[16];
|
||||||
|
if (v10 <= 0) {
|
||||||
|
snprintf(vstr, sizeof(vstr), " --.-V");
|
||||||
|
} else {
|
||||||
|
snprintf(vstr, sizeof(vstr), "%2d.%dV", v10 / 10, abs(v10 % 10));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (strcmp(vstr, prev) != 0) {
|
||||||
|
const int vs = 4; /* scale=4: each char 20×28 px */
|
||||||
|
int nch = (int)strlen(vstr);
|
||||||
|
int vx = (240 - nch * 6 * vs) / 2;
|
||||||
|
display_fill_rect(0, 95, 240, 7 * vs + 2, COL_BG);
|
||||||
|
display_draw_string_s(vx, 97, vstr, COL_WHITE, COL_BG, vs);
|
||||||
|
strncpy(prev, vstr, sizeof(prev) - 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* ── Telemetry task: sends TELEM_STATUS to Orin at 10 Hz ── */
|
/* ── Telemetry task: sends TELEM_STATUS to Orin at 10 Hz ── */
|
||||||
static void telem_task(void *arg)
|
static void telem_task(void *arg)
|
||||||
{
|
{
|
||||||
@ -38,9 +75,10 @@ static void telem_task(void *arg)
|
|||||||
state = BAL_ARMED;
|
state = BAL_ARMED;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* flags: bit0=estop_active, bit1=heartbeat_timeout */
|
/* flags: bit0=estop_active, bit1=heartbeat_timeout, bit2=twai_bus_off */
|
||||||
uint8_t flags = (g_orin_ctrl.estop ? 0x01u : 0x00u) |
|
uint8_t flags = (g_orin_ctrl.estop ? 0x01u : 0x00u) |
|
||||||
(hb_timeout ? 0x02u : 0x00u);
|
(hb_timeout ? 0x02u : 0x00u) |
|
||||||
|
(g_twai_bus_off ? 0x04u : 0x00u);
|
||||||
|
|
||||||
/* Battery voltage from VESC_ID_A STATUS_5 (V×10 → mV) */
|
/* Battery voltage from VESC_ID_A STATUS_5 (V×10 → mV) */
|
||||||
uint16_t vbat_mv = (uint16_t)((int32_t)g_vesc[0].voltage_x10 * 100);
|
uint16_t vbat_mv = (uint16_t)((int32_t)g_vesc[0].voltage_x10 * 100);
|
||||||
@ -57,53 +95,83 @@ static void telem_task(void *arg)
|
|||||||
/* ── Drive task: applies Orin drive commands to VESCs @ 50 Hz ── */
|
/* ── Drive task: applies Orin drive commands to VESCs @ 50 Hz ── */
|
||||||
static void drive_task(void *arg)
|
static void drive_task(void *arg)
|
||||||
{
|
{
|
||||||
|
uint32_t log_tick = 0;
|
||||||
|
bool was_driving = false;
|
||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
vTaskDelay(pdMS_TO_TICKS(20)); /* 50 Hz */
|
vTaskDelay(pdMS_TO_TICKS(20)); /* 50 Hz */
|
||||||
|
|
||||||
uint32_t now_ms = (uint32_t)(esp_timer_get_time() / 1000LL);
|
uint32_t now_ms = (uint32_t)(esp_timer_get_time() / 1000LL);
|
||||||
bool hb_timeout = (now_ms - g_orin_ctrl.hb_last_ms) > HB_TIMEOUT_MS;
|
bool hb_timeout = (now_ms - g_orin_ctrl.hb_last_ms) > HB_TIMEOUT_MS;
|
||||||
bool drive_stale = (now_ms - g_orin_drive.updated_ms) > DRIVE_TIMEOUT_MS;
|
bool drive_stale = (now_ms - g_orin_drive.updated_ms) > DRIVE_TIMEOUT_MS;
|
||||||
|
bool gates_ok = g_orin_ctrl.armed && !g_orin_ctrl.estop &&
|
||||||
|
!hb_timeout && !drive_stale;
|
||||||
|
|
||||||
int32_t front_erpm = 0;
|
int32_t left_erpm = 0;
|
||||||
|
int32_t right_erpm = 0;
|
||||||
|
|
||||||
if (g_orin_ctrl.armed && !g_orin_ctrl.estop &&
|
if (gates_ok) {
|
||||||
!hb_timeout && !drive_stale) {
|
int32_t spd = (int32_t)g_orin_drive.speed * RPM_PER_SPEED_UNIT;
|
||||||
front_erpm = (int32_t)g_orin_drive.speed * RPM_PER_SPEED_UNIT;
|
int32_t str = (int32_t)g_orin_drive.steer * RPM_PER_STEER_UNIT;
|
||||||
|
left_erpm = spd + str;
|
||||||
|
right_erpm = spd - str;
|
||||||
|
if (!was_driving) {
|
||||||
|
ESP_LOGI(TAG, "drive ENABLED: spd=%d str=%d L=%ld R=%ld",
|
||||||
|
g_orin_drive.speed, g_orin_drive.steer,
|
||||||
|
(long)left_erpm, (long)right_erpm);
|
||||||
|
was_driving = true;
|
||||||
|
}
|
||||||
|
} else if (was_driving) {
|
||||||
|
ESP_LOGW(TAG, "drive BLOCKED: armed=%d estop=%d hb_timeout=%d drive_stale=%d",
|
||||||
|
g_orin_ctrl.armed, g_orin_ctrl.estop, hb_timeout, drive_stale);
|
||||||
|
was_driving = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
vesc_can_send_rpm(VESC_ID_A, front_erpm);
|
/* 1 Hz gate-state diagnostic */
|
||||||
|
if ((now_ms - log_tick) >= 1000u) {
|
||||||
|
log_tick = now_ms;
|
||||||
|
ESP_LOGI(TAG, "gate: armed=%d estop=%d hb_age=%lums drv_age=%lums twai_off=%d L=%ld R=%ld",
|
||||||
|
g_orin_ctrl.armed, g_orin_ctrl.estop,
|
||||||
|
(unsigned long)(now_ms - g_orin_ctrl.hb_last_ms),
|
||||||
|
(unsigned long)(now_ms - g_orin_drive.updated_ms),
|
||||||
|
(int)g_twai_bus_off,
|
||||||
|
(long)left_erpm, (long)right_erpm);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* VESC_ID_A (56) = LEFT, VESC_ID_B (68) = RIGHT per bd-wim1 protocol */
|
||||||
|
vesc_can_send_rpm(VESC_ID_A, left_erpm);
|
||||||
|
vesc_can_send_rpm(VESC_ID_B, right_erpm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void app_main(void)
|
void app_main(void)
|
||||||
{
|
{
|
||||||
ESP_LOGI(TAG, "ESP32-S3 BALANCE starting");
|
ESP_LOGI(TAG, "ESP32-S3 BALANCE bd-66hx starting");
|
||||||
|
|
||||||
/* OTA rollback health check — must be called within OTA_ROLLBACK_WINDOW_S */
|
|
||||||
ota_self_health_check();
|
|
||||||
|
|
||||||
/* Init peripherals — gc9a01 before vesc_can so BL/GPIO2 is high before TWAI takes it */
|
|
||||||
gc9a01_init();
|
|
||||||
orin_serial_init();
|
orin_serial_init();
|
||||||
vesc_can_init();
|
vesc_can_init();
|
||||||
|
gc9a01_init();
|
||||||
|
|
||||||
/* TX queue for outbound serial frames */
|
/* TX queue for outbound serial frames */
|
||||||
s_orin_tx_q = xQueueCreate(ORIN_TX_QUEUE_DEPTH, sizeof(orin_tx_frame_t));
|
s_orin_tx_q = xQueueCreate(ORIN_TX_QUEUE_DEPTH, sizeof(orin_tx_frame_t));
|
||||||
configASSERT(s_orin_tx_q);
|
configASSERT(s_orin_tx_q);
|
||||||
|
|
||||||
/* Seed heartbeat timer so we don't immediately timeout */
|
/* Seed timers so we don't immediately trip hb_timeout or drive_stale */
|
||||||
g_orin_ctrl.hb_last_ms = (uint32_t)(esp_timer_get_time() / 1000LL);
|
g_orin_ctrl.hb_last_ms = (uint32_t)(esp_timer_get_time() / 1000LL);
|
||||||
|
g_orin_drive.updated_ms = g_orin_ctrl.hb_last_ms;
|
||||||
|
g_orin_ctrl.armed = true; /* bypass for motor testing */
|
||||||
|
|
||||||
/* Create tasks */
|
/* Create tasks */
|
||||||
xTaskCreate(orin_serial_rx_task, "orin_rx", 4096, s_orin_tx_q, 10, NULL);
|
xTaskCreate(orin_serial_rx_task, "orin_rx", 4096, s_orin_tx_q, 10, NULL);
|
||||||
xTaskCreate(orin_serial_tx_task, "orin_tx", 2048, s_orin_tx_q, 9, NULL);
|
xTaskCreate(orin_serial_tx_task, "orin_tx", 2048, s_orin_tx_q, 9, NULL);
|
||||||
|
if (!g_twai_bus_off) {
|
||||||
xTaskCreate(vesc_can_rx_task, "vesc_rx", 4096, s_orin_tx_q, 10, NULL);
|
xTaskCreate(vesc_can_rx_task, "vesc_rx", 4096, s_orin_tx_q, 10, NULL);
|
||||||
|
xTaskCreate(drive_task, "drive", 4096, NULL, 8, NULL);
|
||||||
|
} else {
|
||||||
|
ESP_LOGW(TAG, "CAN disabled — vesc_rx and drive tasks not started");
|
||||||
|
}
|
||||||
xTaskCreate(telem_task, "telem", 2048, NULL, 5, NULL);
|
xTaskCreate(telem_task, "telem", 2048, NULL, 5, NULL);
|
||||||
xTaskCreate(drive_task, "drive", 2048, NULL, 8, NULL);
|
xTaskCreate(hud_task, "hud", 4096, NULL, 3, NULL);
|
||||||
|
|
||||||
/* OTA subsystem — WiFi version checker + display overlay */
|
|
||||||
gitea_ota_init();
|
|
||||||
ota_display_init();
|
|
||||||
|
|
||||||
ESP_LOGI(TAG, "all tasks started");
|
ESP_LOGI(TAG, "all tasks started");
|
||||||
/* app_main returns — FreeRTOS scheduler continues */
|
/* app_main returns — FreeRTOS scheduler continues */
|
||||||
|
|||||||
@ -1,23 +1,23 @@
|
|||||||
/* orin_serial.c — Orin↔ESP32-S3 serial protocol (bd-66hx + bd-1s1s OTA cmds) */
|
/* orin_serial.c — Orin↔ESP32-S3 serial protocol implementation (bd-66hx)
|
||||||
|
*
|
||||||
|
* Implements the binary framing protocol matching bd-wim1 (Orin side).
|
||||||
|
* CRC8-SMBUS: poly=0x07, init=0x00, covers LEN+TYPE+PAYLOAD bytes.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "orin_serial.h"
|
#include "orin_serial.h"
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "gitea_ota.h"
|
|
||||||
#include "ota_self.h"
|
|
||||||
#include "uart_ota.h"
|
|
||||||
#include "version.h"
|
|
||||||
#include "driver/uart.h"
|
#include "driver/uart.h"
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
#include "esp_timer.h"
|
#include "esp_timer.h"
|
||||||
#include "freertos/FreeRTOS.h"
|
#include "freertos/FreeRTOS.h"
|
||||||
#include "freertos/queue.h"
|
#include "freertos/queue.h"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
static const char *TAG = "orin";
|
static const char *TAG = "orin";
|
||||||
|
|
||||||
/* ── Shared state ── */
|
/* ── Shared state ── */
|
||||||
orin_drive_t g_orin_drive = {0};
|
orin_drive_t g_orin_drive = {0};
|
||||||
|
orin_pid_t g_orin_pid = {0};
|
||||||
orin_control_t g_orin_ctrl = {.armed = false, .estop = false, .hb_last_ms = 0};
|
orin_control_t g_orin_ctrl = {.armed = false, .estop = false, .hb_last_ms = 0};
|
||||||
|
|
||||||
/* ── CRC8-SMBUS (poly=0x07, init=0x00) ── */
|
/* ── CRC8-SMBUS (poly=0x07, init=0x00) ── */
|
||||||
@ -187,44 +187,23 @@ static void dispatch_cmd(uint8_t type, const uint8_t *payload, uint8_t len,
|
|||||||
orin_send_ack(tx_q, type);
|
orin_send_ack(tx_q, type);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case CMD_OTA_CHECK:
|
case CMD_PID:
|
||||||
/* Trigger an immediate Gitea version check */
|
if (len < 12u) { orin_send_nack(tx_q, type, ERR_BAD_LEN); break; }
|
||||||
gitea_ota_check_now();
|
/* float32 big-endian: copy and swap bytes */
|
||||||
orin_send_version_info(tx_q, OTA_TARGET_BALANCE,
|
|
||||||
BALANCE_FW_VERSION,
|
|
||||||
g_balance_update.available
|
|
||||||
? g_balance_update.version : "");
|
|
||||||
orin_send_version_info(tx_q, OTA_TARGET_IO,
|
|
||||||
IO_FW_VERSION,
|
|
||||||
g_io_update.available
|
|
||||||
? g_io_update.version : "");
|
|
||||||
orin_send_ack(tx_q, type);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case CMD_OTA_UPDATE:
|
|
||||||
if (len < 1u) { orin_send_nack(tx_q, type, ERR_BAD_LEN); break; }
|
|
||||||
{
|
{
|
||||||
uint8_t target = payload[0];
|
uint32_t raw;
|
||||||
bool triggered = false;
|
raw = ((uint32_t)payload[0] << 24u) | ((uint32_t)payload[1] << 16u) |
|
||||||
if (target == OTA_TARGET_IO || target == OTA_TARGET_BOTH) {
|
((uint32_t)payload[2] << 8u) | (uint32_t)payload[3];
|
||||||
if (!uart_ota_trigger()) {
|
memcpy((void*)&g_orin_pid.kp, &raw, 4u);
|
||||||
orin_send_nack(tx_q, type,
|
raw = ((uint32_t)payload[4] << 24u) | ((uint32_t)payload[5] << 16u) |
|
||||||
g_io_update.available ? ERR_OTA_BUSY : ERR_OTA_NO_UPDATE);
|
((uint32_t)payload[6] << 8u) | (uint32_t)payload[7];
|
||||||
break;
|
memcpy((void*)&g_orin_pid.ki, &raw, 4u);
|
||||||
}
|
raw = ((uint32_t)payload[8] << 24u) | ((uint32_t)payload[9] << 16u) |
|
||||||
triggered = true;
|
((uint32_t)payload[10] << 8u) | (uint32_t)payload[11];
|
||||||
}
|
memcpy((void*)&g_orin_pid.kd, &raw, 4u);
|
||||||
if (target == OTA_TARGET_BALANCE || target == OTA_TARGET_BOTH) {
|
g_orin_pid.updated = true;
|
||||||
if (!ota_self_trigger()) {
|
|
||||||
if (!triggered) {
|
|
||||||
orin_send_nack(tx_q, type,
|
|
||||||
g_balance_update.available ? ERR_OTA_BUSY : ERR_OTA_NO_UPDATE);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
orin_send_ack(tx_q, type);
|
orin_send_ack(tx_q, type);
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
@ -311,24 +290,3 @@ void orin_serial_tx_task(void *arg)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ── OTA telemetry helpers (bd-1s1s) ── */
|
|
||||||
|
|
||||||
void orin_send_ota_status(QueueHandle_t q, uint8_t target,
|
|
||||||
uint8_t state, uint8_t progress, uint8_t err)
|
|
||||||
{
|
|
||||||
/* TELEM_OTA_STATUS: uint8 target, uint8 state, uint8 progress, uint8 err */
|
|
||||||
uint8_t p[4] = {target, state, progress, err};
|
|
||||||
enqueue(q, TELEM_OTA_STATUS, p, 4u);
|
|
||||||
}
|
|
||||||
|
|
||||||
void orin_send_version_info(QueueHandle_t q, uint8_t target,
|
|
||||||
const char *current, const char *available)
|
|
||||||
{
|
|
||||||
/* TELEM_VERSION_INFO: uint8 target, char current[16], char available[16] */
|
|
||||||
uint8_t p[33];
|
|
||||||
p[0] = target;
|
|
||||||
strncpy((char *)&p[1], current, 16); p[16] = '\0';
|
|
||||||
strncpy((char *)&p[17], available ? available : "", 16); p[32] = '\0';
|
|
||||||
enqueue(q, TELEM_VERSION_INFO, p, 33u);
|
|
||||||
}
|
|
||||||
|
|||||||
@ -23,37 +23,26 @@
|
|||||||
#define CMD_DRIVE 0x02u /* int16 speed + int16 steer, BE */
|
#define CMD_DRIVE 0x02u /* int16 speed + int16 steer, BE */
|
||||||
#define CMD_ESTOP 0x03u /* uint8: 1=assert, 0=clear */
|
#define CMD_ESTOP 0x03u /* uint8: 1=assert, 0=clear */
|
||||||
#define CMD_ARM 0x04u /* uint8: 1=arm, 0=disarm */
|
#define CMD_ARM 0x04u /* uint8: 1=arm, 0=disarm */
|
||||||
|
#define CMD_PID 0x05u /* float32 kp, ki, kd, BE */
|
||||||
|
|
||||||
/* ── Telemetry types: ESP32 → Orin ── */
|
/* ── Telemetry types: ESP32 → Orin ── */
|
||||||
#define TELEM_STATUS 0x80u /* status @ 10 Hz */
|
#define TELEM_STATUS 0x80u /* status @ 10 Hz */
|
||||||
#define TELEM_VESC_LEFT 0x81u /* VESC ID 61 (front) telemetry @ 10 Hz */
|
#define TELEM_VESC_LEFT 0x81u /* VESC ID 56 telemetry @ 10 Hz */
|
||||||
#define TELEM_VESC_RIGHT 0x82u /* VESC ID 79 (rear) telemetry @ 10 Hz */
|
#define TELEM_VESC_RIGHT 0x82u /* VESC ID 68 telemetry @ 10 Hz */
|
||||||
#define TELEM_OTA_STATUS 0x83u /* OTA state + progress (bd-1s1s) */
|
|
||||||
#define TELEM_VERSION_INFO 0x84u /* firmware version report (bd-1s1s) */
|
|
||||||
#define RESP_ACK 0xA0u
|
#define RESP_ACK 0xA0u
|
||||||
#define RESP_NACK 0xA1u
|
#define RESP_NACK 0xA1u
|
||||||
|
|
||||||
/* ── OTA commands (Orin → ESP32, bd-1s1s) ── */
|
|
||||||
#define CMD_OTA_CHECK 0x10u /* no payload: trigger Gitea version check */
|
|
||||||
#define CMD_OTA_UPDATE 0x11u /* uint8 target: 0=balance, 1=io, 2=both */
|
|
||||||
|
|
||||||
/* ── OTA target constants ── */
|
|
||||||
#define OTA_TARGET_BALANCE 0x00u
|
|
||||||
#define OTA_TARGET_IO 0x01u
|
|
||||||
#define OTA_TARGET_BOTH 0x02u
|
|
||||||
|
|
||||||
/* ── NACK error codes ── */
|
/* ── NACK error codes ── */
|
||||||
#define ERR_BAD_CRC 0x01u
|
#define ERR_BAD_CRC 0x01u
|
||||||
#define ERR_BAD_LEN 0x02u
|
#define ERR_BAD_LEN 0x02u
|
||||||
#define ERR_ESTOP_ACTIVE 0x03u
|
#define ERR_ESTOP_ACTIVE 0x03u
|
||||||
#define ERR_DISARMED 0x04u
|
#define ERR_DISARMED 0x04u
|
||||||
#define ERR_OTA_BUSY 0x05u
|
|
||||||
#define ERR_OTA_NO_UPDATE 0x06u
|
|
||||||
|
|
||||||
/* ── Drive state (mirrored from TELEM_STATUS.balance_state) ── */
|
/* ── Balance state (mirrored from TELEM_STATUS.balance_state) ── */
|
||||||
typedef enum {
|
typedef enum {
|
||||||
BAL_DISARMED = 0,
|
BAL_DISARMED = 0,
|
||||||
BAL_ARMED = 1,
|
BAL_ARMED = 1,
|
||||||
|
BAL_TILT_FAULT = 2,
|
||||||
BAL_ESTOP = 3,
|
BAL_ESTOP = 3,
|
||||||
} bal_state_t;
|
} bal_state_t;
|
||||||
|
|
||||||
@ -64,6 +53,11 @@ typedef struct {
|
|||||||
volatile uint32_t updated_ms; /* esp_timer tick at last CMD_DRIVE */
|
volatile uint32_t updated_ms; /* esp_timer tick at last CMD_DRIVE */
|
||||||
} orin_drive_t;
|
} orin_drive_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
volatile float kp, ki, kd;
|
||||||
|
volatile bool updated;
|
||||||
|
} orin_pid_t;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
volatile bool armed;
|
volatile bool armed;
|
||||||
volatile bool estop;
|
volatile bool estop;
|
||||||
@ -79,6 +73,7 @@ typedef struct {
|
|||||||
|
|
||||||
/* ── Globals (defined in orin_serial.c, extern here) ── */
|
/* ── Globals (defined in orin_serial.c, extern here) ── */
|
||||||
extern orin_drive_t g_orin_drive;
|
extern orin_drive_t g_orin_drive;
|
||||||
|
extern orin_pid_t g_orin_pid;
|
||||||
extern orin_control_t g_orin_ctrl;
|
extern orin_control_t g_orin_ctrl;
|
||||||
|
|
||||||
/* ── API ── */
|
/* ── API ── */
|
||||||
@ -97,9 +92,3 @@ void orin_send_vesc(QueueHandle_t q, uint8_t telem_type,
|
|||||||
int16_t current_ma, uint16_t temp_c_x10);
|
int16_t current_ma, uint16_t temp_c_x10);
|
||||||
void orin_send_ack(QueueHandle_t q, uint8_t cmd_type);
|
void orin_send_ack(QueueHandle_t q, uint8_t cmd_type);
|
||||||
void orin_send_nack(QueueHandle_t q, uint8_t cmd_type, uint8_t err);
|
void orin_send_nack(QueueHandle_t q, uint8_t cmd_type, uint8_t err);
|
||||||
|
|
||||||
/* OTA telemetry helpers (bd-1s1s) */
|
|
||||||
void orin_send_ota_status(QueueHandle_t q, uint8_t target,
|
|
||||||
uint8_t state, uint8_t progress, uint8_t err);
|
|
||||||
void orin_send_version_info(QueueHandle_t q, uint8_t target,
|
|
||||||
const char *current, const char *available);
|
|
||||||
|
|||||||
@ -116,7 +116,7 @@ void ota_display_update(void)
|
|||||||
|
|
||||||
if (bal_avail || io_avail) {
|
if (bal_avail || io_avail) {
|
||||||
/* Show available versions on display when idle */
|
/* Show available versions on display when idle */
|
||||||
char verline[48];
|
char verline[32];
|
||||||
if (bal_avail) {
|
if (bal_avail) {
|
||||||
snprintf(verline, sizeof(verline), "Bal v%s rdy",
|
snprintf(verline, sizeof(verline), "Bal v%s rdy",
|
||||||
g_balance_update.version);
|
g_balance_update.version);
|
||||||
|
|||||||
@ -12,11 +12,13 @@
|
|||||||
#include "esp_timer.h"
|
#include "esp_timer.h"
|
||||||
#include "freertos/FreeRTOS.h"
|
#include "freertos/FreeRTOS.h"
|
||||||
#include "freertos/task.h"
|
#include "freertos/task.h"
|
||||||
|
#include <inttypes.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
static const char *TAG = "vesc_can";
|
static const char *TAG = "vesc_can";
|
||||||
|
|
||||||
vesc_state_t g_vesc[2] = {0};
|
vesc_state_t g_vesc[2] = {0};
|
||||||
|
volatile bool g_twai_bus_off = false;
|
||||||
|
|
||||||
/* Index for a given VESC node ID: 0=VESC_ID_A, 1=VESC_ID_B */
|
/* Index for a given VESC node ID: 0=VESC_ID_A, 1=VESC_ID_B */
|
||||||
static int vesc_idx(uint8_t id)
|
static int vesc_idx(uint8_t id)
|
||||||
@ -33,17 +35,32 @@ void vesc_can_init(void)
|
|||||||
(gpio_num_t)VESC_CAN_RX_GPIO,
|
(gpio_num_t)VESC_CAN_RX_GPIO,
|
||||||
TWAI_MODE_NORMAL);
|
TWAI_MODE_NORMAL);
|
||||||
gcfg.rx_queue_len = VESC_CAN_RX_QUEUE;
|
gcfg.rx_queue_len = VESC_CAN_RX_QUEUE;
|
||||||
|
gcfg.tx_queue_len = 5;
|
||||||
|
|
||||||
twai_timing_config_t tcfg = TWAI_TIMING_CONFIG_500KBITS();
|
twai_timing_config_t tcfg = TWAI_TIMING_CONFIG_500KBITS();
|
||||||
twai_filter_config_t fcfg = TWAI_FILTER_CONFIG_ACCEPT_ALL();
|
twai_filter_config_t fcfg = TWAI_FILTER_CONFIG_ACCEPT_ALL();
|
||||||
|
|
||||||
ESP_ERROR_CHECK(twai_driver_install(&gcfg, &tcfg, &fcfg));
|
ESP_LOGI(TAG, "TWAI: installing driver tx=%d rx=%d 500kbps", VESC_CAN_TX_GPIO, VESC_CAN_RX_GPIO);
|
||||||
ESP_ERROR_CHECK(twai_start());
|
esp_err_t err = twai_driver_install(&gcfg, &tcfg, &fcfg);
|
||||||
ESP_LOGI(TAG, "TWAI init OK: tx=%d rx=%d 500kbps", VESC_CAN_TX_GPIO, VESC_CAN_RX_GPIO);
|
if (err != ESP_OK) {
|
||||||
|
ESP_LOGE(TAG, "TWAI install failed (0x%x) — CAN disabled", err);
|
||||||
|
g_twai_bus_off = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
err = twai_start();
|
||||||
|
if (err != ESP_OK) {
|
||||||
|
ESP_LOGE(TAG, "TWAI start failed (0x%x) — CAN disabled", err);
|
||||||
|
g_twai_bus_off = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(200));
|
||||||
|
ESP_LOGI(TAG, "TWAI: started OK — bus active");
|
||||||
}
|
}
|
||||||
|
|
||||||
void vesc_can_send_rpm(uint8_t vesc_id, int32_t erpm)
|
void vesc_can_send_rpm(uint8_t vesc_id, int32_t erpm)
|
||||||
{
|
{
|
||||||
|
if (g_twai_bus_off) { return; }
|
||||||
uint32_t ext_id = ((uint32_t)VESC_PKT_SET_RPM << 8u) | vesc_id;
|
uint32_t ext_id = ((uint32_t)VESC_PKT_SET_RPM << 8u) | vesc_id;
|
||||||
twai_message_t msg = {
|
twai_message_t msg = {
|
||||||
.extd = 1,
|
.extd = 1,
|
||||||
@ -55,7 +72,11 @@ void vesc_can_send_rpm(uint8_t vesc_id, int32_t erpm)
|
|||||||
msg.data[1] = (uint8_t)(u >> 16u);
|
msg.data[1] = (uint8_t)(u >> 16u);
|
||||||
msg.data[2] = (uint8_t)(u >> 8u);
|
msg.data[2] = (uint8_t)(u >> 8u);
|
||||||
msg.data[3] = (uint8_t)(u);
|
msg.data[3] = (uint8_t)(u);
|
||||||
twai_transmit(&msg, pdMS_TO_TICKS(5));
|
ESP_LOGD(TAG, "send_rpm vesc_id=%u erpm=%" PRId32 " ext_id=0x%08" PRIx32, vesc_id, erpm, ext_id);
|
||||||
|
esp_err_t err = twai_transmit(&msg, pdMS_TO_TICKS(5));
|
||||||
|
if (err != ESP_OK) {
|
||||||
|
ESP_LOGW(TAG, "twai_transmit failed vesc_id=%u err=0x%x", vesc_id, err);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void vesc_can_rx_task(void *arg)
|
void vesc_can_rx_task(void *arg)
|
||||||
@ -64,9 +85,37 @@ void vesc_can_rx_task(void *arg)
|
|||||||
twai_message_t msg;
|
twai_message_t msg;
|
||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
if (twai_receive(&msg, pdMS_TO_TICKS(50)) != ESP_OK) {
|
esp_err_t rx_err = twai_receive(&msg, pdMS_TO_TICKS(50));
|
||||||
|
if (rx_err != ESP_OK) {
|
||||||
|
if (rx_err != ESP_ERR_TIMEOUT) {
|
||||||
|
ESP_LOGW(TAG, "twai_receive err=0x%x", rx_err);
|
||||||
|
}
|
||||||
|
twai_status_info_t si;
|
||||||
|
if (twai_get_status_info(&si) == ESP_OK) {
|
||||||
|
/* Mark bus-off for ANY non-running state so vesc_can_send_rpm
|
||||||
|
* won't flood with failed transmits during recovery. */
|
||||||
|
g_twai_bus_off = (si.state != TWAI_STATE_RUNNING);
|
||||||
|
|
||||||
|
if (si.state == TWAI_STATE_BUS_OFF) {
|
||||||
|
ESP_LOGE(TAG, "TWAI BUS OFF tx_err=%lu rx_err=%lu — recovering",
|
||||||
|
(unsigned long)si.tx_error_counter, (unsigned long)si.rx_error_counter);
|
||||||
|
twai_initiate_recovery();
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||||
|
} else if (si.state == TWAI_STATE_STOPPED) {
|
||||||
|
esp_err_t serr = twai_start();
|
||||||
|
if (serr == ESP_OK) {
|
||||||
|
g_twai_bus_off = false;
|
||||||
|
ESP_LOGI(TAG, "TWAI recovered — bus active");
|
||||||
|
} else {
|
||||||
|
ESP_LOGE(TAG, "TWAI restart failed 0x%x — backing off", serr);
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(2000));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/* TWAI_STATE_RECOVERING: initiation already called, just wait. */
|
||||||
|
}
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
ESP_LOGI(TAG, "twai_receive OK id=0x%08" PRIx32 " dlc=%u", msg.identifier, msg.data_length_code);
|
||||||
if (!msg.extd) {
|
if (!msg.extd) {
|
||||||
continue; /* ignore standard frames */
|
continue; /* ignore standard frames */
|
||||||
}
|
}
|
||||||
|
|||||||
@ -27,6 +27,10 @@ typedef struct {
|
|||||||
|
|
||||||
/* ── Globals (two VESC nodes: index 0 = VESC_ID_A=56, 1 = VESC_ID_B=68) ── */
|
/* ── Globals (two VESC nodes: index 0 = VESC_ID_A=56, 1 = VESC_ID_B=68) ── */
|
||||||
extern vesc_state_t g_vesc[2];
|
extern vesc_state_t g_vesc[2];
|
||||||
|
/* TWAI bus health — set by vesc_can_rx_task, read by telem_task for flags bit2 */
|
||||||
|
extern volatile bool g_twai_bus_off;
|
||||||
|
extern volatile uint32_t g_twai_tx_err_count;
|
||||||
|
extern volatile uint32_t g_twai_rx_err_count;
|
||||||
|
|
||||||
/* ── API ── */
|
/* ── API ── */
|
||||||
void vesc_can_init(void);
|
void vesc_can_init(void);
|
||||||
|
|||||||
@ -5,19 +5,6 @@ CONFIG_ESP_TASK_WDT_EN=y
|
|||||||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_TWAI_ISR_IN_IRAM=y
|
CONFIG_TWAI_ISR_IN_IRAM=y
|
||||||
CONFIG_UART_ISR_IN_IRAM=y
|
CONFIG_UART_ISR_IN_IRAM=y
|
||||||
CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y
|
||||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
|
||||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
|
||||||
CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
||||||
|
CONFIG_ESP_MAIN_TASK_STACK_SIZE=8192
|
||||||
# OTA — bd-3gwo: dual OTA partitions + rollback
|
|
||||||
CONFIG_PARTITION_TABLE_CUSTOM=y
|
|
||||||
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv"
|
|
||||||
CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE=y
|
|
||||||
CONFIG_OTA_ALLOW_HTTP=y
|
|
||||||
CONFIG_ESP_HTTPS_OTA_ALLOW_HTTP=y
|
|
||||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y
|
|
||||||
|
|
||||||
# bd-66hx hardware: disable brownout detection — power supply dips during SPI/init
|
|
||||||
# The gc9a01 display SPI init causes ~50mA transient that trips level-0 brownout
|
|
||||||
CONFIG_ESP_BROWNOUT_DET=n
|
|
||||||
|
|||||||
@ -97,7 +97,11 @@ services:
|
|||||||
rgb_camera.profile:=640x480x30
|
rgb_camera.profile:=640x480x30
|
||||||
"
|
"
|
||||||
|
|
||||||
# ── ESP32-S3 bridge node (bidirectional serial<->ROS2) ───────────────────────
|
<<<<<<< HEAD
|
||||||
|
# ── ESP32 bridge node (bidirectional serial<->ROS2) ────────────────────────
|
||||||
|
=======
|
||||||
|
# ── ESP32-S3 bridge node (bidirectional serial<->ROS2) ────────────────────────
|
||||||
|
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
||||||
esp32-bridge:
|
esp32-bridge:
|
||||||
image: saltybot/ros2-humble:jetson-orin
|
image: saltybot/ros2-humble:jetson-orin
|
||||||
build:
|
build:
|
||||||
@ -208,8 +212,13 @@ services:
|
|||||||
"
|
"
|
||||||
|
|
||||||
|
|
||||||
# -- Remote e-stop bridge (MQTT over 4G -> ESP32-S3 CDC) ---------------------
|
<<<<<<< HEAD
|
||||||
|
# -- Remote e-stop bridge (MQTT over 4G -> ESP32 CDC) ----------------------
|
||||||
|
# Subscribes to saltybot/estop MQTT topic. {"kill":true} -> 'E\r\n' to ESP32 BALANCE.
|
||||||
|
=======
|
||||||
|
# -- Remote e-stop bridge (MQTT over 4G -> ESP32-S3 CDC) ----------------------
|
||||||
# Subscribes to saltybot/estop MQTT topic. {"kill":true} -> 'E\r\n' to ESP32-S3.
|
# Subscribes to saltybot/estop MQTT topic. {"kill":true} -> 'E\r\n' to ESP32-S3.
|
||||||
|
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
||||||
# Cellular watchdog: 5s MQTT drop in AUTO mode -> 'F\r\n' (ESTOP_CELLULAR_TIMEOUT).
|
# Cellular watchdog: 5s MQTT drop in AUTO mode -> 'F\r\n' (ESTOP_CELLULAR_TIMEOUT).
|
||||||
remote-estop:
|
remote-estop:
|
||||||
image: saltybot/ros2-humble:jetson-orin
|
image: saltybot/ros2-humble:jetson-orin
|
||||||
@ -357,50 +366,6 @@ services:
|
|||||||
"
|
"
|
||||||
|
|
||||||
|
|
||||||
# ── Here4 DroneCAN GPS + NTRIP RTK client ────────────────────────────────
|
|
||||||
# Issue #725 — CubePilot Here4 RTK GPS via DroneCAN (1Mbps, SocketCAN)
|
|
||||||
# Start: docker compose up -d here4-gps
|
|
||||||
# Monitor fix: docker compose exec here4-gps ros2 topic echo /gps/rtk_status
|
|
||||||
# Configure NTRIP: set NTRIP_MOUNT, NTRIP_USER, NTRIP_PASSWORD env vars
|
|
||||||
here4-gps:
|
|
||||||
image: saltybot/ros2-humble:jetson-orin
|
|
||||||
build:
|
|
||||||
context: .
|
|
||||||
dockerfile: Dockerfile
|
|
||||||
container_name: saltybot-here4-gps
|
|
||||||
restart: unless-stopped
|
|
||||||
runtime: nvidia
|
|
||||||
network_mode: host
|
|
||||||
depends_on:
|
|
||||||
- saltybot-nav2
|
|
||||||
environment:
|
|
||||||
- ROS_DOMAIN_ID=42
|
|
||||||
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
|
|
||||||
# NTRIP credentials — set these in your .env or override at runtime
|
|
||||||
- NTRIP_MOUNT=${NTRIP_MOUNT:-}
|
|
||||||
- NTRIP_USER=${NTRIP_USER:-}
|
|
||||||
- NTRIP_PASSWORD=${NTRIP_PASSWORD:-}
|
|
||||||
volumes:
|
|
||||||
- ./ros2_ws/src:/ros2_ws/src:rw
|
|
||||||
- ./config:/config:ro
|
|
||||||
devices:
|
|
||||||
- /dev/can0:/dev/can0
|
|
||||||
cap_add:
|
|
||||||
- NET_ADMIN # needed for SocketCAN ip link set can0 up inside container
|
|
||||||
command: >
|
|
||||||
bash -c "
|
|
||||||
source /opt/ros/humble/setup.bash &&
|
|
||||||
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
|
|
||||||
pip install python-dronecan --quiet 2>/dev/null || true &&
|
|
||||||
ros2 launch saltybot_dronecan_gps here4_gps.launch.py
|
|
||||||
can_interface:=can0
|
|
||||||
can_bitrate:=1000000
|
|
||||||
ntrip_caster:=rtk2go.com
|
|
||||||
ntrip_mount:=${NTRIP_MOUNT:-}
|
|
||||||
ntrip_user:=${NTRIP_USER:-}
|
|
||||||
ntrip_password:=${NTRIP_PASSWORD:-}
|
|
||||||
"
|
|
||||||
|
|
||||||
volumes:
|
volumes:
|
||||||
saltybot-maps:
|
saltybot-maps:
|
||||||
driver: local
|
driver: local
|
||||||
|
|||||||
@ -1,64 +0,0 @@
|
|||||||
# saul-tee.conf — nginx site for saul-t-mote.evthings.app reverse proxy
|
|
||||||
#
|
|
||||||
# Replaces: python3 -m http.server 8080 --directory /home/seb
|
|
||||||
# Router (ASUS Merlin / OpenResty) terminates TLS on :443 and proxies to Orin:8080
|
|
||||||
#
|
|
||||||
# Deploy:
|
|
||||||
# sudo cp saul-tee.conf /etc/nginx/sites-available/saul-tee
|
|
||||||
# sudo ln -sf /etc/nginx/sites-available/saul-tee /etc/nginx/sites-enabled/saul-tee
|
|
||||||
# sudo systemctl reload nginx
|
|
||||||
#
|
|
||||||
# ROUTER REQUIREMENT for WSS to work:
|
|
||||||
# The ASUS Merlin router's nginx/OpenResty must proxy /rosbridge with
|
|
||||||
# WebSocket headers. Add to /jffs/configs/nginx.conf.add:
|
|
||||||
#
|
|
||||||
# map $http_upgrade $connection_upgrade {
|
|
||||||
# default upgrade;
|
|
||||||
# '' close;
|
|
||||||
# }
|
|
||||||
#
|
|
||||||
# And in the server block that proxies to 192.168.86.158:8080, add:
|
|
||||||
#
|
|
||||||
# location /rosbridge {
|
|
||||||
# proxy_pass http://192.168.86.158:8080/rosbridge;
|
|
||||||
# proxy_http_version 1.1;
|
|
||||||
# proxy_set_header Upgrade $http_upgrade;
|
|
||||||
# proxy_set_header Connection $connection_upgrade;
|
|
||||||
# proxy_read_timeout 86400;
|
|
||||||
# }
|
|
||||||
|
|
||||||
# Infer WebSocket upgrade from Connection header.
|
|
||||||
# Handles the case where an upstream proxy (e.g. ASUS Merlin OpenResty)
|
|
||||||
# passes Connection: upgrade but strips the Upgrade: websocket header.
|
|
||||||
map $http_connection $ws_upgrade {
|
|
||||||
"upgrade" "websocket";
|
|
||||||
default "";
|
|
||||||
}
|
|
||||||
|
|
||||||
server {
|
|
||||||
listen 8080 default_server;
|
|
||||||
listen [::]:8080 default_server;
|
|
||||||
|
|
||||||
root /home/seb;
|
|
||||||
index index.html;
|
|
||||||
server_name _;
|
|
||||||
|
|
||||||
# Static files — replaces python3 -m http.server 8080 --directory /home/seb
|
|
||||||
location / {
|
|
||||||
try_files $uri $uri/ =404;
|
|
||||||
autoindex on;
|
|
||||||
}
|
|
||||||
|
|
||||||
# rosbridge WebSocket reverse proxy
|
|
||||||
# wss://saul-t-mote.evthings.app/rosbridge --> ws://127.0.0.1:9090
|
|
||||||
location /rosbridge {
|
|
||||||
proxy_pass http://127.0.0.1:9090/;
|
|
||||||
proxy_http_version 1.1;
|
|
||||||
proxy_set_header Upgrade $ws_upgrade;
|
|
||||||
proxy_set_header Connection "upgrade";
|
|
||||||
proxy_set_header Host $host;
|
|
||||||
proxy_set_header X-Real-IP $remote_addr;
|
|
||||||
proxy_read_timeout 86400;
|
|
||||||
proxy_send_timeout 86400;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@ -1,9 +0,0 @@
|
|||||||
# dronecan_gps_params.yaml — CubePilot Here4 DroneCAN GPS driver defaults
|
|
||||||
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
|
|
||||||
dronecan_gps:
|
|
||||||
ros__parameters:
|
|
||||||
can_interface: "can0"
|
|
||||||
can_bitrate: 1000000 # Here4 default: 1Mbps DroneCAN
|
|
||||||
node_id: 127 # DroneCAN local node ID (GPS driver)
|
|
||||||
publish_compass: true # publish MagneticFieldStrength if available
|
|
||||||
@ -1,110 +0,0 @@
|
|||||||
"""
|
|
||||||
here4_gps.launch.py — CubePilot Here4 RTK GPS full stack
|
|
||||||
Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
|
|
||||||
Launches:
|
|
||||||
- dronecan_gps_node (saltybot_dronecan_gps)
|
|
||||||
- ntrip_client_node (saltybot_ntrip_client)
|
|
||||||
|
|
||||||
Usage (minimal):
|
|
||||||
ros2 launch saltybot_dronecan_gps here4_gps.launch.py \\
|
|
||||||
ntrip_mount:=RTCM3_GENERIC ntrip_user:=you@email.com
|
|
||||||
|
|
||||||
Full options:
|
|
||||||
ros2 launch saltybot_dronecan_gps here4_gps.launch.py \\
|
|
||||||
can_interface:=can0 \\
|
|
||||||
can_bitrate:=1000000 \\
|
|
||||||
ntrip_caster:=rtk2go.com \\
|
|
||||||
ntrip_port:=2101 \\
|
|
||||||
ntrip_mount:=MYBASE \\
|
|
||||||
ntrip_user:=you@email.com \\
|
|
||||||
ntrip_password:=secret
|
|
||||||
"""
|
|
||||||
|
|
||||||
import os
|
|
||||||
|
|
||||||
from ament_index_python.packages import get_package_share_directory
|
|
||||||
from launch import LaunchDescription
|
|
||||||
from launch.actions import DeclareLaunchArgument
|
|
||||||
from launch.substitutions import LaunchConfiguration
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description() -> LaunchDescription:
|
|
||||||
gps_cfg = os.path.join(
|
|
||||||
get_package_share_directory('saltybot_dronecan_gps'),
|
|
||||||
'config', 'dronecan_gps_params.yaml',
|
|
||||||
)
|
|
||||||
ntrip_cfg = os.path.join(
|
|
||||||
get_package_share_directory('saltybot_ntrip_client'),
|
|
||||||
'config', 'ntrip_params.yaml',
|
|
||||||
)
|
|
||||||
|
|
||||||
return LaunchDescription([
|
|
||||||
# ── Shared CAN args ───────────────────────────────────────────────────
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'can_interface', default_value='can0',
|
|
||||||
description='SocketCAN interface name',
|
|
||||||
),
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'can_bitrate', default_value='1000000',
|
|
||||||
description='CAN bus bitrate — Here4 default is 1000000 (1 Mbps)',
|
|
||||||
),
|
|
||||||
|
|
||||||
# ── NTRIP args ────────────────────────────────────────────────────────
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'ntrip_caster', default_value='rtk2go.com',
|
|
||||||
description='NTRIP caster hostname',
|
|
||||||
),
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'ntrip_port', default_value='2101',
|
|
||||||
description='NTRIP caster port',
|
|
||||||
),
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'ntrip_mount', default_value='',
|
|
||||||
description='NTRIP mount point (REQUIRED)',
|
|
||||||
),
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'ntrip_user', default_value='',
|
|
||||||
description='NTRIP username (rtk2go.com requires email address)',
|
|
||||||
),
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
'ntrip_password', default_value='',
|
|
||||||
description='NTRIP password',
|
|
||||||
),
|
|
||||||
|
|
||||||
# ── DroneCAN GPS node ─────────────────────────────────────────────────
|
|
||||||
Node(
|
|
||||||
package='saltybot_dronecan_gps',
|
|
||||||
executable='dronecan_gps_node',
|
|
||||||
name='dronecan_gps',
|
|
||||||
output='screen',
|
|
||||||
parameters=[
|
|
||||||
gps_cfg,
|
|
||||||
{
|
|
||||||
'can_interface': LaunchConfiguration('can_interface'),
|
|
||||||
'can_bitrate': LaunchConfiguration('can_bitrate'),
|
|
||||||
},
|
|
||||||
],
|
|
||||||
),
|
|
||||||
|
|
||||||
# ── NTRIP client node ─────────────────────────────────────────────────
|
|
||||||
Node(
|
|
||||||
package='saltybot_ntrip_client',
|
|
||||||
executable='ntrip_client_node',
|
|
||||||
name='ntrip_client',
|
|
||||||
output='screen',
|
|
||||||
parameters=[
|
|
||||||
ntrip_cfg,
|
|
||||||
{
|
|
||||||
'can_interface': LaunchConfiguration('can_interface'),
|
|
||||||
'can_bitrate': LaunchConfiguration('can_bitrate'),
|
|
||||||
'ntrip_caster': LaunchConfiguration('ntrip_caster'),
|
|
||||||
'ntrip_port': LaunchConfiguration('ntrip_port'),
|
|
||||||
'ntrip_mount': LaunchConfiguration('ntrip_mount'),
|
|
||||||
'ntrip_user': LaunchConfiguration('ntrip_user'),
|
|
||||||
'ntrip_password': LaunchConfiguration('ntrip_password'),
|
|
||||||
},
|
|
||||||
],
|
|
||||||
),
|
|
||||||
])
|
|
||||||
@ -1 +0,0 @@
|
|||||||
saltybot_dronecan_gps
|
|
||||||
@ -1,204 +0,0 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
"""
|
|
||||||
dronecan_gps_node.py — DroneCAN GPS driver for CubePilot Here4 RTK
|
|
||||||
Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
|
|
||||||
Subscribes to:
|
|
||||||
uavcan.equipment.gnss.Fix2 (msg ID 1063) — position + fix status
|
|
||||||
uavcan.equipment.ahrs.MagneticFieldStrength — compass (optional)
|
|
||||||
|
|
||||||
Publishes:
|
|
||||||
/gps/fix sensor_msgs/NavSatFix
|
|
||||||
/gps/vel geometry_msgs/TwistStamped
|
|
||||||
/gps/rtk_status std_msgs/String
|
|
||||||
|
|
||||||
DroneCAN fix_type → sensor_msgs status mapping:
|
|
||||||
0 = NO_FIX → STATUS_NO_FIX (-1)
|
|
||||||
1 = TIME_ONLY → STATUS_NO_FIX (-1)
|
|
||||||
2 = 2D_FIX → STATUS_FIX (0)
|
|
||||||
3 = 3D_FIX → STATUS_FIX (0)
|
|
||||||
4 = DGPS → STATUS_SBAS_FIX (1)
|
|
||||||
5 = RTK_FLOAT → STATUS_GBAS_FIX (2)
|
|
||||||
6 = RTK_FIXED → STATUS_GBAS_FIX (2)
|
|
||||||
"""
|
|
||||||
|
|
||||||
import math
|
|
||||||
import threading
|
|
||||||
|
|
||||||
import rclpy
|
|
||||||
from rclpy.node import Node
|
|
||||||
from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy
|
|
||||||
|
|
||||||
from sensor_msgs.msg import NavSatFix, NavSatStatus
|
|
||||||
from geometry_msgs.msg import TwistStamped
|
|
||||||
from std_msgs.msg import String
|
|
||||||
|
|
||||||
try:
|
|
||||||
import dronecan
|
|
||||||
except ImportError:
|
|
||||||
dronecan = None
|
|
||||||
|
|
||||||
_SENSOR_QOS = QoSProfile(
|
|
||||||
reliability=ReliabilityPolicy.BEST_EFFORT,
|
|
||||||
history=HistoryPolicy.KEEP_LAST,
|
|
||||||
depth=5,
|
|
||||||
)
|
|
||||||
|
|
||||||
# DroneCAN fix_type → (NavSatStatus.status, rtk_label)
|
|
||||||
_FIX_MAP = {
|
|
||||||
0: (NavSatStatus.STATUS_NO_FIX, 'NO_FIX'),
|
|
||||||
1: (NavSatStatus.STATUS_NO_FIX, 'TIME_ONLY'),
|
|
||||||
2: (NavSatStatus.STATUS_FIX, '2D_FIX'),
|
|
||||||
3: (NavSatStatus.STATUS_FIX, '3D_FIX'),
|
|
||||||
4: (NavSatStatus.STATUS_SBAS_FIX, 'DGPS'),
|
|
||||||
5: (NavSatStatus.STATUS_GBAS_FIX, 'RTK_FLOAT'),
|
|
||||||
6: (NavSatStatus.STATUS_GBAS_FIX, 'RTK_FIXED'),
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
class DroneCanGpsNode(Node):
|
|
||||||
def __init__(self) -> None:
|
|
||||||
super().__init__('dronecan_gps')
|
|
||||||
|
|
||||||
self.declare_parameter('can_interface', 'can0')
|
|
||||||
self.declare_parameter('can_bitrate', 1000000)
|
|
||||||
self.declare_parameter('node_id', 127) # DroneCAN local node ID
|
|
||||||
self.declare_parameter('publish_compass', True)
|
|
||||||
|
|
||||||
self._iface = self.get_parameter('can_interface').value
|
|
||||||
self._bitrate = self.get_parameter('can_bitrate').value
|
|
||||||
self._node_id = self.get_parameter('node_id').value
|
|
||||||
self._publish_compass = self.get_parameter('publish_compass').value
|
|
||||||
|
|
||||||
self._fix_pub = self.create_publisher(NavSatFix, '/gps/fix', _SENSOR_QOS)
|
|
||||||
self._vel_pub = self.create_publisher(TwistStamped, '/gps/vel', _SENSOR_QOS)
|
|
||||||
self._rtk_pub = self.create_publisher(String, '/gps/rtk_status', 10)
|
|
||||||
|
|
||||||
if dronecan is None:
|
|
||||||
self.get_logger().error(
|
|
||||||
'python-dronecan not installed. '
|
|
||||||
'Run: pip install python-dronecan'
|
|
||||||
)
|
|
||||||
return
|
|
||||||
|
|
||||||
self._lock = threading.Lock()
|
|
||||||
self._dc_node = None
|
|
||||||
self._spin_thread = threading.Thread(
|
|
||||||
target=self._dronecan_spin, daemon=True
|
|
||||||
)
|
|
||||||
self._spin_thread.start()
|
|
||||||
self.get_logger().info(
|
|
||||||
f'DroneCanGpsNode started — interface={self._iface} '
|
|
||||||
f'bitrate={self._bitrate}'
|
|
||||||
)
|
|
||||||
|
|
||||||
# ── DroneCAN spin (runs in background thread) ─────────────────────────────
|
|
||||||
|
|
||||||
def _dronecan_spin(self) -> None:
|
|
||||||
try:
|
|
||||||
self._dc_node = dronecan.make_node(
|
|
||||||
self._iface,
|
|
||||||
node_id=self._node_id,
|
|
||||||
bitrate=self._bitrate,
|
|
||||||
)
|
|
||||||
self._dc_node.add_handler(
|
|
||||||
dronecan.uavcan.equipment.gnss.Fix2,
|
|
||||||
self._on_fix2,
|
|
||||||
)
|
|
||||||
if self._publish_compass:
|
|
||||||
self._dc_node.add_handler(
|
|
||||||
dronecan.uavcan.equipment.ahrs.MagneticFieldStrength,
|
|
||||||
self._on_mag,
|
|
||||||
)
|
|
||||||
self.get_logger().info(
|
|
||||||
f'DroneCAN node online on {self._iface}'
|
|
||||||
)
|
|
||||||
while rclpy.ok():
|
|
||||||
self._dc_node.spin(timeout=0.1)
|
|
||||||
except Exception as exc:
|
|
||||||
self.get_logger().error(f'DroneCAN spin error: {exc}')
|
|
||||||
|
|
||||||
# ── Message handlers ──────────────────────────────────────────────────────
|
|
||||||
|
|
||||||
def _on_fix2(self, event) -> None:
|
|
||||||
msg = event.message
|
|
||||||
now = self.get_clock().now().to_msg()
|
|
||||||
|
|
||||||
fix_type = int(msg.fix_type)
|
|
||||||
nav_status, rtk_label = _FIX_MAP.get(
|
|
||||||
fix_type, (NavSatStatus.STATUS_NO_FIX, 'UNKNOWN')
|
|
||||||
)
|
|
||||||
|
|
||||||
# NavSatFix
|
|
||||||
fix = NavSatFix()
|
|
||||||
fix.header.stamp = now
|
|
||||||
fix.header.frame_id = 'gps'
|
|
||||||
fix.status.status = nav_status
|
|
||||||
fix.status.service = NavSatStatus.SERVICE_GPS
|
|
||||||
|
|
||||||
fix.latitude = math.degrees(msg.latitude_deg_1e8 * 1e-8)
|
|
||||||
fix.longitude = math.degrees(msg.longitude_deg_1e8 * 1e-8)
|
|
||||||
fix.altitude = msg.height_msl_mm * 1e-3 # mm → m
|
|
||||||
|
|
||||||
# Covariance from position_covariance if available, else diagonal guess
|
|
||||||
if hasattr(msg, 'position_covariance') and len(msg.position_covariance) >= 9:
|
|
||||||
fix.position_covariance = list(msg.position_covariance)
|
|
||||||
fix.position_covariance_type = NavSatFix.COVARIANCE_TYPE_FULL
|
|
||||||
else:
|
|
||||||
h_var = (msg.horizontal_pos_accuracy_m_1e2 * 1e-2) ** 2 \
|
|
||||||
if hasattr(msg, 'horizontal_pos_accuracy_m_1e2') else 4.0
|
|
||||||
v_var = (msg.vertical_pos_accuracy_m_1e2 * 1e-2) ** 2 \
|
|
||||||
if hasattr(msg, 'vertical_pos_accuracy_m_1e2') else 4.0
|
|
||||||
fix.position_covariance = [
|
|
||||||
h_var, 0.0, 0.0,
|
|
||||||
0.0, h_var, 0.0,
|
|
||||||
0.0, 0.0, v_var,
|
|
||||||
]
|
|
||||||
fix.position_covariance_type = NavSatFix.COVARIANCE_TYPE_DIAGONAL_KNOWN
|
|
||||||
|
|
||||||
self._fix_pub.publish(fix)
|
|
||||||
|
|
||||||
# TwistStamped velocity
|
|
||||||
if hasattr(msg, 'ned_velocity'):
|
|
||||||
vel = TwistStamped()
|
|
||||||
vel.header.stamp = now
|
|
||||||
vel.header.frame_id = 'gps'
|
|
||||||
vel.twist.linear.x = float(msg.ned_velocity[0]) # North m/s
|
|
||||||
vel.twist.linear.y = float(msg.ned_velocity[1]) # East m/s
|
|
||||||
vel.twist.linear.z = float(msg.ned_velocity[2]) # Down m/s (ROS: up+)
|
|
||||||
self._vel_pub.publish(vel)
|
|
||||||
|
|
||||||
# RTK status string
|
|
||||||
rtk_msg = String()
|
|
||||||
rtk_msg.data = rtk_label
|
|
||||||
self._rtk_pub.publish(rtk_msg)
|
|
||||||
|
|
||||||
self.get_logger().debug(
|
|
||||||
f'Fix2: {fix.latitude:.6f},{fix.longitude:.6f} '
|
|
||||||
f'alt={fix.altitude:.1f}m status={rtk_label}'
|
|
||||||
)
|
|
||||||
|
|
||||||
def _on_mag(self, event) -> None:
|
|
||||||
# Compass data logged; extend to publish /imu/mag if needed
|
|
||||||
msg = event.message
|
|
||||||
self.get_logger().debug(
|
|
||||||
f'Mag: {msg.magnetic_field_ga[0]:.3f} '
|
|
||||||
f'{msg.magnetic_field_ga[1]:.3f} '
|
|
||||||
f'{msg.magnetic_field_ga[2]:.3f} Ga'
|
|
||||||
)
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None) -> None:
|
|
||||||
rclpy.init(args=args)
|
|
||||||
node = DroneCanGpsNode()
|
|
||||||
try:
|
|
||||||
rclpy.spin(node)
|
|
||||||
except KeyboardInterrupt:
|
|
||||||
pass
|
|
||||||
finally:
|
|
||||||
node.destroy_node()
|
|
||||||
rclpy.shutdown()
|
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
|
||||||
main()
|
|
||||||
@ -1,18 +0,0 @@
|
|||||||
# ntrip_params.yaml — NTRIP client configuration for Here4 RTK corrections
|
|
||||||
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
#
|
|
||||||
# Override at launch:
|
|
||||||
# ros2 launch saltybot_dronecan_gps here4_gps.launch.py \
|
|
||||||
# ntrip_mount:=MYBASE ntrip_user:=user ntrip_password:=pass
|
|
||||||
|
|
||||||
ntrip_client:
|
|
||||||
ros__parameters:
|
|
||||||
ntrip_caster: "rtk2go.com"
|
|
||||||
ntrip_port: 2101
|
|
||||||
ntrip_mount: "" # REQUIRED — set your mount point
|
|
||||||
ntrip_user: "" # empty = anonymous (rtk2go requires email)
|
|
||||||
ntrip_password: ""
|
|
||||||
can_interface: "can0"
|
|
||||||
can_bitrate: 1000000
|
|
||||||
can_node_id: 126 # DroneCAN local node ID (NTRIP node)
|
|
||||||
reconnect_delay: 5.0 # seconds between reconnect attempts
|
|
||||||
@ -1,32 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
|
||||||
<package format="3">
|
|
||||||
<name>saltybot_ntrip_client</name>
|
|
||||||
<version>0.1.0</version>
|
|
||||||
<description>
|
|
||||||
NTRIP client for RTK corrections.
|
|
||||||
Connects to an NTRIP caster (default: rtk2go.com:2101), receives RTCM3
|
|
||||||
correction data, and forwards it to the Here4 via DroneCAN
|
|
||||||
(uavcan.equipment.gnss.RTCMStream) on the CAN bus.
|
|
||||||
Reconnects automatically on disconnect.
|
|
||||||
Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
</description>
|
|
||||||
<maintainer email="seb@vayrette.com">Sebastien Vayrette</maintainer>
|
|
||||||
<license>MIT</license>
|
|
||||||
|
|
||||||
<buildtool_depend>ament_python</buildtool_depend>
|
|
||||||
|
|
||||||
<depend>rclpy</depend>
|
|
||||||
<depend>std_msgs</depend>
|
|
||||||
|
|
||||||
<exec_depend>python3-pip</exec_depend>
|
|
||||||
|
|
||||||
<test_depend>ament_copyright</test_depend>
|
|
||||||
<test_depend>ament_flake8</test_depend>
|
|
||||||
<test_depend>ament_pep257</test_depend>
|
|
||||||
<test_depend>python3-pytest</test_depend>
|
|
||||||
|
|
||||||
<export>
|
|
||||||
<build_type>ament_python</build_type>
|
|
||||||
</export>
|
|
||||||
</package>
|
|
||||||
@ -1 +0,0 @@
|
|||||||
saltybot_ntrip_client
|
|
||||||
@ -1,207 +0,0 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
"""
|
|
||||||
ntrip_client_node.py — NTRIP client for Here4 RTK corrections
|
|
||||||
Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/725
|
|
||||||
|
|
||||||
Connects to an NTRIP caster (default: rtk2go.com:2101), streams RTCM3
|
|
||||||
correction data, and forwards it to the Here4 GPS via DroneCAN
|
|
||||||
(uavcan.equipment.gnss.RTCMStream) on the CAN bus.
|
|
||||||
|
|
||||||
Publishes:
|
|
||||||
/ntrip/status std_msgs/String — CONNECTED / DISCONNECTED / ERROR:<reason>
|
|
||||||
|
|
||||||
Parameters:
|
|
||||||
ntrip_caster (str) rtk2go.com
|
|
||||||
ntrip_port (int) 2101
|
|
||||||
ntrip_mount (str) '' — required, e.g. 'RTCM3_GENERIC'
|
|
||||||
ntrip_user (str) '' — leave empty for anonymous casters
|
|
||||||
ntrip_password (str) ''
|
|
||||||
can_interface (str) can0
|
|
||||||
can_bitrate (int) 1000000
|
|
||||||
can_node_id (int) 126 — DroneCAN local node ID for NTRIP node
|
|
||||||
reconnect_delay (float) 5.0 — seconds between reconnect attempts
|
|
||||||
"""
|
|
||||||
|
|
||||||
import base64
|
|
||||||
import socket
|
|
||||||
import threading
|
|
||||||
import time
|
|
||||||
|
|
||||||
import rclpy
|
|
||||||
from rclpy.node import Node
|
|
||||||
from std_msgs.msg import String
|
|
||||||
|
|
||||||
try:
|
|
||||||
import dronecan
|
|
||||||
except ImportError:
|
|
||||||
dronecan = None
|
|
||||||
|
|
||||||
_NTRIP_AGENT = 'saltybot-ntrip/1.0'
|
|
||||||
_RTCM_CHUNK = 512 # bytes per DroneCAN RTCMStream message (max 128 per frame)
|
|
||||||
_RECV_BUF = 4096
|
|
||||||
|
|
||||||
|
|
||||||
class NtripClientNode(Node):
|
|
||||||
def __init__(self) -> None:
|
|
||||||
super().__init__('ntrip_client')
|
|
||||||
|
|
||||||
self.declare_parameter('ntrip_caster', 'rtk2go.com')
|
|
||||||
self.declare_parameter('ntrip_port', 2101)
|
|
||||||
self.declare_parameter('ntrip_mount', '')
|
|
||||||
self.declare_parameter('ntrip_user', '')
|
|
||||||
self.declare_parameter('ntrip_password', '')
|
|
||||||
self.declare_parameter('can_interface', 'can0')
|
|
||||||
self.declare_parameter('can_bitrate', 1000000)
|
|
||||||
self.declare_parameter('can_node_id', 126)
|
|
||||||
self.declare_parameter('reconnect_delay', 5.0)
|
|
||||||
|
|
||||||
self._caster = self.get_parameter('ntrip_caster').value
|
|
||||||
self._port = self.get_parameter('ntrip_port').value
|
|
||||||
self._mount = self.get_parameter('ntrip_mount').value
|
|
||||||
self._user = self.get_parameter('ntrip_user').value
|
|
||||||
self._password = self.get_parameter('ntrip_password').value
|
|
||||||
self._iface = self.get_parameter('can_interface').value
|
|
||||||
self._bitrate = self.get_parameter('can_bitrate').value
|
|
||||||
self._node_id = self.get_parameter('can_node_id').value
|
|
||||||
self._reconnect_delay = self.get_parameter('reconnect_delay').value
|
|
||||||
|
|
||||||
self._status_pub = self.create_publisher(String, '/ntrip/status', 10)
|
|
||||||
|
|
||||||
if dronecan is None:
|
|
||||||
self.get_logger().error(
|
|
||||||
'python-dronecan not installed. Run: pip install python-dronecan'
|
|
||||||
)
|
|
||||||
self._publish_status('ERROR:dronecan_not_installed')
|
|
||||||
return
|
|
||||||
|
|
||||||
if not self._mount:
|
|
||||||
self.get_logger().error(
|
|
||||||
'ntrip_mount parameter is required (e.g. RTCM3_GENERIC)'
|
|
||||||
)
|
|
||||||
self._publish_status('ERROR:no_mount_point')
|
|
||||||
return
|
|
||||||
|
|
||||||
self._dc_node = dronecan.make_node(
|
|
||||||
self._iface,
|
|
||||||
node_id=self._node_id,
|
|
||||||
bitrate=self._bitrate,
|
|
||||||
)
|
|
||||||
|
|
||||||
self._stop_event = threading.Event()
|
|
||||||
self._thread = threading.Thread(
|
|
||||||
target=self._ntrip_loop, daemon=True
|
|
||||||
)
|
|
||||||
self._thread.start()
|
|
||||||
|
|
||||||
self.get_logger().info(
|
|
||||||
f'NTRIP client started — '
|
|
||||||
f'{self._caster}:{self._port}/{self._mount}'
|
|
||||||
)
|
|
||||||
|
|
||||||
# ── NTRIP loop (reconnects on any error) ──────────────────────────────────
|
|
||||||
|
|
||||||
def _ntrip_loop(self) -> None:
|
|
||||||
while not self._stop_event.is_set() and rclpy.ok():
|
|
||||||
try:
|
|
||||||
self._connect_and_stream()
|
|
||||||
except Exception as exc:
|
|
||||||
self.get_logger().warn(f'NTRIP disconnected: {exc}')
|
|
||||||
self._publish_status(f'DISCONNECTED')
|
|
||||||
if not self._stop_event.is_set() and rclpy.ok():
|
|
||||||
self.get_logger().info(
|
|
||||||
f'Reconnecting in {self._reconnect_delay}s…'
|
|
||||||
)
|
|
||||||
time.sleep(self._reconnect_delay)
|
|
||||||
|
|
||||||
def _connect_and_stream(self) -> None:
|
|
||||||
sock = socket.create_connection(
|
|
||||||
(self._caster, self._port), timeout=10.0
|
|
||||||
)
|
|
||||||
sock.settimeout(30.0)
|
|
||||||
|
|
||||||
# Send NTRIP HTTP/1.1 GET request
|
|
||||||
request = self._build_request()
|
|
||||||
sock.sendall(request.encode('ascii'))
|
|
||||||
|
|
||||||
# Read response header
|
|
||||||
header = b''
|
|
||||||
while b'\r\n\r\n' not in header:
|
|
||||||
chunk = sock.recv(256)
|
|
||||||
if not chunk:
|
|
||||||
raise ConnectionError('Connection closed during header read')
|
|
||||||
header += chunk
|
|
||||||
|
|
||||||
header_str = header.split(b'\r\n\r\n')[0].decode('ascii', errors='replace')
|
|
||||||
if 'ICY 200 OK' not in header_str and '200 OK' not in header_str:
|
|
||||||
raise ConnectionError(f'NTRIP rejected: {header_str[:120]}')
|
|
||||||
|
|
||||||
self.get_logger().info(
|
|
||||||
f'NTRIP connected to {self._caster}:{self._port}/{self._mount}'
|
|
||||||
)
|
|
||||||
self._publish_status('CONNECTED')
|
|
||||||
|
|
||||||
# Any trailing bytes after header are RTCM data
|
|
||||||
leftover = header.split(b'\r\n\r\n', 1)[1] if b'\r\n\r\n' in header else b''
|
|
||||||
if leftover:
|
|
||||||
self._forward_rtcm(leftover)
|
|
||||||
|
|
||||||
while not self._stop_event.is_set() and rclpy.ok():
|
|
||||||
data = sock.recv(_RECV_BUF)
|
|
||||||
if not data:
|
|
||||||
raise ConnectionError('NTRIP stream closed by server')
|
|
||||||
self._forward_rtcm(data)
|
|
||||||
|
|
||||||
def _build_request(self) -> str:
|
|
||||||
lines = [
|
|
||||||
f'GET /{self._mount} HTTP/1.1',
|
|
||||||
f'Host: {self._caster}:{self._port}',
|
|
||||||
f'User-Agent: {_NTRIP_AGENT}',
|
|
||||||
'Ntrip-Version: Ntrip/2.0',
|
|
||||||
'Connection: close',
|
|
||||||
]
|
|
||||||
if self._user:
|
|
||||||
creds = base64.b64encode(
|
|
||||||
f'{self._user}:{self._password}'.encode()
|
|
||||||
).decode()
|
|
||||||
lines.append(f'Authorization: Basic {creds}')
|
|
||||||
lines += ['', '']
|
|
||||||
return '\r\n'.join(lines)
|
|
||||||
|
|
||||||
# ── DroneCAN RTCMStream forwarding ────────────────────────────────────────
|
|
||||||
|
|
||||||
def _forward_rtcm(self, data: bytes) -> None:
|
|
||||||
"""Chunk RTCM data into DroneCAN RTCMStream messages."""
|
|
||||||
for i in range(0, len(data), _RTCM_CHUNK):
|
|
||||||
chunk = data[i:i + _RTCM_CHUNK]
|
|
||||||
try:
|
|
||||||
msg = dronecan.uavcan.equipment.gnss.RTCMStream()
|
|
||||||
msg.data = list(chunk)
|
|
||||||
self._dc_node.broadcast(msg)
|
|
||||||
self._dc_node.spin(timeout=0.0)
|
|
||||||
except Exception as exc:
|
|
||||||
self.get_logger().warn(f'DroneCAN send error: {exc}')
|
|
||||||
|
|
||||||
def _publish_status(self, status: str) -> None:
|
|
||||||
msg = String()
|
|
||||||
msg.data = status
|
|
||||||
self._status_pub.publish(msg)
|
|
||||||
|
|
||||||
def destroy_node(self) -> None:
|
|
||||||
self._stop_event.set()
|
|
||||||
super().destroy_node()
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None) -> None:
|
|
||||||
rclpy.init(args=args)
|
|
||||||
node = NtripClientNode()
|
|
||||||
try:
|
|
||||||
rclpy.spin(node)
|
|
||||||
except KeyboardInterrupt:
|
|
||||||
pass
|
|
||||||
finally:
|
|
||||||
node.destroy_node()
|
|
||||||
rclpy.shutdown()
|
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
|
||||||
main()
|
|
||||||
@ -1,4 +0,0 @@
|
|||||||
[develop]
|
|
||||||
script_dir=$base/lib/saltybot_ntrip_client
|
|
||||||
[install]
|
|
||||||
install_scripts=$base/lib/saltybot_ntrip_client
|
|
||||||
@ -1,32 +0,0 @@
|
|||||||
from setuptools import find_packages, setup
|
|
||||||
import os
|
|
||||||
from glob import glob
|
|
||||||
|
|
||||||
package_name = 'saltybot_ntrip_client'
|
|
||||||
|
|
||||||
setup(
|
|
||||||
name=package_name,
|
|
||||||
version='0.1.0',
|
|
||||||
packages=find_packages(exclude=['test']),
|
|
||||||
data_files=[
|
|
||||||
('share/ament_index/resource_index/packages',
|
|
||||||
['resource/' + package_name]),
|
|
||||||
('share/' + package_name, ['package.xml']),
|
|
||||||
(os.path.join('share', package_name, 'launch'),
|
|
||||||
glob('launch/*.py')),
|
|
||||||
(os.path.join('share', package_name, 'config'),
|
|
||||||
glob('config/*.yaml')),
|
|
||||||
],
|
|
||||||
install_requires=['setuptools'],
|
|
||||||
zip_safe=True,
|
|
||||||
maintainer='Sebastien Vayrette',
|
|
||||||
maintainer_email='seb@vayrette.com',
|
|
||||||
description='NTRIP client — RTCM3 corrections via DroneCAN to Here4',
|
|
||||||
license='MIT',
|
|
||||||
tests_require=['pytest'],
|
|
||||||
entry_points={
|
|
||||||
'console_scripts': [
|
|
||||||
'ntrip_client_node = saltybot_ntrip_client.ntrip_client_node:main',
|
|
||||||
],
|
|
||||||
},
|
|
||||||
)
|
|
||||||
@ -1,29 +1,22 @@
|
|||||||
# outdoor_nav_params.yaml — Outdoor navigation configuration for SaltyBot
|
# outdoor_nav_params.yaml — Outdoor navigation configuration for SaltyBot
|
||||||
#
|
#
|
||||||
# Hardware: Jetson Orin Nano Super / SIM7600X cellular GPS (±2.5 m CEP)
|
# Hardware: Jetson Orin Nano Super / SIM7600X cellular GPS (±2.5 m CEP)
|
||||||
# RTK (active): CubePilot Here4 → ±2 cm CEP via DroneCAN (Issue #725)
|
# RTK upgrade: u-blox ZED-F9P → ±2 cm CEP (set use_rtk: true when installed)
|
||||||
# - Connected via CANable 2.0 (SocketCAN can0) at 1 Mbps
|
|
||||||
# - RTK corrections from NTRIP caster via saltybot_ntrip_client
|
|
||||||
# - Launch: docker compose up -d here4-gps
|
|
||||||
# (set NTRIP_MOUNT / NTRIP_USER / NTRIP_PASSWORD env vars)
|
|
||||||
#
|
#
|
||||||
# ── GPS quality notes ────────────────────────────────────────────────────────
|
# ── GPS quality notes ────────────────────────────────────────────────────────
|
||||||
# SIM7600X reports STATUS_FIX (0) in open sky, STATUS_NO_FIX (-1) indoors.
|
# SIM7600X reports STATUS_FIX (0) in open sky, STATUS_NO_FIX (-1) indoors.
|
||||||
# Here4 DroneCAN fix_type mapping (saltybot_dronecan_gps):
|
# RTK ZED-F9P reports STATUS_GBAS_FIX (2) when corrections received.
|
||||||
# 5 = RTK_FLOAT → STATUS_GBAS_FIX (2) — sub-metre
|
|
||||||
# 6 = RTK_FIXED → STATUS_GBAS_FIX (2) — ±2 cm (best)
|
|
||||||
# Monitor: ros2 topic echo /gps/rtk_status
|
|
||||||
# Goal tolerance automatically tightens from 2.0m (cellular) to 0.3m (RTK).
|
# Goal tolerance automatically tightens from 2.0m (cellular) to 0.3m (RTK).
|
||||||
#
|
#
|
||||||
# ── Here4 setup procedure ───────────────────────────────────────────────────
|
# ── RTK upgrade procedure ────────────────────────────────────────────────────
|
||||||
# 1. can_setup.sh up dronecan # bring up can0 at 1Mbps
|
# 1. Connect ZED-F9P to /dev/ttyTHS0 (Orin 40-pin UART, pins 8/10)
|
||||||
# 2. Set NTRIP_MOUNT, NTRIP_USER, NTRIP_PASSWORD in .env
|
# 2. Set NTRIP credentials in rtk_gps.launch.py
|
||||||
# 3. docker compose up -d here4-gps
|
# 3. Run: ros2 launch saltybot_outdoor rtk_gps.launch.py
|
||||||
# 4. Verify: ros2 topic echo /gps/rtk_status → RTK_FIXED
|
# 4. Verify: ros2 topic echo /gps/fix | grep status
|
||||||
# 5. saltybot-outdoor: set use_rtk:=true in docker-compose.yml
|
# → status.status == 2 (STATUS_GBAS_FIX) = RTK fixed
|
||||||
#
|
#
|
||||||
# References:
|
# References:
|
||||||
# Here4 manual: https://docs.cubepilot.org/user-guides/here-4/here-4-manual
|
# SparkFun RTK Express: https://docs.sparkfun.com/SparkFun_RTK_Everywhere_Firmware/
|
||||||
# NTRIP caster list: https://rtk2go.com/sample-map/
|
# NTRIP caster list: https://rtk2go.com/sample-map/
|
||||||
# ─────────────────────────────────────────────────────────────────────────────
|
# ─────────────────────────────────────────────────────────────────────────────
|
||||||
|
|
||||||
@ -103,26 +96,3 @@ global_costmap:
|
|||||||
inflation_radius: 0.50
|
inflation_radius: 0.50
|
||||||
obstacle_layer:
|
obstacle_layer:
|
||||||
observation_sources: scan surround_cameras
|
observation_sources: scan surround_cameras
|
||||||
|
|
||||||
# ── Here4 RTK GPS configuration (Issue #725) ────────────────────────────────
|
|
||||||
# Active when here4-gps docker service is running.
|
|
||||||
# The dronecan_gps node publishes on the same /gps/fix topic as SIM7600X,
|
|
||||||
# so gps_waypoint_follower picks up RTK automatically.
|
|
||||||
# Set use_rtk:=true in saltybot-outdoor docker command to tighten tolerances.
|
|
||||||
here4_gps:
|
|
||||||
ros__parameters:
|
|
||||||
# CAN bus — must match can_setup.sh dronecan mode and docker-compose device
|
|
||||||
can_interface: "can0"
|
|
||||||
can_bitrate: 1000000 # 1 Mbps — Here4 DroneCAN default
|
|
||||||
# DroneCAN node IDs (must be unique on bus; VESCs use 61 and 79)
|
|
||||||
gps_node_id: 127
|
|
||||||
ntrip_node_id: 126
|
|
||||||
# NTRIP — override via env vars NTRIP_MOUNT / NTRIP_USER / NTRIP_PASSWORD
|
|
||||||
ntrip_caster: "rtk2go.com"
|
|
||||||
ntrip_port: 2101
|
|
||||||
ntrip_mount: "" # set your mount point
|
|
||||||
ntrip_user: "" # rtk2go.com requires a valid email address
|
|
||||||
ntrip_password: ""
|
|
||||||
reconnect_delay: 5.0 # seconds between NTRIP reconnect attempts
|
|
||||||
# RTK goal tolerance — applied by gps_waypoint_follower when use_rtk:=true
|
|
||||||
goal_tolerance_xy_rtk: 0.3 # metres (vs 2.0m cellular)
|
|
||||||
|
|||||||
@ -1,36 +1,22 @@
|
|||||||
#!/usr/bin/env bash
|
#!/usr/bin/env bash
|
||||||
# can_setup.sh — Bring up CANable 2.0 (gs_usb) as can0
|
# can_setup.sh — Bring up CANable 2.0 (gs_usb) as can0 at 500 kbps
|
||||||
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
||||||
#
|
#
|
||||||
# Usage:
|
# Usage:
|
||||||
# sudo ./can_setup.sh # bring up (default: 500kbps for VESC)
|
# sudo ./can_setup.sh # bring up
|
||||||
# sudo ./can_setup.sh up dronecan # bring up at 1Mbps for Here4 DroneCAN
|
# sudo ./can_setup.sh down # bring down
|
||||||
# sudo ./can_setup.sh down
|
|
||||||
# sudo ./can_setup.sh verify # candump one-shot check (Ctrl-C to stop)
|
# sudo ./can_setup.sh verify # candump one-shot check (Ctrl-C to stop)
|
||||||
#
|
#
|
||||||
# Bitrate modes:
|
# VESCs on bus: CAN ID 61 (0x3D) and CAN ID 79 (0x4F), 500 kbps
|
||||||
# default / vesc — 500 kbps (VESC IDs 0x3D/0x4F)
|
|
||||||
# dronecan / here4 — 1000 kbps (CubePilot Here4 RTK GPS, DroneCAN default)
|
|
||||||
#
|
|
||||||
# CAN_BITRATE env var overrides both modes.
|
|
||||||
set -euo pipefail
|
set -euo pipefail
|
||||||
|
|
||||||
IFACE="${CAN_IFACE:-can0}"
|
IFACE="${CAN_IFACE:-can0}"
|
||||||
|
BITRATE="${CAN_BITRATE:-500000}"
|
||||||
|
|
||||||
log() { echo "[can_setup] $*"; }
|
log() { echo "[can_setup] $*"; }
|
||||||
die() { echo "[can_setup] ERROR: $*" >&2; exit 1; }
|
die() { echo "[can_setup] ERROR: $*" >&2; exit 1; }
|
||||||
|
|
||||||
cmd="${1:-up}"
|
cmd="${1:-up}"
|
||||||
mode="${2:-vesc}"
|
|
||||||
|
|
||||||
# Resolve bitrate: env var wins, then mode keyword, then 500k default
|
|
||||||
if [[ -n "${CAN_BITRATE:-}" ]]; then
|
|
||||||
BITRATE="$CAN_BITRATE"
|
|
||||||
elif [[ "$mode" == "dronecan" || "$mode" == "here4" ]]; then
|
|
||||||
BITRATE=1000000
|
|
||||||
else
|
|
||||||
BITRATE=500000
|
|
||||||
fi
|
|
||||||
|
|
||||||
case "$cmd" in
|
case "$cmd" in
|
||||||
up)
|
up)
|
||||||
@ -39,7 +25,7 @@ case "$cmd" in
|
|||||||
die "$IFACE not found — is CANable 2.0 plugged in and gs_usb loaded?"
|
die "$IFACE not found — is CANable 2.0 plugged in and gs_usb loaded?"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
log "Bringing up $IFACE at ${BITRATE} bps (mode: ${mode})..."
|
log "Bringing up $IFACE at ${BITRATE} bps..."
|
||||||
ip link set "$IFACE" down 2>/dev/null || true
|
ip link set "$IFACE" down 2>/dev/null || true
|
||||||
ip link set "$IFACE" up type can bitrate "$BITRATE"
|
ip link set "$IFACE" up type can bitrate "$BITRATE"
|
||||||
ip link set "$IFACE" up
|
ip link set "$IFACE" up
|
||||||
@ -54,17 +40,13 @@ case "$cmd" in
|
|||||||
;;
|
;;
|
||||||
|
|
||||||
verify)
|
verify)
|
||||||
if [[ "$mode" == "dronecan" || "$mode" == "here4" ]]; then
|
|
||||||
log "Listening on $IFACE — expecting DroneCAN frames from Here4 GPS (1Mbps)"
|
|
||||||
else
|
|
||||||
log "Listening on $IFACE — expecting frames from VESC IDs 0x3D (61) and 0x4F (79)"
|
log "Listening on $IFACE — expecting frames from VESC IDs 0x3D (61) and 0x4F (79)"
|
||||||
fi
|
|
||||||
log "Press Ctrl-C to stop."
|
log "Press Ctrl-C to stop."
|
||||||
exec candump "$IFACE"
|
exec candump "$IFACE"
|
||||||
;;
|
;;
|
||||||
|
|
||||||
*)
|
*)
|
||||||
echo "Usage: $0 [up [vesc|dronecan]|down|verify [dronecan]]"
|
echo "Usage: $0 [up|down|verify]"
|
||||||
exit 1
|
exit 1
|
||||||
;;
|
;;
|
||||||
esac
|
esac
|
||||||
|
|||||||
@ -227,7 +227,7 @@ body {
|
|||||||
<div class="logo">⚡ SAUL-TEE TRACKER</div>
|
<div class="logo">⚡ SAUL-TEE TRACKER</div>
|
||||||
<div id="conn-bar">
|
<div id="conn-bar">
|
||||||
<div id="ros-dot" title="ROS Bridge"></div>
|
<div id="ros-dot" title="ROS Bridge"></div>
|
||||||
<input id="ws-input" type="text" value="" placeholder="ws://host:port" />
|
<input id="ws-input" type="text" value="ws://100.64.0.2:9090" placeholder="ws://host:port" />
|
||||||
<button class="hbtn" id="btn-connect">CONNECT</button>
|
<button class="hbtn" id="btn-connect">CONNECT</button>
|
||||||
<span id="conn-label">Not connected</span>
|
<span id="conn-label">Not connected</span>
|
||||||
</div>
|
</div>
|
||||||
@ -732,10 +732,7 @@ map.on('dragstart', () => {
|
|||||||
// ── Init ──────────────────────────────────────────────────────────────────────
|
// ── Init ──────────────────────────────────────────────────────────────────────
|
||||||
|
|
||||||
(function init() {
|
(function init() {
|
||||||
const defaultUrl = location.protocol === 'https:'
|
const saved = localStorage.getItem('saul_tee_ws_url') || 'ws://100.64.0.2:9090';
|
||||||
? 'wss://saul-t-mote.evthings.app/rosbridge'
|
|
||||||
: 'ws://100.64.0.2:9090';
|
|
||||||
const saved = localStorage.getItem('saul_tee_ws_url') || defaultUrl;
|
|
||||||
$('ws-input').value = saved;
|
$('ws-input').value = saved;
|
||||||
drawCompass(null);
|
drawCompass(null);
|
||||||
connectRos(saved);
|
connectRos(saved);
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user