From 3a40ea8338206b247aadb40e3709a22e0699135b Mon Sep 17 00:00:00 2001 From: Holger Steinhaus L Date: Mon, 11 Nov 2013 12:14:03 +0100 Subject: more precise range conversion for SBus input signals --- src/modules/px4iofirmware/sbus.c | 23 +++++++++++++++++++++-- 1 file changed, 21 insertions(+), 2 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index c523df6ca..8034e7077 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -55,6 +55,24 @@ #define SBUS_FRAME_SIZE 25 #define SBUS_INPUT_CHANNELS 16 +/* + Measured values with Futaba FX-30/R6108SB: + -+100% on TX: PCM 1.100/1.520/1.950ms -> SBus raw values: 350/1024/1700 (100% ATV) + -+140% on TX: PCM 0.930/1.520/2.112ms -> SBus raw values: 78/1024/1964 (140% ATV) + -+152% on TX: PCM 0.884/1.520/2.160ms -> SBus raw values: 1/1024/2047 (140% ATV plus dirty tricks) +*/ + +/* define range mapping here, -+100% -> 1000..2000 */ +#define SBUS_RANGE_MIN 350.0f +#define SBUS_RANGE_MAX 1700.0f + +#define SBUS_TARGET_MIN 1000.0f +#define SBUS_TARGET_MAX 2000.0f + +/* pre-calculate the floating point stuff as far as possible at compile time */ +#define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN)) +#define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f)) + static int sbus_fd = -1; static hrt_abstime last_rx_time; @@ -234,8 +252,9 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint } } - /* convert 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */ - values[channel] = (value / 2) + 998; + + /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */ + values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET; } /* decode switch channels if data fields are wide enough */ -- cgit v1.2.3 From a673fa3926d18163841f817c08bf089a0a8224f7 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus L Date: Sun, 17 Nov 2013 12:56:26 +0100 Subject: Non-destructive handling of failsafe signals, distinction between frame loss and signal loss. This kind of handling might be moved upstream into the application, once alarms are propagated by the ORB system. This change is compatible with RX failsafe settings, but does not rely on it (uses SBus flags instead). --- src/modules/px4iofirmware/sbus.c | 31 ++++++++++++++++++++----------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 8034e7077..68af85dc9 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -54,6 +54,9 @@ #define SBUS_FRAME_SIZE 25 #define SBUS_INPUT_CHANNELS 16 +#define SBUS_FLAGS_BYTE 23 +#define SBUS_FAILSAFE_BIT 3 +#define SBUS_FRAMELOST_BIT 2 /* Measured values with Futaba FX-30/R6108SB: @@ -220,15 +223,6 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint return false; } - /* if the failsafe or connection lost bit is set, we consider the frame invalid */ - if ((frame[23] & (1 << 2)) && /* signal lost */ - (frame[23] & (1 << 3))) { /* failsafe */ - - /* actively announce signal loss */ - *values = 0; - return false; - } - /* we have received something we think is a frame */ last_frame_time = frame_time; @@ -262,13 +256,28 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint chancount = 18; /* channel 17 (index 16) */ - values[16] = (frame[23] & (1 << 0)) * 1000 + 998; + values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998; /* channel 18 (index 17) */ - values[17] = (frame[23] & (1 << 1)) * 1000 + 998; + values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998; } /* note the number of channels decoded */ *num_values = chancount; + /* decode and handle failsafe and frame-lost flags */ + if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */ + /* emulate throttle failsafe for maximum compatibility and do not destroy any channel data */ + values[2] = 900; + } + else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ + /* set a special warning flag or try to calculate some kind of RSSI information - to be implemented + * + * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this + * condition as fail-safe greatly reduces the reliability and range of the radio link, + * e.g. by prematurely issueing return-to-launch!!! */ + + // values[2] = 888; // marker for debug purposes + } + return true; } -- cgit v1.2.3 From 9883a346a022131b20a292d96a87f20fb7921b1c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 13 Dec 2013 18:01:55 +0100 Subject: First stab at implementing better RSSI based connection status estimation, still needs some work and testing --- src/drivers/drv_rc_input.h | 3 +++ src/modules/px4iofirmware/controls.c | 21 +++++++++++++++++---- src/modules/px4iofirmware/protocol.h | 1 + src/modules/px4iofirmware/px4io.h | 2 +- src/modules/px4iofirmware/registers.c | 2 +- src/modules/px4iofirmware/sbus.c | 17 ++++++++++------- 6 files changed, 33 insertions(+), 13 deletions(-) diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h index 78ffad9d7..86e5a149a 100644 --- a/src/drivers/drv_rc_input.h +++ b/src/drivers/drv_rc_input.h @@ -89,6 +89,9 @@ struct rc_input_values { /** number of channels actually being seen */ uint32_t channel_count; + /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 1000: full reception */ + int32_t rssi; + /** Input source */ enum RC_INPUT_SOURCE input_source; diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 5c621cfb2..194d8aab9 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -94,6 +94,9 @@ controls_tick() { * other. Don't do that. */ + /* receive signal strenght indicator (RSSI). 0 = no connection, 1000: perfect connection */ + uint16_t rssi = 0; + perf_begin(c_gather_dsm); uint16_t temp_count = r_raw_rc_count; bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count); @@ -104,14 +107,15 @@ controls_tick() { r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11; else r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11; + + rssi = 1000; } perf_end(c_gather_dsm); perf_begin(c_gather_sbus); - bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, PX4IO_CONTROL_CHANNELS /* XXX this should be INPUT channels, once untangled */); + bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &rssi, PX4IO_CONTROL_CHANNELS /* XXX this should be INPUT channels, once untangled */); if (sbus_updated) { r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS; - r_raw_rc_count = 8; } perf_end(c_gather_sbus); @@ -122,10 +126,19 @@ controls_tick() { */ perf_begin(c_gather_ppm); bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count); - if (ppm_updated) + if (ppm_updated) { + + /* XXX sample RSSI properly here */ + rssi = 1000; + r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM; + } perf_end(c_gather_ppm); + /* limit number of channels to allowable data size */ + if (r_raw_rc_count > PX4IO_INPUT_CHANNELS) + r_raw_rc_count = PX4IO_INPUT_CHANNELS; + /* * In some cases we may have received a frame, but input has still * been lost. @@ -221,7 +234,7 @@ controls_tick() { * This might happen if a protocol-based receiver returns an update * that contains no channels that we have mapped. */ - if (assigned_channels == 0) { + if (assigned_channels == 0 || rssi == 0) { rc_input_lost = true; } else { /* set RC OK flag */ diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index cffabbb45..11e380397 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -124,6 +124,7 @@ #define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */ #define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */ #define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */ +#define PX4IO_P_STATUS_NRSSI 9 /* [2] Normalized RSSI value, 0: no reception, 1000: perfect reception */ /* array of post-mix actuator outputs, -10000..10000 */ #define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */ diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index 4fea0288c..b9c9e0232 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -209,7 +209,7 @@ extern int dsm_init(const char *device); extern bool dsm_input(uint16_t *values, uint16_t *num_values); extern void dsm_bind(uint16_t cmd, int pulses); extern int sbus_init(const char *device); -extern bool sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels); +extern bool sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels); /** global debug level for isr_debug() */ extern volatile uint8_t debug_level; diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 1a8519aec..3f9e111ba 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -114,7 +114,7 @@ uint16_t r_page_servos[PX4IO_SERVO_COUNT]; uint16_t r_page_raw_rc_input[] = { [PX4IO_P_RAW_RC_COUNT] = 0, - [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_CONTROL_CHANNELS)] = 0 + [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + 24)] = 0 // XXX ensure we have enough space to decode beefy RX, will be replaced by patch soon }; /** diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 68af85dc9..2153fadc8 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -87,7 +87,7 @@ static unsigned partial_frame_count; unsigned sbus_frame_drops; -static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t max_channels); +static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels); int sbus_init(const char *device) @@ -118,7 +118,7 @@ sbus_init(const char *device) } bool -sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels) +sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels) { ssize_t ret; hrt_abstime now; @@ -175,7 +175,7 @@ sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels) * decode it. */ partial_frame_count = 0; - return sbus_decode(now, values, num_values, max_channels); + return sbus_decode(now, values, num_values, rssi, max_channels); } /* @@ -215,7 +215,7 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = { }; static bool -sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t max_values) +sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_values) { /* check frame boundary markers to avoid out-of-sync cases */ if ((frame[0] != 0x0f) || (frame[24] != 0x00)) { @@ -266,8 +266,9 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint /* decode and handle failsafe and frame-lost flags */ if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */ - /* emulate throttle failsafe for maximum compatibility and do not destroy any channel data */ - values[2] = 900; + /* report that we failed to read anything valid off the receiver */ + *rssi = 0; + return false; } else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ /* set a special warning flag or try to calculate some kind of RSSI information - to be implemented @@ -276,8 +277,10 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint * condition as fail-safe greatly reduces the reliability and range of the radio link, * e.g. by prematurely issueing return-to-launch!!! */ - // values[2] = 888; // marker for debug purposes + *rssi = 100; // XXX magic number indicating bad signal, but not a signal loss (yet) } + *rssi = 1000; + return true; } -- cgit v1.2.3 From 00dc339d2ece42161e36af7cc52c042c4fcec697 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 14 Dec 2013 14:52:57 +0100 Subject: Improved S.Bus scaling based on scope measurements --- src/modules/px4iofirmware/sbus.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 2153fadc8..65e14a18f 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -66,8 +66,8 @@ */ /* define range mapping here, -+100% -> 1000..2000 */ -#define SBUS_RANGE_MIN 350.0f -#define SBUS_RANGE_MAX 1700.0f +#define SBUS_RANGE_MIN 215.0f +#define SBUS_RANGE_MAX 1790.0f #define SBUS_TARGET_MIN 1000.0f #define SBUS_TARGET_MAX 2000.0f -- cgit v1.2.3 From 10b2dc67e4529759b9dcbef6a18360eba610b5a3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 14 Dec 2013 14:54:02 +0100 Subject: Allow forceupdate in all conditions --- src/drivers/px4io/px4io.cpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 5d35ecb8d..685a9746d 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2653,22 +2653,22 @@ px4io_main(int argc, char *argv[]) the user to hold the safety switch down */ if (argc <= 3) { - printf("usage: px4io forceupdate MAGIC filename\n"); + warnx("usage: px4io forceupdate MAGIC filename"); exit(1); } if (g_dev == nullptr) { - printf("px4io is not started\n"); - exit(1); - } - uint16_t arg = atol(argv[2]); - int ret = g_dev->ioctl(nullptr, PX4IO_REBOOT_BOOTLOADER, arg); - if (ret != OK) { - printf("reboot failed - %d\n", ret); - exit(1); - } + warnx("px4io is not started, still attempting upgrade"); + } else { + uint16_t arg = atol(argv[2]); + int ret = g_dev->ioctl(nullptr, PX4IO_REBOOT_BOOTLOADER, arg); + if (ret != OK) { + printf("reboot failed - %d\n", ret); + exit(1); + } - // tear down the px4io instance - delete g_dev; + // tear down the px4io instance + delete g_dev; + } // upload the specified firmware const char *fn[2]; -- cgit v1.2.3 From ea10d55d71b25b4440c6b4dc139dda519a0d2797 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 14 Dec 2013 15:08:56 +0100 Subject: Auto-update of IO firmware, shorter preflight check alarm --- ROMFS/px4fmu_common/init.d/rcS | 47 ++++++++++++++++++------ src/drivers/px4io/px4io.cpp | 2 +- src/systemcmds/preflight_check/preflight_check.c | 2 +- 3 files changed, 38 insertions(+), 13 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f1df99048..f551c1aa8 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -8,6 +8,8 @@ # set MODE autostart +set logfile /fs/microsd/bootlog.txt + # # Try to mount the microSD card. # @@ -147,26 +149,49 @@ then nshterm /dev/ttyACM0 & fi - # # Upgrade PX4IO firmware # - if px4io detect + + if [ -f /etc/extras/px4io-v2_default.bin ] + then + set io_file /etc/extras/px4io-v2_default.bin + else + set io_file /etc/extras/px4io-v1_default.bin + fi + + if px4io start then - echo "PX4IO running, not upgrading" + echo "PX4IO OK" + echo "PX4IO OK" >> $logfile + fi + + if px4io checkcrc $io_file + then + echo "PX4IO CRC OK" + echo "PX4IO CRC OK" >> $logfile else - echo "Attempting to upgrade PX4IO" - if px4io update + echo "PX4IO CRC failure" + echo "PX4IO CRC failure" >> $logfile + tone_alarm MBABGP + if px4io forceupdate 14662 $io_file then - if [ -d /fs/microsd ] + usleep 200000 + if px4io start then - echo "Flashed PX4IO Firmware OK" > /fs/microsd/px4io.log + echo "PX4IO restart OK" + echo "PX4IO restart OK" >> $logfile + tone_alarm MSPAA + else + echo "PX4IO restart failed" + echo "PX4IO restart failed" >> $logfile + tone_alarm MNGGG + sh /etc/init.d/rc.error fi - - # Allow IO to safely kick back to app - usleep 200000 else - echo "No PX4IO to upgrade here" + echo "PX4IO update failed" + echo "PX4IO update failed" >> $logfile + tone_alarm MNGGG fi fi diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 685a9746d..569f1e413 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2229,7 +2229,7 @@ void start(int argc, char *argv[]) { if (g_dev != nullptr) - errx(1, "already loaded"); + errx(0, "already loaded"); /* allocate the interface */ device::Device *interface = get_interface(); diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index 07581459b..982b03782 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -200,7 +200,7 @@ system_eval: led_toggle(leds, LED_BLUE); /* display and sound error */ - for (int i = 0; i < 50; i++) + for (int i = 0; i < 14; i++) { led_toggle(leds, LED_BLUE); led_toggle(leds, LED_AMBER); -- cgit v1.2.3 From d6a6d59d2de7270fd978fcb6029edc3f315899a0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 14 Dec 2013 15:09:20 +0100 Subject: Further improved S.Bus scaling --- src/modules/px4iofirmware/sbus.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 65e14a18f..388502b40 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -66,8 +66,8 @@ */ /* define range mapping here, -+100% -> 1000..2000 */ -#define SBUS_RANGE_MIN 215.0f -#define SBUS_RANGE_MAX 1790.0f +#define SBUS_RANGE_MIN 200.0f +#define SBUS_RANGE_MAX 1800.0f #define SBUS_TARGET_MIN 1000.0f #define SBUS_TARGET_MAX 2000.0f -- cgit v1.2.3 From f4ac204f4650dedcde52aa9ec001fafb5e7c5284 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 15 Dec 2013 18:32:46 +0100 Subject: Cranking up bus speeds for all sensors to achievable 10.4 MHz, will cut the bus lock time to half --- src/drivers/l3gd20/l3gd20.cpp | 2 +- src/drivers/lsm303d/lsm303d.cpp | 2 +- src/drivers/mpu6000/mpu6000.cpp | 2 +- src/drivers/ms5611/ms5611_spi.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index d639acba1..670e51b97 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -316,7 +316,7 @@ private: }; L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) : - SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 8000000), + SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */), _call_interval(0), _reports(nullptr), _gyro_range_scale(0.0f), diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 11e5b95a7..969b5e25f 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -486,7 +486,7 @@ private: LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) : - SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 8000000), + SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */), _mag(new LSM303D_mag(this)), _call_accel_interval(0), _call_mag_interval(0), diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index c95d11c83..be4e422b0 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -170,7 +170,7 @@ SPI speed */ #define MPU6000_LOW_BUS_SPEED 1000*1000 -#define MPU6000_HIGH_BUS_SPEED 10*1000*1000 +#define MPU6000_HIGH_BUS_SPEED 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for MPU6K */ class MPU6000_gyro; diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp index bc4074c55..26216e840 100644 --- a/src/drivers/ms5611/ms5611_spi.cpp +++ b/src/drivers/ms5611/ms5611_spi.cpp @@ -121,7 +121,7 @@ MS5611_spi_interface(ms5611::prom_u &prom_buf) } MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) : - SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 6*1000*1000), + SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz */), _prom(prom_buf) { } -- cgit v1.2.3 From b63d4809dedb965d2342ff5803e6604b11ff18c7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 15 Dec 2013 19:35:23 +0100 Subject: Enabled MPU6K and updated startup script to start all sensors --- ROMFS/px4fmu_common/init.d/rc.sensors | 16 +++++++++++----- makefiles/config_px4fmu-v2_default.mk | 1 + 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index f17b650bc..7f73acf85 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -19,12 +19,18 @@ fi if mpu6000 start then echo "using MPU6000" - set BOARD fmuv1 -else - echo "using L3GD20 and LSM303D" - l3gd20 start - lsm303d start +fi + +if l3gd20 start +then + echo "using L3GD20(H)" +fi + +if lsm303d start +then set BOARD fmuv2 +else + set BOARD fmuv1 fi # Start airspeed sensors diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 015a7387a..68673c055 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -21,6 +21,7 @@ MODULES += drivers/px4fmu MODULES += drivers/px4io MODULES += drivers/boards/px4fmu-v2 MODULES += drivers/rgbled +MODULES += drivers/mpu6000 MODULES += drivers/lsm303d MODULES += drivers/l3gd20 MODULES += drivers/hmc5883 -- cgit v1.2.3 From da539ec83f30609700970ad7f06ad635e01ee658 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 16 Dec 2013 09:01:56 +0100 Subject: Added LOG_ MAVLink messages --- .../mavlink/v1.0/ardupilotmega/ardupilotmega.h | 23 +- .../ardupilotmega/mavlink_msg_rally_fetch_point.h | 221 ++++ .../v1.0/ardupilotmega/mavlink_msg_rally_point.h | 375 ++++++ .../include/mavlink/v1.0/ardupilotmega/testsuite.h | 344 +++-- .../include/mavlink/v1.0/ardupilotmega/version.h | 2 +- mavlink/include/mavlink/v1.0/autoquad/autoquad.h | 123 -- mavlink/include/mavlink/v1.0/autoquad/mavlink.h | 27 - .../v1.0/autoquad/mavlink_msg_aq_telemetry_f.h | 617 --------- mavlink/include/mavlink/v1.0/autoquad/testsuite.h | 118 -- mavlink/include/mavlink/v1.0/autoquad/version.h | 12 - mavlink/include/mavlink/v1.0/common/common.h | 46 +- .../v1.0/common/mavlink_msg_battery_status.h | 154 ++- .../mavlink/v1.0/common/mavlink_msg_gps_raw_int.h | 10 +- .../mavlink/v1.0/common/mavlink_msg_hil_gps.h | 10 +- .../mavlink/v1.0/common/mavlink_msg_log_data.h | 237 ++++ .../mavlink/v1.0/common/mavlink_msg_log_entry.h | 265 ++++ .../mavlink/v1.0/common/mavlink_msg_log_erase.h | 199 +++ .../v1.0/common/mavlink_msg_log_request_data.h | 265 ++++ .../v1.0/common/mavlink_msg_log_request_end.h | 199 +++ .../v1.0/common/mavlink_msg_log_request_list.h | 243 ++++ .../mavlink/v1.0/common/mavlink_msg_mission_item.h | 50 +- .../mavlink/v1.0/common/mavlink_msg_scaled_imu2.h | 375 ++++++ .../mavlink/v1.0/common/mavlink_msg_sys_status.h | 30 +- mavlink/include/mavlink/v1.0/common/testsuite.h | 1380 ++++++++++++-------- mavlink/include/mavlink/v1.0/common/version.h | 2 +- .../include/mavlink/v1.0/matrixpilot/matrixpilot.h | 6 +- .../include/mavlink/v1.0/matrixpilot/testsuite.h | 282 ++-- mavlink/include/mavlink/v1.0/matrixpilot/version.h | 2 +- mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h | 6 +- mavlink/include/mavlink/v1.0/pixhawk/testsuite.h | 228 ++-- mavlink/include/mavlink/v1.0/pixhawk/version.h | 2 +- 31 files changed, 3952 insertions(+), 1901 deletions(-) create mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h create mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/autoquad.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/version.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index 3aad8e678..4dc9aed26 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -79,6 +79,7 @@ enum MAV_CMD MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ 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| */ @@ -100,7 +101,8 @@ enum FENCE_ACTION FENCE_ACTION_NONE=0, /* Disable fenced mode | */ FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ - FENCE_ACTION_ENUM_END=3, /* | */ + FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ + FENCE_ACTION_ENUM_END=4, /* | */ }; #endif @@ -144,6 +146,17 @@ enum LIMIT_MODULE }; #endif +/** @brief Flags in RALLY_POINT message */ +#ifndef HAVE_ENUM_RALLY_FLAGS +#define HAVE_ENUM_RALLY_FLAGS +enum RALLY_FLAGS +{ + FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */ + LAND_IMMEDIATELY=2, /* Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. | */ + RALLY_FLAGS_ENUM_END=3, /* | */ +}; +#endif + #include "../common/common.h" // MAVLINK VERSION @@ -182,6 +195,8 @@ enum LIMIT_MODULE #include "./mavlink_msg_data96.h" #include "./mavlink_msg_rangefinder.h" #include "./mavlink_msg_airspeed_autocal.h" +#include "./mavlink_msg_rally_point.h" +#include "./mavlink_msg_rally_fetch_point.h" #ifdef __cplusplus } diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h new file mode 100644 index 000000000..f057e3c33 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h @@ -0,0 +1,221 @@ +// MESSAGE RALLY_FETCH_POINT PACKING + +#define MAVLINK_MSG_ID_RALLY_FETCH_POINT 176 + +typedef struct __mavlink_rally_fetch_point_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t idx; ///< point index (first point is 0) +} mavlink_rally_fetch_point_t; + +#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN 3 +#define MAVLINK_MSG_ID_176_LEN 3 + +#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC 234 +#define MAVLINK_MSG_ID_176_CRC 234 + + + +#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \ + "RALLY_FETCH_POINT", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \ + { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \ + } \ +} + + +/** + * @brief Pack a rally_fetch_point 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 target_component Component ID + * @param idx point index (first point is 0) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rally_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#else + mavlink_rally_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif +} + +/** + * @brief Pack a rally_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 will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 0) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rally_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#else + mavlink_rally_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif +} + +/** + * @brief Encode a rally_fetch_point 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 rally_fetch_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rally_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point) +{ + return mavlink_msg_rally_fetch_point_pack(system_id, component_id, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx); +} + +/** + * @brief Encode a rally_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 rally_fetch_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rally_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point) +{ + return mavlink_msg_rally_fetch_point_pack_chan(system_id, component_id, chan, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx); +} + +/** + * @brief Send a rally_fetch_point message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 0) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rally_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif +#else + mavlink_rally_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif +#endif +} + +#endif + +// MESSAGE RALLY_FETCH_POINT UNPACKING + + +/** + * @brief Get field target_system from rally_fetch_point message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rally_fetch_point_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from rally_fetch_point message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rally_fetch_point_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field idx from rally_fetch_point message + * + * @return point index (first point is 0) + */ +static inline uint8_t mavlink_msg_rally_fetch_point_get_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a rally_fetch_point message into a struct + * + * @param msg The message to decode + * @param rally_fetch_point C-struct to decode the message contents into + */ +static inline void mavlink_msg_rally_fetch_point_decode(const mavlink_message_t* msg, mavlink_rally_fetch_point_t* rally_fetch_point) +{ +#if MAVLINK_NEED_BYTE_SWAP + rally_fetch_point->target_system = mavlink_msg_rally_fetch_point_get_target_system(msg); + rally_fetch_point->target_component = mavlink_msg_rally_fetch_point_get_target_component(msg); + rally_fetch_point->idx = mavlink_msg_rally_fetch_point_get_idx(msg); +#else + memcpy(rally_fetch_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h new file mode 100644 index 000000000..2c21db4c0 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h @@ -0,0 +1,375 @@ +// MESSAGE RALLY_POINT PACKING + +#define MAVLINK_MSG_ID_RALLY_POINT 175 + +typedef struct __mavlink_rally_point_t +{ + int32_t lat; ///< Latitude of point in degrees * 1E7 + int32_t lng; ///< Longitude of point in degrees * 1E7 + int16_t alt; ///< Transit / loiter altitude in meters relative to home + int16_t break_alt; ///< Break altitude in meters relative to home + uint16_t land_dir; ///< Heading to aim for when landing. In centi-degrees. + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t idx; ///< point index (first point is 0) + uint8_t count; ///< total number of points (for sanity checking) + uint8_t flags; ///< See RALLY_FLAGS enum for definition of the bitmask. +} mavlink_rally_point_t; + +#define MAVLINK_MSG_ID_RALLY_POINT_LEN 19 +#define MAVLINK_MSG_ID_175_LEN 19 + +#define MAVLINK_MSG_ID_RALLY_POINT_CRC 138 +#define MAVLINK_MSG_ID_175_CRC 138 + + + +#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \ + "RALLY_POINT", \ + 10, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \ + { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \ + { "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \ + { "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \ + { "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \ + { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a rally_point 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 target_component Component ID + * @param idx point index (first point is 0) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point in degrees * 1E7 + * @param lng Longitude of point in degrees * 1E7 + * @param alt Transit / loiter altitude in meters relative to home + * @param break_alt Break altitude in meters relative to home + * @param land_dir Heading to aim for when landing. In centi-degrees. + * @param flags See RALLY_FLAGS enum for definition of the bitmask. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rally_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lng); + _mav_put_int16_t(buf, 8, alt); + _mav_put_int16_t(buf, 10, break_alt); + _mav_put_uint16_t(buf, 12, land_dir); + _mav_put_uint8_t(buf, 14, target_system); + _mav_put_uint8_t(buf, 15, target_component); + _mav_put_uint8_t(buf, 16, idx); + _mav_put_uint8_t(buf, 17, count); + _mav_put_uint8_t(buf, 18, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#else + mavlink_rally_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.break_alt = break_alt; + packet.land_dir = land_dir; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RALLY_POINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif +} + +/** + * @brief Pack a rally_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 will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 0) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point in degrees * 1E7 + * @param lng Longitude of point in degrees * 1E7 + * @param alt Transit / loiter altitude in meters relative to home + * @param break_alt Break altitude in meters relative to home + * @param land_dir Heading to aim for when landing. In centi-degrees. + * @param flags See RALLY_FLAGS enum for definition of the bitmask. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rally_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,int32_t lat,int32_t lng,int16_t alt,int16_t break_alt,uint16_t land_dir,uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lng); + _mav_put_int16_t(buf, 8, alt); + _mav_put_int16_t(buf, 10, break_alt); + _mav_put_uint16_t(buf, 12, land_dir); + _mav_put_uint8_t(buf, 14, target_system); + _mav_put_uint8_t(buf, 15, target_component); + _mav_put_uint8_t(buf, 16, idx); + _mav_put_uint8_t(buf, 17, count); + _mav_put_uint8_t(buf, 18, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#else + mavlink_rally_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.break_alt = break_alt; + packet.land_dir = land_dir; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RALLY_POINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif +} + +/** + * @brief Encode a rally_point 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 rally_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rally_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point) +{ + return mavlink_msg_rally_point_pack(system_id, component_id, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags); +} + +/** + * @brief Encode a rally_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 rally_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rally_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point) +{ + return mavlink_msg_rally_point_pack_chan(system_id, component_id, chan, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags); +} + +/** + * @brief Send a rally_point message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 0) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point in degrees * 1E7 + * @param lng Longitude of point in degrees * 1E7 + * @param alt Transit / loiter altitude in meters relative to home + * @param break_alt Break altitude in meters relative to home + * @param land_dir Heading to aim for when landing. In centi-degrees. + * @param flags See RALLY_FLAGS enum for definition of the bitmask. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rally_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lng); + _mav_put_int16_t(buf, 8, alt); + _mav_put_int16_t(buf, 10, break_alt); + _mav_put_uint16_t(buf, 12, land_dir); + _mav_put_uint8_t(buf, 14, target_system); + _mav_put_uint8_t(buf, 15, target_component); + _mav_put_uint8_t(buf, 16, idx); + _mav_put_uint8_t(buf, 17, count); + _mav_put_uint8_t(buf, 18, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif +#else + mavlink_rally_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.break_alt = break_alt; + packet.land_dir = land_dir; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif +#endif +} + +#endif + +// MESSAGE RALLY_POINT UNPACKING + + +/** + * @brief Get field target_system from rally_point message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rally_point_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field target_component from rally_point message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rally_point_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 15); +} + +/** + * @brief Get field idx from rally_point message + * + * @return point index (first point is 0) + */ +static inline uint8_t mavlink_msg_rally_point_get_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field count from rally_point message + * + * @return total number of points (for sanity checking) + */ +static inline uint8_t mavlink_msg_rally_point_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field lat from rally_point message + * + * @return Latitude of point in degrees * 1E7 + */ +static inline int32_t mavlink_msg_rally_point_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lng from rally_point message + * + * @return Longitude of point in degrees * 1E7 + */ +static inline int32_t mavlink_msg_rally_point_get_lng(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field alt from rally_point message + * + * @return Transit / loiter altitude in meters relative to home + */ +static inline int16_t mavlink_msg_rally_point_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field break_alt from rally_point message + * + * @return Break altitude in meters relative to home + */ +static inline int16_t mavlink_msg_rally_point_get_break_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field land_dir from rally_point message + * + * @return Heading to aim for when landing. In centi-degrees. + */ +static inline uint16_t mavlink_msg_rally_point_get_land_dir(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field flags from rally_point message + * + * @return See RALLY_FLAGS enum for definition of the bitmask. + */ +static inline uint8_t mavlink_msg_rally_point_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Decode a rally_point message into a struct + * + * @param msg The message to decode + * @param rally_point C-struct to decode the message contents into + */ +static inline void mavlink_msg_rally_point_decode(const mavlink_message_t* msg, mavlink_rally_point_t* rally_point) +{ +#if MAVLINK_NEED_BYTE_SWAP + rally_point->lat = mavlink_msg_rally_point_get_lat(msg); + rally_point->lng = mavlink_msg_rally_point_get_lng(msg); + rally_point->alt = mavlink_msg_rally_point_get_alt(msg); + rally_point->break_alt = mavlink_msg_rally_point_get_break_alt(msg); + rally_point->land_dir = mavlink_msg_rally_point_get_land_dir(msg); + rally_point->target_system = mavlink_msg_rally_point_get_target_system(msg); + rally_point->target_component = mavlink_msg_rally_point_get_target_component(msg); + rally_point->idx = mavlink_msg_rally_point_get_idx(msg); + rally_point->count = mavlink_msg_rally_point_get_count(msg); + rally_point->flags = mavlink_msg_rally_point_get_flags(msg); +#else + memcpy(rally_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RALLY_POINT_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 2c9cfef3d..eb3bc6a75 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -31,17 +31,17 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, uint16_t i; mavlink_sensor_offsets_t packet_in = { 17.0, - 963497672, - 963497880, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, - 19107, - 19211, - 19315, + }963497672, + }963497880, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }19107, + }19211, + }19315, }; mavlink_sensor_offsets_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -96,10 +96,10 @@ static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_set_mag_offsets_t packet_in = { 17235, - 17339, - 17443, - 151, - 218, + }17339, + }17443, + }151, + }218, }; mavlink_set_mag_offsets_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -147,7 +147,7 @@ static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlin uint16_t i; mavlink_meminfo_t packet_in = { 17235, - 17339, + }17339, }; mavlink_meminfo_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -192,11 +192,11 @@ static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink uint16_t i; mavlink_ap_adc_t packet_in = { 17235, - 17339, - 17443, - 17547, - 17651, - 17755, + }17339, + }17443, + }17547, + }17651, + }17755, }; mavlink_ap_adc_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -245,16 +245,16 @@ static void mavlink_test_digicam_configure(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_digicam_configure_t packet_in = { 17.0, - 17443, - 151, - 218, - 29, - 96, - 163, - 230, - 41, - 108, - 175, + }17443, + }151, + }218, + }29, + }96, + }163, + }230, + }41, + }108, + }175, }; mavlink_digicam_configure_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -308,15 +308,15 @@ static void mavlink_test_digicam_control(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_digicam_control_t packet_in = { 17.0, - 17, - 84, - 151, - 218, - 29, - 96, - 163, - 230, - 41, + }17, + }84, + }151, + }218, + }29, + }96, + }163, + }230, + }41, }; mavlink_digicam_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -369,11 +369,11 @@ static void mavlink_test_mount_configure(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_mount_configure_t packet_in = { 5, - 72, - 139, - 206, - 17, - 84, + }72, + }139, + }206, + }17, + }84, }; mavlink_mount_configure_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -422,11 +422,11 @@ static void mavlink_test_mount_control(uint8_t system_id, uint8_t component_id, uint16_t i; mavlink_mount_control_t packet_in = { 963497464, - 963497672, - 963497880, - 41, - 108, - 175, + }963497672, + }963497880, + }41, + }108, + }175, }; mavlink_mount_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -475,10 +475,10 @@ static void mavlink_test_mount_status(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_mount_status_t packet_in = { 963497464, - 963497672, - 963497880, - 41, - 108, + }963497672, + }963497880, + }41, + }108, }; mavlink_mount_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -526,11 +526,11 @@ static void mavlink_test_fence_point(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_fence_point_t packet_in = { 17.0, - 45.0, - 29, - 96, - 163, - 230, + }45.0, + }29, + }96, + }163, + }230, }; mavlink_fence_point_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -579,8 +579,8 @@ static void mavlink_test_fence_fetch_point(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_fence_fetch_point_t packet_in = { 5, - 72, - 139, + }72, + }139, }; mavlink_fence_fetch_point_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -626,9 +626,9 @@ static void mavlink_test_fence_status(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_fence_status_t packet_in = { 963497464, - 17443, - 151, - 218, + }17443, + }151, + }218, }; mavlink_fence_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -675,12 +675,12 @@ static void mavlink_test_ahrs(uint8_t system_id, uint8_t component_id, mavlink_m uint16_t i; mavlink_ahrs_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, }; mavlink_ahrs_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -730,16 +730,16 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli uint16_t i; mavlink_simstate_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, - 963499336, - 963499544, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }963499336, + }963499544, }; mavlink_simstate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -793,7 +793,7 @@ static void mavlink_test_hwstatus(uint8_t system_id, uint8_t component_id, mavli uint16_t i; mavlink_hwstatus_t packet_in = { 17235, - 139, + }139, }; mavlink_hwstatus_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -838,12 +838,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_ uint16_t i; mavlink_radio_t packet_in = { 17235, - 17339, - 17, - 84, - 151, - 218, - 29, + }17339, + }17, + }84, + }151, + }218, + }29, }; mavlink_radio_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -893,14 +893,14 @@ static void mavlink_test_limits_status(uint8_t system_id, uint8_t component_id, uint16_t i; mavlink_limits_status_t packet_in = { 963497464, - 963497672, - 963497880, - 963498088, - 18067, - 187, - 254, - 65, - 132, + }963497672, + }963497880, + }963498088, + }18067, + }187, + }254, + }65, + }132, }; mavlink_limits_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -952,8 +952,8 @@ static void mavlink_test_wind(uint8_t system_id, uint8_t component_id, mavlink_m uint16_t i; mavlink_wind_t packet_in = { 17.0, - 45.0, - 73.0, + }45.0, + }73.0, }; mavlink_wind_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -999,8 +999,8 @@ static void mavlink_test_data16(uint8_t system_id, uint8_t component_id, mavlink uint16_t i; mavlink_data16_t packet_in = { 5, - 72, - { 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154 }, + }72, + }{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154 }, }; mavlink_data16_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1046,8 +1046,8 @@ static void mavlink_test_data32(uint8_t system_id, uint8_t component_id, mavlink uint16_t i; mavlink_data32_t packet_in = { 5, - 72, - { 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 }, + }72, + }{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 }, }; mavlink_data32_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1093,8 +1093,8 @@ static void mavlink_test_data64(uint8_t system_id, uint8_t component_id, mavlink uint16_t i; mavlink_data64_t packet_in = { 5, - 72, - { 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202 }, + }72, + }{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202 }, }; mavlink_data64_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1140,8 +1140,8 @@ static void mavlink_test_data96(uint8_t system_id, uint8_t component_id, mavlink uint16_t i; mavlink_data96_t packet_in = { 5, - 72, - { 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234 }, + }72, + }{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234 }, }; mavlink_data96_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1187,7 +1187,7 @@ static void mavlink_test_rangefinder(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_rangefinder_t packet_in = { 17.0, - 45.0, + }45.0, }; mavlink_rangefinder_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1232,17 +1232,17 @@ static void mavlink_test_airspeed_autocal(uint8_t system_id, uint8_t component_i 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, + }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)); @@ -1290,6 +1290,114 @@ static void mavlink_test_airspeed_autocal(uint8_t system_id, uint8_t component_i MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_rally_point(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_rally_point_t packet_in = { + 963497464, + }963497672, + }17651, + }17755, + }17859, + }175, + }242, + }53, + }120, + }187, + }; + mavlink_rally_point_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.lat = packet_in.lat; + packet1.lng = packet_in.lng; + packet1.alt = packet_in.alt; + packet1.break_alt = packet_in.break_alt; + packet1.land_dir = packet_in.land_dir; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; + packet1.idx = packet_in.idx; + packet1.count = packet_in.count; + packet1.flags = packet_in.flags; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rally_point_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_rally_point_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rally_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng , packet1.alt , packet1.break_alt , packet1.land_dir , packet1.flags ); + mavlink_msg_rally_point_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rally_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng , packet1.alt , packet1.break_alt , packet1.land_dir , packet1.flags ); + mavlink_msg_rally_point_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 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* 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_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - 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| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - 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_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_ENUM_END=501, /* | */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_aq_telemetry_f.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // AUTOQUAD_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h deleted file mode 100644 index 3f80c9a41..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from autoquad.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "autoquad.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h deleted file mode 100644 index ed7c86bcb..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h +++ /dev/null @@ -1,617 +0,0 @@ -// MESSAGE AQ_TELEMETRY_F PACKING - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F 150 - -typedef struct __mavlink_aq_telemetry_f_t -{ - float value1; ///< value1 - float value2; ///< value2 - float value3; ///< value3 - float value4; ///< value4 - float value5; ///< value5 - float value6; ///< value6 - float value7; ///< value7 - float value8; ///< value8 - float value9; ///< value9 - float value10; ///< value10 - float value11; ///< value11 - float value12; ///< value12 - float value13; ///< value13 - float value14; ///< value14 - float value15; ///< value15 - float value16; ///< value16 - float value17; ///< value17 - float value18; ///< value18 - float value19; ///< value19 - float value20; ///< value20 - uint16_t Index; ///< Index of message -} mavlink_aq_telemetry_f_t; - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN 82 -#define MAVLINK_MSG_ID_150_LEN 82 - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC 241 -#define MAVLINK_MSG_ID_150_CRC 241 - - - -#define MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F { \ - "AQ_TELEMETRY_F", \ - 21, \ - { { "value1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_aq_telemetry_f_t, value1) }, \ - { "value2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_aq_telemetry_f_t, value2) }, \ - { "value3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aq_telemetry_f_t, value3) }, \ - { "value4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aq_telemetry_f_t, value4) }, \ - { "value5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aq_telemetry_f_t, value5) }, \ - { "value6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aq_telemetry_f_t, value6) }, \ - { "value7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aq_telemetry_f_t, value7) }, \ - { "value8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aq_telemetry_f_t, value8) }, \ - { "value9", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aq_telemetry_f_t, value9) }, \ - { "value10", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aq_telemetry_f_t, value10) }, \ - { "value11", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aq_telemetry_f_t, value11) }, \ - { "value12", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aq_telemetry_f_t, value12) }, \ - { "value13", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aq_telemetry_f_t, value13) }, \ - { "value14", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aq_telemetry_f_t, value14) }, \ - { "value15", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aq_telemetry_f_t, value15) }, \ - { "value16", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aq_telemetry_f_t, value16) }, \ - { "value17", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aq_telemetry_f_t, value17) }, \ - { "value18", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aq_telemetry_f_t, value18) }, \ - { "value19", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aq_telemetry_f_t, value19) }, \ - { "value20", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aq_telemetry_f_t, value20) }, \ - { "Index", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_aq_telemetry_f_t, Index) }, \ - } \ -} - - -/** - * @brief Pack a aq_telemetry_f 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 Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Index,float value1,float value2,float value3,float value4,float value5,float value6,float value7,float value8,float value9,float value10,float value11,float value12,float value13,float value14,float value15,float value16,float value17,float value18,float value19,float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} - -/** - * @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) - * @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(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f) -{ - 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 - * - * @param Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_aq_telemetry_f_send(mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#endif -} - -#endif - -// MESSAGE AQ_TELEMETRY_F UNPACKING - - -/** - * @brief Get field Index from aq_telemetry_f message - * - * @return Index of message - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_get_Index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 80); -} - -/** - * @brief Get field value1 from aq_telemetry_f message - * - * @return value1 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field value2 from aq_telemetry_f message - * - * @return value2 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field value3 from aq_telemetry_f message - * - * @return value3 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field value4 from aq_telemetry_f message - * - * @return value4 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field value5 from aq_telemetry_f message - * - * @return value5 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field value6 from aq_telemetry_f message - * - * @return value6 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field value7 from aq_telemetry_f message - * - * @return value7 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field value8 from aq_telemetry_f message - * - * @return value8 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field value9 from aq_telemetry_f message - * - * @return value9 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value9(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field value10 from aq_telemetry_f message - * - * @return value10 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value10(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field value11 from aq_telemetry_f message - * - * @return value11 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value11(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field value12 from aq_telemetry_f message - * - * @return value12 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value12(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field value13 from aq_telemetry_f message - * - * @return value13 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value13(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field value14 from aq_telemetry_f message - * - * @return value14 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value14(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field value15 from aq_telemetry_f message - * - * @return value15 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value15(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field value16 from aq_telemetry_f message - * - * @return value16 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field value17 from aq_telemetry_f message - * - * @return value17 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value17(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field value18 from aq_telemetry_f message - * - * @return value18 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value18(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field value19 from aq_telemetry_f message - * - * @return value19 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value19(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field value20 from aq_telemetry_f message - * - * @return value20 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value20(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Decode a aq_telemetry_f message into a struct - * - * @param msg The message to decode - * @param aq_telemetry_f C-struct to decode the message contents into - */ -static inline void mavlink_msg_aq_telemetry_f_decode(const mavlink_message_t* msg, mavlink_aq_telemetry_f_t* aq_telemetry_f) -{ -#if MAVLINK_NEED_BYTE_SWAP - aq_telemetry_f->value1 = mavlink_msg_aq_telemetry_f_get_value1(msg); - aq_telemetry_f->value2 = mavlink_msg_aq_telemetry_f_get_value2(msg); - aq_telemetry_f->value3 = mavlink_msg_aq_telemetry_f_get_value3(msg); - aq_telemetry_f->value4 = mavlink_msg_aq_telemetry_f_get_value4(msg); - aq_telemetry_f->value5 = mavlink_msg_aq_telemetry_f_get_value5(msg); - aq_telemetry_f->value6 = mavlink_msg_aq_telemetry_f_get_value6(msg); - aq_telemetry_f->value7 = mavlink_msg_aq_telemetry_f_get_value7(msg); - aq_telemetry_f->value8 = mavlink_msg_aq_telemetry_f_get_value8(msg); - aq_telemetry_f->value9 = mavlink_msg_aq_telemetry_f_get_value9(msg); - aq_telemetry_f->value10 = mavlink_msg_aq_telemetry_f_get_value10(msg); - aq_telemetry_f->value11 = mavlink_msg_aq_telemetry_f_get_value11(msg); - aq_telemetry_f->value12 = mavlink_msg_aq_telemetry_f_get_value12(msg); - aq_telemetry_f->value13 = mavlink_msg_aq_telemetry_f_get_value13(msg); - aq_telemetry_f->value14 = mavlink_msg_aq_telemetry_f_get_value14(msg); - aq_telemetry_f->value15 = mavlink_msg_aq_telemetry_f_get_value15(msg); - aq_telemetry_f->value16 = mavlink_msg_aq_telemetry_f_get_value16(msg); - aq_telemetry_f->value17 = mavlink_msg_aq_telemetry_f_get_value17(msg); - aq_telemetry_f->value18 = mavlink_msg_aq_telemetry_f_get_value18(msg); - aq_telemetry_f->value19 = mavlink_msg_aq_telemetry_f_get_value19(msg); - aq_telemetry_f->value20 = mavlink_msg_aq_telemetry_f_get_value20(msg); - aq_telemetry_f->Index = mavlink_msg_aq_telemetry_f_get_Index(msg); -#else - memcpy(aq_telemetry_f, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h deleted file mode 100644 index dbec869ce..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h +++ /dev/null @@ -1,118 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from autoquad.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef AUTOQUAD_TESTSUITE_H -#define AUTOQUAD_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_autoquad(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_autoquad(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_aq_telemetry_f(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_aq_telemetry_f_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, - 353.0, - 381.0, - 409.0, - 437.0, - 465.0, - 493.0, - 521.0, - 549.0, - 21395, - }; - mavlink_aq_telemetry_f_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.value1 = packet_in.value1; - packet1.value2 = packet_in.value2; - packet1.value3 = packet_in.value3; - packet1.value4 = packet_in.value4; - packet1.value5 = packet_in.value5; - packet1.value6 = packet_in.value6; - packet1.value7 = packet_in.value7; - packet1.value8 = packet_in.value8; - packet1.value9 = packet_in.value9; - packet1.value10 = packet_in.value10; - packet1.value11 = packet_in.value11; - packet1.value12 = packet_in.value12; - packet1.value13 = packet_in.value13; - packet1.value14 = packet_in.value14; - packet1.value15 = packet_in.value15; - packet1.value16 = packet_in.value16; - packet1.value17 = packet_in.value17; - packet1.value18 = packet_in.value18; - packet1.value19 = packet_in.value19; - packet1.value20 = packet_in.value20; - packet1.Index = packet_in.Index; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_pack(system_id, component_id, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); - mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); - mavlink_msg_aq_telemetry_f_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; iaccu_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); + 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->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); } /** @@ -176,7 +192,7 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint */ 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); + 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->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); } /** @@ -191,23 +207,27 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int8_t battery_remaining) +static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, voltage_cell_1); - _mav_put_uint16_t(buf, 2, voltage_cell_2); - _mav_put_uint16_t(buf, 4, voltage_cell_3); - _mav_put_uint16_t(buf, 6, voltage_cell_4); - _mav_put_uint16_t(buf, 8, voltage_cell_5); - _mav_put_uint16_t(buf, 10, voltage_cell_6); - _mav_put_int16_t(buf, 12, current_battery); - _mav_put_uint8_t(buf, 14, accu_id); - _mav_put_int8_t(buf, 15, battery_remaining); + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_uint16_t(buf, 8, voltage_cell_1); + _mav_put_uint16_t(buf, 10, voltage_cell_2); + _mav_put_uint16_t(buf, 12, voltage_cell_3); + _mav_put_uint16_t(buf, 14, voltage_cell_4); + _mav_put_uint16_t(buf, 16, voltage_cell_5); + _mav_put_uint16_t(buf, 18, voltage_cell_6); + _mav_put_int16_t(buf, 20, current_battery); + _mav_put_uint8_t(buf, 22, accu_id); + _mav_put_int8_t(buf, 23, battery_remaining); #if MAVLINK_CRC_EXTRA _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); @@ -216,6 +236,8 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8 #endif #else mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; packet.voltage_cell_1 = voltage_cell_1; packet.voltage_cell_2 = voltage_cell_2; packet.voltage_cell_3 = voltage_cell_3; @@ -246,7 +268,7 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8 */ static inline uint8_t mavlink_msg_battery_status_get_accu_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 14); + return _MAV_RETURN_uint8_t(msg, 22); } /** @@ -256,7 +278,7 @@ static inline uint8_t mavlink_msg_battery_status_get_accu_id(const mavlink_messa */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_1(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 8); } /** @@ -266,7 +288,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_1(const mavli */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_2(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 2); + return _MAV_RETURN_uint16_t(msg, 10); } /** @@ -276,7 +298,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_2(const mavli */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_3(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 4); + return _MAV_RETURN_uint16_t(msg, 12); } /** @@ -286,7 +308,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_3(const mavli */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_4(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 6); + return _MAV_RETURN_uint16_t(msg, 14); } /** @@ -296,7 +318,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_4(const mavli */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_5(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 8); + return _MAV_RETURN_uint16_t(msg, 16); } /** @@ -306,7 +328,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_5(const mavli */ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 10); + return _MAV_RETURN_uint16_t(msg, 18); } /** @@ -316,7 +338,27 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavli */ static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) { - return _MAV_RETURN_int16_t(msg, 12); + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field current_consumed from battery_status message + * + * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field energy_consumed from battery_status message + * + * @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); } /** @@ -326,7 +368,7 @@ static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavli */ static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) { - return _MAV_RETURN_int8_t(msg, 15); + return _MAV_RETURN_int8_t(msg, 23); } /** @@ -338,6 +380,8 @@ static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavl static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) { #if MAVLINK_NEED_BYTE_SWAP + battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); + battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); battery_status->voltage_cell_1 = mavlink_msg_battery_status_get_voltage_cell_1(msg); battery_status->voltage_cell_2 = mavlink_msg_battery_status_get_voltage_cell_2(msg); battery_status->voltage_cell_3 = mavlink_msg_battery_status_get_voltage_cell_3(msg); diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h index 3054d4fda..a105f8cda 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -9,7 +9,7 @@ typedef struct __mavlink_gps_raw_int_t int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. @@ -53,7 +53,7 @@ typedef struct __mavlink_gps_raw_int_t * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX * @param satellites_visible Number of satellites visible. If unknown, set to 255 @@ -112,7 +112,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX * @param satellites_visible Number of satellites visible. If unknown, set to 255 @@ -197,7 +197,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX * @param satellites_visible Number of satellites visible. If unknown, set to 255 @@ -313,7 +313,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* /** * @brief Get field epv from gps_raw_int message * - * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h index 36a551872..91aec5b08 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h @@ -9,7 +9,7 @@ typedef struct __mavlink_hil_gps_t int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535 int16_t vn; ///< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame int16_t ve; ///< GPS velocity in cm/s in EAST direction in earth-fixed NED frame @@ -59,7 +59,7 @@ typedef struct __mavlink_hil_gps_t * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame @@ -127,7 +127,7 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame @@ -221,7 +221,7 @@ static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_ * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame @@ -346,7 +346,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) /** * @brief Get field epv from hil_gps message * - * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 */ static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h new file mode 100644 index 000000000..1cf5d15e4 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h @@ -0,0 +1,237 @@ +// MESSAGE LOG_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_DATA 120 + +typedef struct __mavlink_log_data_t +{ + uint32_t ofs; ///< Offset into the log + uint16_t id; ///< Log id (from LOG_ENTRY reply) + uint8_t count; ///< Number of bytes (zero for end of log) + uint8_t data[90]; ///< log data +} mavlink_log_data_t; + +#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 +#define MAVLINK_MSG_ID_120_LEN 97 + +#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 +#define MAVLINK_MSG_ID_120_CRC 134 + +#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 + +#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ + "LOG_DATA", \ + 4, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a log_data 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 id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_data 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 id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_data 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 log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Encode a log_data 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 log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Send a log_data message + * @param chan MAVLink channel to send the message + * + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_DATA UNPACKING + + +/** + * @brief Get field id from log_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field ofs from log_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_data message + * + * @return Number of bytes (zero for end of log) + */ +static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field data from log_data message + * + * @return log data + */ +static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); +} + +/** + * @brief Decode a log_data message into a struct + * + * @param msg The message to decode + * @param log_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_data->ofs = mavlink_msg_log_data_get_ofs(msg); + log_data->id = mavlink_msg_log_data_get_id(msg); + log_data->count = mavlink_msg_log_data_get_count(msg); + mavlink_msg_log_data_get_data(msg, log_data->data); +#else + memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h new file mode 100644 index 000000000..681d8f07c --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h @@ -0,0 +1,265 @@ +// MESSAGE LOG_ENTRY PACKING + +#define MAVLINK_MSG_ID_LOG_ENTRY 118 + +typedef struct __mavlink_log_entry_t +{ + uint32_t time_utc; ///< UTC timestamp of log in seconds since 1970, or 0 if not available + uint32_t size; ///< Size of the log (may be approximate) in bytes + uint16_t id; ///< Log id + uint16_t num_logs; ///< Total number of logs + uint16_t last_log_num; ///< High log number +} mavlink_log_entry_t; + +#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 +#define MAVLINK_MSG_ID_118_LEN 14 + +#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 +#define MAVLINK_MSG_ID_118_CRC 56 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ + "LOG_ENTRY", \ + 5, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ + { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ + { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ + } \ +} + + +/** + * @brief Pack a log_entry 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 id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Pack a log_entry 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 id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Encode a log_entry 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 log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Encode a log_entry 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 log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Send a log_entry message + * @param chan MAVLink channel to send the message + * + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_ENTRY UNPACKING + + +/** + * @brief Get field id from log_entry message + * + * @return Log id + */ +static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field num_logs from log_entry message + * + * @return Total number of logs + */ +static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field last_log_num from log_entry message + * + * @return High log number + */ +static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field time_utc from log_entry message + * + * @return UTC timestamp of log in seconds since 1970, or 0 if not available + */ +static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field size from log_entry message + * + * @return Size of the log (may be approximate) in bytes + */ +static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_entry message into a struct + * + * @param msg The message to decode + * @param log_entry C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); + log_entry->size = mavlink_msg_log_entry_get_size(msg); + log_entry->id = mavlink_msg_log_entry_get_id(msg); + log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); + log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); +#else + memcpy(log_entry, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h new file mode 100644 index 000000000..feafeaf16 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h @@ -0,0 +1,199 @@ +// MESSAGE LOG_ERASE PACKING + +#define MAVLINK_MSG_ID_LOG_ERASE 121 + +typedef struct __mavlink_log_erase_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_log_erase_t; + +#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 +#define MAVLINK_MSG_ID_121_LEN 2 + +#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 +#define MAVLINK_MSG_ID_121_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ + "LOG_ERASE", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_erase 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 target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Pack a log_erase 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 target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Encode a log_erase 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 log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Encode a log_erase 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 log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Send a log_erase message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_ERASE UNPACKING + + +/** + * @brief Get field target_system from log_erase message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_erase message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_erase message into a struct + * + * @param msg The message to decode + * @param log_erase C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); + log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); +#else + memcpy(log_erase, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h new file mode 100644 index 000000000..5be9eea47 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h @@ -0,0 +1,265 @@ +// MESSAGE LOG_REQUEST_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 + +typedef struct __mavlink_log_request_data_t +{ + uint32_t ofs; ///< Offset into the log + uint32_t count; ///< Number of bytes + uint16_t id; ///< Log id (from LOG_ENTRY reply) + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_log_request_data_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 +#define MAVLINK_MSG_ID_119_LEN 12 + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 +#define MAVLINK_MSG_ID_119_CRC 116 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ + "LOG_REQUEST_DATA", \ + 5, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ + { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_data 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 target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_request_data 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 target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_request_data 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 log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Encode a log_request_data 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 log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Send a log_request_data message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_REQUEST_DATA UNPACKING + + +/** + * @brief Get field target_system from log_request_data message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field target_component from log_request_data message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field id from log_request_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field ofs from log_request_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_request_data message + * + * @return Number of bytes + */ +static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_request_data message into a struct + * + * @param msg The message to decode + * @param log_request_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); + log_request_data->count = mavlink_msg_log_request_data_get_count(msg); + log_request_data->id = mavlink_msg_log_request_data_get_id(msg); + log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); + log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); +#else + memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h new file mode 100644 index 000000000..48a5a03b4 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h @@ -0,0 +1,199 @@ +// MESSAGE LOG_REQUEST_END PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 + +typedef struct __mavlink_log_request_end_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_log_request_end_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 +#define MAVLINK_MSG_ID_122_LEN 2 + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 +#define MAVLINK_MSG_ID_122_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ + "LOG_REQUEST_END", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_end 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 target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Pack a log_request_end 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 target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Encode a log_request_end 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 log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Encode a log_request_end 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 log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Send a log_request_end message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_REQUEST_END UNPACKING + + +/** + * @brief Get field target_system from log_request_end message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_request_end message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_request_end message into a struct + * + * @param msg The message to decode + * @param log_request_end C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); + log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); +#else + memcpy(log_request_end, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h new file mode 100644 index 000000000..7a5b25c17 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h @@ -0,0 +1,243 @@ +// MESSAGE LOG_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 + +typedef struct __mavlink_log_request_list_t +{ + uint16_t start; ///< First log id (0 for first available) + uint16_t end; ///< Last log id (0xffff for last available) + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_log_request_list_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 +#define MAVLINK_MSG_ID_117_LEN 6 + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 +#define MAVLINK_MSG_ID_117_CRC 128 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ + "LOG_REQUEST_LIST", \ + 4, \ + { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ + { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_list 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 target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a log_request_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 will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a log_request_list 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 log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Encode a log_request_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 log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Send a log_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#endif +} + +#endif + +// MESSAGE LOG_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from log_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from log_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start from log_request_list message + * + * @return First log id (0 for first available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field end from log_request_list message + * + * @return Last log id (0xffff for last available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a log_request_list message into a struct + * + * @param msg The message to decode + * @param log_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_list->start = mavlink_msg_log_request_list_get_start(msg); + log_request_list->end = mavlink_msg_log_request_list_get_end(msg); + log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); + log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); +#else + memcpy(log_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h index 634f80c37..a8d60eca7 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h @@ -4,13 +4,13 @@ typedef struct __mavlink_mission_item_t { - float param1; ///< PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters - float param2; ///< PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - float param3; ///< PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - float param4; ///< PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + float param1; ///< PARAM1, see MAV_CMD enum + float param2; ///< PARAM2, see MAV_CMD enum + float param3; ///< PARAM3, see MAV_CMD enum + float param4; ///< PARAM4, see MAV_CMD enum float x; ///< PARAM5 / local: x position, global: latitude float y; ///< PARAM6 / y position: global: longitude - float z; ///< PARAM7 / z position: global: altitude + float z; ///< PARAM7 / z position: global: altitude (relative or absolute, depending on frame. uint16_t seq; ///< Sequence uint16_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs uint8_t target_system; ///< System ID @@ -62,13 +62,13 @@ typedef struct __mavlink_mission_item_t * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs * @param current false:0, true:1 * @param autocontinue autocontinue to next wp - * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters - * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum * @param x PARAM5 / local: x position, global: latitude * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -133,13 +133,13 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs * @param current false:0, true:1 * @param autocontinue autocontinue to next wp - * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters - * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum * @param x PARAM5 / local: x position, global: latitude * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -230,13 +230,13 @@ static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, u * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs * @param current false:0, true:1 * @param autocontinue autocontinue to next wp - * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters - * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum * @param x PARAM5 / local: x position, global: latitude * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -367,7 +367,7 @@ static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_me /** * @brief Get field param1 from mission_item message * - * @return PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @return PARAM1, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) { @@ -377,7 +377,7 @@ static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* /** * @brief Get field param2 from mission_item message * - * @return PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @return PARAM2, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) { @@ -387,7 +387,7 @@ static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* /** * @brief Get field param3 from mission_item message * - * @return PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @return PARAM3, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) { @@ -397,7 +397,7 @@ static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* /** * @brief Get field param4 from mission_item message * - * @return PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @return PARAM4, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) { @@ -427,7 +427,7 @@ static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) /** * @brief Get field z from mission_item message * - * @return PARAM7 / z position: global: altitude + * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. */ static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h new file mode 100644 index 000000000..ea4dbbf81 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h @@ -0,0 +1,375 @@ +// MESSAGE SCALED_IMU2 PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU2 116 + +typedef struct __mavlink_scaled_imu2_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) + int16_t xgyro; ///< Angular speed around X axis (millirad /sec) + int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) + int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) + int16_t xmag; ///< X Magnetic field (milli tesla) + int16_t ymag; ///< Y Magnetic field (milli tesla) + int16_t zmag; ///< Z Magnetic field (milli tesla) +} mavlink_scaled_imu2_t; + +#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 +#define MAVLINK_MSG_ID_116_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 +#define MAVLINK_MSG_ID_116_CRC 76 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ + "SCALED_IMU2", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu2 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 time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu2 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 time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu2 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 scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Encode a scaled_imu2 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 scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Send a scaled_imu2 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#endif +} + +#endif + +// MESSAGE SCALED_IMU2 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu2 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu2 message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu2 message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu2 message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu2 message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu2 message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu2 message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu2 message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu2 message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu2 message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu2 message into a struct + * + * @param msg The message to decode + * @param scaled_imu2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); + scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); + scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); + scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); + scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); + scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); + scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); + scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); + scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); + scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); +#else + memcpy(scaled_imu2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h index 058c630dd..101b36678 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h @@ -4,9 +4,9 @@ typedef struct __mavlink_sys_status_t { - uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 uint16_t voltage_battery; ///< Battery voltage, in millivolts (1 = 1 millivolt) int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current @@ -53,9 +53,9 @@ typedef struct __mavlink_sys_status_t * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current @@ -121,9 +121,9 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co * @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 onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current @@ -215,9 +215,9 @@ static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uin * @brief Send a sys_status message * @param chan MAVLink channel to send the message * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current @@ -286,7 +286,7 @@ static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t /** * @brief Get field onboard_control_sensors_present from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_presen /** * @brief Get field onboard_control_sensors_enabled from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enable /** * @brief Get field onboard_control_sensors_health from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h index 08dc66403..16250ab42 100644 --- a/mavlink/include/mavlink/v1.0/common/testsuite.h +++ b/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -31,11 +31,11 @@ static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavl uint16_t i; mavlink_heartbeat_t packet_in = { 963497464, - 17, - 84, - 151, - 218, - 3, + }17, + }84, + }151, + }218, + }3, }; mavlink_heartbeat_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -84,18 +84,18 @@ static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mav uint16_t i; mavlink_sys_status_t packet_in = { 963497464, - 963497672, - 963497880, - 17859, - 17963, - 18067, - 18171, - 18275, - 18379, - 18483, - 18587, - 18691, - 223, + }963497672, + }963497880, + }17859, + }17963, + }18067, + }18171, + }18275, + }18379, + }18483, + }18587, + }18691, + }223, }; mavlink_sys_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -151,7 +151,7 @@ static void mavlink_test_system_time(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_system_time_t packet_in = { 93372036854775807ULL, - 963497880, + }963497880, }; mavlink_system_time_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -196,9 +196,9 @@ static void mavlink_test_ping(uint8_t system_id, uint8_t component_id, mavlink_m uint16_t i; mavlink_ping_t packet_in = { 93372036854775807ULL, - 963497880, - 41, - 108, + }963497880, + }41, + }108, }; mavlink_ping_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -245,9 +245,9 @@ static void mavlink_test_change_operator_control(uint8_t system_id, uint8_t comp uint16_t i; mavlink_change_operator_control_t packet_in = { 5, - 72, - 139, - "DEFGHIJKLMNOPQRSTUVWXYZA", + }72, + }139, + }"DEFGHIJKLMNOPQRSTUVWXYZA", }; mavlink_change_operator_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -294,8 +294,8 @@ static void mavlink_test_change_operator_control_ack(uint8_t system_id, uint8_t uint16_t i; mavlink_change_operator_control_ack_t packet_in = { 5, - 72, - 139, + }72, + }139, }; mavlink_change_operator_control_ack_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -384,8 +384,8 @@ static void mavlink_test_set_mode(uint8_t system_id, uint8_t component_id, mavli uint16_t i; mavlink_set_mode_t packet_in = { 963497464, - 17, - 84, + }17, + }84, }; mavlink_set_mode_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -431,9 +431,9 @@ static void mavlink_test_param_request_read(uint8_t system_id, uint8_t component uint16_t i; mavlink_param_request_read_t packet_in = { 17235, - 139, - 206, - "EFGHIJKLMNOPQRS", + }139, + }206, + }"EFGHIJKLMNOPQRS", }; mavlink_param_request_read_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -480,7 +480,7 @@ static void mavlink_test_param_request_list(uint8_t system_id, uint8_t component uint16_t i; mavlink_param_request_list_t packet_in = { 5, - 72, + }72, }; mavlink_param_request_list_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -525,10 +525,10 @@ static void mavlink_test_param_value(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_param_value_t packet_in = { 17.0, - 17443, - 17547, - "IJKLMNOPQRSTUVW", - 77, + }17443, + }17547, + }"IJKLMNOPQRSTUVW", + }77, }; mavlink_param_value_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -576,10 +576,10 @@ static void mavlink_test_param_set(uint8_t system_id, uint8_t component_id, mavl uint16_t i; mavlink_param_set_t packet_in = { 17.0, - 17, - 84, - "GHIJKLMNOPQRSTU", - 199, + }17, + }84, + }"GHIJKLMNOPQRSTU", + }199, }; mavlink_param_set_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -627,15 +627,15 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_gps_raw_int_t packet_in = { 93372036854775807ULL, - 963497880, - 963498088, - 963498296, - 18275, - 18379, - 18483, - 18587, - 89, - 156, + }963497880, + }963498088, + }963498296, + }18275, + }18379, + }18483, + }18587, + }89, + }156, }; mavlink_gps_raw_int_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -688,11 +688,11 @@ static void mavlink_test_gps_status(uint8_t system_id, uint8_t component_id, mav uint16_t i; mavlink_gps_status_t packet_in = { 5, - { 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 }, - { 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 }, - { 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 }, - { 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, - { 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 }, + }{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 }, + }{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 }, + }{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 }, + }{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + }{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 }, }; mavlink_gps_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -741,15 +741,15 @@ static void mavlink_test_scaled_imu(uint8_t system_id, uint8_t component_id, mav uint16_t i; mavlink_scaled_imu_t packet_in = { 963497464, - 17443, - 17547, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 18275, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }18275, }; mavlink_scaled_imu_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -802,15 +802,15 @@ static void mavlink_test_raw_imu(uint8_t system_id, uint8_t component_id, mavlin uint16_t i; mavlink_raw_imu_t packet_in = { 93372036854775807ULL, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 18275, - 18379, - 18483, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }18275, + }18379, + }18483, }; mavlink_raw_imu_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -863,10 +863,10 @@ static void mavlink_test_raw_pressure(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_raw_pressure_t packet_in = { 93372036854775807ULL, - 17651, - 17755, - 17859, - 17963, + }17651, + }17755, + }17859, + }17963, }; mavlink_raw_pressure_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -914,9 +914,9 @@ static void mavlink_test_scaled_pressure(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_scaled_pressure_t packet_in = { 963497464, - 45.0, - 73.0, - 17859, + }45.0, + }73.0, + }17859, }; mavlink_scaled_pressure_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -963,12 +963,12 @@ static void mavlink_test_attitude(uint8_t system_id, uint8_t component_id, mavli uint16_t i; mavlink_attitude_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, }; mavlink_attitude_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1018,13 +1018,13 @@ static void mavlink_test_attitude_quaternion(uint8_t system_id, uint8_t componen uint16_t i; mavlink_attitude_quaternion_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, }; mavlink_attitude_quaternion_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1075,12 +1075,12 @@ static void mavlink_test_local_position_ned(uint8_t system_id, uint8_t component uint16_t i; mavlink_local_position_ned_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, }; mavlink_local_position_ned_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1130,14 +1130,14 @@ static void mavlink_test_global_position_int(uint8_t system_id, uint8_t componen uint16_t i; mavlink_global_position_int_t packet_in = { 963497464, - 963497672, - 963497880, - 963498088, - 963498296, - 18275, - 18379, - 18483, - 18587, + }963497672, + }963497880, + }963498088, + }963498296, + }18275, + }18379, + }18483, + }18587, }; mavlink_global_position_int_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1189,16 +1189,16 @@ static void mavlink_test_rc_channels_scaled(uint8_t system_id, uint8_t component uint16_t i; mavlink_rc_channels_scaled_t packet_in = { 963497464, - 17443, - 17547, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 65, - 132, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }65, + }132, }; mavlink_rc_channels_scaled_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1252,16 +1252,16 @@ static void mavlink_test_rc_channels_raw(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_rc_channels_raw_t packet_in = { 963497464, - 17443, - 17547, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 65, - 132, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }65, + }132, }; mavlink_rc_channels_raw_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1315,15 +1315,15 @@ static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_i uint16_t i; mavlink_servo_output_raw_t packet_in = { 963497464, - 17443, - 17547, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 65, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }65, }; mavlink_servo_output_raw_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1376,9 +1376,9 @@ static void mavlink_test_mission_request_partial_list(uint8_t system_id, uint8_t uint16_t i; mavlink_mission_request_partial_list_t packet_in = { 17235, - 17339, - 17, - 84, + }17339, + }17, + }84, }; mavlink_mission_request_partial_list_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1425,9 +1425,9 @@ static void mavlink_test_mission_write_partial_list(uint8_t system_id, uint8_t c uint16_t i; mavlink_mission_write_partial_list_t packet_in = { 17235, - 17339, - 17, - 84, + }17339, + }17, + }84, }; mavlink_mission_write_partial_list_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1474,19 +1474,19 @@ static void mavlink_test_mission_item(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_mission_item_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 18691, - 18795, - 101, - 168, - 235, - 46, - 113, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }18691, + }18795, + }101, + }168, + }235, + }46, + }113, }; mavlink_mission_item_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1543,8 +1543,8 @@ static void mavlink_test_mission_request(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_mission_request_t packet_in = { 17235, - 139, - 206, + }139, + }206, }; mavlink_mission_request_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1590,8 +1590,8 @@ static void mavlink_test_mission_set_current(uint8_t system_id, uint8_t componen uint16_t i; mavlink_mission_set_current_t packet_in = { 17235, - 139, - 206, + }139, + }206, }; mavlink_mission_set_current_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1680,7 +1680,7 @@ static void mavlink_test_mission_request_list(uint8_t system_id, uint8_t compone uint16_t i; mavlink_mission_request_list_t packet_in = { 5, - 72, + }72, }; mavlink_mission_request_list_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1725,8 +1725,8 @@ static void mavlink_test_mission_count(uint8_t system_id, uint8_t component_id, uint16_t i; mavlink_mission_count_t packet_in = { 17235, - 139, - 206, + }139, + }206, }; mavlink_mission_count_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1772,7 +1772,7 @@ static void mavlink_test_mission_clear_all(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_mission_clear_all_t packet_in = { 5, - 72, + }72, }; mavlink_mission_clear_all_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1860,8 +1860,8 @@ static void mavlink_test_mission_ack(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_mission_ack_t packet_in = { 5, - 72, - 139, + }72, + }139, }; mavlink_mission_ack_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1907,9 +1907,9 @@ static void mavlink_test_set_gps_global_origin(uint8_t system_id, uint8_t compon uint16_t i; mavlink_set_gps_global_origin_t packet_in = { 963497464, - 963497672, - 963497880, - 41, + }963497672, + }963497880, + }41, }; mavlink_set_gps_global_origin_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1956,8 +1956,8 @@ static void mavlink_test_gps_global_origin(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_gps_global_origin_t packet_in = { 963497464, - 963497672, - 963497880, + }963497672, + }963497880, }; mavlink_gps_global_origin_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2003,12 +2003,12 @@ static void mavlink_test_set_local_position_setpoint(uint8_t system_id, uint8_t uint16_t i; mavlink_set_local_position_setpoint_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 53, - 120, - 187, + }45.0, + }73.0, + }101.0, + }53, + }120, + }187, }; mavlink_set_local_position_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2058,10 +2058,10 @@ static void mavlink_test_local_position_setpoint(uint8_t system_id, uint8_t comp uint16_t i; mavlink_local_position_setpoint_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 53, + }45.0, + }73.0, + }101.0, + }53, }; mavlink_local_position_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2109,10 +2109,10 @@ static void mavlink_test_global_position_setpoint_int(uint8_t system_id, uint8_t uint16_t i; mavlink_global_position_setpoint_int_t packet_in = { 963497464, - 963497672, - 963497880, - 17859, - 175, + }963497672, + }963497880, + }17859, + }175, }; mavlink_global_position_setpoint_int_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2160,10 +2160,10 @@ static void mavlink_test_set_global_position_setpoint_int(uint8_t system_id, uin uint16_t i; mavlink_set_global_position_setpoint_int_t packet_in = { 963497464, - 963497672, - 963497880, - 17859, - 175, + }963497672, + }963497880, + }17859, + }175, }; mavlink_set_global_position_setpoint_int_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2211,14 +2211,14 @@ static void mavlink_test_safety_set_allowed_area(uint8_t system_id, uint8_t comp uint16_t i; mavlink_safety_set_allowed_area_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 77, - 144, - 211, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }77, + }144, + }211, }; mavlink_safety_set_allowed_area_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2270,12 +2270,12 @@ static void mavlink_test_safety_allowed_area(uint8_t system_id, uint8_t componen uint16_t i; mavlink_safety_allowed_area_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 77, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }77, }; mavlink_safety_allowed_area_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2325,11 +2325,11 @@ static void mavlink_test_set_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t co uint16_t i; mavlink_set_roll_pitch_yaw_thrust_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 53, - 120, + }45.0, + }73.0, + }101.0, + }53, + }120, }; mavlink_set_roll_pitch_yaw_thrust_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2378,11 +2378,11 @@ static void mavlink_test_set_roll_pitch_yaw_speed_thrust(uint8_t system_id, uint uint16_t i; mavlink_set_roll_pitch_yaw_speed_thrust_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 53, - 120, + }45.0, + }73.0, + }101.0, + }53, + }120, }; mavlink_set_roll_pitch_yaw_speed_thrust_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2431,10 +2431,10 @@ static void mavlink_test_roll_pitch_yaw_thrust_setpoint(uint8_t system_id, uint8 uint16_t i; mavlink_roll_pitch_yaw_thrust_setpoint_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, + }45.0, + }73.0, + }101.0, + }129.0, }; mavlink_roll_pitch_yaw_thrust_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2482,10 +2482,10 @@ static void mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(uint8_t system_id, uint16_t i; mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, + }45.0, + }73.0, + }101.0, + }129.0, }; mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2533,10 +2533,10 @@ static void mavlink_test_set_quad_motors_setpoint(uint8_t system_id, uint8_t com uint16_t i; mavlink_set_quad_motors_setpoint_t packet_in = { 17235, - 17339, - 17443, - 17547, - 29, + }17339, + }17443, + }17547, + }29, }; mavlink_set_quad_motors_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2584,11 +2584,11 @@ static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id, uint16_t i; mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet_in = { { 17235, 17236, 17237, 17238 }, - { 17651, 17652, 17653, 17654 }, - { 18067, 18068, 18069, 18070 }, - { 18483, 18484, 18485, 18486 }, - 101, - 168, + }{ 17651, 17652, 17653, 17654 }, + }{ 18067, 18068, 18069, 18070 }, + }{ 18483, 18484, 18485, 18486 }, + }101, + }168, }; mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2637,13 +2637,13 @@ static void mavlink_test_nav_controller_output(uint8_t system_id, uint8_t compon uint16_t i; mavlink_nav_controller_output_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 18275, - 18379, - 18483, + }45.0, + }73.0, + }101.0, + }129.0, + }18275, + }18379, + }18483, }; mavlink_nav_controller_output_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2694,14 +2694,14 @@ static void mavlink_test_set_quad_swarm_led_roll_pitch_yaw_thrust(uint8_t system uint16_t i; mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet_in = { { 17235, 17236, 17237, 17238 }, - { 17651, 17652, 17653, 17654 }, - { 18067, 18068, 18069, 18070 }, - { 18483, 18484, 18485, 18486 }, - 101, - 168, - { 235, 236, 237, 238 }, - { 247, 248, 249, 250 }, - { 3, 4, 5, 6 }, + }{ 17651, 17652, 17653, 17654 }, + }{ 18067, 18068, 18069, 18070 }, + }{ 18483, 18484, 18485, 18486 }, + }101, + }168, + }{ 235, 236, 237, 238 }, + }{ 247, 248, 249, 250 }, + }{ 3, 4, 5, 6 }, }; mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2753,14 +2753,14 @@ static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_i uint16_t i; mavlink_state_correction_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, }; mavlink_state_correction_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2812,10 +2812,10 @@ static void mavlink_test_request_data_stream(uint8_t system_id, uint8_t componen uint16_t i; mavlink_request_data_stream_t packet_in = { 17235, - 139, - 206, - 17, - 84, + }139, + }206, + }17, + }84, }; mavlink_request_data_stream_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2863,8 +2863,8 @@ static void mavlink_test_data_stream(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_data_stream_t packet_in = { 17235, - 139, - 206, + }139, + }206, }; mavlink_data_stream_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2910,11 +2910,11 @@ static void mavlink_test_manual_control(uint8_t system_id, uint8_t component_id, uint16_t i; mavlink_manual_control_t packet_in = { 17235, - 17339, - 17443, - 17547, - 17651, - 163, + }17339, + }17443, + }17547, + }17651, + }163, }; mavlink_manual_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2963,15 +2963,15 @@ static void mavlink_test_rc_channels_override(uint8_t system_id, uint8_t compone uint16_t i; mavlink_rc_channels_override_t packet_in = { 17235, - 17339, - 17443, - 17547, - 17651, - 17755, - 17859, - 17963, - 53, - 120, + }17339, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }53, + }120, }; mavlink_rc_channels_override_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3024,11 +3024,11 @@ static void mavlink_test_vfr_hud(uint8_t system_id, uint8_t component_id, mavlin uint16_t i; mavlink_vfr_hud_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 18067, - 18171, + }45.0, + }73.0, + }101.0, + }18067, + }18171, }; mavlink_vfr_hud_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3077,16 +3077,16 @@ static void mavlink_test_command_long(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_command_long_t packet_in = { 17.0, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 18691, - 223, - 34, - 101, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }18691, + }223, + }34, + }101, }; mavlink_command_long_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3140,7 +3140,7 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_command_ack_t packet_in = { 17235, - 139, + }139, }; mavlink_command_ack_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3185,10 +3185,10 @@ static void mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(uint8_t system_id, uint16_t i; mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, + }45.0, + }73.0, + }101.0, + }129.0, }; mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3236,12 +3236,12 @@ static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_manual_setpoint_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, - 65, - 132, + }45.0, + }73.0, + }101.0, + }129.0, + }65, + }132, }; mavlink_manual_setpoint_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3291,12 +3291,12 @@ static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_ uint16_t i; mavlink_local_position_ned_system_global_offset_t packet_in = { 963497464, - 45.0, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, }; mavlink_local_position_ned_system_global_offset_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3346,21 +3346,21 @@ static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavl uint16_t i; mavlink_hil_state_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 963499128, - 963499336, - 963499544, - 19523, - 19627, - 19731, - 19835, - 19939, - 20043, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }963499128, + }963499336, + }963499544, + }19523, + }19627, + }19731, + }19835, + }19939, + }20043, }; mavlink_hil_state_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3419,16 +3419,16 @@ static void mavlink_test_hil_controls(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_hil_controls_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, - 269.0, - 125, - 192, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }269.0, + }125, + }192, }; mavlink_hil_controls_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3482,19 +3482,19 @@ static void mavlink_test_hil_rc_inputs_raw(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_hil_rc_inputs_raw_t packet_in = { 93372036854775807ULL, - 17651, - 17755, - 17859, - 17963, - 18067, - 18171, - 18275, - 18379, - 18483, - 18587, - 18691, - 18795, - 101, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }18275, + }18379, + }18483, + }18587, + }18691, + }18795, + }101, }; mavlink_hil_rc_inputs_raw_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3551,13 +3551,13 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_optical_flow_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 18275, - 18379, - 77, - 144, + }73.0, + }101.0, + }129.0, + }18275, + }18379, + }77, + }144, }; mavlink_optical_flow_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3608,12 +3608,12 @@ static void mavlink_test_global_vision_position_estimate(uint8_t system_id, uint uint16_t i; mavlink_global_vision_position_estimate_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, }; mavlink_global_vision_position_estimate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3663,12 +3663,12 @@ static void mavlink_test_vision_position_estimate(uint8_t system_id, uint8_t com uint16_t i; mavlink_vision_position_estimate_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, }; mavlink_vision_position_estimate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3718,9 +3718,9 @@ static void mavlink_test_vision_speed_estimate(uint8_t system_id, uint8_t compon uint16_t i; mavlink_vision_speed_estimate_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, + }73.0, + }101.0, + }129.0, }; mavlink_vision_speed_estimate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3767,12 +3767,12 @@ static void mavlink_test_vicon_position_estimate(uint8_t system_id, uint8_t comp uint16_t i; mavlink_vicon_position_estimate_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, }; mavlink_vicon_position_estimate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3822,20 +3822,20 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma uint16_t i; mavlink_highres_imu_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, - 269.0, - 297.0, - 325.0, - 353.0, - 381.0, - 409.0, - 20355, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }269.0, + }297.0, + }325.0, + }353.0, + }381.0, + }409.0, + }20355, }; mavlink_highres_imu_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3893,11 +3893,11 @@ static void mavlink_test_omnidirectional_flow(uint8_t system_id, uint8_t compone uint16_t i; mavlink_omnidirectional_flow_t packet_in = { 93372036854775807ULL, - 73.0, - { 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 }, - { 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 }, - 161, - 228, + }73.0, + }{ 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 }, + }{ 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 }, + }161, + }228, }; mavlink_omnidirectional_flow_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3946,20 +3946,20 @@ static void mavlink_test_hil_sensor(uint8_t system_id, uint8_t component_id, mav uint16_t i; mavlink_hil_sensor_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - 241.0, - 269.0, - 297.0, - 325.0, - 353.0, - 381.0, - 409.0, - 963500584, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }269.0, + }297.0, + }325.0, + }353.0, + }381.0, + }409.0, + }963500584, }; mavlink_hil_sensor_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4017,26 +4017,26 @@ static void mavlink_test_sim_state(uint8_t system_id, uint8_t component_id, mavl uint16_t i; mavlink_sim_state_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, - 353.0, - 381.0, - 409.0, - 437.0, - 465.0, - 493.0, - 521.0, - 549.0, - 577.0, + }45.0, + }73.0, + }101.0, + }129.0, + }157.0, + }185.0, + }213.0, + }241.0, + }269.0, + }297.0, + }325.0, + }353.0, + }381.0, + }409.0, + }437.0, + }465.0, + }493.0, + }521.0, + }549.0, + }577.0, }; mavlink_sim_state_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4100,12 +4100,12 @@ static void mavlink_test_radio_status(uint8_t system_id, uint8_t component_id, m uint16_t i; mavlink_radio_status_t packet_in = { 17235, - 17339, - 17, - 84, - 151, - 218, - 29, + }17339, + }17, + }84, + }151, + }218, + }29, }; mavlink_radio_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4155,10 +4155,10 @@ static void mavlink_test_file_transfer_start(uint8_t system_id, uint8_t componen uint16_t i; mavlink_file_transfer_start_t packet_in = { 93372036854775807ULL, - 963497880, - "MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ", - 249, - 60, + }963497880, + }"MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ", + }249, + }60, }; mavlink_file_transfer_start_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4206,8 +4206,8 @@ static void mavlink_test_file_transfer_dir_list(uint8_t system_id, uint8_t compo uint16_t i; mavlink_file_transfer_dir_list_t packet_in = { 93372036854775807ULL, - "IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM", - 237, + }"IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM", + }237, }; mavlink_file_transfer_dir_list_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4253,7 +4253,7 @@ static void mavlink_test_file_transfer_res(uint8_t system_id, uint8_t component_ uint16_t i; mavlink_file_transfer_res_t packet_in = { 93372036854775807ULL, - 29, + }29, }; mavlink_file_transfer_res_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4298,18 +4298,18 @@ static void mavlink_test_hil_gps(uint8_t system_id, uint8_t component_id, mavlin uint16_t i; mavlink_hil_gps_t packet_in = { 93372036854775807ULL, - 963497880, - 963498088, - 963498296, - 18275, - 18379, - 18483, - 18587, - 18691, - 18795, - 18899, - 235, - 46, + }963497880, + }963498088, + }963498296, + }18275, + }18379, + }18483, + }18587, + }18691, + }18795, + }18899, + }235, + }46, }; mavlink_hil_gps_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4365,13 +4365,13 @@ static void mavlink_test_hil_optical_flow(uint8_t system_id, uint8_t component_i uint16_t i; mavlink_hil_optical_flow_t packet_in = { 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 18275, - 18379, - 77, - 144, + }73.0, + }101.0, + }129.0, + }18275, + }18379, + }77, + }144, }; mavlink_hil_optical_flow_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4422,21 +4422,21 @@ static void mavlink_test_hil_state_quaternion(uint8_t system_id, uint8_t compone uint16_t i; mavlink_hil_state_quaternion_t packet_in = { 93372036854775807ULL, - { 73.0, 74.0, 75.0, 76.0 }, - 185.0, - 213.0, - 241.0, - 963499336, - 963499544, - 963499752, - 19731, - 19835, - 19939, - 20043, - 20147, - 20251, - 20355, - 20459, + }{ 73.0, 74.0, 75.0, 76.0 }, + }185.0, + }213.0, + }241.0, + }963499336, + }963499544, + }963499752, + }19731, + }19835, + }19939, + }20043, + }20147, + }20251, + }20355, + }20459, }; mavlink_hil_state_quaternion_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -4488,24 +4488,379 @@ static void mavlink_test_hil_state_quaternion(uint8_t system_id, uint8_t compone MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_scaled_imu2(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_scaled_imu2_t packet_in = { + 963497464, + }17443, + }17547, + }17651, + }17755, + }17859, + }17963, + }18067, + }18171, + }18275, + }; + mavlink_scaled_imu2_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_boot_ms = packet_in.time_boot_ms; + packet1.xacc = packet_in.xacc; + packet1.yacc = packet_in.yacc; + packet1.zacc = packet_in.zacc; + packet1.xgyro = packet_in.xgyro; + packet1.ygyro = packet_in.ygyro; + packet1.zgyro = packet_in.zgyro; + packet1.xmag = packet_in.xmag; + packet1.ymag = packet_in.ymag; + packet1.zmag = packet_in.zmag; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_scaled_imu2_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_scaled_imu2_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_scaled_imu2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); + mavlink_msg_scaled_imu2_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); + mavlink_msg_scaled_imu2_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 Date: Mon, 16 Dec 2013 09:04:03 +0100 Subject: Re-introduced AQ MAVLink files since we have had them around before --- mavlink/include/mavlink/v1.0/autoquad/autoquad.h | 123 ++++ mavlink/include/mavlink/v1.0/autoquad/mavlink.h | 27 + .../v1.0/autoquad/mavlink_msg_aq_telemetry_f.h | 617 +++++++++++++++++++++ mavlink/include/mavlink/v1.0/autoquad/testsuite.h | 118 ++++ mavlink/include/mavlink/v1.0/autoquad/version.h | 12 + 5 files changed, 897 insertions(+) create mode 100644 mavlink/include/mavlink/v1.0/autoquad/autoquad.h create mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink.h create mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h create mode 100644 mavlink/include/mavlink/v1.0/autoquad/testsuite.h create mode 100644 mavlink/include/mavlink/v1.0/autoquad/version.h diff --git a/mavlink/include/mavlink/v1.0/autoquad/autoquad.h b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h new file mode 100644 index 000000000..281aa8975 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h @@ -0,0 +1,123 @@ +/** @file + * @brief MAVLink comm protocol generated from autoquad.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef AUTOQUAD_H +#define AUTOQUAD_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_AUTOQUAD + +// 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 +enum MAV_CMD +{ + MAV_CMD_AQ_TELEMETRY=2, /* Start/stop AutoQuad telemetry values stream. |Start or stop (1 or 0)| Stream frequency in us| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_AQ_FOLLOW=3, /* Command AutoQuad to go to a particular place at a set speed. |Latitude| Lontitude| Altitude| Speed| Empty| Empty| Empty| */ + MAV_CMD_AQ_REQUEST_VERSION=4, /* Request AutoQuad firmware version number. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* 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_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + 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| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + 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_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_ENUM_END=501, /* | */ +}; +#endif + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_aq_telemetry_f.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // AUTOQUAD_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h new file mode 100644 index 000000000..3f80c9a41 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from autoquad.xml + * @see http://pixhawk.ethz.ch/software/mavlink + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX 254 +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS 1 +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA 1 +#endif + +#include "version.h" +#include "autoquad.h" + +#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h new file mode 100644 index 000000000..ed7c86bcb --- /dev/null +++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h @@ -0,0 +1,617 @@ +// MESSAGE AQ_TELEMETRY_F PACKING + +#define MAVLINK_MSG_ID_AQ_TELEMETRY_F 150 + +typedef struct __mavlink_aq_telemetry_f_t +{ + float value1; ///< value1 + float value2; ///< value2 + float value3; ///< value3 + float value4; ///< value4 + float value5; ///< value5 + float value6; ///< value6 + float value7; ///< value7 + float value8; ///< value8 + float value9; ///< value9 + float value10; ///< value10 + float value11; ///< value11 + float value12; ///< value12 + float value13; ///< value13 + float value14; ///< value14 + float value15; ///< value15 + float value16; ///< value16 + float value17; ///< value17 + float value18; ///< value18 + float value19; ///< value19 + float value20; ///< value20 + uint16_t Index; ///< Index of message +} mavlink_aq_telemetry_f_t; + +#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN 82 +#define MAVLINK_MSG_ID_150_LEN 82 + +#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC 241 +#define MAVLINK_MSG_ID_150_CRC 241 + + + +#define MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F { \ + "AQ_TELEMETRY_F", \ + 21, \ + { { "value1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_aq_telemetry_f_t, value1) }, \ + { "value2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_aq_telemetry_f_t, value2) }, \ + { "value3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aq_telemetry_f_t, value3) }, \ + { "value4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aq_telemetry_f_t, value4) }, \ + { "value5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aq_telemetry_f_t, value5) }, \ + { "value6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aq_telemetry_f_t, value6) }, \ + { "value7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aq_telemetry_f_t, value7) }, \ + { "value8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aq_telemetry_f_t, value8) }, \ + { "value9", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aq_telemetry_f_t, value9) }, \ + { "value10", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aq_telemetry_f_t, value10) }, \ + { "value11", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aq_telemetry_f_t, value11) }, \ + { "value12", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aq_telemetry_f_t, value12) }, \ + { "value13", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aq_telemetry_f_t, value13) }, \ + { "value14", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aq_telemetry_f_t, value14) }, \ + { "value15", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aq_telemetry_f_t, value15) }, \ + { "value16", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aq_telemetry_f_t, value16) }, \ + { "value17", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aq_telemetry_f_t, value17) }, \ + { "value18", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aq_telemetry_f_t, value18) }, \ + { "value19", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aq_telemetry_f_t, value19) }, \ + { "value20", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aq_telemetry_f_t, value20) }, \ + { "Index", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_aq_telemetry_f_t, Index) }, \ + } \ +} + + +/** + * @brief Pack a aq_telemetry_f 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 Index Index of message + * @param value1 value1 + * @param value2 value2 + * @param value3 value3 + * @param value4 value4 + * @param value5 value5 + * @param value6 value6 + * @param value7 value7 + * @param value8 value8 + * @param value9 value9 + * @param value10 value10 + * @param value11 value11 + * @param value12 value12 + * @param value13 value13 + * @param value14 value14 + * @param value15 value15 + * @param value16 value16 + * @param value17 value17 + * @param value18 value18 + * @param value19 value19 + * @param value20 value20 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; + _mav_put_float(buf, 0, value1); + _mav_put_float(buf, 4, value2); + _mav_put_float(buf, 8, value3); + _mav_put_float(buf, 12, value4); + _mav_put_float(buf, 16, value5); + _mav_put_float(buf, 20, value6); + _mav_put_float(buf, 24, value7); + _mav_put_float(buf, 28, value8); + _mav_put_float(buf, 32, value9); + _mav_put_float(buf, 36, value10); + _mav_put_float(buf, 40, value11); + _mav_put_float(buf, 44, value12); + _mav_put_float(buf, 48, value13); + _mav_put_float(buf, 52, value14); + _mav_put_float(buf, 56, value15); + _mav_put_float(buf, 60, value16); + _mav_put_float(buf, 64, value17); + _mav_put_float(buf, 68, value18); + _mav_put_float(buf, 72, value19); + _mav_put_float(buf, 76, value20); + _mav_put_uint16_t(buf, 80, Index); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#else + mavlink_aq_telemetry_f_t packet; + packet.value1 = value1; + packet.value2 = value2; + packet.value3 = value3; + packet.value4 = value4; + packet.value5 = value5; + packet.value6 = value6; + packet.value7 = value7; + packet.value8 = value8; + packet.value9 = value9; + packet.value10 = value10; + packet.value11 = value11; + packet.value12 = value12; + packet.value13 = value13; + packet.value14 = value14; + packet.value15 = value15; + packet.value16 = value16; + packet.value17 = value17; + packet.value18 = value18; + packet.value19 = value19; + packet.value20 = value20; + packet.Index = Index; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif +} + +/** + * @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 will be sent over + * @param msg The MAVLink message to compress the data into + * @param Index Index of message + * @param value1 value1 + * @param value2 value2 + * @param value3 value3 + * @param value4 value4 + * @param value5 value5 + * @param value6 value6 + * @param value7 value7 + * @param value8 value8 + * @param value9 value9 + * @param value10 value10 + * @param value11 value11 + * @param value12 value12 + * @param value13 value13 + * @param value14 value14 + * @param value15 value15 + * @param value16 value16 + * @param value17 value17 + * @param value18 value18 + * @param value19 value19 + * @param value20 value20 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t Index,float value1,float value2,float value3,float value4,float value5,float value6,float value7,float value8,float value9,float value10,float value11,float value12,float value13,float value14,float value15,float value16,float value17,float value18,float value19,float value20) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; + _mav_put_float(buf, 0, value1); + _mav_put_float(buf, 4, value2); + _mav_put_float(buf, 8, value3); + _mav_put_float(buf, 12, value4); + _mav_put_float(buf, 16, value5); + _mav_put_float(buf, 20, value6); + _mav_put_float(buf, 24, value7); + _mav_put_float(buf, 28, value8); + _mav_put_float(buf, 32, value9); + _mav_put_float(buf, 36, value10); + _mav_put_float(buf, 40, value11); + _mav_put_float(buf, 44, value12); + _mav_put_float(buf, 48, value13); + _mav_put_float(buf, 52, value14); + _mav_put_float(buf, 56, value15); + _mav_put_float(buf, 60, value16); + _mav_put_float(buf, 64, value17); + _mav_put_float(buf, 68, value18); + _mav_put_float(buf, 72, value19); + _mav_put_float(buf, 76, value20); + _mav_put_uint16_t(buf, 80, Index); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#else + mavlink_aq_telemetry_f_t packet; + packet.value1 = value1; + packet.value2 = value2; + packet.value3 = value3; + packet.value4 = value4; + packet.value5 = value5; + packet.value6 = value6; + packet.value7 = value7; + packet.value8 = value8; + packet.value9 = value9; + packet.value10 = value10; + packet.value11 = value11; + packet.value12 = value12; + packet.value13 = value13; + packet.value14 = value14; + packet.value15 = value15; + packet.value16 = value16; + packet.value17 = value17; + packet.value18 = value18; + packet.value19 = value19; + packet.value20 = value20; + packet.Index = Index; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif +} + +/** + * @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) + * @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(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f) +{ + 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 + * + * @param Index Index of message + * @param value1 value1 + * @param value2 value2 + * @param value3 value3 + * @param value4 value4 + * @param value5 value5 + * @param value6 value6 + * @param value7 value7 + * @param value8 value8 + * @param value9 value9 + * @param value10 value10 + * @param value11 value11 + * @param value12 value12 + * @param value13 value13 + * @param value14 value14 + * @param value15 value15 + * @param value16 value16 + * @param value17 value17 + * @param value18 value18 + * @param value19 value19 + * @param value20 value20 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_aq_telemetry_f_send(mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; + _mav_put_float(buf, 0, value1); + _mav_put_float(buf, 4, value2); + _mav_put_float(buf, 8, value3); + _mav_put_float(buf, 12, value4); + _mav_put_float(buf, 16, value5); + _mav_put_float(buf, 20, value6); + _mav_put_float(buf, 24, value7); + _mav_put_float(buf, 28, value8); + _mav_put_float(buf, 32, value9); + _mav_put_float(buf, 36, value10); + _mav_put_float(buf, 40, value11); + _mav_put_float(buf, 44, value12); + _mav_put_float(buf, 48, value13); + _mav_put_float(buf, 52, value14); + _mav_put_float(buf, 56, value15); + _mav_put_float(buf, 60, value16); + _mav_put_float(buf, 64, value17); + _mav_put_float(buf, 68, value18); + _mav_put_float(buf, 72, value19); + _mav_put_float(buf, 76, value20); + _mav_put_uint16_t(buf, 80, Index); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif +#else + mavlink_aq_telemetry_f_t packet; + packet.value1 = value1; + packet.value2 = value2; + packet.value3 = value3; + packet.value4 = value4; + packet.value5 = value5; + packet.value6 = value6; + packet.value7 = value7; + packet.value8 = value8; + packet.value9 = value9; + packet.value10 = value10; + packet.value11 = value11; + packet.value12 = value12; + packet.value13 = value13; + packet.value14 = value14; + packet.value15 = value15; + packet.value16 = value16; + packet.value17 = value17; + packet.value18 = value18; + packet.value19 = value19; + packet.value20 = value20; + packet.Index = Index; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif +#endif +} + +#endif + +// MESSAGE AQ_TELEMETRY_F UNPACKING + + +/** + * @brief Get field Index from aq_telemetry_f message + * + * @return Index of message + */ +static inline uint16_t mavlink_msg_aq_telemetry_f_get_Index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 80); +} + +/** + * @brief Get field value1 from aq_telemetry_f message + * + * @return value1 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field value2 from aq_telemetry_f message + * + * @return value2 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field value3 from aq_telemetry_f message + * + * @return value3 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field value4 from aq_telemetry_f message + * + * @return value4 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field value5 from aq_telemetry_f message + * + * @return value5 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field value6 from aq_telemetry_f message + * + * @return value6 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field value7 from aq_telemetry_f message + * + * @return value7 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value7(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field value8 from aq_telemetry_f message + * + * @return value8 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field value9 from aq_telemetry_f message + * + * @return value9 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value9(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field value10 from aq_telemetry_f message + * + * @return value10 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value10(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field value11 from aq_telemetry_f message + * + * @return value11 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value11(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field value12 from aq_telemetry_f message + * + * @return value12 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value12(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field value13 from aq_telemetry_f message + * + * @return value13 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value13(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field value14 from aq_telemetry_f message + * + * @return value14 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value14(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field value15 from aq_telemetry_f message + * + * @return value15 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value15(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field value16 from aq_telemetry_f message + * + * @return value16 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 60); +} + +/** + * @brief Get field value17 from aq_telemetry_f message + * + * @return value17 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value17(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field value18 from aq_telemetry_f message + * + * @return value18 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value18(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); +} + +/** + * @brief Get field value19 from aq_telemetry_f message + * + * @return value19 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value19(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 72); +} + +/** + * @brief Get field value20 from aq_telemetry_f message + * + * @return value20 + */ +static inline float mavlink_msg_aq_telemetry_f_get_value20(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 76); +} + +/** + * @brief Decode a aq_telemetry_f message into a struct + * + * @param msg The message to decode + * @param aq_telemetry_f C-struct to decode the message contents into + */ +static inline void mavlink_msg_aq_telemetry_f_decode(const mavlink_message_t* msg, mavlink_aq_telemetry_f_t* aq_telemetry_f) +{ +#if MAVLINK_NEED_BYTE_SWAP + aq_telemetry_f->value1 = mavlink_msg_aq_telemetry_f_get_value1(msg); + aq_telemetry_f->value2 = mavlink_msg_aq_telemetry_f_get_value2(msg); + aq_telemetry_f->value3 = mavlink_msg_aq_telemetry_f_get_value3(msg); + aq_telemetry_f->value4 = mavlink_msg_aq_telemetry_f_get_value4(msg); + aq_telemetry_f->value5 = mavlink_msg_aq_telemetry_f_get_value5(msg); + aq_telemetry_f->value6 = mavlink_msg_aq_telemetry_f_get_value6(msg); + aq_telemetry_f->value7 = mavlink_msg_aq_telemetry_f_get_value7(msg); + aq_telemetry_f->value8 = mavlink_msg_aq_telemetry_f_get_value8(msg); + aq_telemetry_f->value9 = mavlink_msg_aq_telemetry_f_get_value9(msg); + aq_telemetry_f->value10 = mavlink_msg_aq_telemetry_f_get_value10(msg); + aq_telemetry_f->value11 = mavlink_msg_aq_telemetry_f_get_value11(msg); + aq_telemetry_f->value12 = mavlink_msg_aq_telemetry_f_get_value12(msg); + aq_telemetry_f->value13 = mavlink_msg_aq_telemetry_f_get_value13(msg); + aq_telemetry_f->value14 = mavlink_msg_aq_telemetry_f_get_value14(msg); + aq_telemetry_f->value15 = mavlink_msg_aq_telemetry_f_get_value15(msg); + aq_telemetry_f->value16 = mavlink_msg_aq_telemetry_f_get_value16(msg); + aq_telemetry_f->value17 = mavlink_msg_aq_telemetry_f_get_value17(msg); + aq_telemetry_f->value18 = mavlink_msg_aq_telemetry_f_get_value18(msg); + aq_telemetry_f->value19 = mavlink_msg_aq_telemetry_f_get_value19(msg); + aq_telemetry_f->value20 = mavlink_msg_aq_telemetry_f_get_value20(msg); + aq_telemetry_f->Index = mavlink_msg_aq_telemetry_f_get_Index(msg); +#else + memcpy(aq_telemetry_f, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h new file mode 100644 index 000000000..4eafe7be5 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h @@ -0,0 +1,118 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from autoquad.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef AUTOQUAD_TESTSUITE_H +#define AUTOQUAD_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_autoquad(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_autoquad(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_aq_telemetry_f(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_aq_telemetry_f_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, + }353.0, + }381.0, + }409.0, + }437.0, + }465.0, + }493.0, + }521.0, + }549.0, + }21395, + }; + mavlink_aq_telemetry_f_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.value1 = packet_in.value1; + packet1.value2 = packet_in.value2; + packet1.value3 = packet_in.value3; + packet1.value4 = packet_in.value4; + packet1.value5 = packet_in.value5; + packet1.value6 = packet_in.value6; + packet1.value7 = packet_in.value7; + packet1.value8 = packet_in.value8; + packet1.value9 = packet_in.value9; + packet1.value10 = packet_in.value10; + packet1.value11 = packet_in.value11; + packet1.value12 = packet_in.value12; + packet1.value13 = packet_in.value13; + packet1.value14 = packet_in.value14; + packet1.value15 = packet_in.value15; + packet1.value16 = packet_in.value16; + packet1.value17 = packet_in.value17; + packet1.value18 = packet_in.value18; + packet1.value19 = packet_in.value19; + packet1.value20 = packet_in.value20; + packet1.Index = packet_in.Index; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_aq_telemetry_f_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_aq_telemetry_f_pack(system_id, component_id, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); + mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); + mavlink_msg_aq_telemetry_f_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