From c51eed1f2ab49a0a359fa697b1118d60dc1f55d3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Nov 2019 16:13:07 +1100 Subject: [PATCH] AP_Periph: use enum-class for RangeFinder Status --- Tools/AP_Periph/can.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 59a0f4f933..8a72c68b4b 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1310,21 +1310,21 @@ void AP_Periph_FW::can_rangefinder_update(void) } last_update_ms = now; rangefinder.update(); - RangeFinder::RangeFinder_Status status = rangefinder.status_orient(ROTATION_NONE); - if (status <= RangeFinder::RangeFinder_NoData) { + RangeFinder::Status status = rangefinder.status_orient(ROTATION_NONE); + if (status <= RangeFinder::Status::NoData) { // don't send any data return; } uint16_t dist_cm = rangefinder.distance_cm_orient(ROTATION_NONE); uavcan_equipment_range_sensor_Measurement pkt {}; switch (status) { - case RangeFinder::RangeFinder_OutOfRangeLow: + case RangeFinder::Status::OutOfRangeLow: pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE; break; - case RangeFinder::RangeFinder_OutOfRangeHigh: + case RangeFinder::Status::OutOfRangeHigh: pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; break; - case RangeFinder::RangeFinder_Good: + case RangeFinder::Status::Good: pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; break; default: