AP_ExternalAHRS_VectorNav: Update VectorNav sim to respond to received commands

Aside from the RRG,1 call, the simulation should reply with exactly what was received as a receipt confirmation to allow the driver to proceed past init
This commit is contained in:
BLash 2024-07-16 00:48:01 -05:00 committed by Andrew Tridgell
parent 34031cc6b6
commit b3961ec2eb
2 changed files with 9 additions and 5 deletions

View File

@ -213,11 +213,13 @@ void VectorNav::update(void)
send_packet2();
}
// Strictly we should send this in responce to the request
// but sending it occasionally acheaves the same thing
if (now - last_type_us >= 1000000) {
last_type_us = now;
nmea_printf("$VNRRG,01,VN-300-SITL");
const ssize_t n = read_from_autopilot(&receive_buf[0], ARRAY_SIZE(receive_buf));
if (n > 0) {
if (strncmp(receive_buf, "$VNRRG,01", 9) == 0) {
nmea_printf("$VNRRG,01,VN-300-SITL");
} else {
nmea_printf("$%s", receive_buf);
}
}
}

View File

@ -45,6 +45,8 @@ private:
uint32_t last_pkt2_us;
uint32_t last_type_us;
char receive_buf[50];
void send_packet1();
void send_packet2();
void nmea_printf(const char *fmt, ...);