Changes from review.

This commit is contained in:
mikeller 2018-05-30 22:29:42 +12:00
parent e75eaf85ce
commit 6eea0d45ca
5 changed files with 6 additions and 6 deletions

View File

@ -269,7 +269,7 @@ static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
} else { } else {
result = sbusChannelsDecode(rxRuntimeConfig, &frame->data.controlData.channels); result = sbusChannelsDecode(rxRuntimeConfig, &frame->data.controlData.channels);
setRssi(scaleRange(frame->data.controlData.rssi, 0, 100, 0, 1024), RSSI_SOURCE_RX_PROTOCOL); setRssi(scaleRange(frame->data.controlData.rssi, 0, 100, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_PROTOCOL);
lastRcFrameReceivedMs = millis(); lastRcFrameReceivedMs = millis();
} }

View File

@ -77,7 +77,7 @@ static timeUs_t lastMspRssiUpdateUs = 0;
#define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec #define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
#define RSSI_ADC_DIVISOR 4 // 4096 / 1024 #define RSSI_ADC_DIVISOR (4096 / 1024)
rssiSource_e rssiSource; rssiSource_e rssiSource;
@ -655,7 +655,7 @@ static void updateRSSIADC(timeUs_t currentTimeUs)
rssiValue = RSSI_MAX_VALUE - rssiValue; rssiValue = RSSI_MAX_VALUE - rssiValue;
} }
setRssi((uint16_t)rssiValue, RSSI_SOURCE_ADC); setRssi(rssiValue, RSSI_SOURCE_ADC);
#endif #endif
} }

View File

@ -196,7 +196,7 @@ static void ltm_sframe(void)
ltm_initialise_packet('S'); ltm_initialise_packet('S');
ltm_serialise_16(getBatteryVoltage() * 100); //vbat converted to mv ltm_serialise_16(getBatteryVoltage() * 100); //vbat converted to mv
ltm_serialise_16(0); // current, not implemented ltm_serialise_16(0); // current, not implemented
ltm_serialise_8(scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255)); // scaled RSSI (uchar) ltm_serialise_8(constrain(scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255), 0, 255)); // scaled RSSI (uchar)
ltm_serialise_8(0); // no airspeed ltm_serialise_8(0); // no airspeed
ltm_serialise_8((lt_flightmode << 2) | lt_statemode); ltm_serialise_8((lt_flightmode << 2) | lt_statemode);
ltm_finalise(); ltm_finalise();

View File

@ -281,7 +281,7 @@ void mavlinkSendRCChannelsAndRSSI(void)
// chan8_raw RC channel 8 value, in microseconds // chan8_raw RC channel 8 value, in microseconds
(rxRuntimeConfig.channelCount >= 8) ? rcData[7] : 0, (rxRuntimeConfig.channelCount >= 8) ? rcData[7] : 0,
// rssi Receive signal strength indicator, 0: 0%, 255: 100% // rssi Receive signal strength indicator, 0: 0%, 255: 100%
scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255)); constrain(scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255), 0, 255));
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg); msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);
mavlinkSerialWrite(mavBuffer, msgLength); mavlinkSerialWrite(mavBuffer, msgLength);
} }

View File

@ -1015,7 +1015,7 @@ extern "C" {
uint16_t getRssi(void) { return rssi; } uint16_t getRssi(void) { return rssi; }
uint8_t getRssiPercent(void) { return rssi * 100 / 1024; } uint8_t getRssiPercent(void) { return scaleRange(rssi, 0, RSSI_MAX_VALUE, 0, 100); }
uint16_t getCoreTemperatureCelsius(void) { return simulationCoreTemperature; } uint16_t getCoreTemperatureCelsius(void) { return simulationCoreTemperature; }