Copter: rename MSG_RADIO_OUT to MSG_SERVO_OUTPUT_RAW to better describe what it is

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-01-10 16:19:55 +01:00 committed by Andrew Tridgell
parent 5012b2e899
commit 4161c34e61
2 changed files with 3 additions and 3 deletions

View File

@ -419,7 +419,7 @@ void Copter::twentyfive_hz_logging()
{ {
#if HIL_MODE != HIL_MODE_DISABLED #if HIL_MODE != HIL_MODE_DISABLED
// HIL for a copter needs very fast update of the servo values // 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 #endif
#if HIL_MODE == HIL_MODE_DISABLED #if HIL_MODE == HIL_MODE_DISABLED

View File

@ -414,7 +414,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
send_radio_in(copter.receiver_rssi); send_radio_in(copter.receiver_rssi);
break; break;
case MSG_RADIO_OUT: case MSG_SERVO_OUTPUT_RAW:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_servo_output_raw(false); send_servo_output_raw(false);
break; break;
@ -744,7 +744,7 @@ GCS_MAVLINK_Copter::data_stream_send(void)
if (copter.gcs_out_of_time) return; if (copter.gcs_out_of_time) return;
if (stream_trigger(STREAM_RC_CHANNELS)) { if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT); send_message(MSG_SERVO_OUTPUT_RAW);
send_message(MSG_RADIO_IN); send_message(MSG_RADIO_IN);
} }