Skip to content

Commit

Permalink
AP_RangeFinder: Move the flag setting location of has_data
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and peterbarker committed Sep 28, 2024
1 parent 637aec0 commit c05c520
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,6 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m)
reading_m = UINT16_VALUE(buffer[3], buffer[4]) * 0.01;
const uint8_t snr = buffer[5];

has_data = true;

#if AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS
const uint32_t now_ms = AP_HAL::millis();
if (malfunction_alert_prev != malfunction_alert && now_ms - malfunction_alert_last_send_ms >= 1000) {
Expand Down Expand Up @@ -102,6 +100,7 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m)
state.status = RangeFinder::Status::NoData;
}
} else {
has_data = true;
state.status = RangeFinder::Status::Good;
}
}
Expand Down

0 comments on commit c05c520

Please sign in to comment.