From 63e894e7e12887b26a5223e6f6b8aee7a60746c2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 17 Feb 2019 15:53:15 +1100 Subject: [PATCH] AP_AHRS: rename set_orientation to update_orientation set_ should be reserved for setters --- libraries/AP_AHRS/AP_AHRS.cpp | 2 +- libraries/AP_AHRS/AP_AHRS.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 23af48c138..23ea69e341 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -214,7 +214,7 @@ void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_ } // Set the board mounting orientation, may be called while disarmed -void AP_AHRS::set_orientation() +void AP_AHRS::update_orientation() { const enum Rotation orientation = (enum Rotation)_board_orientation.get(); if (orientation != ROTATION_CUSTOM) { diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index a2f9e0f9ce..3b1e10520a 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -87,7 +87,7 @@ public: // init sets up INS board orientation virtual void init() { - set_orientation(); + update_orientation(); }; // Accessors @@ -145,7 +145,7 @@ public: void set_compass(Compass *compass) { _compass = compass; - set_orientation(); + update_orientation(); } const Compass* get_compass() const { @@ -162,7 +162,7 @@ public: // allow for runtime change of orientation // this makes initial config easier - void set_orientation(); + void update_orientation(); void set_airspeed(AP_Airspeed *airspeed) { _airspeed = airspeed;