mirror of https://github.com/ArduPilot/ardupilot
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:
parent
34031cc6b6
commit
b3961ec2eb
|
@ -213,11 +213,13 @@ void VectorNav::update(void)
|
||||||
send_packet2();
|
send_packet2();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Strictly we should send this in responce to the request
|
const ssize_t n = read_from_autopilot(&receive_buf[0], ARRAY_SIZE(receive_buf));
|
||||||
// but sending it occasionally acheaves the same thing
|
if (n > 0) {
|
||||||
if (now - last_type_us >= 1000000) {
|
if (strncmp(receive_buf, "$VNRRG,01", 9) == 0) {
|
||||||
last_type_us = now;
|
nmea_printf("$VNRRG,01,VN-300-SITL");
|
||||||
nmea_printf("$VNRRG,01,VN-300-SITL");
|
} else {
|
||||||
|
nmea_printf("$%s", receive_buf);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -45,6 +45,8 @@ private:
|
||||||
uint32_t last_pkt2_us;
|
uint32_t last_pkt2_us;
|
||||||
uint32_t last_type_us;
|
uint32_t last_type_us;
|
||||||
|
|
||||||
|
char receive_buf[50];
|
||||||
|
|
||||||
void send_packet1();
|
void send_packet1();
|
||||||
void send_packet2();
|
void send_packet2();
|
||||||
void nmea_printf(const char *fmt, ...);
|
void nmea_printf(const char *fmt, ...);
|
||||||
|
|
Loading…
Reference in New Issue