mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: nuke clang warnings
This commit is contained in:
parent
ac7ee37b20
commit
6a31e4d816
|
@ -246,7 +246,7 @@ extern const AP_HAL::HAL& hal;
|
|||
bool AP_Frsky_SPortParser::should_process_packet(const uint8_t *packet, bool discard_duplicates)
|
||||
{
|
||||
// check for duplicate packets
|
||||
if (discard_duplicates && _parse_state.last_packet != nullptr) {
|
||||
if (discard_duplicates) {
|
||||
/*
|
||||
Note: the polling byte packet[0] should be ignored in the comparison
|
||||
because we might get the same packet with different polling bytes
|
||||
|
@ -323,10 +323,10 @@ bool AP_Frsky_SPortParser::get_packet(AP_Frsky_SPort::sport_packet_t &sport_pack
|
|||
}
|
||||
|
||||
const AP_Frsky_SPort::sport_packet_t sp {
|
||||
_parse_state.rx_buffer[0],
|
||||
{ _parse_state.rx_buffer[0],
|
||||
_parse_state.rx_buffer[1],
|
||||
le16toh_ptr(&_parse_state.rx_buffer[2]),
|
||||
le32toh_ptr(&_parse_state.rx_buffer[4])
|
||||
le32toh_ptr(&_parse_state.rx_buffer[4]) },
|
||||
};
|
||||
|
||||
sport_packet = sp;
|
||||
|
|
|
@ -857,10 +857,10 @@ bool AP_Frsky_SPort_Passthrough::set_telem_data(const uint8_t frame, const uint1
|
|||
// queue only Uplink packets
|
||||
if (frame == SPORT_UPLINK_FRAME || frame == SPORT_UPLINK_FRAME_RW) {
|
||||
const AP_Frsky_SPort::sport_packet_t sp {
|
||||
0x00, // this is ignored by process_sport_rx_queue() so no need for a real sensor ID
|
||||
{ 0x00, // this is ignored by process_sport_rx_queue() so no need for a real sensor ID
|
||||
frame,
|
||||
appid,
|
||||
data
|
||||
data }
|
||||
};
|
||||
|
||||
_SPort_bidir.rx_packet_queue.push_force(sp);
|
||||
|
|
Loading…
Reference in New Issue