forked from Archive/PX4-Autopilot
mavlink:
- implement get_free_tx_buf() for UDP and TCP - gefine get_uart_fd for all platforms
This commit is contained in:
parent
ecbc286469
commit
655617f958
|
@ -435,7 +435,6 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef __PX4_POSIX
|
|
||||||
int
|
int
|
||||||
Mavlink::get_uart_fd(unsigned index)
|
Mavlink::get_uart_fd(unsigned index)
|
||||||
{
|
{
|
||||||
|
@ -453,7 +452,6 @@ Mavlink::get_uart_fd()
|
||||||
{
|
{
|
||||||
return _uart_fd;
|
return _uart_fd;
|
||||||
}
|
}
|
||||||
#endif // __PX4_POSIX
|
|
||||||
|
|
||||||
int
|
int
|
||||||
Mavlink::get_instance_id()
|
Mavlink::get_instance_id()
|
||||||
|
@ -810,6 +808,11 @@ Mavlink::get_free_tx_buf()
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// if we are using network sockets, return max lenght of one packet
|
||||||
|
if (get_protocol() == UDP || get_protocol() == TCP ) {
|
||||||
|
return 1500;
|
||||||
|
}
|
||||||
|
|
||||||
return buf_free;
|
return buf_free;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -123,11 +123,9 @@ public:
|
||||||
|
|
||||||
static void forward_message(const mavlink_message_t *msg, Mavlink *self);
|
static void forward_message(const mavlink_message_t *msg, Mavlink *self);
|
||||||
|
|
||||||
#ifndef __PX4_QURT
|
|
||||||
static int get_uart_fd(unsigned index);
|
static int get_uart_fd(unsigned index);
|
||||||
|
|
||||||
int get_uart_fd();
|
int get_uart_fd();
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the MAVLink system id.
|
* Get the MAVLink system id.
|
||||||
|
|
Loading…
Reference in New Issue