Browse Source

Added PWM RSSI based on receiver signal to display at OSD

master
Englebert 3 years ago
parent
commit
73ac25abf1
  1. 49
      src/main.cpp

49
src/main.cpp

@ -22,11 +22,18 @@ int16_t sbus_packets_sent = 0;
int16_t sbus_packets_sent_raw = 0;
int16_t nrf_packets_received = 0;
int16_t nrf_packets_received_raw = 0;
int16_t nrf_packets_tmp = 0;
uint8_t rssi_on_time = 0;
uint8_t rssi_off_time = 0;
uint32_t last_rssi_on = 0;
uint32_t last_rssi_off = 0;
bool rssi_state = false;
bool first_load = true;
uint16_t last_receive = 0;
uint32_t uptime_total = 0;
uint8_t channel = 8;
bool sbus_enable = true;
Scheduler scheduler;
RXMessage rxMessage;
@ -63,6 +70,12 @@ void setup() {
// Setting up status led
pinMode(LED_HEARTBEAT, OUTPUT);
// Configure RSSI PWM resolutions and set to LOW @ 100Hz
/// analogWriteRange(256);
/// analogWriteFreq(100);
/// analogWrite(RSSI_PIN, 0);
pinMode(RSSI_PIN, OUTPUT);
// Starting up storage
storage.begin();
@ -94,7 +107,6 @@ void setup() {
task_web.enable();
task_ota.enable();
task_uptime.enable();
//// Serial.println("SimpleRX OK");
}
@ -122,12 +134,34 @@ void status_heartbeat(void) {
} else {
GPOC = (1 << LED_HEARTBEAT);
}
rssi_handler();
}
// Main Process
void main_processor(void) {
nrf_rx(); // Receving data
sbus.writePackets(); // Write Packets to SBUS port
// If only enable. When disable is for flashing FC
if(sbus_enable)
sbus.writePackets(); // Write Packets to SBUS port
// Generating PWM in software way
if(rssi_state) {
// On State
if((uint32_t)(millis() - last_rssi_on) > rssi_on_time) {
rssi_state = false;
GPOC = (1 << RSSI_PIN);
last_rssi_off = millis();
}
} else {
// Off state
if((uint32_t)(millis() - last_rssi_off) > rssi_off_time) {
rssi_state = true;
GPOS = (1 << RSSI_PIN);
last_rssi_on = millis();
}
}
}
@ -140,6 +174,17 @@ void uptime_tracker(void) {
}
void rssi_handler(void) {
// Also controls sending signal as PWM via RSSI_PIN represents the signal. 0 = No signal (Totally packet lost), 99 = Maximum packets received (150 packets / seconds).
// Anything more than 150 packets also consider 150.
// 99 also meaning 99mS on time 1mS off time
nrf_packets_tmp = (nrf_packets_received >= MAX_NRF_PACKETS) ? MAX_NRF_PACKETS : nrf_packets_received;
rssi_on_time = map(nrf_packets_tmp, 0, 150, 0, 250);
rssi_off_time = 250 - rssi_on_time;
/// analogWrite(RSSI_PIN, packets_in_rssi);
}
// Processing received data
void nrf_rx(void) {
if(first_load == true) {

Loading…
Cancel
Save