ArduSub: pass mavlink_message_t to handle_command_*_packet

the "special case" blocks are getting longer and longer.  Merge the switch statements for the command type to be handled by passing around the message.
This commit is contained in:
Peter Barker 2023-08-17 17:53:02 +10:00 committed by Andrew Tridgell
parent 7df3d29e9d
commit f064dcd902
2 changed files with 3 additions and 3 deletions

View File

@ -460,7 +460,7 @@ bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) {
}
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
case MAV_CMD_NAV_LOITER_UNLIM:
@ -516,7 +516,7 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon
return MAV_RESULT_ACCEPTED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}

View File

@ -20,7 +20,7 @@ protected:
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
// override sending of scaled_pressure3 to send on-board temperature:
void send_scaled_pressure3() override;