mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 10:37:36 +08:00
Linux: Update mavlink files to track nuttx upstream
Modified LInux impl to track changes to nuttx impl. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
@@ -751,7 +751,7 @@ Mavlink::get_free_tx_buf()
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::send_message(const uint8_t msgid, const void *msg)
|
||||
Mavlink::send_message(const uint8_t msgid, const void *msg, uint8_t component_ID)
|
||||
{
|
||||
/* If the wait until transmit flag is on, only transmit after we've received messages.
|
||||
Otherwise, transmit all the time. */
|
||||
@@ -785,7 +785,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg)
|
||||
/* use mavlink's internal counter for the TX seq */
|
||||
buf[2] = mavlink_get_channel_status(_channel)->current_tx_seq++;
|
||||
buf[3] = mavlink_system.sysid;
|
||||
buf[4] = mavlink_system.compid;
|
||||
buf[4] = (component_ID == 0) ? mavlink_system.compid : component_ID;
|
||||
buf[5] = msgid;
|
||||
|
||||
/* payload */
|
||||
|
||||
@@ -144,6 +144,13 @@ public:
|
||||
|
||||
bool get_forwarding_on() { return _forwarding_on; }
|
||||
|
||||
/**
|
||||
* Get the free space in the transmit buffer
|
||||
*
|
||||
* @return free space in the UART TX buffer
|
||||
*/
|
||||
unsigned get_free_tx_buf();
|
||||
|
||||
static int start_helper(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
@@ -163,12 +170,12 @@ public:
|
||||
*/
|
||||
int set_hil_enabled(bool hil_enabled);
|
||||
|
||||
void send_message(const uint8_t msgid, const void *msg);
|
||||
void send_message(const uint8_t msgid, const void *msg, uint8_t component_ID = 0);
|
||||
|
||||
/**
|
||||
* Resend message as is, don't change sequence number and CRC.
|
||||
*/
|
||||
void resend_message(mavlink_message_t *msg);
|
||||
void resend_message(mavlink_message_t *msg);
|
||||
|
||||
void handle_message(const mavlink_message_t *msg);
|
||||
|
||||
@@ -310,7 +317,7 @@ private:
|
||||
int _baudrate;
|
||||
int _datarate; ///< data rate for normal streams (attitude, position, etc.)
|
||||
int _datarate_events; ///< data rate for params, waypoints, text messages
|
||||
float _rate_mult;
|
||||
float _rate_mult;
|
||||
|
||||
/**
|
||||
* If the queue index is not at 0, the queue sending
|
||||
@@ -332,9 +339,9 @@ private:
|
||||
unsigned _bytes_txerr;
|
||||
unsigned _bytes_rx;
|
||||
uint64_t _bytes_timestamp;
|
||||
float _rate_tx;
|
||||
float _rate_txerr;
|
||||
float _rate_rx;
|
||||
float _rate_tx;
|
||||
float _rate_txerr;
|
||||
float _rate_rx;
|
||||
|
||||
struct telemetry_status_s _rstatus; ///< receive status
|
||||
|
||||
@@ -364,16 +371,9 @@ private:
|
||||
|
||||
void mavlink_update_system();
|
||||
|
||||
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
|
||||
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
|
||||
|
||||
/**
|
||||
* Get the free space in the transmit buffer
|
||||
*
|
||||
* @return free space in the UART TX buffer
|
||||
*/
|
||||
unsigned get_free_tx_buf();
|
||||
|
||||
static unsigned int interval_from_rate(float rate);
|
||||
static unsigned int interval_from_rate(float rate);
|
||||
|
||||
int configure_stream(const char *stream_name, const float rate);
|
||||
|
||||
@@ -404,7 +404,6 @@ private:
|
||||
void update_rate_mult();
|
||||
|
||||
virtual int ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long arg);
|
||||
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Main mavlink task.
|
||||
|
||||
Reference in New Issue
Block a user