AP_Periph: check return of get_RelPosHeading

This commit is contained in:
Andrew Tridgell 2024-04-22 08:31:01 +10:00
parent fe42171268
commit 0eded27a9f
1 changed files with 2 additions and 2 deletions

View File

@ -295,8 +295,8 @@ void AP_Periph_FW::send_relposheading_msg() {
float relative_down_pos; float relative_down_pos;
float reported_heading_acc; float reported_heading_acc;
uint32_t curr_timestamp = 0; uint32_t curr_timestamp = 0;
gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc); if (!gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc) ||
if (last_relposheading_ms == curr_timestamp) { last_relposheading_ms == curr_timestamp) {
return; return;
} }
last_relposheading_ms = curr_timestamp; last_relposheading_ms = curr_timestamp;