mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Copter: eliminate gcs_send_mission_item_reached wrapper
This commit is contained in:
parent
2692ee22d3
commit
358555446b
@ -718,7 +718,6 @@ private:
|
|||||||
void init_visual_odom();
|
void init_visual_odom();
|
||||||
void update_visual_odom();
|
void update_visual_odom();
|
||||||
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);
|
||||||
|
@ -2046,14 +2046,6 @@ void Copter::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 Copter::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
|
||||||
*/
|
*/
|
||||||
|
@ -182,7 +182,7 @@ bool Copter::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