From bfb29ce22b80a48e275fa0c31ea5848ed6c43749 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 2 Mar 2013 00:00:37 +0900 Subject: [PATCH] Compass: remove virtual functions to save RAM --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 7 ------- libraries/AP_Compass/AP_Compass_HMC5843.h | 1 - libraries/AP_Compass/Compass.h | 20 ++++++++++---------- 3 files changed, 10 insertions(+), 18 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index f893a1a56b..68566a2f51 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -348,10 +348,3 @@ bool AP_Compass_HMC5843::read() return true; } - -// set orientation -void -AP_Compass_HMC5843::set_orientation(enum Rotation rotation) -{ - _orientation = rotation; -} diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.h b/libraries/AP_Compass/AP_Compass_HMC5843.h index d9aab89f88..05deb87b26 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.h +++ b/libraries/AP_Compass/AP_Compass_HMC5843.h @@ -73,7 +73,6 @@ public: bool init(void); bool read(void); void accumulate(void); - void set_orientation(enum Rotation rotation); }; #endif diff --git a/libraries/AP_Compass/Compass.h b/libraries/AP_Compass/Compass.h index 90fd2870e5..10e17a29c3 100644 --- a/libraries/AP_Compass/Compass.h +++ b/libraries/AP_Compass/Compass.h @@ -51,7 +51,7 @@ public: /// /// @returns heading in radians /// - virtual float calculate_heading(float roll, float pitch); + float calculate_heading(float roll, float pitch); /// Calculate the tilt-compensated heading_ variables. /// @@ -59,7 +59,7 @@ public: /// /// @returns heading in radians /// - virtual float calculate_heading(const Matrix3f &dcm_matrix); + float calculate_heading(const Matrix3f &dcm_matrix); /// Set the compass orientation matrix, used to correct for /// various compass mounting positions. @@ -67,26 +67,26 @@ public: /// @param rotation_matrix Rotation matrix to transform magnetometer readings /// to the body frame. /// - virtual void set_orientation(enum Rotation rotation); + void set_orientation(enum Rotation rotation); /// Sets the compass offset x/y/z values. /// /// @param offsets Offsets to the raw mag_ values. /// - virtual void set_offsets(const Vector3f &offsets); + void set_offsets(const Vector3f &offsets); /// Saves the current compass offset x/y/z values. /// /// This should be invoked periodically to save the offset values maintained by /// ::null_offsets. /// - virtual void save_offsets(); + void save_offsets(); /// Returns the current offset values /// /// @returns The current compass offsets. /// - virtual Vector3f &get_offsets(); + Vector3f &get_offsets(); /// Sets the initial location used to get declination /// @@ -118,7 +118,7 @@ public: /// /// @param radians Local field declination. /// - virtual void set_declination(float radians); + void set_declination(float radians); float get_declination(); // set overall board orientation @@ -130,7 +130,7 @@ public: /// /// @param offsets Offsets multiplied by the throttle value and added to the raw mag_ values. /// - virtual void set_motor_compensation(const Vector3f &motor_comp_factor); + void set_motor_compensation(const Vector3f &motor_comp_factor); /// Set new motor compensation factors as a vector /// @@ -146,13 +146,13 @@ public: /// /// This should be invoked periodically to save the offset values calculated by the motor compensation auto learning /// - virtual void save_motor_compensation(); + void save_motor_compensation(); /// Returns the current motor compensation offset values /// /// @returns The current compass offsets. /// - virtual Vector3f &get_motor_offsets() { return _motor_offset; } + Vector3f &get_motor_offsets() { return _motor_offset; } /// Set the throttle as a percentage from 0.0 to 1.0 /// @param thr_pct throttle expressed as a percentage from 0 to 1.0