From 4161c34e619a1ffd1dd448a9ea5dd39eeaaae09b Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Tue, 10 Jan 2017 16:19:55 +0100 Subject: [PATCH] Copter: rename MSG_RADIO_OUT to MSG_SERVO_OUTPUT_RAW to better describe what it is --- ArduCopter/ArduCopter.cpp | 2 +- ArduCopter/GCS_Mavlink.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 32a49decf0..b4dba0abc0 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -419,7 +419,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_RADIO_OUT); + gcs_send_message(MSG_SERVO_OUTPUT_RAW); #endif #if HIL_MODE == HIL_MODE_DISABLED diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 4910699723..588d7aaae9 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -414,7 +414,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) send_radio_in(copter.receiver_rssi); break; - case MSG_RADIO_OUT: + case MSG_SERVO_OUTPUT_RAW: CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); send_servo_output_raw(false); break; @@ -744,7 +744,7 @@ GCS_MAVLINK_Copter::data_stream_send(void) if (copter.gcs_out_of_time) return; if (stream_trigger(STREAM_RC_CHANNELS)) { - send_message(MSG_RADIO_OUT); + send_message(MSG_SERVO_OUTPUT_RAW); send_message(MSG_RADIO_IN); }