AP_DAL: minor review cleanups

This commit is contained in:
Andrew Tridgell 2020-11-09 19:49:27 +11:00
parent 790a5ffa38
commit 2a210549f9
3 changed files with 4 additions and 8 deletions

View File

@ -22,8 +22,7 @@ void AP_DAL_Baro::start_frame()
for (uint8_t i=0; i<_RBRH.num_instances; i++) {
log_RBRI &RBRI = _RBRI[i];
log_RBRI old = RBRI;
const uint32_t last_update_ms = baro.get_last_update(i);
RBRI.last_update_ms = last_update_ms;
RBRI.last_update_ms = baro.get_last_update(i);
RBRI.healthy = baro.healthy(i);
RBRI.altitude = baro.get_altitude(i);
WRITE_REPLAY_BLOCK_IFCHANGED(RBRI, _RBRI[i], old);

View File

@ -75,8 +75,5 @@ private:
uint8_t _primary_gyro;
void log_header(uint64_t time_us);
void log_instance(uint64_t time_us, uint8_t i);
void update_filtered(uint8_t i);
};

View File

@ -35,9 +35,8 @@ int16_t AP_DAL_RangeFinder::ground_clearance_cm_orient(enum Rotation orientation
int16_t AP_DAL_RangeFinder::max_distance_cm_orient(enum Rotation orientation) const
{
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone)
const auto *rangefinder = AP::rangefinder();
if (orientation != ROTATION_PITCH_270) {
const auto *rangefinder = AP::rangefinder();
// the EKF only asks for this from a specific orientation. Thankfully.
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return rangefinder->ground_clearance_cm_orient(orientation);
@ -54,8 +53,9 @@ void AP_DAL_RangeFinder::start_frame()
return;
}
// EKF only asks for this *down*.
const log_RRNH old = _RRNH;
// EKF only asks for this *down*.
_RRNH.ground_clearance_cm = rangefinder->ground_clearance_cm_orient(ROTATION_PITCH_270);
_RRNH.max_distance_cm = rangefinder->max_distance_cm_orient(ROTATION_PITCH_270);
_RRNH.backend_mask = 0;