ArduCopter: use virtual method for GCS_MAVLink::handle_message

use more appropriate naming for the method.
This commit is contained in:
Peter Barker 2024-01-23 17:41:49 +11:00 committed by Peter Barker
parent c7f7ec3312
commit 8cda4ad924
2 changed files with 3 additions and 3 deletions

View File

@ -1167,7 +1167,7 @@ bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const
return true;
}
void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
{
#if MODE_GUIDED_ENABLED == ENABLED
// for mavlink SET_POSITION_TARGET messages
@ -1510,7 +1510,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
#endif
default:
handle_common_message(msg);
GCS_MAVLINK::handle_message(msg);
break;
} // end switch
} // end handle mavlink

View File

@ -66,7 +66,7 @@ private:
MISSION_STATE mission_state(const class AP_Mission &mission) const override;
void handleMessage(const mavlink_message_t &msg) override;
void handle_message(const mavlink_message_t &msg) override;
void handle_command_ack(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
bool try_send_message(enum ap_message id) override;