From a98d8131974beeeedec6b94415d248cbc47613b0 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Tue, 19 Nov 2019 15:10:45 +0800 Subject: [PATCH] Arducopter: Primary Compass is always serial# 0 --- ArduCopter/compassmot.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 8795e83f45..1955b73380 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -221,10 +221,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) mavlink_msg_compassmot_status_send(gcs_chan.get_chan(), channel_throttle->get_control_in(), current, - interference_pct[compass.get_primary()], - motor_compensation[compass.get_primary()].x, - motor_compensation[compass.get_primary()].y, - motor_compensation[compass.get_primary()].z); + interference_pct[0], + motor_compensation[0].x, + motor_compensation[0].y, + motor_compensation[0].z); } }