aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/mavlink_main.h')
-rw-r--r--src/modules/mavlink/mavlink_main.h89
1 files changed, 42 insertions, 47 deletions
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 70d13acb0..1e2e94cef 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -58,7 +58,7 @@
#include "mavlink_stream.h"
#include "mavlink_messages.h"
#include "mavlink_mission.h"
-
+#include "mavlink_parameters.h"
class Mavlink
{
@@ -160,7 +160,12 @@ public:
*/
int set_hil_enabled(bool hil_enabled);
- void send_message(const mavlink_message_t *msg);
+ void send_message(const uint8_t msgid, const void *msg);
+
+ /**
+ * Resend message as is, don't change sequence number and CRC.
+ */
+ void resend_message(mavlink_message_t *msg);
void handle_message(const mavlink_message_t *msg);
@@ -188,29 +193,33 @@ public:
*
* @param string the message to send (will be capped by mavlink max string length)
*/
- int send_statustext_info(const char *string);
+ void send_statustext_info(const char *string);
/**
* Send a status text with loglevel CRITICAL
*
* @param string the message to send (will be capped by mavlink max string length)
*/
- int send_statustext_critical(const char *string);
+ void send_statustext_critical(const char *string);
/**
* Send a status text with loglevel EMERGENCY
*
* @param string the message to send (will be capped by mavlink max string length)
*/
- int send_statustext_emergency(const char *string);
+ void send_statustext_emergency(const char *string);
/**
- * Send a status text with loglevel
+ * Send a status text with loglevel, the difference from mavlink_log_xxx() is that message sent
+ * only on this mavlink connection. Useful for reporting communication specific, not system-wide info
+ * only to client interested in it. Message will be not sent immediately but queued in buffer as
+ * for mavlink_log_xxx().
*
* @param string the message to send (will be capped by mavlink max string length)
- * @param severity the log level, one of
+ * @param severity the log level
*/
- int send_statustext(unsigned severity, const char *string);
+ void send_statustext(unsigned char severity, const char *string);
+
MavlinkStream * get_streams() const { return _streams; }
float get_rate_mult();
@@ -252,6 +261,8 @@ public:
*/
struct telemetry_status_s& get_rx_status() { return _rstatus; }
+ struct mavlink_logbuffer *get_logbuffer() { return &_logbuffer; }
+
protected:
Mavlink *next;
@@ -274,9 +285,8 @@ private:
MavlinkStream *_streams;
MavlinkMissionManager *_mission_manager;
+ MavlinkParametersManager *_parameters_manager;
- orb_advert_t _mission_pub;
- int _mission_result_sub;
MAVLINK_MODE _mode;
mavlink_channel_t _channel;
@@ -292,7 +302,9 @@ private:
bool _ftp_on;
int _uart_fd;
int _baudrate;
- int _datarate;
+ int _datarate; ///< data rate for normal streams (attitude, position, etc.)
+ int _datarate_events; ///< data rate for params, waypoints, text messages
+ float _rate_mult;
/**
* If the queue index is not at 0, the queue sending
@@ -307,6 +319,8 @@ private:
float _subscribe_to_stream_rate;
bool _flow_control_enabled;
+ uint64_t _last_write_success_time;
+ uint64_t _last_write_try_time;
unsigned _bytes_tx;
unsigned _bytes_txerr;
@@ -328,6 +342,7 @@ private:
mavlink_message_buffer _message_buffer;
pthread_mutex_t _message_buffer_mutex;
+ pthread_mutex_t _send_mutex;
bool _param_initialized;
param_t _param_system_id;
@@ -338,52 +353,27 @@ private:
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _txerr_perf; /**< TX error counter */
- /**
- * Send one parameter.
- *
- * @param param The parameter id to send.
- * @return zero on success, nonzero on failure.
- */
- int mavlink_pm_send_param(param_t param);
+ void mavlink_update_system();
- /**
- * Send one parameter identified by index.
- *
- * @param index The index of the parameter to send.
- * @return zero on success, nonzero else.
- */
- int mavlink_pm_send_param_for_index(uint16_t index);
+ int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
/**
- * Send one parameter identified by name.
+ * Get the free space in the transmit buffer
*
- * @param name The index of the parameter to send.
- * @return zero on success, nonzero else.
+ * @return free space in the UART TX buffer
*/
- int mavlink_pm_send_param_for_name(const char *name);
+ unsigned get_free_tx_buf();
- /**
- * Send a queue of parameters, one parameter per function call.
- *
- * @return zero on success, nonzero on failure
- */
- int mavlink_pm_queued_send(void);
+ static unsigned int interval_from_rate(float rate);
+
+ int configure_stream(const char *stream_name, const float rate);
/**
- * Start sending the parameter queue.
+ * Adjust the stream rates based on the current rate
*
- * This function will not directly send parameters, but instead
- * activate the sending of one parameter on each call of
- * mavlink_pm_queued_send().
- * @see mavlink_pm_queued_send()
+ * @param multiplier if greater than 1, the transmission rate will increase, if smaller than one decrease
*/
- void mavlink_pm_start_queued_send();
-
- void mavlink_update_system();
-
- int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
-
- int configure_stream(const char *stream_name, const float rate);
+ void adjust_stream_rates(const float multiplier);
int message_buffer_init(int size);
@@ -399,6 +389,11 @@ private:
void pass_message(const mavlink_message_t *msg);
+ /**
+ * Update rate mult so total bitrate will be equal to _datarate.
+ */
+ void update_rate_mult();
+
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
/**