Arducopter: Primary Compass is always serial# 0

This commit is contained in:
Siddharth Purohit 2019-11-19 15:10:45 +08:00 committed by Andrew Tridgell
parent de86342e93
commit a98d813197
1 changed files with 4 additions and 4 deletions

View File

@ -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);
}
}