Adds saltybot_cellular ROS2 package for the Waveshare SIM7600X 4G HAT
(SIMCom SIM7600A-H) providing GPS telemetry, modem monitoring, and
MQTT relay over cellular for remote operation.
gps_driver_node:
- Opens /dev/ttyUSB2 (NMEA), optionally sends AT+CGPS=1 on /dev/ttyUSB0
- Parses GGA (position) + RMC (velocity) from any NMEA talker (GP/GN/GL/GA)
- Validates NMEA checksum before parsing
- Publishes /gps/fix (NavSatFix, covariance from HDOP × ±2.5m CEP)
- Publishes /gps/vel (TwistStamped, ENU vE/vN from course-over-ground)
- Publishes /diagnostics (fix quality, sat count, HDOP)
cellular_manager_node:
- Polls AT+CSQ, AT+CREG?, AT+COPS? every 5s over /dev/ttyUSB0
- Publishes /cellular/status (DiagnosticArray: rssi, network, connected)
- Publishes /cellular/rssi (Int32, dBm) and /cellular/connected (Bool)
- Auto-reconnect via nmcli or pppd when data link drops
mqtt_bridge_node:
- paho-mqtt client (graceful degradation if not installed)
- ROS2→MQTT QoS 0: /saltybot/imu, /gps/fix, /gps/vel, /uwb/ranges,
/person/target, /cellular/status
- MQTT→ROS2 QoS 1: saltybot/cmd→/saltybot/cmd, saltybot/estop→/saltybot/estop
- Per-topic rate limiting (imu:5Hz, gps:1Hz, person:2Hz) → <<50KB/s budget
- Optional TLS, configurable broker/port/prefix/auth
Deliverables:
saltybot_cellular/gps_driver_node.py — 402 lines
saltybot_cellular/cellular_manager_node.py — 362 lines
saltybot_cellular/mqtt_bridge_node.py — 317 lines
config/cellular_params.yaml — full config documented
launch/cellular.launch.py — all nodes, all params as args
test/test_cellular.py — 60 pytest tests, no ROS2
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
71 lines
3.7 KiB
YAML
71 lines
3.7 KiB
YAML
# cellular_params.yaml
|
||
# Configuration for saltybot_cellular package — SIM7600X 4G HAT.
|
||
#
|
||
# Run with:
|
||
# ros2 launch saltybot_cellular cellular.launch.py
|
||
#
|
||
# Hardware: Waveshare SIM7600X 4G HAT (SIMCom SIM7600A-H)
|
||
# /dev/ttyUSB0 — AT commands
|
||
# /dev/ttyUSB1 — PPP data (managed by NetworkManager/pppd, not ROS2)
|
||
# /dev/ttyUSB2 — NMEA GPS output
|
||
|
||
# ── GPS driver ─────────────────────────────────────────────────────────────────
|
||
# The GPS port streams NMEA sentences once AT+CGPS=1 is sent.
|
||
# If GPS is already running (e.g., from a previous session), set gps_init_enable: false.
|
||
|
||
gps_port: /dev/ttyUSB2 # NMEA output port
|
||
at_port: /dev/ttyUSB0 # AT command port (for CGPS=1 init)
|
||
baud_rate: 115200
|
||
publish_rate: 1.0 # Hz — GPS updates at 1 Hz max
|
||
frame_id: gps # Header frame_id for NavSatFix + TwistStamped
|
||
|
||
gps_init_enable: true # Send AT+CGPS=1 on startup
|
||
gps_init_cmd: AT+CGPS=1 # Command to start GNSS receiver
|
||
at_init_timeout: 3.0 # Seconds to wait for AT response
|
||
|
||
# GPS accuracy (used for NavSatFix covariance computation)
|
||
# SIM7600A-H spec: ±2.5m CEP (circular error probable) at HDOP=1
|
||
gps_accuracy: 2.5 # metres CEP at HDOP=1
|
||
|
||
# ── Cellular manager ───────────────────────────────────────────────────────────
|
||
# AT commands are polled to monitor signal quality and registration status.
|
||
# The data connection itself (4G LTE) is managed by the OS (NetworkManager or pppd).
|
||
|
||
poll_rate: 0.2 # Hz (poll every 5 seconds — avoid AT flooding)
|
||
at_timeout: 2.0 # Seconds per AT command
|
||
|
||
# Data connection management
|
||
# "nmcli": NetworkManager profile (recommended for Orin Nano running Ubuntu)
|
||
# "pppd": pppd service unit (systemctl restart pppd-cellular)
|
||
# "none": monitoring only, no auto-reconnect
|
||
connection_method: nmcli
|
||
nmcli_profile: saltybot-cellular # nmcli connection profile name
|
||
apn: "" # APN (set if NetworkManager needs it)
|
||
reconnect_interval: 30.0 # Seconds between reconnect attempts
|
||
|
||
# ── MQTT bridge ────────────────────────────────────────────────────────────────
|
||
# Relay telemetry to a remote MQTT broker over the cellular link.
|
||
# For home-lab deployment: run mosquitto on the Jetson or a cloud VM.
|
||
# For production: use TLS + authentication.
|
||
|
||
mqtt_broker: mqtt.saltylab.local # Broker hostname or IP
|
||
mqtt_port: 1883 # 1883 = plain, 8883 = TLS
|
||
mqtt_user: "" # Leave empty to disable auth
|
||
mqtt_password: ""
|
||
topic_prefix: saltybot # MQTT topic prefix (saltybot/gps/fix, etc.)
|
||
client_id: saltybot-jetson
|
||
keepalive: 60 # MQTT keepalive interval (seconds)
|
||
reconnect_delay: 5.0 # Seconds between MQTT reconnect attempts
|
||
|
||
# TLS (set mqtt_port: 8883 and provide CA cert path)
|
||
tls_enable: false
|
||
tls_ca_cert: "" # e.g. /etc/ssl/certs/mqtt-ca.crt
|
||
|
||
# Per-topic outbound rate limits (Hz). Keeps cellular bandwidth < 50 KB/s.
|
||
# At 1 Hz per topic × ~100 bytes/msg × 6 topics ≈ 600 bytes/s = 0.6 KB/s
|
||
imu_rate: 5.0 # Hz — /saltybot/imu → saltybot/imu
|
||
gps_rate: 1.0 # Hz — /gps/fix, /gps/vel
|
||
person_rate: 2.0 # Hz — /person/target
|
||
uwb_rate: 1.0 # Hz — /uwb/ranges
|
||
cellular_rate: 0.2 # Hz — /cellular/status (once per 5s)
|