mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:55:34 +08:00
Merge branch 'master' into takeoff_sp_fix
This commit is contained in:
+1
-1
@@ -56,7 +56,7 @@ define vecstate
|
||||
if $mmfsr & (1<<3)
|
||||
printf " during exception return"
|
||||
end
|
||||
if $mmfsr & (1<<0)
|
||||
if $mmfsr & (1<<1)
|
||||
printf " during data access"
|
||||
end
|
||||
if $mmfsr & (1<<0)
|
||||
|
||||
+191
@@ -0,0 +1,191 @@
|
||||
/*
|
||||
* Building: cc -o com com.c
|
||||
* Usage : ./com /dev/device [speed]
|
||||
* Example : ./com /dev/ttyS0 [115200]
|
||||
* Keys : Ctrl-A - exit, Ctrl-X - display control lines status
|
||||
* Darcs : darcs get http://tinyserial.sf.net/
|
||||
* Homepage: http://tinyserial.sourceforge.net
|
||||
* Version : 2009-03-05
|
||||
*
|
||||
* Ivan Tikhonov, http://www.brokestream.com, kefeer@brokestream.com
|
||||
* Patches by Jim Kou, Henry Nestler, Jon Miner, Alan Horstmann
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
/* Copyright (C) 2007 Ivan Tikhonov
|
||||
|
||||
This software is provided 'as-is', without any express or implied
|
||||
warranty. In no event will the authors be held liable for any damages
|
||||
arising from the use of this software.
|
||||
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it
|
||||
freely, subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not
|
||||
claim that you wrote the original software. If you use this software
|
||||
in a product, an acknowledgment in the product documentation would be
|
||||
appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be
|
||||
misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
Ivan Tikhonov, kefeer@brokestream.com
|
||||
|
||||
*/
|
||||
|
||||
#include <termios.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <sys/signal.h>
|
||||
#include <sys/types.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
|
||||
int transfer_byte(int from, int to, int is_control);
|
||||
|
||||
typedef struct {char *name; int flag; } speed_spec;
|
||||
|
||||
|
||||
void print_status(int fd) {
|
||||
int status;
|
||||
unsigned int arg;
|
||||
status = ioctl(fd, TIOCMGET, &arg);
|
||||
fprintf(stderr, "[STATUS]: ");
|
||||
if(arg & TIOCM_RTS) fprintf(stderr, "RTS ");
|
||||
if(arg & TIOCM_CTS) fprintf(stderr, "CTS ");
|
||||
if(arg & TIOCM_DSR) fprintf(stderr, "DSR ");
|
||||
if(arg & TIOCM_CAR) fprintf(stderr, "DCD ");
|
||||
if(arg & TIOCM_DTR) fprintf(stderr, "DTR ");
|
||||
if(arg & TIOCM_RNG) fprintf(stderr, "RI ");
|
||||
fprintf(stderr, "\r\n");
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
int comfd;
|
||||
struct termios oldtio, newtio; //place for old and new port settings for serial port
|
||||
struct termios oldkey, newkey; //place tor old and new port settings for keyboard teletype
|
||||
char *devicename = argv[1];
|
||||
int need_exit = 0;
|
||||
speed_spec speeds[] =
|
||||
{
|
||||
{"1200", B1200},
|
||||
{"2400", B2400},
|
||||
{"4800", B4800},
|
||||
{"9600", B9600},
|
||||
{"19200", B19200},
|
||||
{"38400", B38400},
|
||||
{"57600", B57600},
|
||||
{"115200", B115200},
|
||||
{NULL, 0}
|
||||
};
|
||||
int speed = B9600;
|
||||
|
||||
if(argc < 2) {
|
||||
fprintf(stderr, "example: %s /dev/ttyS0 [115200]\n", argv[0]);
|
||||
exit(1);
|
||||
}
|
||||
|
||||
comfd = open(devicename, O_RDWR | O_NOCTTY | O_NONBLOCK);
|
||||
if (comfd < 0)
|
||||
{
|
||||
perror(devicename);
|
||||
exit(-1);
|
||||
}
|
||||
|
||||
if(argc > 2) {
|
||||
speed_spec *s;
|
||||
for(s = speeds; s->name; s++) {
|
||||
if(strcmp(s->name, argv[2]) == 0) {
|
||||
speed = s->flag;
|
||||
fprintf(stderr, "setting speed %s\n", s->name);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
fprintf(stderr, "C-a exit, C-x modem lines status\n");
|
||||
|
||||
tcgetattr(STDIN_FILENO,&oldkey);
|
||||
newkey.c_cflag = B9600 | CRTSCTS | CS8 | CLOCAL | CREAD;
|
||||
newkey.c_iflag = IGNPAR;
|
||||
newkey.c_oflag = 0;
|
||||
newkey.c_lflag = 0;
|
||||
newkey.c_cc[VMIN]=1;
|
||||
newkey.c_cc[VTIME]=0;
|
||||
tcflush(STDIN_FILENO, TCIFLUSH);
|
||||
tcsetattr(STDIN_FILENO,TCSANOW,&newkey);
|
||||
|
||||
|
||||
tcgetattr(comfd,&oldtio); // save current port settings
|
||||
newtio.c_cflag = speed | CS8 | CLOCAL | CREAD;
|
||||
newtio.c_iflag = IGNPAR;
|
||||
newtio.c_oflag = 0;
|
||||
newtio.c_lflag = 0;
|
||||
newtio.c_cc[VMIN]=1;
|
||||
newtio.c_cc[VTIME]=0;
|
||||
tcflush(comfd, TCIFLUSH);
|
||||
tcsetattr(comfd,TCSANOW,&newtio);
|
||||
|
||||
print_status(comfd);
|
||||
|
||||
while(!need_exit) {
|
||||
fd_set fds;
|
||||
int ret;
|
||||
|
||||
FD_ZERO(&fds);
|
||||
FD_SET(STDIN_FILENO, &fds);
|
||||
FD_SET(comfd, &fds);
|
||||
|
||||
|
||||
ret = select(comfd+1, &fds, NULL, NULL, NULL);
|
||||
if(ret == -1) {
|
||||
perror("select");
|
||||
} else if (ret > 0) {
|
||||
if(FD_ISSET(STDIN_FILENO, &fds)) {
|
||||
need_exit = transfer_byte(STDIN_FILENO, comfd, 1);
|
||||
}
|
||||
if(FD_ISSET(comfd, &fds)) {
|
||||
need_exit = transfer_byte(comfd, STDIN_FILENO, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
tcsetattr(comfd,TCSANOW,&oldtio);
|
||||
tcsetattr(STDIN_FILENO,TCSANOW,&oldkey);
|
||||
close(comfd);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int transfer_byte(int from, int to, int is_control) {
|
||||
char c;
|
||||
int ret;
|
||||
do {
|
||||
ret = read(from, &c, 1);
|
||||
} while (ret < 0 && errno == EINTR);
|
||||
if(ret == 1) {
|
||||
if(is_control) {
|
||||
if(c == '\x01') { // C-a
|
||||
return -1;
|
||||
} else if(c == '\x18') { // C-x
|
||||
print_status(to);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
while(write(to, &c, 1) == -1) {
|
||||
if(errno!=EAGAIN && errno!=EINTR) { perror("write failed"); break; }
|
||||
}
|
||||
} else {
|
||||
fprintf(stderr, "\nnothing to read. probably port disconnected.\n");
|
||||
return -2;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -436,7 +436,7 @@ while True:
|
||||
print("attempting reboot on %s..." % port)
|
||||
up.send_reboot()
|
||||
# wait for the reboot, without we might run into Serial I/O Error 5
|
||||
time.sleep(1.5)
|
||||
time.sleep(0.5)
|
||||
continue
|
||||
|
||||
try:
|
||||
|
||||
File diff suppressed because one or more lines are too long
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t componen
|
||||
* @brief Pack a ahrs message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param omegaIx X gyro drift estimate rad/s
|
||||
* @param omegaIy Y gyro drift estimate rad/s
|
||||
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t com
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ahrs struct into a message
|
||||
* @brief Encode a ahrs struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t compon
|
||||
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ahrs struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param ahrs C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ahrs_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
|
||||
{
|
||||
return mavlink_msg_ahrs_pack_chan(system_id, component_id, chan, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a ahrs message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -0,0 +1,419 @@
|
||||
// MESSAGE AIRSPEED_AUTOCAL PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL 174
|
||||
|
||||
typedef struct __mavlink_airspeed_autocal_t
|
||||
{
|
||||
float vx; ///< GPS velocity north m/s
|
||||
float vy; ///< GPS velocity east m/s
|
||||
float vz; ///< GPS velocity down m/s
|
||||
float diff_pressure; ///< Differential pressure pascals
|
||||
float EAS2TAS; ///< Estimated to true airspeed ratio
|
||||
float ratio; ///< Airspeed ratio
|
||||
float state_x; ///< EKF state x
|
||||
float state_y; ///< EKF state y
|
||||
float state_z; ///< EKF state z
|
||||
float Pax; ///< EKF Pax
|
||||
float Pby; ///< EKF Pby
|
||||
float Pcz; ///< EKF Pcz
|
||||
} mavlink_airspeed_autocal_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48
|
||||
#define MAVLINK_MSG_ID_174_LEN 48
|
||||
|
||||
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC 167
|
||||
#define MAVLINK_MSG_ID_174_CRC 167
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
|
||||
"AIRSPEED_AUTOCAL", \
|
||||
12, \
|
||||
{ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
|
||||
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
|
||||
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
|
||||
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
|
||||
{ "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
|
||||
{ "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
|
||||
{ "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
|
||||
{ "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
|
||||
{ "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
|
||||
{ "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
|
||||
{ "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
|
||||
{ "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a airspeed_autocal message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param vx GPS velocity north m/s
|
||||
* @param vy GPS velocity east m/s
|
||||
* @param vz GPS velocity down m/s
|
||||
* @param diff_pressure Differential pressure pascals
|
||||
* @param EAS2TAS Estimated to true airspeed ratio
|
||||
* @param ratio Airspeed ratio
|
||||
* @param state_x EKF state x
|
||||
* @param state_y EKF state y
|
||||
* @param state_z EKF state z
|
||||
* @param Pax EKF Pax
|
||||
* @param Pby EKF Pby
|
||||
* @param Pcz EKF Pcz
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_airspeed_autocal_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
|
||||
_mav_put_float(buf, 0, vx);
|
||||
_mav_put_float(buf, 4, vy);
|
||||
_mav_put_float(buf, 8, vz);
|
||||
_mav_put_float(buf, 12, diff_pressure);
|
||||
_mav_put_float(buf, 16, EAS2TAS);
|
||||
_mav_put_float(buf, 20, ratio);
|
||||
_mav_put_float(buf, 24, state_x);
|
||||
_mav_put_float(buf, 28, state_y);
|
||||
_mav_put_float(buf, 32, state_z);
|
||||
_mav_put_float(buf, 36, Pax);
|
||||
_mav_put_float(buf, 40, Pby);
|
||||
_mav_put_float(buf, 44, Pcz);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#else
|
||||
mavlink_airspeed_autocal_t packet;
|
||||
packet.vx = vx;
|
||||
packet.vy = vy;
|
||||
packet.vz = vz;
|
||||
packet.diff_pressure = diff_pressure;
|
||||
packet.EAS2TAS = EAS2TAS;
|
||||
packet.ratio = ratio;
|
||||
packet.state_x = state_x;
|
||||
packet.state_y = state_y;
|
||||
packet.state_z = state_z;
|
||||
packet.Pax = Pax;
|
||||
packet.Pby = Pby;
|
||||
packet.Pcz = Pcz;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a airspeed_autocal message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param vx GPS velocity north m/s
|
||||
* @param vy GPS velocity east m/s
|
||||
* @param vz GPS velocity down m/s
|
||||
* @param diff_pressure Differential pressure pascals
|
||||
* @param EAS2TAS Estimated to true airspeed ratio
|
||||
* @param ratio Airspeed ratio
|
||||
* @param state_x EKF state x
|
||||
* @param state_y EKF state y
|
||||
* @param state_z EKF state z
|
||||
* @param Pax EKF Pax
|
||||
* @param Pby EKF Pby
|
||||
* @param Pcz EKF Pcz
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_airspeed_autocal_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
|
||||
_mav_put_float(buf, 0, vx);
|
||||
_mav_put_float(buf, 4, vy);
|
||||
_mav_put_float(buf, 8, vz);
|
||||
_mav_put_float(buf, 12, diff_pressure);
|
||||
_mav_put_float(buf, 16, EAS2TAS);
|
||||
_mav_put_float(buf, 20, ratio);
|
||||
_mav_put_float(buf, 24, state_x);
|
||||
_mav_put_float(buf, 28, state_y);
|
||||
_mav_put_float(buf, 32, state_z);
|
||||
_mav_put_float(buf, 36, Pax);
|
||||
_mav_put_float(buf, 40, Pby);
|
||||
_mav_put_float(buf, 44, Pcz);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#else
|
||||
mavlink_airspeed_autocal_t packet;
|
||||
packet.vx = vx;
|
||||
packet.vy = vy;
|
||||
packet.vz = vz;
|
||||
packet.diff_pressure = diff_pressure;
|
||||
packet.EAS2TAS = EAS2TAS;
|
||||
packet.ratio = ratio;
|
||||
packet.state_x = state_x;
|
||||
packet.state_y = state_y;
|
||||
packet.state_z = state_z;
|
||||
packet.Pax = Pax;
|
||||
packet.Pby = Pby;
|
||||
packet.Pcz = Pcz;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a airspeed_autocal struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param airspeed_autocal C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_airspeed_autocal_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
|
||||
{
|
||||
return mavlink_msg_airspeed_autocal_pack(system_id, component_id, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a airspeed_autocal struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param airspeed_autocal C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_airspeed_autocal_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
|
||||
{
|
||||
return mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, chan, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a airspeed_autocal message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param vx GPS velocity north m/s
|
||||
* @param vy GPS velocity east m/s
|
||||
* @param vz GPS velocity down m/s
|
||||
* @param diff_pressure Differential pressure pascals
|
||||
* @param EAS2TAS Estimated to true airspeed ratio
|
||||
* @param ratio Airspeed ratio
|
||||
* @param state_x EKF state x
|
||||
* @param state_y EKF state y
|
||||
* @param state_z EKF state z
|
||||
* @param Pax EKF Pax
|
||||
* @param Pby EKF Pby
|
||||
* @param Pcz EKF Pcz
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_airspeed_autocal_send(mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
|
||||
_mav_put_float(buf, 0, vx);
|
||||
_mav_put_float(buf, 4, vy);
|
||||
_mav_put_float(buf, 8, vz);
|
||||
_mav_put_float(buf, 12, diff_pressure);
|
||||
_mav_put_float(buf, 16, EAS2TAS);
|
||||
_mav_put_float(buf, 20, ratio);
|
||||
_mav_put_float(buf, 24, state_x);
|
||||
_mav_put_float(buf, 28, state_y);
|
||||
_mav_put_float(buf, 32, state_z);
|
||||
_mav_put_float(buf, 36, Pax);
|
||||
_mav_put_float(buf, 40, Pby);
|
||||
_mav_put_float(buf, 44, Pcz);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_airspeed_autocal_t packet;
|
||||
packet.vx = vx;
|
||||
packet.vy = vy;
|
||||
packet.vz = vz;
|
||||
packet.diff_pressure = diff_pressure;
|
||||
packet.EAS2TAS = EAS2TAS;
|
||||
packet.ratio = ratio;
|
||||
packet.state_x = state_x;
|
||||
packet.state_y = state_y;
|
||||
packet.state_z = state_z;
|
||||
packet.Pax = Pax;
|
||||
packet.Pby = Pby;
|
||||
packet.Pcz = Pcz;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE AIRSPEED_AUTOCAL UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field vx from airspeed_autocal message
|
||||
*
|
||||
* @return GPS velocity north m/s
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_vx(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vy from airspeed_autocal message
|
||||
*
|
||||
* @return GPS velocity east m/s
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_vy(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vz from airspeed_autocal message
|
||||
*
|
||||
* @return GPS velocity down m/s
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_vz(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field diff_pressure from airspeed_autocal message
|
||||
*
|
||||
* @return Differential pressure pascals
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_diff_pressure(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field EAS2TAS from airspeed_autocal message
|
||||
*
|
||||
* @return Estimated to true airspeed ratio
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_EAS2TAS(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field ratio from airspeed_autocal message
|
||||
*
|
||||
* @return Airspeed ratio
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_ratio(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field state_x from airspeed_autocal message
|
||||
*
|
||||
* @return EKF state x
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_state_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field state_y from airspeed_autocal message
|
||||
*
|
||||
* @return EKF state y
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_state_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field state_z from airspeed_autocal message
|
||||
*
|
||||
* @return EKF state z
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_state_z(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field Pax from airspeed_autocal message
|
||||
*
|
||||
* @return EKF Pax
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_Pax(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field Pby from airspeed_autocal message
|
||||
*
|
||||
* @return EKF Pby
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_Pby(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 40);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field Pcz from airspeed_autocal message
|
||||
*
|
||||
* @return EKF Pcz
|
||||
*/
|
||||
static inline float mavlink_msg_airspeed_autocal_get_Pcz(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 44);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a airspeed_autocal message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param airspeed_autocal C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_airspeed_autocal_decode(const mavlink_message_t* msg, mavlink_airspeed_autocal_t* airspeed_autocal)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
airspeed_autocal->vx = mavlink_msg_airspeed_autocal_get_vx(msg);
|
||||
airspeed_autocal->vy = mavlink_msg_airspeed_autocal_get_vy(msg);
|
||||
airspeed_autocal->vz = mavlink_msg_airspeed_autocal_get_vz(msg);
|
||||
airspeed_autocal->diff_pressure = mavlink_msg_airspeed_autocal_get_diff_pressure(msg);
|
||||
airspeed_autocal->EAS2TAS = mavlink_msg_airspeed_autocal_get_EAS2TAS(msg);
|
||||
airspeed_autocal->ratio = mavlink_msg_airspeed_autocal_get_ratio(msg);
|
||||
airspeed_autocal->state_x = mavlink_msg_airspeed_autocal_get_state_x(msg);
|
||||
airspeed_autocal->state_y = mavlink_msg_airspeed_autocal_get_state_y(msg);
|
||||
airspeed_autocal->state_z = mavlink_msg_airspeed_autocal_get_state_z(msg);
|
||||
airspeed_autocal->Pax = mavlink_msg_airspeed_autocal_get_Pax(msg);
|
||||
airspeed_autocal->Pby = mavlink_msg_airspeed_autocal_get_Pby(msg);
|
||||
airspeed_autocal->Pcz = mavlink_msg_airspeed_autocal_get_Pcz(msg);
|
||||
#else
|
||||
memcpy(airspeed_autocal, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon
|
||||
* @brief Pack a ap_adc message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param adc1 ADC output 1
|
||||
* @param adc2 ADC output 2
|
||||
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ap_adc struct into a message
|
||||
* @brief Encode a ap_adc struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t comp
|
||||
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ap_adc struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param ap_adc C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ap_adc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
|
||||
{
|
||||
return mavlink_msg_ap_adc_pack_chan(system_id, component_id, chan, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a ap_adc message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t compon
|
||||
* @brief Pack a data16 message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param type data type
|
||||
* @param len data length
|
||||
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t c
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data16 struct into a message
|
||||
* @brief Encode a data16 struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t comp
|
||||
return mavlink_msg_data16_pack(system_id, component_id, msg, data16->type, data16->len, data16->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data16 struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param data16 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data16_t* data16)
|
||||
{
|
||||
return mavlink_msg_data16_pack_chan(system_id, component_id, chan, msg, data16->type, data16->len, data16->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a data16 message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t compon
|
||||
* @brief Pack a data32 message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param type data type
|
||||
* @param len data length
|
||||
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t c
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data32 struct into a message
|
||||
* @brief Encode a data32 struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t comp
|
||||
return mavlink_msg_data32_pack(system_id, component_id, msg, data32->type, data32->len, data32->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data32 struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param data32 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data32_t* data32)
|
||||
{
|
||||
return mavlink_msg_data32_pack_chan(system_id, component_id, chan, msg, data32->type, data32->len, data32->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a data32 message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t compon
|
||||
* @brief Pack a data64 message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param type data type
|
||||
* @param len data length
|
||||
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t c
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data64 struct into a message
|
||||
* @brief Encode a data64 struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t comp
|
||||
return mavlink_msg_data64_pack(system_id, component_id, msg, data64->type, data64->len, data64->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data64 struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param data64 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data64_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data64_t* data64)
|
||||
{
|
||||
return mavlink_msg_data64_pack_chan(system_id, component_id, chan, msg, data64->type, data64->len, data64->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a data64 message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t compon
|
||||
* @brief Pack a data96 message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param type data type
|
||||
* @param len data length
|
||||
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t c
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data96 struct into a message
|
||||
* @brief Encode a data96 struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t comp
|
||||
return mavlink_msg_data96_pack(system_id, component_id, msg, data96->type, data96->len, data96->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data96 struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param data96 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data96_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data96_t* data96)
|
||||
{
|
||||
return mavlink_msg_data96_pack_chan(system_id, component_id, chan, msg, data96->type, data96->len, data96->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a data96 message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin
|
||||
* @brief Pack a digicam_configure message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a digicam_configure struct into a message
|
||||
* @brief Encode a digicam_configure struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, u
|
||||
return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a digicam_configure struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param digicam_configure C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
|
||||
{
|
||||
return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a digicam_configure message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8
|
||||
* @brief Pack a digicam_control message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id,
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a digicam_control struct into a message
|
||||
* @brief Encode a digicam_control struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uin
|
||||
return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a digicam_control struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param digicam_control C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_digicam_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
|
||||
{
|
||||
return mavlink_msg_digicam_control_pack_chan(system_id, component_id, chan, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a digicam_control message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uin
|
||||
* @brief Pack a fence_fetch_point message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_fetch_point struct into a message
|
||||
* @brief Encode a fence_fetch_point struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, u
|
||||
return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_fetch_point struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param fence_fetch_point C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_fence_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
|
||||
{
|
||||
return mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, chan, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a fence_fetch_point message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
|
||||
* @brief Pack a fence_point message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_point struct into a message
|
||||
* @brief Encode a fence_point struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t
|
||||
return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_point struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param fence_point C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
|
||||
{
|
||||
return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a fence_point message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
|
||||
* @brief Pack a fence_status message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param breach_status 0 if currently inside fence, 1 if outside
|
||||
* @param breach_count number of fence breaches
|
||||
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_status struct into a message
|
||||
* @brief Encode a fence_status struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_
|
||||
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a fence_status struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param fence_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
|
||||
{
|
||||
return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a fence_status message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t comp
|
||||
* @brief Pack a hwstatus message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param Vcc board voltage (mV)
|
||||
* @param I2Cerr I2C error count
|
||||
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a hwstatus struct into a message
|
||||
* @brief Encode a hwstatus struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t co
|
||||
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a hwstatus struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param hwstatus C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_hwstatus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
|
||||
{
|
||||
return mavlink_msg_hwstatus_pack_chan(system_id, component_id, chan, msg, hwstatus->Vcc, hwstatus->I2Cerr);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a hwstatus message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t
|
||||
* @brief Pack a limits_status message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param limits_state state of AP_Limits, (see enum LimitState, LIMITS_STATE)
|
||||
* @param last_trigger time of last breach in milliseconds since boot
|
||||
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, ui
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a limits_status struct into a message
|
||||
* @brief Encode a limits_status struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8
|
||||
return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a limits_status struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param limits_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
|
||||
{
|
||||
return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a limits_status message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t compo
|
||||
* @brief Pack a meminfo message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param brkval heap top
|
||||
* @param freemem free memory
|
||||
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a meminfo struct into a message
|
||||
* @brief Encode a meminfo struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t com
|
||||
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a meminfo struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param meminfo C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_meminfo_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
|
||||
{
|
||||
return mavlink_msg_meminfo_pack_chan(system_id, component_id, chan, msg, meminfo->brkval, meminfo->freemem);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a meminfo message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8
|
||||
* @brief Pack a mount_configure message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id,
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_configure struct into a message
|
||||
* @brief Encode a mount_configure struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uin
|
||||
return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_configure struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param mount_configure C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_mount_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
|
||||
{
|
||||
return mavlink_msg_mount_configure_pack_chan(system_id, component_id, chan, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a mount_configure message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t
|
||||
* @brief Pack a mount_control message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_control struct into a message
|
||||
* @brief Encode a mount_control struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8
|
||||
return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_control struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param mount_control C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_mount_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
|
||||
{
|
||||
return mavlink_msg_mount_control_pack_chan(system_id, component_id, chan, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a mount_control message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t
|
||||
* @brief Pack a mount_status message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_status struct into a message
|
||||
* @brief Encode a mount_status struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_
|
||||
return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a mount_status struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param mount_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_mount_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
|
||||
{
|
||||
return mavlink_msg_mount_status_pack_chan(system_id, component_id, chan, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a mount_status message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
|
||||
* @brief Pack a radio message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param rssi local signal strength
|
||||
* @param remrssi remote signal strength
|
||||
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a radio struct into a message
|
||||
* @brief Encode a radio struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
|
||||
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a radio struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param radio C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_radio_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_t* radio)
|
||||
{
|
||||
return mavlink_msg_radio_pack_chan(system_id, component_id, chan, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a radio message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t c
|
||||
* @brief Pack a rangefinder message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param distance distance in meters
|
||||
* @param voltage raw voltage if available, zero otherwise
|
||||
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a rangefinder struct into a message
|
||||
* @brief Encode a rangefinder struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t
|
||||
return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a rangefinder struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param rangefinder C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_rangefinder_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
|
||||
{
|
||||
return mavlink_msg_rangefinder_pack_chan(system_id, component_id, chan, msg, rangefinder->distance, rangefinder->voltage);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a rangefinder message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_
|
||||
* @brief Pack a sensor_offsets message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param mag_ofs_x magnetometer X offset
|
||||
* @param mag_ofs_y magnetometer Y offset
|
||||
@@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a sensor_offsets struct into a message
|
||||
* @brief Encode a sensor_offsets struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -189,6 +189,20 @@ static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint
|
||||
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a sensor_offsets struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param sensor_offsets C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_sensor_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
|
||||
{
|
||||
return mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, chan, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a sensor_offsets message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8
|
||||
* @brief Pack a set_mag_offsets message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id,
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a set_mag_offsets struct into a message
|
||||
* @brief Encode a set_mag_offsets struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uin
|
||||
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a set_mag_offsets struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param set_mag_offsets C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
|
||||
{
|
||||
return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a set_mag_offsets message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -13,15 +13,15 @@ typedef struct __mavlink_simstate_t
|
||||
float xgyro; ///< Angular speed around X axis rad/s
|
||||
float ygyro; ///< Angular speed around Y axis rad/s
|
||||
float zgyro; ///< Angular speed around Z axis rad/s
|
||||
float lat; ///< Latitude in degrees
|
||||
float lng; ///< Longitude in degrees
|
||||
int32_t lat; ///< Latitude in degrees * 1E7
|
||||
int32_t lng; ///< Longitude in degrees * 1E7
|
||||
} mavlink_simstate_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_SIMSTATE_LEN 44
|
||||
#define MAVLINK_MSG_ID_164_LEN 44
|
||||
|
||||
#define MAVLINK_MSG_ID_SIMSTATE_CRC 111
|
||||
#define MAVLINK_MSG_ID_164_CRC 111
|
||||
#define MAVLINK_MSG_ID_SIMSTATE_CRC 154
|
||||
#define MAVLINK_MSG_ID_164_CRC 154
|
||||
|
||||
|
||||
|
||||
@@ -37,8 +37,8 @@ typedef struct __mavlink_simstate_t
|
||||
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
|
||||
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
|
||||
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
|
||||
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
|
||||
{ "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
|
||||
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
|
||||
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
@@ -58,12 +58,12 @@ typedef struct __mavlink_simstate_t
|
||||
* @param xgyro Angular speed around X axis rad/s
|
||||
* @param ygyro Angular speed around Y axis rad/s
|
||||
* @param zgyro Angular speed around Z axis rad/s
|
||||
* @param lat Latitude in degrees
|
||||
* @param lng Longitude in degrees
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng)
|
||||
float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
|
||||
@@ -76,8 +76,8 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
|
||||
_mav_put_float(buf, 24, xgyro);
|
||||
_mav_put_float(buf, 28, ygyro);
|
||||
_mav_put_float(buf, 32, zgyro);
|
||||
_mav_put_float(buf, 36, lat);
|
||||
_mav_put_float(buf, 40, lng);
|
||||
_mav_put_int32_t(buf, 36, lat);
|
||||
_mav_put_int32_t(buf, 40, lng);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
|
||||
#else
|
||||
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
|
||||
* @brief Pack a simstate message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
@@ -120,13 +120,13 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
|
||||
* @param xgyro Angular speed around X axis rad/s
|
||||
* @param ygyro Angular speed around Y axis rad/s
|
||||
* @param zgyro Angular speed around Z axis rad/s
|
||||
* @param lat Latitude in degrees
|
||||
* @param lng Longitude in degrees
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lng)
|
||||
float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int32_t lat,int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
|
||||
@@ -139,8 +139,8 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
|
||||
_mav_put_float(buf, 24, xgyro);
|
||||
_mav_put_float(buf, 28, ygyro);
|
||||
_mav_put_float(buf, 32, zgyro);
|
||||
_mav_put_float(buf, 36, lat);
|
||||
_mav_put_float(buf, 40, lng);
|
||||
_mav_put_int32_t(buf, 36, lat);
|
||||
_mav_put_int32_t(buf, 40, lng);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
|
||||
#else
|
||||
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a simstate struct into a message
|
||||
* @brief Encode a simstate struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co
|
||||
return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a simstate struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param simstate C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_simstate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
|
||||
{
|
||||
return mavlink_msg_simstate_pack_chan(system_id, component_id, chan, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a simstate message
|
||||
* @param chan MAVLink channel to send the message
|
||||
@@ -194,12 +208,12 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co
|
||||
* @param xgyro Angular speed around X axis rad/s
|
||||
* @param ygyro Angular speed around Y axis rad/s
|
||||
* @param zgyro Angular speed around Z axis rad/s
|
||||
* @param lat Latitude in degrees
|
||||
* @param lng Longitude in degrees
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng)
|
||||
static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
|
||||
@@ -212,8 +226,8 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll,
|
||||
_mav_put_float(buf, 24, xgyro);
|
||||
_mav_put_float(buf, 28, ygyro);
|
||||
_mav_put_float(buf, 32, zgyro);
|
||||
_mav_put_float(buf, 36, lat);
|
||||
_mav_put_float(buf, 40, lng);
|
||||
_mav_put_int32_t(buf, 36, lat);
|
||||
_mav_put_int32_t(buf, 40, lng);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
|
||||
@@ -340,21 +354,21 @@ static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
|
||||
/**
|
||||
* @brief Get field lat from simstate message
|
||||
*
|
||||
* @return Latitude in degrees
|
||||
* @return Latitude in degrees * 1E7
|
||||
*/
|
||||
static inline float mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 36);
|
||||
return _MAV_RETURN_int32_t(msg, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lng from simstate message
|
||||
*
|
||||
* @return Longitude in degrees
|
||||
* @return Longitude in degrees * 1E7
|
||||
*/
|
||||
static inline float mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 40);
|
||||
return _MAV_RETURN_int32_t(msg, 40);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t componen
|
||||
* @brief Pack a wind message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param direction wind direction that wind is coming from (degrees)
|
||||
* @param speed wind speed in ground plane (m/s)
|
||||
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t com
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a wind struct into a message
|
||||
* @brief Encode a wind struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t compon
|
||||
return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a wind struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param wind C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_t* wind)
|
||||
{
|
||||
return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a wind message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -738,8 +738,8 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli
|
||||
185.0,
|
||||
213.0,
|
||||
241.0,
|
||||
269.0,
|
||||
297.0,
|
||||
963499336,
|
||||
963499544,
|
||||
};
|
||||
mavlink_simstate_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
@@ -1225,6 +1225,71 @@ static void mavlink_test_rangefinder(uint8_t system_id, uint8_t component_id, ma
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_airspeed_autocal(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_airspeed_autocal_t packet_in = {
|
||||
17.0,
|
||||
45.0,
|
||||
73.0,
|
||||
101.0,
|
||||
129.0,
|
||||
157.0,
|
||||
185.0,
|
||||
213.0,
|
||||
241.0,
|
||||
269.0,
|
||||
297.0,
|
||||
325.0,
|
||||
};
|
||||
mavlink_airspeed_autocal_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.vx = packet_in.vx;
|
||||
packet1.vy = packet_in.vy;
|
||||
packet1.vz = packet_in.vz;
|
||||
packet1.diff_pressure = packet_in.diff_pressure;
|
||||
packet1.EAS2TAS = packet_in.EAS2TAS;
|
||||
packet1.ratio = packet_in.ratio;
|
||||
packet1.state_x = packet_in.state_x;
|
||||
packet1.state_y = packet_in.state_y;
|
||||
packet1.state_z = packet_in.state_z;
|
||||
packet1.Pax = packet_in.Pax;
|
||||
packet1.Pby = packet_in.Pby;
|
||||
packet1.Pcz = packet_in.Pcz;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_airspeed_autocal_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_airspeed_autocal_pack(system_id, component_id, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
|
||||
mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
|
||||
mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_airspeed_autocal_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_airspeed_autocal_send(MAVLINK_COMM_1 , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
|
||||
mavlink_msg_airspeed_autocal_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
|
||||
@@ -1250,6 +1315,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
||||
mavlink_test_data64(system_id, component_id, last_msg);
|
||||
mavlink_test_data96(system_id, component_id, last_msg);
|
||||
mavlink_test_rangefinder(system_id, component_id, last_msg);
|
||||
mavlink_test_airspeed_autocal(system_id, component_id, last_msg);
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 4 13:11:17 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Sep 10 23:49:25 2013"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
|
||||
|
||||
@@ -30,6 +30,30 @@ extern "C" {
|
||||
// ENUM DEFINITIONS
|
||||
|
||||
|
||||
/** @brief Available operating modes/statuses for AutoQuad flight controller.
|
||||
Bitmask up to 32 bits. Low side bits for base modes, high side for
|
||||
additional active features/modifiers/constraints. */
|
||||
#ifndef HAVE_ENUM_AUTOQUAD_NAV_STATUS
|
||||
#define HAVE_ENUM_AUTOQUAD_NAV_STATUS
|
||||
enum AUTOQUAD_NAV_STATUS
|
||||
{
|
||||
AQ_NAV_STATUS_INIT=0, /* System is initializing | */
|
||||
AQ_NAV_STATUS_STANDBY=1, /* System is standing by, not active | */
|
||||
AQ_NAV_STATUS_MANUAL=2, /* Stabilized, under full manual control | */
|
||||
AQ_NAV_STATUS_ALTHOLD=4, /* Altitude hold engaged | */
|
||||
AQ_NAV_STATUS_POSHOLD=8, /* Position hold engaged | */
|
||||
AQ_NAV_STATUS_DVH=16, /* Dynamic Velocity Hold is active | */
|
||||
AQ_NAV_STATUS_MISSION=32, /* Autonomous mission execution mode | */
|
||||
AQ_NAV_STATUS_CEILING_REACHED=67108864, /* Craft is at ceiling altitude | */
|
||||
AQ_NAV_STATUS_CEILING=134217728, /* Ceiling altitude is set | */
|
||||
AQ_NAV_STATUS_HF_DYNAMIC=268435456, /* Heading-Free dynamic mode active | */
|
||||
AQ_NAV_STATUS_HF_LOCKED=536870912, /* Heading-Free locked mode active | */
|
||||
AQ_NAV_STATUS_RTH=1073741824, /* Automatic Return to Home is active | */
|
||||
AQ_NAV_STATUS_FAILSAFE=2147483648, /* System is in failsafe recovery mode | */
|
||||
AUTOQUAD_NAV_STATUS_ENUM_END=2147483649, /* | */
|
||||
};
|
||||
#endif
|
||||
|
||||
/** @brief */
|
||||
#ifndef HAVE_ENUM_MAV_CMD
|
||||
#define HAVE_ENUM_MAV_CMD
|
||||
@@ -63,6 +87,7 @@ enum MAV_CMD
|
||||
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
|
||||
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
|
||||
@@ -71,7 +96,8 @@ enum MAV_CMD
|
||||
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
|
||||
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
||||
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
||||
MAV_CMD_ENUM_END=401, /* | */
|
||||
MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
||||
MAV_CMD_ENUM_END=501, /* | */
|
||||
};
|
||||
#endif
|
||||
|
||||
|
||||
@@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_
|
||||
* @brief Pack a aq_telemetry_f message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param Index Index of message
|
||||
* @param value1 value1
|
||||
@@ -249,7 +249,7 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, u
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a aq_telemetry_f struct into a message
|
||||
* @brief Encode a aq_telemetry_f struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -261,6 +261,20 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_encode(uint8_t system_id, uint
|
||||
return mavlink_msg_aq_telemetry_f_pack(system_id, component_id, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a aq_telemetry_f struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param aq_telemetry_f C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_aq_telemetry_f_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f)
|
||||
{
|
||||
return mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, chan, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a aq_telemetry_f message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Thu Jul 4 13:11:37 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Sep 10 23:49:36 2013"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
|
||||
|
||||
@@ -260,6 +260,7 @@ enum MAV_CMD
|
||||
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
|
||||
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
|
||||
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
|
||||
@@ -268,7 +269,8 @@ enum MAV_CMD
|
||||
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
|
||||
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
||||
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
||||
MAV_CMD_ENUM_END=401, /* | */
|
||||
MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
||||
MAV_CMD_ENUM_END=501, /* | */
|
||||
};
|
||||
#endif
|
||||
|
||||
|
||||
@@ -1,276 +0,0 @@
|
||||
// MESSAGE 6DOF_SETPOINT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_6DOF_SETPOINT 149
|
||||
|
||||
typedef struct __mavlink_6dof_setpoint_t
|
||||
{
|
||||
float trans_x; ///< Translational Component in x
|
||||
float trans_y; ///< Translational Component in y
|
||||
float trans_z; ///< Translational Component in z
|
||||
float rot_x; ///< Rotational Component in x
|
||||
float rot_y; ///< Rotational Component in y
|
||||
float rot_z; ///< Rotational Component in z
|
||||
uint8_t target_system; ///< System ID
|
||||
} mavlink_6dof_setpoint_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_6DOF_SETPOINT_LEN 25
|
||||
#define MAVLINK_MSG_ID_149_LEN 25
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_6DOF_SETPOINT { \
|
||||
"6DOF_SETPOINT", \
|
||||
7, \
|
||||
{ { "trans_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_6dof_setpoint_t, trans_x) }, \
|
||||
{ "trans_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_6dof_setpoint_t, trans_y) }, \
|
||||
{ "trans_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_6dof_setpoint_t, trans_z) }, \
|
||||
{ "rot_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_6dof_setpoint_t, rot_x) }, \
|
||||
{ "rot_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_6dof_setpoint_t, rot_y) }, \
|
||||
{ "rot_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_6dof_setpoint_t, rot_z) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_6dof_setpoint_t, target_system) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a 6dof_setpoint message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param trans_x Translational Component in x
|
||||
* @param trans_y Translational Component in y
|
||||
* @param trans_z Translational Component in z
|
||||
* @param rot_x Rotational Component in x
|
||||
* @param rot_y Rotational Component in y
|
||||
* @param rot_z Rotational Component in z
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_6dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[25];
|
||||
_mav_put_float(buf, 0, trans_x);
|
||||
_mav_put_float(buf, 4, trans_y);
|
||||
_mav_put_float(buf, 8, trans_z);
|
||||
_mav_put_float(buf, 12, rot_x);
|
||||
_mav_put_float(buf, 16, rot_y);
|
||||
_mav_put_float(buf, 20, rot_z);
|
||||
_mav_put_uint8_t(buf, 24, target_system);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
|
||||
#else
|
||||
mavlink_6dof_setpoint_t packet;
|
||||
packet.trans_x = trans_x;
|
||||
packet.trans_y = trans_y;
|
||||
packet.trans_z = trans_z;
|
||||
packet.rot_x = rot_x;
|
||||
packet.rot_y = rot_y;
|
||||
packet.rot_z = rot_z;
|
||||
packet.target_system = target_system;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
|
||||
return mavlink_finalize_message(msg, system_id, component_id, 25, 144);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a 6dof_setpoint message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param trans_x Translational Component in x
|
||||
* @param trans_y Translational Component in y
|
||||
* @param trans_z Translational Component in z
|
||||
* @param rot_x Rotational Component in x
|
||||
* @param rot_y Rotational Component in y
|
||||
* @param rot_z Rotational Component in z
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_6dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[25];
|
||||
_mav_put_float(buf, 0, trans_x);
|
||||
_mav_put_float(buf, 4, trans_y);
|
||||
_mav_put_float(buf, 8, trans_z);
|
||||
_mav_put_float(buf, 12, rot_x);
|
||||
_mav_put_float(buf, 16, rot_y);
|
||||
_mav_put_float(buf, 20, rot_z);
|
||||
_mav_put_uint8_t(buf, 24, target_system);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
|
||||
#else
|
||||
mavlink_6dof_setpoint_t packet;
|
||||
packet.trans_x = trans_x;
|
||||
packet.trans_y = trans_y;
|
||||
packet.trans_z = trans_z;
|
||||
packet.rot_x = rot_x;
|
||||
packet.rot_y = rot_y;
|
||||
packet.rot_z = rot_z;
|
||||
packet.target_system = target_system;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 144);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a 6dof_setpoint struct into a message
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param 6dof_setpoint C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_6dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_6dof_setpoint_t* 6dof_setpoint)
|
||||
{
|
||||
return mavlink_msg_6dof_setpoint_pack(system_id, component_id, msg, 6dof_setpoint->target_system, 6dof_setpoint->trans_x, 6dof_setpoint->trans_y, 6dof_setpoint->trans_z, 6dof_setpoint->rot_x, 6dof_setpoint->rot_y, 6dof_setpoint->rot_z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a 6dof_setpoint message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param trans_x Translational Component in x
|
||||
* @param trans_y Translational Component in y
|
||||
* @param trans_z Translational Component in z
|
||||
* @param rot_x Rotational Component in x
|
||||
* @param rot_y Rotational Component in y
|
||||
* @param rot_z Rotational Component in z
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_6dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[25];
|
||||
_mav_put_float(buf, 0, trans_x);
|
||||
_mav_put_float(buf, 4, trans_y);
|
||||
_mav_put_float(buf, 8, trans_z);
|
||||
_mav_put_float(buf, 12, rot_x);
|
||||
_mav_put_float(buf, 16, rot_y);
|
||||
_mav_put_float(buf, 20, rot_z);
|
||||
_mav_put_uint8_t(buf, 24, target_system);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, buf, 25, 144);
|
||||
#else
|
||||
mavlink_6dof_setpoint_t packet;
|
||||
packet.trans_x = trans_x;
|
||||
packet.trans_y = trans_y;
|
||||
packet.trans_z = trans_z;
|
||||
packet.rot_x = rot_x;
|
||||
packet.rot_y = rot_y;
|
||||
packet.rot_z = rot_z;
|
||||
packet.target_system = target_system;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, (const char *)&packet, 25, 144);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE 6DOF_SETPOINT UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from 6dof_setpoint message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_6dof_setpoint_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field trans_x from 6dof_setpoint message
|
||||
*
|
||||
* @return Translational Component in x
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_trans_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field trans_y from 6dof_setpoint message
|
||||
*
|
||||
* @return Translational Component in y
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_trans_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field trans_z from 6dof_setpoint message
|
||||
*
|
||||
* @return Translational Component in z
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_trans_z(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field rot_x from 6dof_setpoint message
|
||||
*
|
||||
* @return Rotational Component in x
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_rot_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field rot_y from 6dof_setpoint message
|
||||
*
|
||||
* @return Rotational Component in y
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_rot_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field rot_z from 6dof_setpoint message
|
||||
*
|
||||
* @return Rotational Component in z
|
||||
*/
|
||||
static inline float mavlink_msg_6dof_setpoint_get_rot_z(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a 6dof_setpoint message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param 6dof_setpoint C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_6dof_setpoint_decode(const mavlink_message_t* msg, mavlink_6dof_setpoint_t* 6dof_setpoint)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
6dof_setpoint->trans_x = mavlink_msg_6dof_setpoint_get_trans_x(msg);
|
||||
6dof_setpoint->trans_y = mavlink_msg_6dof_setpoint_get_trans_y(msg);
|
||||
6dof_setpoint->trans_z = mavlink_msg_6dof_setpoint_get_trans_z(msg);
|
||||
6dof_setpoint->rot_x = mavlink_msg_6dof_setpoint_get_rot_x(msg);
|
||||
6dof_setpoint->rot_y = mavlink_msg_6dof_setpoint_get_rot_y(msg);
|
||||
6dof_setpoint->rot_z = mavlink_msg_6dof_setpoint_get_rot_z(msg);
|
||||
6dof_setpoint->target_system = mavlink_msg_6dof_setpoint_get_target_system(msg);
|
||||
#else
|
||||
memcpy(6dof_setpoint, _MAV_PAYLOAD(msg), 25);
|
||||
#endif
|
||||
}
|
||||
@@ -1,320 +0,0 @@
|
||||
// MESSAGE 8DOF_SETPOINT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_8DOF_SETPOINT 148
|
||||
|
||||
typedef struct __mavlink_8dof_setpoint_t
|
||||
{
|
||||
float val1; ///< Value 1
|
||||
float val2; ///< Value 2
|
||||
float val3; ///< Value 3
|
||||
float val4; ///< Value 4
|
||||
float val5; ///< Value 5
|
||||
float val6; ///< Value 6
|
||||
float val7; ///< Value 7
|
||||
float val8; ///< Value 8
|
||||
uint8_t target_system; ///< System ID
|
||||
} mavlink_8dof_setpoint_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_8DOF_SETPOINT_LEN 33
|
||||
#define MAVLINK_MSG_ID_148_LEN 33
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_8DOF_SETPOINT { \
|
||||
"8DOF_SETPOINT", \
|
||||
9, \
|
||||
{ { "val1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_8dof_setpoint_t, val1) }, \
|
||||
{ "val2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_8dof_setpoint_t, val2) }, \
|
||||
{ "val3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_8dof_setpoint_t, val3) }, \
|
||||
{ "val4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_8dof_setpoint_t, val4) }, \
|
||||
{ "val5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_8dof_setpoint_t, val5) }, \
|
||||
{ "val6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_8dof_setpoint_t, val6) }, \
|
||||
{ "val7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_8dof_setpoint_t, val7) }, \
|
||||
{ "val8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_8dof_setpoint_t, val8) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_8dof_setpoint_t, target_system) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a 8dof_setpoint message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param val1 Value 1
|
||||
* @param val2 Value 2
|
||||
* @param val3 Value 3
|
||||
* @param val4 Value 4
|
||||
* @param val5 Value 5
|
||||
* @param val6 Value 6
|
||||
* @param val7 Value 7
|
||||
* @param val8 Value 8
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_8dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[33];
|
||||
_mav_put_float(buf, 0, val1);
|
||||
_mav_put_float(buf, 4, val2);
|
||||
_mav_put_float(buf, 8, val3);
|
||||
_mav_put_float(buf, 12, val4);
|
||||
_mav_put_float(buf, 16, val5);
|
||||
_mav_put_float(buf, 20, val6);
|
||||
_mav_put_float(buf, 24, val7);
|
||||
_mav_put_float(buf, 28, val8);
|
||||
_mav_put_uint8_t(buf, 32, target_system);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
|
||||
#else
|
||||
mavlink_8dof_setpoint_t packet;
|
||||
packet.val1 = val1;
|
||||
packet.val2 = val2;
|
||||
packet.val3 = val3;
|
||||
packet.val4 = val4;
|
||||
packet.val5 = val5;
|
||||
packet.val6 = val6;
|
||||
packet.val7 = val7;
|
||||
packet.val8 = val8;
|
||||
packet.target_system = target_system;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
|
||||
return mavlink_finalize_message(msg, system_id, component_id, 33, 42);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a 8dof_setpoint message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param val1 Value 1
|
||||
* @param val2 Value 2
|
||||
* @param val3 Value 3
|
||||
* @param val4 Value 4
|
||||
* @param val5 Value 5
|
||||
* @param val6 Value 6
|
||||
* @param val7 Value 7
|
||||
* @param val8 Value 8
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_8dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[33];
|
||||
_mav_put_float(buf, 0, val1);
|
||||
_mav_put_float(buf, 4, val2);
|
||||
_mav_put_float(buf, 8, val3);
|
||||
_mav_put_float(buf, 12, val4);
|
||||
_mav_put_float(buf, 16, val5);
|
||||
_mav_put_float(buf, 20, val6);
|
||||
_mav_put_float(buf, 24, val7);
|
||||
_mav_put_float(buf, 28, val8);
|
||||
_mav_put_uint8_t(buf, 32, target_system);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
|
||||
#else
|
||||
mavlink_8dof_setpoint_t packet;
|
||||
packet.val1 = val1;
|
||||
packet.val2 = val2;
|
||||
packet.val3 = val3;
|
||||
packet.val4 = val4;
|
||||
packet.val5 = val5;
|
||||
packet.val6 = val6;
|
||||
packet.val7 = val7;
|
||||
packet.val8 = val8;
|
||||
packet.target_system = target_system;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 42);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a 8dof_setpoint struct into a message
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param 8dof_setpoint C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_8dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_8dof_setpoint_t* 8dof_setpoint)
|
||||
{
|
||||
return mavlink_msg_8dof_setpoint_pack(system_id, component_id, msg, 8dof_setpoint->target_system, 8dof_setpoint->val1, 8dof_setpoint->val2, 8dof_setpoint->val3, 8dof_setpoint->val4, 8dof_setpoint->val5, 8dof_setpoint->val6, 8dof_setpoint->val7, 8dof_setpoint->val8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a 8dof_setpoint message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param val1 Value 1
|
||||
* @param val2 Value 2
|
||||
* @param val3 Value 3
|
||||
* @param val4 Value 4
|
||||
* @param val5 Value 5
|
||||
* @param val6 Value 6
|
||||
* @param val7 Value 7
|
||||
* @param val8 Value 8
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_8dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[33];
|
||||
_mav_put_float(buf, 0, val1);
|
||||
_mav_put_float(buf, 4, val2);
|
||||
_mav_put_float(buf, 8, val3);
|
||||
_mav_put_float(buf, 12, val4);
|
||||
_mav_put_float(buf, 16, val5);
|
||||
_mav_put_float(buf, 20, val6);
|
||||
_mav_put_float(buf, 24, val7);
|
||||
_mav_put_float(buf, 28, val8);
|
||||
_mav_put_uint8_t(buf, 32, target_system);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, buf, 33, 42);
|
||||
#else
|
||||
mavlink_8dof_setpoint_t packet;
|
||||
packet.val1 = val1;
|
||||
packet.val2 = val2;
|
||||
packet.val3 = val3;
|
||||
packet.val4 = val4;
|
||||
packet.val5 = val5;
|
||||
packet.val6 = val6;
|
||||
packet.val7 = val7;
|
||||
packet.val8 = val8;
|
||||
packet.target_system = target_system;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, (const char *)&packet, 33, 42);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE 8DOF_SETPOINT UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from 8dof_setpoint message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_8dof_setpoint_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val1 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 1
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val1(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val2 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 2
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val2(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val3 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 3
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val3(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val4 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 4
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val4(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val5 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 5
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val5(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val6 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 6
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val6(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val7 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 7
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val7(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field val8 from 8dof_setpoint message
|
||||
*
|
||||
* @return Value 8
|
||||
*/
|
||||
static inline float mavlink_msg_8dof_setpoint_get_val8(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a 8dof_setpoint message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param 8dof_setpoint C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_8dof_setpoint_decode(const mavlink_message_t* msg, mavlink_8dof_setpoint_t* 8dof_setpoint)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
8dof_setpoint->val1 = mavlink_msg_8dof_setpoint_get_val1(msg);
|
||||
8dof_setpoint->val2 = mavlink_msg_8dof_setpoint_get_val2(msg);
|
||||
8dof_setpoint->val3 = mavlink_msg_8dof_setpoint_get_val3(msg);
|
||||
8dof_setpoint->val4 = mavlink_msg_8dof_setpoint_get_val4(msg);
|
||||
8dof_setpoint->val5 = mavlink_msg_8dof_setpoint_get_val5(msg);
|
||||
8dof_setpoint->val6 = mavlink_msg_8dof_setpoint_get_val6(msg);
|
||||
8dof_setpoint->val7 = mavlink_msg_8dof_setpoint_get_val7(msg);
|
||||
8dof_setpoint->val8 = mavlink_msg_8dof_setpoint_get_val8(msg);
|
||||
8dof_setpoint->target_system = mavlink_msg_8dof_setpoint_get_target_system(msg);
|
||||
#else
|
||||
memcpy(8dof_setpoint, _MAV_PAYLOAD(msg), 33);
|
||||
#endif
|
||||
}
|
||||
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
|
||||
* @brief Pack a attitude message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param roll Roll angle (rad, -pi..+pi)
|
||||
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a attitude struct into a message
|
||||
* @brief Encode a attitude struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
|
||||
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a attitude struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param attitude C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
|
||||
{
|
||||
return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a attitude message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
|
||||
* @brief Pack a attitude_quaternion message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param q1 Quaternion component 1
|
||||
@@ -145,7 +145,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a attitude_quaternion struct into a message
|
||||
* @brief Encode a attitude_quaternion struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -157,6 +157,20 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id,
|
||||
return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a attitude_quaternion struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param attitude_quaternion C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
|
||||
{
|
||||
return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a attitude_quaternion message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp
|
||||
* @brief Pack a auth_key message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param key key
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a auth_key struct into a message
|
||||
* @brief Encode a auth_key struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -101,6 +101,20 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co
|
||||
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a auth_key struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param auth_key C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
|
||||
{
|
||||
return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a auth_key message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
|
||||
* @brief Pack a battery_status message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param accu_id Accupack ID
|
||||
* @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
|
||||
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a battery_status struct into a message
|
||||
* @brief Encode a battery_status struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint
|
||||
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->battery_remaining);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a battery_status struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param battery_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
|
||||
{
|
||||
return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->battery_remaining);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a battery_status message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i
|
||||
* @brief Pack a change_operator_control message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System the GCS requests control for
|
||||
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
|
||||
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a change_operator_control struct into a message
|
||||
* @brief Encode a change_operator_control struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system
|
||||
return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a change_operator_control struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param change_operator_control C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
|
||||
{
|
||||
return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a change_operator_control message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst
|
||||
* @brief Pack a change_operator_control_ack message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gcs_system_id ID of the GCS this message
|
||||
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
|
||||
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a change_operator_control_ack struct into a message
|
||||
* @brief Encode a change_operator_control_ack struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy
|
||||
return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a change_operator_control_ack struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param change_operator_control_ack C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
|
||||
{
|
||||
return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a change_operator_control_ack message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
|
||||
* @brief Pack a command_ack message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param command Command ID, as defined by MAV_CMD enum.
|
||||
* @param result See MAV_RESULT enum
|
||||
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a command_ack struct into a message
|
||||
* @brief Encode a command_ack struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
|
||||
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a command_ack struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param command_ack C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
|
||||
{
|
||||
return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a command_ack message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t
|
||||
* @brief Pack a command_long message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System which should execute the command
|
||||
* @param target_component Component which should execute the command, 0 for all components
|
||||
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uin
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a command_long struct into a message
|
||||
* @brief Encode a command_long struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_
|
||||
return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a command_long struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param command_long C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
|
||||
{
|
||||
return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a command_long message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c
|
||||
* @brief Pack a data_stream message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param stream_id The ID of the requested data stream
|
||||
* @param message_rate The requested interval between two messages of this type
|
||||
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data_stream struct into a message
|
||||
* @brief Encode a data_stream struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t
|
||||
return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a data_stream struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param data_stream C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream)
|
||||
{
|
||||
return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a data_stream message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
|
||||
* @brief Pack a debug message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param ind index of debug variable
|
||||
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a debug struct into a message
|
||||
* @brief Encode a debug struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
|
||||
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a debug struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param debug C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug)
|
||||
{
|
||||
return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a debug message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
|
||||
* @brief Pack a debug_vect message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param name Name
|
||||
* @param time_usec Timestamp
|
||||
@@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a debug_vect struct into a message
|
||||
* @brief Encode a debug_vect struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -129,6 +129,20 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
|
||||
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a debug_vect struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param debug_vect C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
|
||||
{
|
||||
return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a debug_vect message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id
|
||||
* @brief Pack a file_transfer_dir_list message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param transfer_uid Unique transfer ID
|
||||
* @param dir_path Directory path to list
|
||||
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t syst
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a file_transfer_dir_list struct into a message
|
||||
* @brief Encode a file_transfer_dir_list struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_
|
||||
return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a file_transfer_dir_list struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param file_transfer_dir_list C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_file_transfer_dir_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
|
||||
{
|
||||
return mavlink_msg_file_transfer_dir_list_pack_chan(system_id, component_id, chan, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a file_transfer_dir_list message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uin
|
||||
* @brief Pack a file_transfer_res message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message was sent over
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param transfer_uid Unique transfer ID
|
||||
* @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
|
||||
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a file_transfer_res struct into a message
|
||||
* @brief Encode a file_transfer_res struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, u
|
||||
return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a file_transfer_res struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param file_transfer_res C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_file_transfer_res_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res)
|
||||
{
|
||||
return mavlink_msg_file_transfer_res_pack_chan(system_id, component_id, chan, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a file_transfer_res message
|
||||
* @param chan MAVLink channel to send the message
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user