mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: added get_view_rotation()
This commit is contained in:
parent
63fcb804b3
commit
3f043dd933
|
@ -3058,6 +3058,13 @@ void AP_AHRS::set_alt_measurement_noise(float noise)
|
|||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
get the current views rotation, or ROTATION_NONE
|
||||
*/
|
||||
enum Rotation AP_AHRS::get_view_rotation(void) const
|
||||
{
|
||||
return _view?_view->get_rotation():ROTATION_NONE;
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
AP_AHRS *AP_AHRS::_singleton;
|
||||
|
|
|
@ -457,6 +457,9 @@ public:
|
|||
_vehicle_class = vclass;
|
||||
}
|
||||
|
||||
// get the views rotation, or ROTATION_NONE
|
||||
enum Rotation get_view_rotation(void) const;
|
||||
|
||||
protected:
|
||||
// optional view class
|
||||
AP_AHRS_View *_view;
|
||||
|
|
|
@ -185,6 +185,12 @@ public:
|
|||
int32_t pitch_sensor;
|
||||
int32_t yaw_sensor;
|
||||
|
||||
|
||||
// get current rotation
|
||||
enum Rotation get_rotation(void) const {
|
||||
return rotation;
|
||||
}
|
||||
|
||||
private:
|
||||
const enum Rotation rotation;
|
||||
AP_AHRS &ahrs;
|
||||
|
|
Loading…
Reference in New Issue