From 1f0a6334258d1ae8d02102cc9bd374c6b5aacd7f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 17 Aug 2022 10:56:18 +0900 Subject: [PATCH] AP_Proximity: fixup handle_msg comment --- libraries/AP_Proximity/AP_Proximity.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity.h | 2 +- libraries/AP_Proximity/AP_Proximity_Backend.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 1015b6aeb1..a0fa739ac5 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -185,7 +185,7 @@ void AP_Proximity::init() drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance], params[instance]); break; #endif - } // switch (get_type(instance)) + } if (drivers[instance] != nullptr) { // we loaded a driver for this instance, so it must be @@ -310,7 +310,7 @@ bool AP_Proximity::get_object_angle_and_distance(uint8_t object_number, float& a return boundary.get_horizontal_object_angle_and_distance(object_number, angle_deg, distance); } -// handle mavlink DISTANCE_SENSOR messages +// handle mavlink messages void AP_Proximity::handle_msg(const mavlink_message_t &msg) { for (uint8_t i=0; i