forked from Archive/PX4-Autopilot
Fix proto version selection
This commit is contained in:
parent
19c2ae615f
commit
d4b588f84a
|
@ -216,7 +216,7 @@ Mavlink::Mavlink() :
|
|||
_last_write_success_time(0),
|
||||
_last_write_try_time(0),
|
||||
_mavlink_start_time(0),
|
||||
_protocol_version_switch(0),
|
||||
_protocol_version_switch(-1),
|
||||
_protocol_version(0),
|
||||
_bytes_tx(0),
|
||||
_bytes_txerr(0),
|
||||
|
@ -336,7 +336,8 @@ Mavlink::~Mavlink()
|
|||
void
|
||||
Mavlink::set_proto_version(unsigned version)
|
||||
{
|
||||
if (version == 1 || ((version == 0) && !_received_messages)) {
|
||||
if ((version == 1 || version == 0) &&
|
||||
((_protocol_version_switch == 0) || (_protocol_version_switch == 1))) {
|
||||
get_status()->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
||||
_protocol_version = 1;
|
||||
|
||||
|
|
|
@ -2090,7 +2090,7 @@ MavlinkReceiver::receive_thread(void *arg)
|
|||
#endif
|
||||
mavlink_message_t msg;
|
||||
|
||||
struct pollfd fds[1];
|
||||
struct pollfd fds[1] = {};
|
||||
|
||||
if (_mavlink->get_protocol() == SERIAL) {
|
||||
fds[0].fd = _mavlink->get_uart_fd();
|
||||
|
|
Loading…
Reference in New Issue