diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index d47f3dbbee..71a32689ea 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1440,12 +1440,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) plane.autotune_enable(!is_zero(packet.param1)); break; - case MAV_CMD_DO_START_MAG_CAL: - case MAV_CMD_DO_ACCEPT_MAG_CAL: - case MAV_CMD_DO_CANCEL_MAG_CAL: - result = plane.compass.handle_mag_cal_command(packet); - break; - #if PARACHUTE == ENABLED case MAV_CMD_DO_PARACHUTE: // configure or release parachute @@ -2019,6 +2013,11 @@ bool GCS_MAVLINK_Plane::accept_packet(const mavlink_status_t &status, mavlink_me return (msg.sysid == plane.g.sysid_my_gcs); } +Compass *GCS_MAVLINK_Plane::get_compass() const +{ + return &plane.compass; +} + AP_Mission *GCS_MAVLINK_Plane::get_mission() { return &plane.mission; diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 497b91ff43..6635c268dd 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -21,6 +21,7 @@ protected: AP_Mission *get_mission() override; void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override; + Compass *get_compass() const override; AP_ServoRelayEvents *get_servorelayevents() const override; AP_Rally *get_rally() const override;