mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_Linux: support receiver based RSSI
This commit is contained in:
parent
94b5a9c6f0
commit
9868ffe13b
@ -448,6 +448,7 @@ bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
_num_channels = channel_count;
|
_num_channels = channel_count;
|
||||||
rc_input_count++;
|
rc_input_count++;
|
||||||
ret = true;
|
ret = true;
|
||||||
|
_rssi = rssi;
|
||||||
}
|
}
|
||||||
nbytes--;
|
nbytes--;
|
||||||
}
|
}
|
||||||
@ -478,6 +479,7 @@ bool RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
_num_channels = channel_count;
|
_num_channels = channel_count;
|
||||||
rc_input_count++;
|
rc_input_count++;
|
||||||
ret = true;
|
ret = true;
|
||||||
|
_rssi = rssi;
|
||||||
}
|
}
|
||||||
nbytes--;
|
nbytes--;
|
||||||
}
|
}
|
||||||
|
@ -22,6 +22,10 @@ public:
|
|||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
|
|
||||||
|
int16_t get_rssi(void) override {
|
||||||
|
return _rssi;
|
||||||
|
}
|
||||||
|
|
||||||
bool set_overrides(int16_t *overrides, uint8_t len);
|
bool set_overrides(int16_t *overrides, uint8_t len);
|
||||||
bool set_override(uint8_t channel, int16_t override);
|
bool set_override(uint8_t channel, int16_t override);
|
||||||
void clear_overrides();
|
void clear_overrides();
|
||||||
@ -93,6 +97,8 @@ protected:
|
|||||||
uint8_t partial_frame_count;
|
uint8_t partial_frame_count;
|
||||||
uint32_t last_input_ms;
|
uint32_t last_input_ms;
|
||||||
} sbus;
|
} sbus;
|
||||||
|
|
||||||
|
int16_t _rssi = -1;
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user