diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 37bdf02be4..a80e7ab44f 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1223,7 +1223,7 @@ void GCS_MAVLINK_Plane::handle_manual_control_axes(const mavlink_manual_control_ manual_override(plane.channel_rudder, packet.r, 1000, 2000, tnow); } -void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) +void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg) { switch (msg.msgid) { @@ -1394,7 +1394,7 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) } default: - handle_common_message(msg); + GCS_MAVLINK::handle_message(msg); break; } // end switch } // end handle mavlink diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index e497a56710..d3c476318b 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -50,7 +50,7 @@ private: void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); - void handleMessage(const mavlink_message_t &msg) override; + void handle_message(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);