GCS_Common: fix updated messages

This commit is contained in:
Willian Galvani 2024-01-11 14:48:34 -03:00
parent 4f762a9763
commit a2e634ed5e
1 changed files with 8 additions and 7 deletions

View File

@ -265,7 +265,8 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
percentage,
0, // time remaining, seconds (not provided)
battery.get_mavlink_charge_state(instance), // battery charge state
cell_volts_ext); // Cell 11..14 voltages
cell_volts_ext,
0, 0); // Cell 11..14 voltages
}
// returns true if all battery instances were reported
@ -541,7 +542,7 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_
// exactly that sequence number in it, even if ArduPilot never
// actually holds that as a sequence number (e.g. packet.seq==0).
if (HAVE_PAYLOAD_SPACE(chan, MISSION_CURRENT)) {
mavlink_msg_mission_current_send(chan, packet.seq);
mavlink_msg_mission_current_send(chan, packet.seq, 0, 0, 0);
} else {
// schedule it for later:
send_message(MSG_CURRENT_WAYPOINT);
@ -2246,7 +2247,7 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg)
// exist, but if it did we'd probably be acking something
// completely unrelated to setting modes.
if (HAVE_PAYLOAD_SPACE(chan, COMMAND_ACK)) {
mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result);
mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result, 0, 0, 0, 0);
}
}
@ -2811,7 +2812,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
}
// send ack before we reboot
mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED);
mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED, 0, 0, 0, 0);
// when packet.param1 == 3 we reboot to hold in bootloader
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
@ -4305,7 +4306,7 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg)
const MAV_RESULT result = handle_command_long_packet(packet);
// send ACK or NAK
mavlink_msg_command_ack_send(chan, packet.command, result);
mavlink_msg_command_ack_send(chan, packet.command, result, 0, 0, 0, 0);
// log the packet:
mavlink_command_int_t packet_int;
@ -4492,7 +4493,7 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg)
const MAV_RESULT result = handle_command_int_packet(packet);
// send ACK or NAK
mavlink_msg_command_ack_send(chan, packet.command, result);
mavlink_msg_command_ack_send(chan, packet.command, result, 0, 0, 0, 0);
AP::logger().Write_Command(packet, result);
@ -4518,7 +4519,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
switch (id) {
case MSG_CURRENT_WAYPOINT:
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index(), 0, 0, 0);
ret = true;
break;
case MSG_MISSION_ITEM_REACHED: