mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS_View: add method to get pitch trim and note on rotation
This commit is contained in:
parent
902b895aef
commit
04fdfea74a
@ -187,10 +187,14 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
// get current rotation
|
// get current rotation
|
||||||
|
// note that this may not be the rotation were actually using, see _pitch_trim_deg
|
||||||
enum Rotation get_rotation(void) const {
|
enum Rotation get_rotation(void) const {
|
||||||
return rotation;
|
return rotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get pitch trim (deg)
|
||||||
|
float get_pitch_trim() const { return _pitch_trim_deg; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const enum Rotation rotation;
|
const enum Rotation rotation;
|
||||||
AP_AHRS &ahrs;
|
AP_AHRS &ahrs;
|
||||||
|
Loading…
Reference in New Issue
Block a user