forked from Archive/PX4-Autopilot
Formatting and some ftp drive-by
This commit is contained in:
parent
dfe71b615c
commit
f84e18f27a
|
@ -145,6 +145,20 @@ public:
|
|||
|
||||
int get_uart_fd();
|
||||
|
||||
/**
|
||||
* Get the MAVLink system id.
|
||||
*
|
||||
* @return The system ID of this vehicle
|
||||
*/
|
||||
int get_system_id();
|
||||
|
||||
/**
|
||||
* Get the MAVLink component id.
|
||||
*
|
||||
* @return The component ID of this vehicle
|
||||
*/
|
||||
int get_component_id();
|
||||
|
||||
const char *_device_name;
|
||||
|
||||
enum MAVLINK_MODE {
|
||||
|
@ -199,7 +213,7 @@ public:
|
|||
*/
|
||||
int enable_flow_control(bool enabled);
|
||||
|
||||
mavlink_channel_t get_channel();
|
||||
const mavlink_channel_t get_channel();
|
||||
|
||||
bool _task_should_exit; /**< if true, mavlink task should exit */
|
||||
|
||||
|
@ -213,6 +227,8 @@ public:
|
|||
bool get_wait_to_transmit() { return _wait_to_transmit; }
|
||||
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
||||
|
||||
bool message_buffer_write(void *ptr, int size);
|
||||
|
||||
protected:
|
||||
Mavlink *next;
|
||||
|
||||
|
@ -253,6 +269,7 @@ private:
|
|||
bool _verbose;
|
||||
bool _forwarding_on;
|
||||
bool _passing_on;
|
||||
bool _ftp_on;
|
||||
int _uart_fd;
|
||||
int _baudrate;
|
||||
int _datarate;
|
||||
|
@ -277,6 +294,7 @@ private:
|
|||
int size;
|
||||
char *data;
|
||||
};
|
||||
|
||||
mavlink_message_buffer _message_buffer;
|
||||
|
||||
pthread_mutex_t _message_buffer_mutex;
|
||||
|
@ -354,8 +372,6 @@ private:
|
|||
|
||||
int message_buffer_is_empty();
|
||||
|
||||
bool message_buffer_write(void *ptr, int size);
|
||||
|
||||
int message_buffer_get_ptr(void **ptr, bool *is_part);
|
||||
|
||||
void message_buffer_mark_read(int n);
|
||||
|
|
Loading…
Reference in New Issue