mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: remove useless virtual qualifier
This commit is contained in:
parent
d87853d93e
commit
3b96794fb5
|
@ -391,10 +391,10 @@ public:
|
|||
}
|
||||
|
||||
// set trim
|
||||
virtual void set_trim(const Vector3f &new_trim);
|
||||
void set_trim(const Vector3f &new_trim);
|
||||
|
||||
// add_trim - adjust the roll and pitch trim up to a total of 10 degrees
|
||||
virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);
|
||||
void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);
|
||||
|
||||
// helper trig value accessors
|
||||
float cos_roll() const {
|
||||
|
|
Loading…
Reference in New Issue