mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: save trim to eeprom when set_trim is called
This commit is contained in:
parent
0ab82f8c4e
commit
1f7614929f
|
@ -145,7 +145,7 @@ public:
|
|||
Vector3f get_trim() { return _trim; }
|
||||
|
||||
// set_trim
|
||||
virtual void set_trim(Vector3f new_trim) { _trim.set(new_trim); }
|
||||
virtual void set_trim(Vector3f new_trim) { _trim.set_and_save(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);
|
||||
|
|
Loading…
Reference in New Issue