ArduPlane: 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 57eeda0439
commit 7df3d29e9d
2 changed files with 6 additions and 6 deletions

View File

@ -950,7 +950,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl
}
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet)
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch(packet.command) {
@ -974,11 +974,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
#endif
default:
return GCS_MAVLINK::handle_command_int_packet(packet);
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
{
switch(packet.command) {
@ -1103,7 +1103,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
#endif
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}

View File

@ -24,8 +24,8 @@ protected:
bool sysid_enforce() const override;
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) 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_do_set_mission_current(const mavlink_command_long_t &packet) override;
void send_position_target_global_int() override;