2024-07-05 20:07:40 -03:00
|
|
|
|
|
|
|
#include <stdint.h>
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#define QURT_MSG_ID_MAVLINK_MSG 1
|
2024-07-12 21:45:16 -03:00
|
|
|
#define QURT_MSG_ID_REBOOT 2
|
2024-07-05 20:07:40 -03:00
|
|
|
|
2024-07-30 13:33:08 -03:00
|
|
|
#define MAX_MAVLINK_INSTANCES 2
|
|
|
|
|
2024-07-12 21:45:16 -03:00
|
|
|
struct __attribute__((__packed__)) qurt_rpc_msg {
|
|
|
|
uint8_t msg_id;
|
2024-07-30 13:33:08 -03:00
|
|
|
uint8_t inst;
|
2024-07-05 20:07:40 -03:00
|
|
|
uint16_t data_length;
|
|
|
|
uint32_t seq;
|
2024-07-12 21:45:16 -03:00
|
|
|
uint8_t data[300];
|
2024-07-05 20:07:40 -03:00
|
|
|
};
|
|
|
|
|
2024-07-30 13:33:08 -03:00
|
|
|
#define QURT_RPC_MSG_HEADER_LEN 8
|
2024-07-12 21:45:16 -03:00
|
|
|
|