Blimp: 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:03 +10:00 committed by Andrew Tridgell
parent f064dcd902
commit 0bf4a0a39a
2 changed files with 6 additions and 6 deletions

View File

@ -466,17 +466,17 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_com
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet)
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
case MAV_CMD_DO_REPOSITION:
return handle_command_int_do_reposition(packet);
default:
return GCS_MAVLINK::handle_command_int_packet(packet);
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
@ -502,7 +502,7 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_l
return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}

View File

@ -26,8 +26,8 @@ protected:
void send_position_target_global_int() override;
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);