AP_IOMCU: support RSSI from receiver
This commit is contained in:
parent
63b454d5ce
commit
63c199a600
@ -71,6 +71,11 @@ public:
|
|||||||
// get the name of the RC protocol
|
// get the name of the RC protocol
|
||||||
const char *get_rc_protocol(void);
|
const char *get_rc_protocol(void);
|
||||||
|
|
||||||
|
// get receiver RSSI
|
||||||
|
int16_t get_RSSI(void) const {
|
||||||
|
return rc_input.rssi;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get servo rail voltage
|
get servo rail voltage
|
||||||
*/
|
*/
|
||||||
|
@ -306,6 +306,7 @@ void AP_IOMCU_FW::rcin_update()
|
|||||||
}
|
}
|
||||||
rc_last_input_ms = last_ms;
|
rc_last_input_ms = last_ms;
|
||||||
rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected();
|
rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected();
|
||||||
|
rc_input.rssi = AP::RC().get_RSSI();
|
||||||
} else if (last_ms - rc_last_input_ms > 200U) {
|
} else if (last_ms - rc_last_input_ms > 200U) {
|
||||||
rc_input.flags_rc_ok = false;
|
rc_input.flags_rc_ok = false;
|
||||||
}
|
}
|
||||||
|
@ -123,6 +123,7 @@ struct page_rc_input {
|
|||||||
uint8_t flags_rc_ok:1;
|
uint8_t flags_rc_ok:1;
|
||||||
uint8_t rc_protocol;
|
uint8_t rc_protocol;
|
||||||
uint16_t pwm[IOMCU_MAX_CHANNELS];
|
uint16_t pwm[IOMCU_MAX_CHANNELS];
|
||||||
|
int16_t rssi;
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user