A full-duplex communication bridge linking ESP32-based avionics nodes to a ROSĀ 2 network, using custom-framed packets with explicit CRC error checking and type-safe dispatch. Built for reliability and clarity across embedded and Linux domains.
graph TD
ESP32[ESP32<br/>AvionicsāCOTS] -->|UART 115āÆ200| Pi5
Pi5[RaspberryĀ PiĀ 5<br/>ROSĀ 2 Foxy] -->|Ethernet| Mission[GroundĀ Station ROSĀ 2]
subgraph Pi5
CoscoNode[C++ node<br/>avionics_costco] -->|Publishes| Topics[(/mass<br/>/dust<br/>/servo_resp)]
PySensors[Python node<br/>python_node] -->|Publishes| /bms & /four_in_one
end
- Framing: Every packet begins with two fixed sync bytes:
0xA5, 0x5A(seeSerialProtocol.hpp). - Length and ID: 16-bit little-endian payload length, followed by a single-byte ID.
- CRC: CRC16 (X25/Modbus) is computed over the whole frame (see CRC routines in
SerialProtocol.hppandSPISlaveProtocol.hpp). - Static Buffering: Both transmission and receive buffers are fixed at compile time via templates; no use of dynamic allocation.
Code excerpt:
template <std::size_t MaxPayload>
class SerialProtocol {
public:
struct Frame {
uint8_t id; // Packet ID (router key)
uint16_t length; // Payload size, HAS TO BE less than MaxPayload (def above)
std::array<uint8_t, MaxPayload> payload; // Raw payload bytes
};
/* With this you can plug in any Arduino Stream (HardwareSerial, Wire, ā¦) which I find very cool and also very flexible */
explicit SerialProtocol(Stream &stream) : s_(stream) {}
/****************************** Send ******************************
* @brief Push an already-formed payload onto the wire.
* @param id: application-level packet identification,these are definied in lib>Packets>packet_id.hpp
* @param payload: raw bytes to send
* @param len: it's in the name, length of packet(len ℠1, ⤠MaxPayload)
*
* Safety guards:
* ā oversized or zero-length payloads are silently dropped.
* ā send() is synchronous; call from a low-duty loop or wrap
* it in a task if you need async.
* +------------+------------+----------------+----------+----------------+---------+
* | 0xA5 (STX) | 0x5A | uint16 len | uint8 id | payload[len-1] | CRC16 |
* +------------+------------+----------------+----------+----------------+---------+
* - len counts *id + payload* (so min len=1). CRC is X25/Modbus (poly 0xA001).
*/
void send(uint8_t id, const void *payload, uint16_t len)- Self-Synchronization: Parser resets on CRC or length error, or if sync bytes lost, ensuring no state is carried between corrupted packets.
- Endian & Packing: All multi-byte fields are stored little-endian and structs are
#pragma pack(1)or static_assert'ed for padding.
- Parsing is performed as a deterministic FSM. Each byte advances a single state and there is no heap use.
// SerialProtocol.hpp (excerpt)
switch (state_) {
/**** 0xA5 hunt ****/
case State::Stx1:
if (b == kStx1) state_ = State::Stx2;
break;
/**** 0x5A confirmation ****/
case State::Stx2:
state_ = (b == kStx2) ? State::LenLo : State::Stx1;
break;
/**** length low byte ****/
case State::LenLo:
len_ = b;
state_ = State::LenHi;
break;
/**** length high byte ****/
case State::LenHi:
len_ |= static_cast<uint16_t>(b) << 8;
// sanity check
if (len_ == 0 || len_ > MaxPayload + 1) { reset(); break; }
bytes_ = 0; // new payload counter
state_ = State::Id;
break;
/**** packet ID ****/
case State::Id:
frame_.id = b;
bytes_ = 0;
state_ = (len_ == 1) ? State::CrcLo : State::Payload;
break;
/**** payload stream ****/
case State::Payload:
frame_.payload[bytes_++] = b;
if (bytes_ == len_ - 1) state_ = State::CrcLo;
break;
/**** CRC16 LSB ****/
case State::CrcLo:
crcRead_ = b;
state_ = State::CrcHi;
break;
/**** CRC16 MSB & verdict ****/
case State::CrcHi:
crcRead_ |= static_cast<uint16_t>(b) << 8;
if (crcRead_ == crc16(frame_.id, frame_.payload.data(), len_ - 1)) {
frame_.length = len_ - 1; // strip ID
reset(); // ready for next frame
return true; // success!
}
/* CRC mismatch ā drop frame and resync */
reset();
break;
}
return false; // frame not yet finished
}- Overflow protection: Parser enforces
MaxPayloadat compile time; oversize packets are rejected before processing. - Buffer boundaries: All index math is explicit and protected from wrap-around.
- Static Dispatch:
Cosco.cpproutes frames via a switch onframe.id. - Payload Extraction: Type extraction uses
reinterpret_castwith compile-time static asserts for field width and alignment, guaranteeing no accidental struct drift.
// Cosco.cpp (excerpt)
template<class FrameT>
static Change handleFrame(const FrameT& f, Servo_Driver* cam, Servo_Driver* drill) {
switch (f.id) {
case ServoCam_ID:
if (f.length == sizeof(ServoRequest)) {
const auto& req = *reinterpret_cast<const ServoRequest*>(f.payload.data());
cam->set_request(req);
cam->handle_servo();
}
break;
case ServoDrill_ID:
if (f.length == sizeof(ServoRequest)) {
const auto& req = *reinterpret_cast<const ServoRequest*>(f.payload.data());
drill->set_request(req);
drill->handle_servo();
}
break;
case .........
}
Change Cosco::receive(Servo_Driver* cam, Servo_Driver* drill) {
Change spiChange = serviceSpi(cam, drill);
if (spiChange.id) return spiChange;
while (Serial.available()) {
if (uartProto.processByte((uint8_t)Serial.read())) {
Change c = handleFrame(uartProto.frame(), cam, drill);
if (c.id) return c;
}
}
return { 0, 0, 0 };
}- No dynamic handler maps: Every possible packet ID is a compile-time case. Extension requires local edit only.
- Every packet struct is a simple C++ type, matching the wire exactly.
- Structs are used for both serialization on the micro and deserialization in the ROS2 bridge.
Example from packet_definition.hpp:
struct DustData {
uint16_t pm1_0_std;
uint16_t pm2_5_std;
uint16_t pm10_std;
// more fields as required
};- Cross-compilation: The same struct definitions are included and compiled in both embedded and ROS2 code, preventing drift.
- Publisher/Subscriber Mapping: Each packet is published or subscribed as a strongly-typed ROS 2 message via
rclcpp::Publisherandrclcpp::Subscription. - Conversion functions (like
toRosMsg) are simple, functional, and statically visible. - Node organization: The bridge node combines all wiring logic for translation in a single, easily auditable file.
- Buffer checks: Each protocol driver enforces space and index checks before enqueue/dequeue.
- CRC errors: If CRC fails, the packet is discarded and parser state is resetāno partial messages leak through.
- No heap use: All protocol memory is statically allocated and bounded at compile time.
- Build checks: There are static_asserts and clear inline comments to ensure structure size, buffer, and protocol field consistency at compile time.
# Build and flash firmware for the ESP32
pio run -e featheresp32
pio run -e featheresp32 -t upload
# Build and launch the bridge on the Pi
colcon build
. install/setup.bash
ros2 run broco broco_bridge_nodeTo add a new sensor, actuator, or ROS2 topic:
- Define the struct and ID in
packet_definition.hpp. - Add a
caseinCosco.cpp. - Add publisher/subscriber wiring in the ROS2 node.
No additional boilerplate or registration is required; the system is organized for low-cognitive-load modification.
This project provides a custom Docker container tailored for deterministic ROSĀ 2 execution and reproducible serial/network I/O.
The container is built from a minimal base image with all ROSĀ 2 Foxy dependencies, real-time kernel optimizations, and udev rules for low-latency access to /dev/ttyUSB* devices.
It supports both interactive development (mapping volumes and devices) and automated launch, ensuring that the bridge can run identically across any Linux host or CI system.
Network configuration and multicast routing for ROSĀ 2 DDS are pre-configured within the container, eliminating host-setup friction.
- Source code is modular: protocol drivers, packets, and ROS2 logic are separated.
- Inline documentation and compile-time assertions are present for every protocol-critical detail.
- No implicit behaviors; all transitions and error checks are explicit.
This bridge provides a maintainable, robust, and efficient solution for reliable communications between embedded avionics and ROSĀ 2 networks. The design ensures protocol safety, extensibility, and clear system boundaries, supporting transparent development and reliable operation.
-
source src/docker_humble_jetson/attach.sh
a) If you are doing a clean build on a new docker you need to do this first otherwise the custom msg won't build. If you see an error message, it's normal and you can ignore it.
b) for clean build do: rm -rf build/ install/ log/
c) NEVER build in the src/ folder. The docker automatically goes into src/ so don't forget to do a cd .. to go back one. -
colcon build --packages-select custom_msg
a) build custom msg first -
colcon build
a) build the project -
source src/docker_humble_jetson/attach.sh
a) Source again for ROS. Not neceassrily needed but sometimes it is and just good practice to avoid debugging for no reason -
ros2 launch avionics_nexus launch.py
a) launch avionics pipeline. Also launches the python node.
b) This is a specific command for the current code. General syntax is: ros2 launch node_name launch_file -
docker exec -it elec_humble_desktop bash
a) If you want multiple terminals, allows you to attach them to the same docker. -
ros2 topic pub /EL/servo_req custom_msg/msg/ServoRequest "{id: 1, increment: 50.0, zero_in: false}"
a) simulate publisher message from CS to see if your system works b) can add a --once and a bunch of other things if you want, just google them. -
ros2 topic echo /EL/mass_topic
a) allows you to see what the message received by the RP from the avionics -
ros2 topic list
a) show all ros2 topics