Copter: eliminate gcs_send_message wrapper

This commit is contained in:
Peter Barker 2017-07-08 11:43:24 +10:00 committed by Francisco Ferreira
parent 130ad52a22
commit 0ac045febe
4 changed files with 6 additions and 15 deletions

View File

@ -339,7 +339,7 @@ void Copter::update_trigger(void)
#if CAMERA == ENABLED
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);
}
@ -416,7 +416,7 @@ void Copter::twentyfive_hz_logging()
{
#if HIL_MODE != HIL_MODE_DISABLED
// HIL for a copter needs very fast update of the servo values
gcs_send_message(MSG_SERVO_OUTPUT_RAW);
gcs().send_message(MSG_SERVO_OUTPUT_RAW);
#endif
#if HIL_MODE == HIL_MODE_DISABLED

View File

@ -718,7 +718,6 @@ private:
void init_visual_odom();
void update_visual_odom();
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);

View File

@ -5,12 +5,12 @@
void Copter::gcs_send_heartbeat(void)
{
gcs_send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_HEARTBEAT);
}
void Copter::gcs_send_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
gcs().send_message(MSG_RETRY_DEFERRED);
gcs().service_statustext();
}
@ -2027,7 +2027,7 @@ void Copter::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;
@ -2046,14 +2046,6 @@ void Copter::mavlink_delay_cb()
in_mavlink_delay = false;
}
/*
* send a message on both GCS links
*/
void Copter::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
*/

View File

@ -1155,7 +1155,7 @@ void Copter::do_take_picture()
void Copter::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);
}