mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: rename MSG_RADIO_OUT to MSG_SERVO_OUTPUT_RAW to better describe what it is
This commit is contained in:
parent
5012b2e899
commit
4161c34e61
@ -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
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user