mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_PX4: support RSSI from receiver protocols
This commit is contained in:
parent
9868ffe13b
commit
a88693c487
@ -118,6 +118,10 @@ void PX4RCInput::_timer_tick(void)
|
|||||||
if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
|
if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
|
||||||
pthread_mutex_lock(&rcin_mutex);
|
pthread_mutex_lock(&rcin_mutex);
|
||||||
orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
|
orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
|
||||||
|
if (_rcin.rssi != 0 || _rssi != -1) {
|
||||||
|
// always zero means not supported
|
||||||
|
_rssi = _rcin.rssi;
|
||||||
|
}
|
||||||
pthread_mutex_unlock(&rcin_mutex);
|
pthread_mutex_unlock(&rcin_mutex);
|
||||||
}
|
}
|
||||||
// note, we rely on the vehicle code checking new_input()
|
// note, we rely on the vehicle code checking new_input()
|
||||||
|
@ -18,6 +18,11 @@ public:
|
|||||||
uint16_t read(uint8_t ch) override;
|
uint16_t read(uint8_t ch) override;
|
||||||
uint8_t read(uint16_t* periods, uint8_t len) override;
|
uint8_t read(uint16_t* periods, uint8_t len) override;
|
||||||
|
|
||||||
|
int16_t get_rssi(void) override {
|
||||||
|
return _rssi;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
bool set_overrides(int16_t *overrides, uint8_t len) override;
|
bool set_overrides(int16_t *overrides, uint8_t len) override;
|
||||||
bool set_override(uint8_t channel, int16_t override) override;
|
bool set_override(uint8_t channel, int16_t override) override;
|
||||||
void clear_overrides() override;
|
void clear_overrides() override;
|
||||||
@ -35,4 +40,5 @@ private:
|
|||||||
bool _override_valid;
|
bool _override_valid;
|
||||||
perf_counter_t _perf_rcin;
|
perf_counter_t _perf_rcin;
|
||||||
pthread_mutex_t rcin_mutex;
|
pthread_mutex_t rcin_mutex;
|
||||||
|
int16_t _rssi = -1;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user