mirror of https://github.com/ArduPilot/ardupilot
Sub: eliminate gcs_end_message wrapper
This commit is contained in:
parent
7865d467d3
commit
f82fa22833
|
@ -240,7 +240,7 @@ void Sub::update_trigger(void)
|
|||
{
|
||||
camera.trigger_pic_cleanup();
|
||||
if (camera.check_trigger_pin()) {
|
||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||
gcs().send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
|
|
|
@ -8,12 +8,12 @@
|
|||
|
||||
void Sub::gcs_send_heartbeat(void)
|
||||
{
|
||||
gcs_send_message(MSG_HEARTBEAT);
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
}
|
||||
|
||||
void Sub::gcs_send_deferred(void)
|
||||
{
|
||||
gcs_send_message(MSG_RETRY_DEFERRED);
|
||||
gcs().send_message(MSG_RETRY_DEFERRED);
|
||||
gcs().service_statustext();
|
||||
}
|
||||
|
||||
|
@ -1815,7 +1815,7 @@ void Sub::mavlink_delay_cb()
|
|||
if (tnow - last_1hz > 1000) {
|
||||
last_1hz = tnow;
|
||||
gcs_send_heartbeat();
|
||||
gcs_send_message(MSG_EXTENDED_STATUS1);
|
||||
gcs().send_message(MSG_EXTENDED_STATUS1);
|
||||
}
|
||||
if (tnow - last_50hz > 20) {
|
||||
last_50hz = tnow;
|
||||
|
@ -1833,14 +1833,6 @@ void Sub::mavlink_delay_cb()
|
|||
in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
/*
|
||||
* send a message on both GCS links
|
||||
*/
|
||||
void Sub::gcs_send_message(enum ap_message id)
|
||||
{
|
||||
gcs().send_message(id);
|
||||
}
|
||||
|
||||
/*
|
||||
* send a mission item reached message and load the index before the send attempt in case it may get delayed
|
||||
*/
|
||||
|
|
|
@ -493,7 +493,6 @@ private:
|
|||
#endif
|
||||
void send_temperature(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void gcs_send_message(enum ap_message id);
|
||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_check_input(void);
|
||||
|
|
|
@ -894,7 +894,7 @@ void Sub::do_take_picture()
|
|||
void Sub::log_picture()
|
||||
{
|
||||
if (!camera.using_feedback_pin()) {
|
||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||
gcs().send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue