From 3586f0e8fb1388cbebc9278f33a765736829828d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 17 Jul 2017 10:47:07 +1000 Subject: [PATCH] Rover: move handling of MAG_CAL command longs up --- APMrover2/GCS_Mavlink.cpp | 11 +++++------ APMrover2/GCS_Mavlink.h | 1 + 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 4a7ba8ce8c..8d2f47f5db 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1029,12 +1029,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) break; } - case MAV_CMD_DO_START_MAG_CAL: - case MAV_CMD_DO_ACCEPT_MAG_CAL: - case MAV_CMD_DO_CANCEL_MAG_CAL: - result = rover.compass.handle_mag_cal_command(packet); - break; - case MAV_CMD_NAV_SET_YAW_SPEED: { // param1 : yaw angle to adjust direction by in centidegress @@ -1538,6 +1532,11 @@ AP_ServoRelayEvents *GCS_MAVLINK_Rover::get_servorelayevents() const return &rover.ServoRelayEvents; } +Compass *GCS_MAVLINK_Rover::get_compass() const +{ + return &rover.compass; +} + AP_Mission *GCS_MAVLINK_Rover::get_mission() { return &rover.mission; diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 0d01bde94f..a4bc7e64aa 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -16,6 +16,7 @@ protected: uint32_t telem_delay() const override; bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override; + Compass *get_compass() const override; AP_Mission *get_mission() override; AP_Rally *get_rally() const override { return nullptr; }; AP_ServoRelayEvents *get_servorelayevents() const override;