Browse Source

AP_AHRS: rename set_orientation to update_orientation

set_ should be reserved for setters
mission-4.1.18
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
63e894e7e1
  1. 2
      libraries/AP_AHRS/AP_AHRS.cpp
  2. 6
      libraries/AP_AHRS/AP_AHRS.h

2
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_ @@ -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) {

6
libraries/AP_AHRS/AP_AHRS.h

@ -87,7 +87,7 @@ public: @@ -87,7 +87,7 @@ public:
// init sets up INS board orientation
virtual void init() {
set_orientation();
update_orientation();
};
// Accessors
@ -145,7 +145,7 @@ public: @@ -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: @@ -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;

Loading…
Cancel
Save