GCS_MAVLink: send primary quat in ATTITUDE_QUATERNION
This commit is contained in:
parent
909decc5be
commit
ad89e9777c
@ -4648,7 +4648,7 @@ void GCS_MAVLINK::send_attitude_quaternion() const
|
||||
{
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
Quaternion quat;
|
||||
if (!ahrs.get_secondary_quaternion(quat)) {
|
||||
if (!ahrs.get_quaternion(quat)) {
|
||||
return;
|
||||
}
|
||||
const Vector3f omega = ahrs.get_gyro();
|
||||
|
Loading…
Reference in New Issue
Block a user