Browse Source

Arducopter: Primary Compass is always serial# 0

c415-sdk
Siddharth Purohit 5 years ago committed by Randy Mackay
parent
commit
b5cf1ecfe1
  1. 8
      ArduCopter/compassmot.cpp

8
ArduCopter/compassmot.cpp

@ -221,10 +221,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -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);
}
}

Loading…
Cancel
Save