mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Sub: eliminate gcs_send_mission_item_reached wrapper
This commit is contained in:
parent
250f315678
commit
9f73d2f9d8
@ -1833,14 +1833,6 @@ void Sub::mavlink_delay_cb()
|
|||||||
in_mavlink_delay = false;
|
in_mavlink_delay = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
* send a mission item reached message and load the index before the send attempt in case it may get delayed
|
|
||||||
*/
|
|
||||||
void Sub::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
|
||||||
{
|
|
||||||
gcs().send_mission_item_reached_message(mission_index);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* send data streams in the given rate range on both links
|
* send data streams in the given rate range on both links
|
||||||
*/
|
*/
|
||||||
|
@ -493,7 +493,6 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
void send_temperature(mavlink_channel_t chan);
|
void send_temperature(mavlink_channel_t chan);
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
void send_pid_tuning(mavlink_channel_t chan);
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_check_input(void);
|
void gcs_check_input(void);
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
|
@ -172,7 +172,7 @@ bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
// send message to GCS
|
// send message to GCS
|
||||||
if (cmd_complete) {
|
if (cmd_complete) {
|
||||||
gcs_send_mission_item_reached_message(cmd.index);
|
gcs().send_mission_item_reached_message(cmd.index);
|
||||||
}
|
}
|
||||||
|
|
||||||
return cmd_complete;
|
return cmd_complete;
|
||||||
|
Loading…
Reference in New Issue
Block a user