mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: add gcs_send_mission_item_reached
This commit is contained in:
parent
a61129f7f8
commit
c62da52259
@ -582,6 +582,7 @@ private:
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_check_input(void);
|
||||
void gcs_send_text_P(gcs_severity severity, const prog_char_t *str);
|
||||
void gcs_send_mission_item_reached(uint16_t seq);
|
||||
void do_erase_logs(void);
|
||||
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
|
||||
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
|
||||
|
@ -1831,3 +1831,15 @@ void Copter::gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* send mission_item_reached message to all GCSs
|
||||
*/
|
||||
void Copter::gcs_send_mission_item_reached(uint16_t seq)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].send_mission_item_reached(seq);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user