mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Module: make AHRS attitude member variables private
This commit is contained in:
parent
0275494042
commit
bcf6578d56
@ -165,9 +165,9 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS &ahrs)
|
|||||||
state.quat[2] = q[2];
|
state.quat[2] = q[2];
|
||||||
state.quat[3] = q[3];
|
state.quat[3] = q[3];
|
||||||
|
|
||||||
state.eulers[0] = ahrs.roll;
|
state.eulers[0] = ahrs.get_roll();
|
||||||
state.eulers[1] = ahrs.pitch;
|
state.eulers[1] = ahrs.get_pitch();
|
||||||
state.eulers[2] = ahrs.yaw;
|
state.eulers[2] = ahrs.get_yaw();
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (ahrs.get_origin(loc)) {
|
if (ahrs.get_origin(loc)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user