Rover: eliminate gcs_send_message wrapper

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

View File

@ -208,7 +208,7 @@ void Rover::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);
}
@ -308,7 +308,7 @@ void Rover::one_second_loop(void)
Log_Write_Current();
}
// send a heartbeat
gcs_send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_HEARTBEAT);
// allow orientation change at runtime to aid config
ahrs.set_orientation();

View File

@ -1573,8 +1573,8 @@ void Rover::mavlink_delay_cb()
const uint32_t tnow = millis();
if (tnow - last_1hz > 1000) {
last_1hz = tnow;
gcs_send_message(MSG_HEARTBEAT);
gcs_send_message(MSG_EXTENDED_STATUS1);
gcs().send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_EXTENDED_STATUS1);
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
@ -1592,14 +1592,6 @@ void Rover::mavlink_delay_cb()
in_mavlink_delay = false;
}
/*
* send a message on both GCS links
*/
void Rover::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
*/
@ -1629,7 +1621,7 @@ void Rover::gcs_update(void)
*/
void Rover::gcs_retry_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
gcs().send_message(MSG_RETRY_DEFERRED);
gcs().service_statustext();
}

View File

@ -451,7 +451,6 @@ private:
void send_rangefinder(mavlink_channel_t chan);
void send_current_waypoint(mavlink_channel_t chan);
bool telemetry_delayed(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_update(void);

View File

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