mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge pull request #10785 from JulioCesarMatias/FixMavLinkRssi
MavLink RSSI Range
This commit is contained in:
parent
3471fd6c1b
commit
7158bd4300
1 changed files with 2 additions and 2 deletions
|
@ -291,8 +291,8 @@ void mavlinkSendRCChannelsAndRSSI(void)
|
||||||
(rxRuntimeState.channelCount >= 7) ? rcData[6] : 0,
|
(rxRuntimeState.channelCount >= 7) ? rcData[6] : 0,
|
||||||
// chan8_raw RC channel 8 value, in microseconds
|
// chan8_raw RC channel 8 value, in microseconds
|
||||||
(rxRuntimeState.channelCount >= 8) ? rcData[7] : 0,
|
(rxRuntimeState.channelCount >= 8) ? rcData[7] : 0,
|
||||||
// rssi Receive signal strength indicator, 0: 0%, 255: 100%
|
// rssi Receive signal strength indicator, 0: 0%, 254: 100%
|
||||||
constrain(scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255), 0, 255));
|
scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 254));
|
||||||
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);
|
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);
|
||||||
mavlinkSerialWrite(mavBuffer, msgLength);
|
mavlinkSerialWrite(mavBuffer, msgLength);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue