Copter: use enum-class for RangeFinder Status

This commit is contained in:
Peter Barker 2019-11-01 16:13:55 +11:00 committed by Peter Barker
parent 11b372a986
commit dfc8349866
3 changed files with 7 additions and 7 deletions

View File

@ -42,7 +42,7 @@ void Copter::check_dynamic_flight(void)
moving = (motors->get_throttle() > 0.8f || ahrs.pitch_sensor < -1500);
}
if (!moving && rangefinder_state.enabled && rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) {
if (!moving && rangefinder_state.enabled && rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) {
// when we are more than 2m from the ground with good
// rangefinder lock consider it to be dynamic flight
moving = (rangefinder.distance_cm_orient(ROTATION_PITCH_270) > 200);

View File

@ -34,18 +34,18 @@ void Copter::landinggear_update()
// use rangefinder if available
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
case RangeFinder::RangeFinder_NotConnected:
case RangeFinder::RangeFinder_NoData:
case RangeFinder::Status::NotConnected:
case RangeFinder::Status::NoData:
// use altitude above home for non-functioning rangefinder
break;
case RangeFinder::RangeFinder_OutOfRangeLow:
case RangeFinder::Status::OutOfRangeLow:
// altitude is close to zero (gear should deploy)
height_cm = 0;
break;
case RangeFinder::RangeFinder_OutOfRangeHigh:
case RangeFinder::RangeFinder_Good:
case RangeFinder::Status::OutOfRangeHigh:
case RangeFinder::Status::Good:
// use last good reading
height_cm = rangefinder_state.alt_cm_filt.get();
break;

View File

@ -48,7 +48,7 @@ void Copter::read_rangefinder(void)
enum Rotation rf_orient = rngfnd[i].orientation;
// update health
rf_state.alt_healthy = ((rangefinder.status_orient(rf_orient) == RangeFinder::RangeFinder_Good) &&
rf_state.alt_healthy = ((rangefinder.status_orient(rf_orient) == RangeFinder::Status::Good) &&
(rangefinder.range_valid_count_orient(rf_orient) >= RANGEFINDER_HEALTH_MAX));
// tilt corrected but unfiltered, not glitch protected alt