mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_Vehicle: make AHRS attitude member variables private
This commit is contained in:
parent
7f43facb37
commit
1183328266
@ -879,8 +879,8 @@ void AP_Vehicle::publish_osd_info()
|
|||||||
|
|
||||||
void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
||||||
{
|
{
|
||||||
roll = ahrs.roll;
|
roll = ahrs.get_roll();
|
||||||
pitch = ahrs.pitch;
|
pitch = ahrs.get_pitch();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_INS_ACCELCAL_ENABLED
|
#if HAL_INS_ACCELCAL_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user