GCS_MAVLink: 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:48 +11:00 committed by Peter Barker
parent 475ef8a06d
commit f18e196fa9
3 changed files with 3 additions and 6 deletions

View File

@ -577,7 +577,7 @@ protected:
void handle_serial_control(const mavlink_message_t &msg);
void handle_vision_position_delta(const mavlink_message_t &msg);
void handle_common_message(const mavlink_message_t &msg);
virtual void handle_message(const mavlink_message_t &msg);
void handle_set_gps_global_origin(const mavlink_message_t &msg);
void handle_setup_signing(const mavlink_message_t &msg) const;
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
@ -776,8 +776,6 @@ private:
void service_statustext(void);
virtual void handleMessage(const mavlink_message_t &msg) = 0;
MAV_RESULT handle_servorelay_message(const mavlink_command_int_t &packet);
bool send_relay_status() const;

View File

@ -1763,7 +1763,7 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
// e.g. enforce-sysid says we shouldn't look at this packet
return;
}
handleMessage(msg);
handle_message(msg);
}
void
@ -3936,7 +3936,7 @@ void GCS_MAVLINK::handle_heartbeat(const mavlink_message_t &msg) const
/*
handle messages which don't require vehicle specific data
*/
void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_message(const mavlink_message_t &msg)
{
switch (msg.msgid) {

View File

@ -24,7 +24,6 @@ public:
private:
uint32_t telem_delay() const override { return 0; }
void handleMessage(const mavlink_message_t &msg) override {}
bool try_send_message(enum ap_message id) override { return true; }
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
uint8_t sysid_my_gcs() const override { return 1; }