mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_ExternalAHRS_VectorNav: Move allocation to local scope
Move receive_buf to method scope allocation rather than class scope
This commit is contained in:
parent
b3961ec2eb
commit
3f00280628
@ -213,6 +213,7 @@ void VectorNav::update(void)
|
|||||||
send_packet2();
|
send_packet2();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
char receive_buf[50];
|
||||||
const ssize_t n = read_from_autopilot(&receive_buf[0], ARRAY_SIZE(receive_buf));
|
const ssize_t n = read_from_autopilot(&receive_buf[0], ARRAY_SIZE(receive_buf));
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
if (strncmp(receive_buf, "$VNRRG,01", 9) == 0) {
|
if (strncmp(receive_buf, "$VNRRG,01", 9) == 0) {
|
||||||
|
@ -45,8 +45,6 @@ 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
Block a user