From f82fa22833dbeeaca94a6d6954f2ea9fd392c1a8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 8 Jul 2017 12:02:04 +1000 Subject: [PATCH] Sub: eliminate gcs_end_message wrapper --- ArduSub/ArduSub.cpp | 2 +- ArduSub/GCS_Mavlink.cpp | 14 +++----------- ArduSub/Sub.h | 1 - ArduSub/commands_logic.cpp | 2 +- 4 files changed, 5 insertions(+), 14 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 883a324f93..05f178220d 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -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); } diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 37284c955b..caf52c3603 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -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 */ diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index d662aeb811..3b63175466 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -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); diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index aafccddce3..f023135052 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -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); }