From fb0ebf75caf9920d1f5b9f4ff7c62b7dcd1bc3a0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 Aug 2023 12:36:29 +1000 Subject: [PATCH] AP_RangeFinder: move rangefinder rotation default down into AP_Periph --- libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index ccd37c9955..34fc046004 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -2,12 +2,7 @@ #include "AP_RangeFinder.h" #ifndef AP_RANGEFINDER_DEFAULT_ORIENTATION -#ifndef HAL_BUILD_AP_PERIPH #define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_PITCH_270 -#else -// AP_Periph expects ROTATION_NONE -#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_NONE -#endif #endif // table of user settable parameters