mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
GCS_MAVLink: move try_send_message handling of RC_CHANNELS_RAW up
This commit is contained in:
parent
ac2fe5f042
commit
b76fa57108
@ -162,7 +162,7 @@ public:
|
||||
bool send_proximity(const AP_Proximity &proximity) const;
|
||||
void send_ahrs2();
|
||||
void send_system_time();
|
||||
void send_radio_in(uint8_t receiver_rssi);
|
||||
void send_radio_in();
|
||||
void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass);
|
||||
void send_scaled_pressure();
|
||||
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass);
|
||||
|
@ -951,8 +951,14 @@ void GCS_MAVLINK::send_system_time()
|
||||
/*
|
||||
send RC_CHANNELS messages
|
||||
*/
|
||||
void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
|
||||
void GCS_MAVLINK::send_radio_in()
|
||||
{
|
||||
AP_RSSI *rssi = AP::rssi();
|
||||
uint8_t receiver_rssi = 0;
|
||||
if (rssi != nullptr) {
|
||||
receiver_rssi = rssi->read_receiver_rssi_uint8();
|
||||
}
|
||||
|
||||
uint32_t now = AP_HAL::millis();
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
|
||||
@ -2674,6 +2680,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
send_local_position();
|
||||
break;
|
||||
|
||||
case MSG_RADIO_IN:
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
|
||||
send_radio_in();
|
||||
break;
|
||||
|
||||
case MSG_AHRS:
|
||||
CHECK_PAYLOAD_SIZE(AHRS);
|
||||
send_ahrs();
|
||||
|
Loading…
Reference in New Issue
Block a user