mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: make AHRS attitude member variables private
This commit is contained in:
parent
c4dc0ae101
commit
caf1e33f17
|
@ -5443,9 +5443,9 @@ void GCS_MAVLINK::send_attitude() const
|
|||
mavlink_msg_attitude_send(
|
||||
chan,
|
||||
AP_HAL::millis(),
|
||||
ahrs.roll,
|
||||
ahrs.pitch,
|
||||
ahrs.yaw,
|
||||
ahrs.get_roll(),
|
||||
ahrs.get_pitch(),
|
||||
ahrs.get_yaw(),
|
||||
omega.x,
|
||||
omega.y,
|
||||
omega.z);
|
||||
|
|
Loading…
Reference in New Issue