diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 2ae7473860..a45173a4e0 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -581,34 +581,6 @@ Mavlink::get_uart_fd(unsigned index) return -1; } -int -Mavlink::get_uart_fd() -{ - return _uart_fd; -} - -int -Mavlink::get_instance_id() -{ - return _instance_id; -} - -mavlink_channel_t -Mavlink::get_channel() -{ - return _channel; -} - -int Mavlink::get_system_id() -{ - return mavlink_system.sysid; -} - -int Mavlink::get_component_id() -{ - return mavlink_system.compid; -} - int Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_control) { #ifndef B460800 @@ -892,14 +864,6 @@ Mavlink::get_free_tx_buf() return buf_free; } -void -Mavlink::begin_send() -{ - // must protect the network buffer so other calls from receive_thread do not - // mangle the message. - pthread_mutex_lock(&_send_mutex); -} - int Mavlink::send_packet() { @@ -1521,13 +1485,6 @@ Mavlink::message_buffer_count() return n; } -int -Mavlink::message_buffer_is_empty() -{ - return _message_buffer.read_ptr == _message_buffer.write_ptr; -} - - bool Mavlink::message_buffer_write(const void *ptr, int size) { @@ -1589,12 +1546,6 @@ Mavlink::message_buffer_get_ptr(void **ptr, bool *is_part) return n; } -void -Mavlink::message_buffer_mark_read(int n) -{ - _message_buffer.read_ptr = (_message_buffer.read_ptr + n) % _message_buffer.size; -} - void Mavlink::pass_message(const mavlink_message_t *msg) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 512fbba42a..3b0ee86f2c 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -154,21 +154,21 @@ public: static int get_uart_fd(unsigned index); - int get_uart_fd(); + int get_uart_fd() const { return _uart_fd; } /** * Get the MAVLink system id. * * @return The system ID of this vehicle */ - int get_system_id(); + int get_system_id() const { return mavlink_system.sysid; } /** * Get the MAVLink component id. * * @return The component ID of this vehicle */ - int get_component_id(); + int get_component_id() const { return mavlink_system.compid; } const char *_device_name; @@ -297,7 +297,7 @@ public: /** * This is the beginning of a MAVLINK_START_UART_SEND/MAVLINK_END_UART_SEND transaction */ - void begin_send(); + void begin_send() { pthread_mutex_lock(&_send_mutex); } /** * Send bytes out on the link. @@ -329,7 +329,7 @@ public: */ MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic, int instance = 0, bool disable_sharing = false); - int get_instance_id(); + int get_instance_id() const { return _instance_id; } /** * Enable / disable hardware flow control. @@ -338,7 +338,7 @@ public: */ int enable_flow_control(enum FLOW_CONTROL_MODE enabled); - mavlink_channel_t get_channel(); + mavlink_channel_t get_channel() const { return _channel; } void configure_stream_threadsafe(const char *stream_name, float rate = -1.0f); @@ -678,11 +678,11 @@ private: int message_buffer_count(); - int message_buffer_is_empty(); + int message_buffer_is_empty() const { return (_message_buffer.read_ptr == _message_buffer.write_ptr); } int message_buffer_get_ptr(void **ptr, bool *is_part); - void message_buffer_mark_read(int n); + void message_buffer_mark_read(int n) { _message_buffer.read_ptr = (_message_buffer.read_ptr + n) % _message_buffer.size; } void pass_message(const mavlink_message_t *msg);