Rover: 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 0bf4a0a39a
commit 460faa8659
2 changed files with 6 additions and 6 deletions

View File

@ -637,7 +637,7 @@ bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) {
return rover.set_home(loc, _lock);
}
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet)
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
@ -658,11 +658,11 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
return MAV_RESULT_ACCEPTED;
default:
return GCS_MAVLINK::handle_command_int_packet(packet);
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
@ -725,7 +725,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
packet.param4);
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}

View File

@ -16,8 +16,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_int_do_reposition(const mavlink_command_int_t &packet);
void send_position_target_global_int() override;