GCS_MAVLINK: add receiver_rssi() method, and use it
This commit is contained in:
parent
70764bfaeb
commit
bacfe82c66
@ -549,6 +549,8 @@ protected:
|
||||
|
||||
void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
||||
|
||||
uint8_t receiver_rssi() const;
|
||||
|
||||
/*
|
||||
correct an offboard timestamp in microseconds to a local time
|
||||
since boot in milliseconds
|
||||
|
@ -1636,12 +1636,6 @@ void GCS_MAVLINK::send_system_time()
|
||||
*/
|
||||
void GCS_MAVLINK::send_rc_channels() const
|
||||
{
|
||||
AP_RSSI *rssi = AP::rssi();
|
||||
uint8_t receiver_rssi = 0;
|
||||
if (rssi != nullptr) {
|
||||
receiver_rssi = rssi->read_receiver_rssi_uint8();
|
||||
}
|
||||
|
||||
uint16_t values[18] = {};
|
||||
rc().get_radio_in(values, ARRAY_SIZE(values));
|
||||
|
||||
@ -1667,7 +1661,7 @@ void GCS_MAVLINK::send_rc_channels() const
|
||||
values[15],
|
||||
values[16],
|
||||
values[17],
|
||||
receiver_rssi);
|
||||
receiver_rssi());
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::sending_mavlink1() const
|
||||
@ -1687,11 +1681,7 @@ void GCS_MAVLINK::send_rc_channels_raw() const
|
||||
if (!sending_mavlink1()) {
|
||||
return;
|
||||
}
|
||||
AP_RSSI *rssi = AP::rssi();
|
||||
uint8_t receiver_rssi = 0;
|
||||
if (rssi != nullptr) {
|
||||
receiver_rssi = rssi->read_receiver_rssi_uint8();
|
||||
}
|
||||
|
||||
uint16_t values[8] = {};
|
||||
rc().get_radio_in(values, ARRAY_SIZE(values));
|
||||
|
||||
@ -1707,7 +1697,7 @@ void GCS_MAVLINK::send_rc_channels_raw() const
|
||||
values[5],
|
||||
values[6],
|
||||
values[7],
|
||||
receiver_rssi);
|
||||
receiver_rssi());
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_raw_imu()
|
||||
@ -5486,6 +5476,21 @@ void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_
|
||||
c->set_override(override_value, tnow);
|
||||
}
|
||||
|
||||
uint8_t GCS_MAVLINK::receiver_rssi() const
|
||||
{
|
||||
AP_RSSI *aprssi = AP::rssi();
|
||||
if (aprssi == nullptr) {
|
||||
return 255;
|
||||
}
|
||||
|
||||
if (!aprssi->enabled()) {
|
||||
return 255;
|
||||
}
|
||||
|
||||
uint8_t rssi = aprssi->read_receiver_rssi() * 255;
|
||||
return (rssi < 255) ? rssi : 254;
|
||||
}
|
||||
|
||||
GCS &gcs()
|
||||
{
|
||||
return *GCS::get_singleton();
|
||||
|
Loading…
Reference in New Issue
Block a user