aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Debug/NuttX20
-rw-r--r--Makefile17
-rw-r--r--ROMFS/logging/logconv.m266
-rw-r--r--ROMFS/scripts/rc.PX4IOAR34
-rw-r--r--Tools/mavlink_px4.py5268
-rwxr-xr-xTools/px_uploader.py2
-rw-r--r--apps/drivers/blinkm/Makefile42
-rw-r--r--apps/drivers/blinkm/blinkm.cpp465
-rw-r--r--apps/drivers/device/i2c.cpp4
-rw-r--r--apps/drivers/device/i2c.h2
-rw-r--r--apps/drivers/drv_blinkm.h69
-rw-r--r--apps/drivers/drv_pwm_output.h2
-rw-r--r--apps/drivers/hmc5883/hmc5883.cpp51
-rw-r--r--apps/drivers/mpu6000/mpu6000.cpp12
-rw-r--r--apps/drivers/px4fmu/fmu.cpp91
-rw-r--r--apps/drivers/px4io/px4io.cpp155
-rw-r--r--apps/drivers/px4io/uploader.cpp6
-rw-r--r--apps/drivers/stm32/drv_pwm_servo.c51
-rw-r--r--apps/gps/mtk.c2
-rw-r--r--apps/gps/nmea_helper.c2
-rw-r--r--apps/mavlink/mavlink.c2
-rw-r--r--apps/mavlink/mavlink_receiver.c4
-rw-r--r--apps/mavlink/orb_listener.c4
-rw-r--r--apps/mavlink/orb_topics.h1
-rw-r--r--apps/px4/tests/test_bson.c1
-rw-r--r--apps/px4/tests/tests_param.c1
-rw-r--r--apps/px4io/comms.c166
-rw-r--r--apps/px4io/controls.c154
-rw-r--r--apps/px4io/dsm.c253
-rw-r--r--apps/px4io/mixer.c64
-rw-r--r--apps/px4io/protocol.h6
-rw-r--r--apps/px4io/px4io.c100
-rw-r--r--apps/px4io/px4io.h30
-rw-r--r--apps/px4io/safety.c67
-rw-r--r--apps/px4io/sbus.c202
-rw-r--r--apps/sensors/sensors.cpp2
-rw-r--r--apps/systemcmds/bl_update/bl_update.c1
-rw-r--r--apps/systemcmds/boardinfo/boardinfo.c1
-rw-r--r--apps/systemcmds/delay_test/Makefile42
-rw-r--r--apps/systemcmds/delay_test/delay_test.c160
-rw-r--r--apps/systemcmds/perf/perf.c5
-rw-r--r--apps/uORB/topics/actuator_controls_effective.h7
-rw-r--r--mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h6
-rw-r--r--mavlink/include/mavlink/v1.0/ardupilotmega/version.h4
-rw-r--r--mavlink/include/mavlink/v1.0/common/common.h9
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h182
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h166
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h226
-rw-r--r--mavlink/include/mavlink/v1.0/common/testsuite.h146
-rw-r--r--mavlink/include/mavlink/v1.0/common/version.h4
-rw-r--r--mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h6
-rw-r--r--mavlink/include/mavlink/v1.0/matrixpilot/version.h4
-rw-r--r--mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h6
-rw-r--r--mavlink/include/mavlink/v1.0/pixhawk/version.h2
-rw-r--r--mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h6
-rw-r--r--mavlink/include/mavlink/v1.0/sensesoar/version.h4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c200
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig3
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig2
-rwxr-xr-xnuttx/configs/px4io/include/board.h12
-rwxr-xr-xnuttx/configs/px4io/io/defconfig22
-rw-r--r--nuttx/drivers/serial/serial.c287
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h4
-rw-r--r--nuttx/include/nuttx/serial/serial.h11
-rw-r--r--nuttx/include/termios.h32
65 files changed, 8285 insertions, 893 deletions
diff --git a/Debug/NuttX b/Debug/NuttX
index 825733554..8e6544842 100644
--- a/Debug/NuttX
+++ b/Debug/NuttX
@@ -168,17 +168,29 @@ define _showsemaphore
printf "\n"
end
-define showtask
+#
+# Print information about a task's stack usage
+#
+define showtaskstack
set $task = (struct _TCB *)$arg0
- printf "%p %.2d ", $task, $task->pid
- _showtaskstate $task
- printf " %s\n", $task->name
set $stack_free = 0
while ($stack_free < $task->adj_stack_size) && *(uint8_t *)($task->stack_alloc_ptr + $stack_free)
set $stack_free = $stack_free + 1
end
printf" stack 0x%08x-0x%08x (%d) %d free\n", $task->stack_alloc_ptr, $task->adj_stack_ptr, $task->adj_stack_size, $stack_free
+end
+
+#
+# Print details of a task
+#
+define showtask
+ set $task = (struct _TCB *)$arg0
+
+ printf "%p %.2d ", $task, $task->pid
+ _showtaskstate $task
+ printf " %s\n", $task->name
+ showtaskstack $task
if $task->task_state == TSTATE_WAIT_SEM
printf " waiting on %p ", $task->waitsem
diff --git a/Makefile b/Makefile
index 0d3e8eb07..d9469bb49 100644
--- a/Makefile
+++ b/Makefile
@@ -109,15 +109,26 @@ ifeq ($(SYSTYPE),Linux)
SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
endif
ifeq ($(SERIAL_PORTS),)
-SERIAL_PORTS = "\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
+SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
endif
upload: $(FIRMWARE_BUNDLE) $(UPLOADER)
@python -u $(UPLOADER) --port $(SERIAL_PORTS) $(FIRMWARE_BUNDLE)
-
+
+#
+# JTAG firmware uploading with OpenOCD
+#
+ifeq ($(JTAGCONFIG),)
+JTAGCONFIG=interface/olimex-jtag-tiny.cfg
+endif
+
upload-jtag-px4fmu:
@echo Attempting to flash PX4FMU board via JTAG
- @openocd -f interface/olimex-jtag-tiny.cfg -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
+
+upload-jtag-px4io: all
+ @echo Attempting to flash PX4IO board via JTAG
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown
#
# Hacks and fixups
diff --git a/ROMFS/logging/logconv.m b/ROMFS/logging/logconv.m
index 48399f1eb..bf70d6d0f 100644
--- a/ROMFS/logging/logconv.m
+++ b/ROMFS/logging/logconv.m
@@ -1,6 +1,14 @@
+% This Matlab Script can be used to import the binary logged values of the
+% PX4FMU into data that can be plotted and analyzed.
+
+% Clear everything
+clc
clear all
close all
+% Set the path to your sysvector.bin file here
+filePath = 'sysvector.bin';
+
%%%%%%%%%%%%%%%%%%%%%%%
% SYSTEM VECTOR
%
@@ -21,224 +29,72 @@ close all
% int32_t gps_raw_position[3]; //latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter]
% float attitude[3]; //pitch, roll, yaw [rad]
% float rotMatrix[9]; //unitvectors
+% float actuator_control[4]; //unitvector
+% float optical_flow[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
+
+% Definition of the logged values
+logFormat{1} = struct('name', 'timestamp', 'bytes', 8, 'array', 1, 'precision', 'uint64', 'machineformat', 'ieee-le.l64');
+logFormat{2} = struct('name', 'gyro', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{3} = struct('name', 'accel', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{4} = struct('name', 'mag', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{5} = struct('name', 'baro', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{6} = struct('name', 'baro_alt', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{7} = struct('name', 'baro_temp', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{8} = struct('name', 'control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{9} = struct('name', 'actuators', 'bytes', 4, 'array', 8, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{10} = struct('name', 'vbat', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{11} = struct('name', 'adc', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{12} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{13} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le');
+logFormat{14} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{15} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{16} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{17} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{18} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
+
+
+% First get length of one line
+columns = length(logFormat);
+lineLength = 0;
+
+for i=1:columns
+ lineLength = lineLength + logFormat{i}.bytes * logFormat{i}.array;
+end
-%myPath = '..\LOG30102012\session0002\'; %set relative path here
-myPath = '.\';
-myFile = 'sysvector.bin';
-filePath = strcat(myPath,myFile);
if exist(filePath, 'file')
+
fileInfo = dir(filePath);
fileSize = fileInfo.bytes;
- fid = fopen(filePath, 'r');
- elements = int64(fileSize./(8+(3+3+3+1+1+1+4+8+1+3+3+3+3+9+6+4+6)*4))
+ elements = int64(fileSize./(lineLength))
- for i=1:elements
- % timestamp
- sensors(i,1) = double(fread(fid, 1, '*uint64', 0, 'ieee-le.l64'));
-
- % gyro (3 channels)
- sensors(i,2:4) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % accelerometer (3 channels)
- sensors(i,5:7) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % mag (3 channels)
- sensors(i,8:10) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % baro pressure
- sensors(i,11) = fread(fid, 1, 'float', 0, 'ieee-le');
-
- % baro alt
- sensors(i,12) = fread(fid, 1, 'float', 0, 'ieee-le');
-
- % baro temp
- sensors(i,13) = fread(fid, 1, 'float', 0, 'ieee-le');
-
- % actuator control (4 channels)
- sensors(i,14:17) = fread(fid, 4, 'float', 0, 'ieee-le');
-
- % actuator outputs (8 channels)
- sensors(i,18:25) = fread(fid, 8, 'float', 0, 'ieee-le');
-
- % vbat
- sensors(i,26) = fread(fid, 1, 'float', 0, 'ieee-le');
-
- % adc voltage (3 channels)
- sensors(i,27:29) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % local position (3 channels)
- sensors(i,30:32) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % gps_raw_position (3 channels)
- sensors(i,33:35) = fread(fid, 3, 'uint32', 0, 'ieee-le');
-
- % attitude (3 channels)
- sensors(i,36:38) = fread(fid, 3, 'float', 0, 'ieee-le');
-
- % RotMatrix (9 channels)
- sensors(i,39:47) = fread(fid, 9, 'float', 0, 'ieee-le');
-
- % vicon position (6 channels)
- sensors(i,48:53) = fread(fid, 6, 'float', 0, 'ieee-le');
-
- % actuator control effective (4 channels)
- sensors(i,54:57) = fread(fid, 4, 'float', 0, 'ieee-le');
-
- % optical flow (6 values)
- sensors(i,58:63) = fread(fid, 6, 'float', 0, 'ieee-le');
+ fid = fopen(filePath, 'r');
+ offset = 0;
+ for i=1:columns
+ % using fread with a skip speeds up the import drastically, do not
+ % import the values one after the other
+ sysvector.(genvarname(logFormat{i}.name)) = transpose(fread(...
+ fid, ...
+ [logFormat{i}.array, elements], [num2str(logFormat{i}.array),'*',logFormat{i}.precision,'=>',logFormat{i}.precision], ...
+ lineLength - logFormat{i}.bytes*logFormat{i}.array, ...
+ logFormat{i}.machineformat) ...
+ );
+ offset = offset + logFormat{i}.bytes*logFormat{i}.array;
+ fseek(fid, offset,'bof');
end
- time_us = sensors(elements,1) - sensors(1,1);
+
+ % shot the flight time
+ time_us = sysvector.timestamp(end) - sysvector.timestamp(1);
time_s = time_us*1e-6
time_m = time_s/60
+
+ % close the logfile
+ fclose(fid);
+
disp(['end log2matlab conversion' char(10)]);
else
disp(['file: ' filePath ' does not exist' char(10)]);
end
-%% old version of reading in different files from sdlog.c
-% if exist('sysvector.bin', 'file')
-% % Read actuators file
-% myFile = java.io.File('sysvector.bin')
-% fileSize = length(myFile)
-%
-% fid = fopen('sysvector.bin', 'r');
-% elements = int64(fileSize./(8+(3+3+3+1+1+1+4+8+4+3+3)*4));
-%
-% for i=1:elements
-% % timestamp
-% sysvector(i,1) = double(fread(fid, 1, '*uint64', 0, 'ieee-le.l64'));
-% % actuators 1-16
-% % quadrotor: motor 1-4 on the first four positions
-% sysvector(i, 2:32) = fread(fid, 28+3, 'float', 'ieee-le');
-% sysvector(i,33:35) = fread(fid, 3, 'int32', 'ieee-le');
-% end
-%
-% sysvector_interval_seconds = (sysvector(end,1) - sysvector(1:1)) / 1000000
-% sysvector_minutes = sysvector_interval_seconds / 60
-%
-% % Normalize time
-% sysvector(:,1) = (sysvector(:,1) - sysvector(1,1)) / 1000000;
-%
-% % Create some basic plots
-%
-% % Remove zero rows from GPS
-% gps = sysvector(:,33:35);
-% gps(~any(gps,2), :) = [];
-%
-% all_data = figure('Name', 'GPS RAW');
-% gps_position = plot3(gps(:,1), gps(:,2), gps(:,3));
-%
-%
-% all_data = figure('Name', 'Complete Log Data (exc. GPS)');
-% plot(sysvector(:,1), sysvector(:,2:32));
-%
-% actuator_inputs = figure('Name', 'Attitude controller outputs');
-% plot(sysvector(:,1), sysvector(:,14:17));
-% legend('roll motor setpoint', 'pitch motor setpoint', 'yaw motor setpoint', 'throttle motor setpoint');
-%
-% actuator_outputs = figure('Name', 'Actuator outputs');
-% plot(sysvector(:,1), sysvector(:,18:25));
-% legend('actuator 0', 'actuator 1', 'actuator 2', 'actuator 3', 'actuator 4', 'actuator 5', 'actuator 6', 'actuator 7');
-%
-% end
-%
-% if exist('actuator_outputs0.bin', 'file')
-% % Read actuators file
-% myFile = java.io.File('actuator_outputs0.bin')
-% fileSize = length(myFile)
-%
-% fid = fopen('actuator_outputs0.bin', 'r');
-% elements = int64(fileSize./(16*4+8))
-%
-% for i=1:elements
-% % timestamp
-% actuators(i,1) = double(fread(fid, 1, '*uint64', 0, 'ieee-le.l64'));
-% % actuators 1-16
-% % quadrotor: motor 1-4 on the first four positions
-% actuators(i, 2:17) = fread(fid, 16, 'float', 'ieee-le');
-% end
-% end
-%
-% if exist('actuator_controls0.bin', 'file')
-% % Read actuators file
-% myFile = java.io.File('actuator_controls0.bin')
-% fileSize = length(myFile)
-%
-% fid = fopen('actuator_controls0.bin', 'r');
-% elements = int64(fileSize./(8*4+8))
-%
-% for i=1:elements
-% % timestamp
-% actuator_controls(i,1) = fread(fid, 1, 'uint64', 0, 'ieee-le.l64');
-% % actuators 1-16
-% % quadrotor: motor 1-4 on the first four positions
-% actuator_controls(i, 2:9) = fread(fid, 8, 'float', 'ieee-le');
-% end
-% end
-%
-%
-% if exist('sensor_combined.bin', 'file')
-% % Read sensor combined file
-% % Type definition: Firmware/apps/uORB/topics/sensor_combined.h
-% % Struct: sensor_combined_s
-% fileInfo = dir('sensor_combined.bin');
-% fileSize = fileInfo.bytes;
-%
-% fid = fopen('sensor_combined.bin', 'r');
-%
-% for i=1:elements
-% % timestamp
-% sensors(i,1) = double(fread(fid, 1, '*uint64', 0, 'ieee-le.l64'));
-% % gyro raw
-% sensors(i,2:4) = fread(fid, 3, 'int16', 0, 'ieee-le');
-% % gyro counter
-% sensors(i,5) = fread(fid, 1, 'uint16', 0, 'ieee-le');
-% % gyro in rad/s
-% sensors(i,6:8) = fread(fid, 3, 'float', 0, 'ieee-le');
-%
-% % accelerometer raw
-% sensors(i,9:11) = fread(fid, 3, 'int16', 0, 'ieee-le');
-% % padding bytes
-% fread(fid, 1, 'int16', 0, 'ieee-le');
-% % accelerometer counter
-% sensors(i,12) = fread(fid, 1, 'uint32', 0, 'ieee-le');
-% % accel in m/s2
-% sensors(i,13:15) = fread(fid, 3, 'float', 0, 'ieee-le');
-% % accel mode
-% sensors(i,16) = fread(fid, 1, 'int32', 0, 'ieee-le');
-% % accel range
-% sensors(i,17) = fread(fid, 1, 'float', 0, 'ieee-le');
-%
-% % mag raw
-% sensors(i,18:20) = fread(fid, 3, 'int16', 0, 'ieee-le');
-% % padding bytes
-% fread(fid, 1, 'int16', 0, 'ieee-le');
-% % mag in Gauss
-% sensors(i,21:23) = fread(fid, 3, 'float', 0, 'ieee-le');
-% % mag mode
-% sensors(i,24) = fread(fid, 1, 'int32', 0, 'ieee-le');
-% % mag range
-% sensors(i,25) = fread(fid, 1, 'float', 0, 'ieee-le');
-% % mag cuttoff freq
-% sensors(i,26) = fread(fid, 1, 'float', 0, 'ieee-le');
-% % mag counter
-% sensors(i,27) = fread(fid, 1, 'int32', 0, 'ieee-le');
-%
-% % baro pressure millibar
-% % baro alt meter
-% % baro temp celcius
-% % battery voltage
-% % adc voltage (3 channels)
-% sensors(i,28:34) = fread(fid, 7, 'float', 0, 'ieee-le');
-% % baro counter and battery counter
-% sensors(i,35:36) = fread(fid, 2, 'uint32', 0, 'ieee-le');
-% % battery voltage valid flag
-% sensors(i,37) = fread(fid, 1, 'uint32', 0, 'ieee-le');
-%
-% end
-% end
-
-
diff --git a/ROMFS/scripts/rc.PX4IOAR b/ROMFS/scripts/rc.PX4IOAR
index d23f03417..640cdf541 100644
--- a/ROMFS/scripts/rc.PX4IOAR
+++ b/ROMFS/scripts/rc.PX4IOAR
@@ -3,8 +3,12 @@
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
+# Disable the USB interface
set USB no
+# Disable autostarting other apps
+set MODE ardrone
+
echo "[init] doing PX4IOAR startup..."
#
@@ -13,27 +17,27 @@ echo "[init] doing PX4IOAR startup..."
uorb start
#
-# Init the EEPROM
+# Load microSD params
#
-echo "[init] eeprom"
-eeprom start
-if [ -f /eeprom/parameters ]
+echo "[init] loading microSD params"
+param select /fs/microsd/parameters
+if [ -f /fs/microsd/parameters ]
then
- param load
+ param load /fs/microsd/parameters
fi
#
-# Start the sensors.
-#
-sh /etc/init.d/rc.sensors
-
-#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
+# Start the sensors and test them.
+#
+sh /etc/init.d/rc.sensors
+
+#
# Start the commander.
#
commander start
@@ -56,13 +60,13 @@ multirotor_att_control start
#
# Fire up the AR.Drone interface.
#
-ardrone_interface start
-
+ardrone_interface start -d /dev/ttyS1
+
#
-# Start logging to microSD if we can
+# Start logging
#
-#sh /etc/init.d/rc.logging
-
+#sdlog start
+
#
# Start GPS capture
#
diff --git a/Tools/mavlink_px4.py b/Tools/mavlink_px4.py
new file mode 100644
index 000000000..bbad57b7d
--- /dev/null
+++ b/Tools/mavlink_px4.py
@@ -0,0 +1,5268 @@
+'''
+MAVLink protocol implementation (auto-generated by mavgen.py)
+
+Generated from: common.xml
+
+Note: this file has been auto-generated. DO NOT EDIT
+'''
+
+import struct, array, mavutil, time, json
+
+WIRE_PROTOCOL_VERSION = "1.0"
+
+
+# some base types from mavlink_types.h
+MAVLINK_TYPE_CHAR = 0
+MAVLINK_TYPE_UINT8_T = 1
+MAVLINK_TYPE_INT8_T = 2
+MAVLINK_TYPE_UINT16_T = 3
+MAVLINK_TYPE_INT16_T = 4
+MAVLINK_TYPE_UINT32_T = 5
+MAVLINK_TYPE_INT32_T = 6
+MAVLINK_TYPE_UINT64_T = 7
+MAVLINK_TYPE_INT64_T = 8
+MAVLINK_TYPE_FLOAT = 9
+MAVLINK_TYPE_DOUBLE = 10
+
+
+class MAVLink_header(object):
+ '''MAVLink message header'''
+ def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0):
+ self.mlen = mlen
+ self.seq = seq
+ self.srcSystem = srcSystem
+ self.srcComponent = srcComponent
+ self.msgId = msgId
+
+ def pack(self):
+ return struct.pack('BBBBBB', 254, self.mlen, self.seq,
+ self.srcSystem, self.srcComponent, self.msgId)
+
+class MAVLink_message(object):
+ '''base MAVLink message class'''
+ def __init__(self, msgId, name):
+ self._header = MAVLink_header(msgId)
+ self._payload = None
+ self._msgbuf = None
+ self._crc = None
+ self._fieldnames = []
+ self._type = name
+
+ def get_msgbuf(self):
+ if isinstance(self._msgbuf, str):
+ return self._msgbuf
+ return self._msgbuf.tostring()
+
+ def get_header(self):
+ return self._header
+
+ def get_payload(self):
+ return self._payload
+
+ def get_crc(self):
+ return self._crc
+
+ def get_fieldnames(self):
+ return self._fieldnames
+
+ def get_type(self):
+ return self._type
+
+ def get_msgId(self):
+ return self._header.msgId
+
+ def get_srcSystem(self):
+ return self._header.srcSystem
+
+ def get_srcComponent(self):
+ return self._header.srcComponent
+
+ def get_seq(self):
+ return self._header.seq
+
+ def __str__(self):
+ ret = '%s {' % self._type
+ for a in self._fieldnames:
+ v = getattr(self, a)
+ ret += '%s : %s, ' % (a, v)
+ ret = ret[0:-2] + '}'
+ return ret
+
+ def to_dict(self):
+ d = dict({})
+ d['mavpackettype'] = self._type
+ for a in self._fieldnames:
+ d[a] = getattr(self, a)
+ return d
+
+ def to_json(self):
+ return json.dumps(self.to_dict)
+
+ def pack(self, mav, crc_extra, payload):
+ self._payload = payload
+ self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq,
+ mav.srcSystem, mav.srcComponent)
+ self._msgbuf = self._header.pack() + payload
+ crc = mavutil.x25crc(self._msgbuf[1:])
+ if True: # using CRC extra
+ crc.accumulate(chr(crc_extra))
+ self._crc = crc.crc
+ self._msgbuf += struct.pack('<H', self._crc)
+ return self._msgbuf
+
+
+# enums
+
+# MAV_AUTOPILOT
+MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything
+MAV_AUTOPILOT_PIXHAWK = 1 # PIXHAWK autopilot, http://pixhawk.ethz.ch
+MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu
+MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com
+MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org
+MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints
+MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation
+ # commands
+MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set
+MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component
+MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi
+MAV_AUTOPILOT_UDB = 10 # UAV Dev Board
+MAV_AUTOPILOT_FP = 11 # FlexiPilot
+MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/
+MAV_AUTOPILOT_ENUM_END = 13 #
+
+# MAV_TYPE
+MAV_TYPE_GENERIC = 0 # Generic micro air vehicle.
+MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft.
+MAV_TYPE_QUADROTOR = 2 # Quadrotor
+MAV_TYPE_COAXIAL = 3 # Coaxial helicopter
+MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor.
+MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation
+MAV_TYPE_GCS = 6 # Operator control unit / ground control station
+MAV_TYPE_AIRSHIP = 7 # Airship, controlled
+MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled
+MAV_TYPE_ROCKET = 9 # Rocket
+MAV_TYPE_GROUND_ROVER = 10 # Ground rover
+MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship
+MAV_TYPE_SUBMARINE = 12 # Submarine
+MAV_TYPE_HEXAROTOR = 13 # Hexarotor
+MAV_TYPE_OCTOROTOR = 14 # Octorotor
+MAV_TYPE_TRICOPTER = 15 # Octorotor
+MAV_TYPE_FLAPPING_WING = 16 # Flapping wing
+MAV_TYPE_KITE = 17 # Flapping wing
+MAV_TYPE_ENUM_END = 18 #
+
+# MAV_MODE_FLAG
+MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use.
+MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for
+ # temporary system tests and should not be
+ # used for stable implementations.
+MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal
+ # positions. Guided flag can be set or not,
+ # depends on the actual implementation.
+MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items.
+MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and
+ # optionally position). It needs however
+ # further control inputs to move around.
+MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are
+ # blocked, but internal software is full
+ # operational.
+MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled.
+MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can
+ # start. Ready to fly.
+MAV_MODE_FLAG_ENUM_END = 129 #
+
+# MAV_MODE_FLAG_DECODE_POSITION
+MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001
+MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010
+MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100
+MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000
+MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000
+MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000
+MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000
+MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000
+MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 #
+
+# MAV_GOTO
+MAV_GOTO_DO_HOLD = 0 # Hold at the current position.
+MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution.
+MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system
+MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action
+MAV_GOTO_ENUM_END = 4 #
+
+# MAV_MODE
+MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set.
+MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no
+ # stabilization
+MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with
+ # caution, intended for developers only.
+MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control.
+MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual
+ # setpoint
+MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and
+ # navigation (the trajectory is decided
+ # onboard and not pre-programmed by MISSIONs)
+MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no
+ # stabilization
+MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with
+ # caution, intended for developers only.
+MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control.
+MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual
+ # setpoint
+MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and
+ # navigation (the trajectory is decided
+ # onboard and not pre-programmed by MISSIONs)
+MAV_MODE_ENUM_END = 221 #
+
+# MAV_STATE
+MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown.
+MAV_STATE_BOOT = 1 # System is booting up.
+MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready.
+MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time.
+MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged.
+MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate.
+MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or
+ # over the whole airframe. It is in mayday and
+ # going down.
+MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now.
+MAV_STATE_ENUM_END = 8 #
+
+# MAV_COMPONENT
+MAV_COMP_ID_ALL = 0 #
+MAV_COMP_ID_CAMERA = 100 #
+MAV_COMP_ID_SERVO1 = 140 #
+MAV_COMP_ID_SERVO2 = 141 #
+MAV_COMP_ID_SERVO3 = 142 #
+MAV_COMP_ID_SERVO4 = 143 #
+MAV_COMP_ID_SERVO5 = 144 #
+MAV_COMP_ID_SERVO6 = 145 #
+MAV_COMP_ID_SERVO7 = 146 #
+MAV_COMP_ID_SERVO8 = 147 #
+MAV_COMP_ID_SERVO9 = 148 #
+MAV_COMP_ID_SERVO10 = 149 #
+MAV_COMP_ID_SERVO11 = 150 #
+MAV_COMP_ID_SERVO12 = 151 #
+MAV_COMP_ID_SERVO13 = 152 #
+MAV_COMP_ID_SERVO14 = 153 #
+MAV_COMP_ID_MAPPER = 180 #
+MAV_COMP_ID_MISSIONPLANNER = 190 #
+MAV_COMP_ID_PATHPLANNER = 195 #
+MAV_COMP_ID_IMU = 200 #
+MAV_COMP_ID_IMU_2 = 201 #
+MAV_COMP_ID_IMU_3 = 202 #
+MAV_COMP_ID_GPS = 220 #
+MAV_COMP_ID_UDP_BRIDGE = 240 #
+MAV_COMP_ID_UART_BRIDGE = 241 #
+MAV_COMP_ID_SYSTEM_CONTROL = 250 #
+MAV_COMPONENT_ENUM_END = 251 #
+
+# MAV_FRAME
+MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x:
+ # latitude, second value / y: longitude, third
+ # value / z: positive altitude over mean sea
+ # level (MSL)
+MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down).
+MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command.
+MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude
+ # over ground with respect to the home
+ # position. First value / x: latitude, second
+ # value / y: longitude, third value / z:
+ # positive altitude with 0 being at the
+ # altitude of the home location.
+MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up)
+MAV_FRAME_ENUM_END = 5 #
+
+# MAVLINK_DATA_STREAM_TYPE
+MAVLINK_DATA_STREAM_IMG_JPEG = 1 #
+MAVLINK_DATA_STREAM_IMG_BMP = 2 #
+MAVLINK_DATA_STREAM_IMG_RAW8U = 3 #
+MAVLINK_DATA_STREAM_IMG_RAW32U = 4 #
+MAVLINK_DATA_STREAM_IMG_PGM = 5 #
+MAVLINK_DATA_STREAM_IMG_PNG = 6 #
+MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 #
+
+# MAV_CMD
+MAV_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION.
+MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time
+MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns
+MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds
+MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location
+MAV_CMD_NAV_LAND = 21 # Land at location
+MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand
+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.
+MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV.
+MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the
+ # NAV/ACTION commands in the enumeration
+MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine.
+MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired
+ # altitude reached.
+MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV
+ # point.
+MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle.
+MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the
+ # CONDITION commands in the enumeration
+MAV_CMD_DO_SET_MODE = 176 # Set system mode.
+MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action
+ # only the specified number of times
+MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points.
+MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a
+ # specified location.
+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.
+MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition.
+MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired
+ # period.
+MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value.
+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.
+MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system.
+MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO
+ # commands in the enumeration
+MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-
+ # flight mode.
+MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-
+ # flight mode.
+MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command
+ # will be only accepted if in pre-flight mode.
+MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components.
+MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action
+MAV_CMD_MISSION_START = 300 # start running a mission
+MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component
+MAV_CMD_ENUM_END = 401 #
+
+# MAV_DATA_STREAM
+MAV_DATA_STREAM_ALL = 0 # Enable all data streams
+MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
+MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
+MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
+MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT,
+ # NAV_CONTROLLER_OUTPUT.
+MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
+MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot
+MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot
+MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot
+MAV_DATA_STREAM_ENUM_END = 13 #
+
+# MAV_ROI
+MAV_ROI_NONE = 0 # No region of interest.
+MAV_ROI_WPNEXT = 1 # Point toward next MISSION.
+MAV_ROI_WPINDEX = 2 # Point toward given MISSION.
+MAV_ROI_LOCATION = 3 # Point toward fixed location.
+MAV_ROI_TARGET = 4 # Point toward of given id.
+MAV_ROI_ENUM_END = 5 #
+
+# MAV_CMD_ACK
+MAV_CMD_ACK_OK = 1 # Command / mission item is ok.
+MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no
+ # detailed error reporting is implemented.
+MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source /
+ # communication partner.
+MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be
+ # accepted.
+MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported.
+MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # The coordinate frame of this command is ok, but he coordinate values
+ # exceed the safety limits of this system.
+ # This is a generic error, please use the more
+ # specific error messages below if possible.
+MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range.
+MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range.
+MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range.
+MAV_CMD_ACK_ENUM_END = 10 #
+
+# MAV_PARAM_TYPE
+MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer
+MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer
+MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer
+MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer
+MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer
+MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer
+MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer
+MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer
+MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point
+MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point
+MAV_PARAM_TYPE_ENUM_END = 11 #
+
+# MAV_RESULT
+MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED
+MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED
+MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED
+MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED
+MAV_RESULT_FAILED = 4 # Command executed, but failed
+MAV_RESULT_ENUM_END = 5 #
+
+# MAV_MISSION_RESULT
+MAV_MISSION_ACCEPTED = 0 # mission accepted OK
+MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now
+MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported
+MAV_MISSION_UNSUPPORTED = 3 # command is not supported
+MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space
+MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value
+MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value
+MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value
+MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value
+MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value
+MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value
+MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value
+MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value
+MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence
+MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner
+MAV_MISSION_RESULT_ENUM_END = 15 #
+
+# MAV_SEVERITY
+MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition.
+MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical
+ # systems.
+MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary
+ # system.
+MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems.
+MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within
+ # a given timeframe. Example would be a low
+ # battery warning.
+MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This
+ # should be investigated for the root cause.
+MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required
+ # for these messages.
+MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These
+ # should not occur during normal operation.
+MAV_SEVERITY_ENUM_END = 8 #
+
+# message IDs
+MAVLINK_MSG_ID_BAD_DATA = -1
+MAVLINK_MSG_ID_HEARTBEAT = 0
+MAVLINK_MSG_ID_SYS_STATUS = 1
+MAVLINK_MSG_ID_SYSTEM_TIME = 2
+MAVLINK_MSG_ID_PING = 4
+MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5
+MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6
+MAVLINK_MSG_ID_AUTH_KEY = 7
+MAVLINK_MSG_ID_SET_MODE = 11
+MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20
+MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21
+MAVLINK_MSG_ID_PARAM_VALUE = 22
+MAVLINK_MSG_ID_PARAM_SET = 23
+MAVLINK_MSG_ID_GPS_RAW_INT = 24
+MAVLINK_MSG_ID_GPS_STATUS = 25
+MAVLINK_MSG_ID_SCALED_IMU = 26
+MAVLINK_MSG_ID_RAW_IMU = 27
+MAVLINK_MSG_ID_RAW_PRESSURE = 28
+MAVLINK_MSG_ID_SCALED_PRESSURE = 29
+MAVLINK_MSG_ID_ATTITUDE = 30
+MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31
+MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32
+MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33
+MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34
+MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35
+MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36
+MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37
+MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38
+MAVLINK_MSG_ID_MISSION_ITEM = 39
+MAVLINK_MSG_ID_MISSION_REQUEST = 40
+MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41
+MAVLINK_MSG_ID_MISSION_CURRENT = 42
+MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43
+MAVLINK_MSG_ID_MISSION_COUNT = 44
+MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45
+MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46
+MAVLINK_MSG_ID_MISSION_ACK = 47
+MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48
+MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49
+MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50
+MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51
+MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52
+MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53
+MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54
+MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55
+MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56
+MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57
+MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58
+MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59
+MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT = 60
+MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST = 61
+MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62
+MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST = 63
+MAVLINK_MSG_ID_STATE_CORRECTION = 64
+MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66
+MAVLINK_MSG_ID_DATA_STREAM = 67
+MAVLINK_MSG_ID_MANUAL_CONTROL = 69
+MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70
+MAVLINK_MSG_ID_VFR_HUD = 74
+MAVLINK_MSG_ID_COMMAND_LONG = 76
+MAVLINK_MSG_ID_COMMAND_ACK = 77
+MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT = 80
+MAVLINK_MSG_ID_MANUAL_SETPOINT = 81
+MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89
+MAVLINK_MSG_ID_HIL_STATE = 90
+MAVLINK_MSG_ID_HIL_CONTROLS = 91
+MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92
+MAVLINK_MSG_ID_OPTICAL_FLOW = 100
+MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101
+MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102
+MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103
+MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104
+MAVLINK_MSG_ID_HIGHRES_IMU = 105
+MAVLINK_MSG_ID_FILE_TRANSFER_START = 110
+MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST = 111
+MAVLINK_MSG_ID_FILE_TRANSFER_RES = 112
+MAVLINK_MSG_ID_BATTERY_STATUS = 147
+MAVLINK_MSG_ID_SETPOINT_8DOF = 148
+MAVLINK_MSG_ID_SETPOINT_6DOF = 149
+MAVLINK_MSG_ID_MEMORY_VECT = 249
+MAVLINK_MSG_ID_DEBUG_VECT = 250
+MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251
+MAVLINK_MSG_ID_NAMED_VALUE_INT = 252
+MAVLINK_MSG_ID_STATUSTEXT = 253
+MAVLINK_MSG_ID_DEBUG = 254
+
+class MAVLink_heartbeat_message(MAVLink_message):
+ '''
+ The heartbeat message shows that a system is present and
+ responding. The type of the MAV and Autopilot hardware allow
+ the receiving system to treat further messages from this
+ system appropriate (e.g. by laying out the user interface
+ based on the autopilot).
+ '''
+ def __init__(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT')
+ self._fieldnames = ['type', 'autopilot', 'base_mode', 'custom_mode', 'system_status', 'mavlink_version']
+ self.type = type
+ self.autopilot = autopilot
+ self.base_mode = base_mode
+ self.custom_mode = custom_mode
+ self.system_status = system_status
+ self.mavlink_version = mavlink_version
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 50, struct.pack('<IBBBBB', self.custom_mode, self.type, self.autopilot, self.base_mode, self.system_status, self.mavlink_version))
+
+class MAVLink_sys_status_message(MAVLink_message):
+ '''
+ The general system state. If the system is following the
+ MAVLink standard, the system state is mainly defined by three
+ orthogonal states/modes: The system mode, which is either
+ LOCKED (motors shut down and locked), MANUAL (system under RC
+ control), GUIDED (system with autonomous position control,
+ position setpoint controlled manually) or AUTO (system guided
+ by path/waypoint planner). The NAV_MODE defined the current
+ flight state: LIFTOFF (often an open-loop maneuver), LANDING,
+ WAYPOINTS or VECTOR. This represents the internal navigation
+ state machine. The system status shows wether the system is
+ currently active or not and if an emergency occured. During
+ the CRITICAL and EMERGENCY states the MAV is still considered
+ to be active, but should start emergency procedures
+ autonomously. After a failure occured it should first move
+ from active to critical to allow manual intervention and then
+ move to emergency after a certain timeout.
+ '''
+ def __init__(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS')
+ self._fieldnames = ['onboard_control_sensors_present', 'onboard_control_sensors_enabled', 'onboard_control_sensors_health', 'load', 'voltage_battery', 'current_battery', 'battery_remaining', 'drop_rate_comm', 'errors_comm', 'errors_count1', 'errors_count2', 'errors_count3', 'errors_count4']
+ self.onboard_control_sensors_present = onboard_control_sensors_present
+ self.onboard_control_sensors_enabled = onboard_control_sensors_enabled
+ self.onboard_control_sensors_health = onboard_control_sensors_health
+ self.load = load
+ self.voltage_battery = voltage_battery
+ self.current_battery = current_battery
+ self.battery_remaining = battery_remaining
+ self.drop_rate_comm = drop_rate_comm
+ self.errors_comm = errors_comm
+ self.errors_count1 = errors_count1
+ self.errors_count2 = errors_count2
+ self.errors_count3 = errors_count3
+ self.errors_count4 = errors_count4
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 124, struct.pack('<IIIHHhHHHHHHb', self.onboard_control_sensors_present, self.onboard_control_sensors_enabled, self.onboard_control_sensors_health, self.load, self.voltage_battery, self.current_battery, self.drop_rate_comm, self.errors_comm, self.errors_count1, self.errors_count2, self.errors_count3, self.errors_count4, self.battery_remaining))
+
+class MAVLink_system_time_message(MAVLink_message):
+ '''
+ The system time is the time of the master clock, typically the
+ computer clock of the main onboard computer.
+ '''
+ def __init__(self, time_unix_usec, time_boot_ms):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME')
+ self._fieldnames = ['time_unix_usec', 'time_boot_ms']
+ self.time_unix_usec = time_unix_usec
+ self.time_boot_ms = time_boot_ms
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 137, struct.pack('<QI', self.time_unix_usec, self.time_boot_ms))
+
+class MAVLink_ping_message(MAVLink_message):
+ '''
+ A ping message either requesting or responding to a ping. This
+ allows to measure the system latencies, including serial port,
+ radio modem and UDP connections.
+ '''
+ def __init__(self, time_usec, seq, target_system, target_component):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING')
+ self._fieldnames = ['time_usec', 'seq', 'target_system', 'target_component']
+ self.time_usec = time_usec
+ self.seq = seq
+ self.target_system = target_system
+ self.target_component = target_component
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 237, struct.pack('<QIBB', self.time_usec, self.seq, self.target_system, self.target_component))
+
+class MAVLink_change_operator_control_message(MAVLink_message):
+ '''
+ Request to control this MAV
+ '''
+ def __init__(self, target_system, control_request, version, passkey):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, 'CHANGE_OPERATOR_CONTROL')
+ self._fieldnames = ['target_system', 'control_request', 'version', 'passkey']
+ self.target_system = target_system
+ self.control_request = control_request
+ self.version = version
+ self.passkey = passkey
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 217, struct.pack('<BBB25s', self.target_system, self.control_request, self.version, self.passkey))
+
+class MAVLink_change_operator_control_ack_message(MAVLink_message):
+ '''
+ Accept / deny control of this MAV
+ '''
+ def __init__(self, gcs_system_id, control_request, ack):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, 'CHANGE_OPERATOR_CONTROL_ACK')
+ self._fieldnames = ['gcs_system_id', 'control_request', 'ack']
+ self.gcs_system_id = gcs_system_id
+ self.control_request = control_request
+ self.ack = ack
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 104, struct.pack('<BBB', self.gcs_system_id, self.control_request, self.ack))
+
+class MAVLink_auth_key_message(MAVLink_message):
+ '''
+ Emit an encrypted signature / key identifying this system.
+ PLEASE NOTE: This protocol has been kept simple, so
+ transmitting the key requires an encrypted channel for true
+ safety.
+ '''
+ def __init__(self, key):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_AUTH_KEY, 'AUTH_KEY')
+ self._fieldnames = ['key']
+ self.key = key
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 119, struct.pack('<32s', self.key))
+
+class MAVLink_set_mode_message(MAVLink_message):
+ '''
+ Set the system mode, as defined by enum MAV_MODE. There is no
+ target component id as the mode is by definition for the
+ overall aircraft, not only for one component.
+ '''
+ def __init__(self, target_system, base_mode, custom_mode):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE')
+ self._fieldnames = ['target_system', 'base_mode', 'custom_mode']
+ self.target_system = target_system
+ self.base_mode = base_mode
+ self.custom_mode = custom_mode
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 89, struct.pack('<IBB', self.custom_mode, self.target_system, self.base_mode))
+
+class MAVLink_param_request_read_message(MAVLink_message):
+ '''
+ Request to read the onboard parameter with the param_id string
+ id. Onboard parameters are stored as key[const char*] ->
+ value[float]. This allows to send a parameter to any other
+ component (such as the GCS) without the need of previous
+ knowledge of possible parameter names. Thus the same GCS can
+ store different parameters for different autopilots. See also
+ http://qgroundcontrol.org/parameter_interface for a full
+ documentation of QGroundControl and IMU code.
+ '''
+ def __init__(self, target_system, target_component, param_id, param_index):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ')
+ self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.param_id = param_id
+ self.param_index = param_index
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 214, struct.pack('<hBB16s', self.param_index, self.target_system, self.target_component, self.param_id))
+
+class MAVLink_param_request_list_message(MAVLink_message):
+ '''
+ Request all parameters of this component. After his request,
+ all parameters are emitted.
+ '''
+ def __init__(self, target_system, target_component):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 'PARAM_REQUEST_LIST')
+ self._fieldnames = ['target_system', 'target_component']
+ self.target_system = target_system
+ self.target_component = target_component
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 159, struct.pack('<BB', self.target_system, self.target_component))
+
+class MAVLink_param_value_message(MAVLink_message):
+ '''
+ Emit the value of a onboard parameter. The inclusion of
+ param_count and param_index in the message allows the
+ recipient to keep track of received parameters and allows him
+ to re-request missing parameters after a loss or timeout.
+ '''
+ def __init__(self, param_id, param_value, param_type, param_count, param_index):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE')
+ self._fieldnames = ['param_id', 'param_value', 'param_type', 'param_count', 'param_index']
+ self.param_id = param_id
+ self.param_value = param_value
+ self.param_type = param_type
+ self.param_count = param_count
+ self.param_index = param_index
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 220, struct.pack('<fHH16sB', self.param_value, self.param_count, self.param_index, self.param_id, self.param_type))
+
+class MAVLink_param_set_message(MAVLink_message):
+ '''
+ Set a parameter value TEMPORARILY to RAM. It will be reset to
+ default on system reboot. Send the ACTION
+ MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents
+ to EEPROM. IMPORTANT: The receiving component should
+ acknowledge the new parameter value by sending a param_value
+ message to all communication partners. This will also ensure
+ that multiple GCS all have an up-to-date list of all
+ parameters. If the sending GCS did not receive a PARAM_VALUE
+ message within its timeout time, it should re-send the
+ PARAM_SET message.
+ '''
+ def __init__(self, target_system, target_component, param_id, param_value, param_type):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET')
+ self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value', 'param_type']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.param_id = param_id
+ self.param_value = param_value
+ self.param_type = param_type
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 168, struct.pack('<fBB16sB', self.param_value, self.target_system, self.target_component, self.param_id, self.param_type))
+
+class MAVLink_gps_raw_int_message(MAVLink_message):
+ '''
+ The global position, as returned by the Global Positioning
+ System (GPS). This is NOT the global position
+ estimate of the sytem, but rather a RAW sensor value. See
+ message GLOBAL_POSITION for the global position estimate.
+ Coordinate frame is right-handed, Z-axis up (GPS frame).
+ '''
+ def __init__(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT')
+ self._fieldnames = ['time_usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'vel', 'cog', 'satellites_visible']
+ self.time_usec = time_usec
+ self.fix_type = fix_type
+ self.lat = lat
+ self.lon = lon
+ self.alt = alt
+ self.eph = eph
+ self.epv = epv
+ self.vel = vel
+ self.cog = cog
+ self.satellites_visible = satellites_visible
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 24, struct.pack('<QiiiHHHHBB', self.time_usec, self.lat, self.lon, self.alt, self.eph, self.epv, self.vel, self.cog, self.fix_type, self.satellites_visible))
+
+class MAVLink_gps_status_message(MAVLink_message):
+ '''
+ The positioning status, as reported by GPS. This message is
+ intended to display status information about each satellite
+ visible to the receiver. See message GLOBAL_POSITION for the
+ global position estimate. This message can contain information
+ for up to 20 satellites.
+ '''
+ def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_STATUS, 'GPS_STATUS')
+ self._fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr']
+ self.satellites_visible = satellites_visible
+ self.satellite_prn = satellite_prn
+ self.satellite_used = satellite_used
+ self.satellite_elevation = satellite_elevation
+ self.satellite_azimuth = satellite_azimuth
+ self.satellite_snr = satellite_snr
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 23, struct.pack('<B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr))
+
+class MAVLink_scaled_imu_message(MAVLink_message):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This
+ message should contain the scaled values to the described
+ units
+ '''
+ def __init__(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU')
+ self._fieldnames = ['time_boot_ms', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
+ self.time_boot_ms = time_boot_ms
+ self.xacc = xacc
+ self.yacc = yacc
+ self.zacc = zacc
+ self.xgyro = xgyro
+ self.ygyro = ygyro
+ self.zgyro = zgyro
+ self.xmag = xmag
+ self.ymag = ymag
+ self.zmag = zmag
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 170, struct.pack('<Ihhhhhhhhh', self.time_boot_ms, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
+
+class MAVLink_raw_imu_message(MAVLink_message):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This
+ message should always contain the true raw values without any
+ scaling to allow data capture and system debugging.
+ '''
+ def __init__(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU')
+ self._fieldnames = ['time_usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
+ self.time_usec = time_usec
+ self.xacc = xacc
+ self.yacc = yacc
+ self.zacc = zacc
+ self.xgyro = xgyro
+ self.ygyro = ygyro
+ self.zgyro = zgyro
+ self.xmag = xmag
+ self.ymag = ymag
+ self.zmag = zmag
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 144, struct.pack('<Qhhhhhhhhh', self.time_usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
+
+class MAVLink_raw_pressure_message(MAVLink_message):
+ '''
+ The RAW pressure readings for the typical setup of one
+ absolute pressure and one differential pressure sensor. The
+ sensor values should be the raw, UNSCALED ADC values.
+ '''
+ def __init__(self, time_usec, press_abs, press_diff1, press_diff2, temperature):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE')
+ self._fieldnames = ['time_usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature']
+ self.time_usec = time_usec
+ self.press_abs = press_abs
+ self.press_diff1 = press_diff1
+ self.press_diff2 = press_diff2
+ self.temperature = temperature
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 67, struct.pack('<Qhhhh', self.time_usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature))
+
+class MAVLink_scaled_pressure_message(MAVLink_message):
+ '''
+ The pressure readings for the typical setup of one absolute
+ and differential pressure sensor. The units are as specified
+ in each field.
+ '''
+ def __init__(self, time_boot_ms, press_abs, press_diff, temperature):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE')
+ self._fieldnames = ['time_boot_ms', 'press_abs', 'press_diff', 'temperature']
+ self.time_boot_ms = time_boot_ms
+ self.press_abs = press_abs
+ self.press_diff = press_diff
+ self.temperature = temperature
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 115, struct.pack('<Iffh', self.time_boot_ms, self.press_abs, self.press_diff, self.temperature))
+
+class MAVLink_attitude_message(MAVLink_message):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down,
+ X-front, Y-right).
+ '''
+ def __init__(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE')
+ self._fieldnames = ['time_boot_ms', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed']
+ self.time_boot_ms = time_boot_ms
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.rollspeed = rollspeed
+ self.pitchspeed = pitchspeed
+ self.yawspeed = yawspeed
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 39, struct.pack('<Iffffff', self.time_boot_ms, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed))
+
+class MAVLink_attitude_quaternion_message(MAVLink_message):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down,
+ X-front, Y-right), expressed as quaternion.
+ '''
+ def __init__(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, 'ATTITUDE_QUATERNION')
+ self._fieldnames = ['time_boot_ms', 'q1', 'q2', 'q3', 'q4', 'rollspeed', 'pitchspeed', 'yawspeed']
+ self.time_boot_ms = time_boot_ms
+ self.q1 = q1
+ self.q2 = q2
+ self.q3 = q3
+ self.q4 = q4
+ self.rollspeed = rollspeed
+ self.pitchspeed = pitchspeed
+ self.yawspeed = yawspeed
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 246, struct.pack('<Ifffffff', self.time_boot_ms, self.q1, self.q2, self.q3, self.q4, self.rollspeed, self.pitchspeed, self.yawspeed))
+
+class MAVLink_local_position_ned_message(MAVLink_message):
+ '''
+ The filtered local position (e.g. fused computer vision and
+ accelerometers). Coordinate frame is right-handed, Z-axis down
+ (aeronautical frame, NED / north-east-down convention)
+ '''
+ def __init__(self, time_boot_ms, x, y, z, vx, vy, vz):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_NED, 'LOCAL_POSITION_NED')
+ self._fieldnames = ['time_boot_ms', 'x', 'y', 'z', 'vx', 'vy', 'vz']
+ self.time_boot_ms = time_boot_ms
+ self.x = x
+ self.y = y
+ self.z = z
+ self.vx = vx
+ self.vy = vy
+ self.vz = vz
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 185, struct.pack('<Iffffff', self.time_boot_ms, self.x, self.y, self.z, self.vx, self.vy, self.vz))
+
+class MAVLink_global_position_int_message(MAVLink_message):
+ '''
+ The filtered global position (e.g. fused GPS and
+ accelerometers). The position is in GPS-frame (right-handed,
+ Z-up). It is designed as scaled integer message
+ since the resolution of float is not sufficient.
+ '''
+ def __init__(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, 'GLOBAL_POSITION_INT')
+ self._fieldnames = ['time_boot_ms', 'lat', 'lon', 'alt', 'relative_alt', 'vx', 'vy', 'vz', 'hdg']
+ self.time_boot_ms = time_boot_ms
+ self.lat = lat
+ self.lon = lon
+ self.alt = alt
+ self.relative_alt = relative_alt
+ self.vx = vx
+ self.vy = vy
+ self.vz = vz
+ self.hdg = hdg
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 104, struct.pack('<IiiiihhhH', self.time_boot_ms, self.lat, self.lon, self.alt, self.relative_alt, self.vx, self.vy, self.vz, self.hdg))
+
+class MAVLink_rc_channels_scaled_message(MAVLink_message):
+ '''
+ The scaled values of the RC channels received. (-100%) -10000,
+ (0%) 0, (100%) 10000. Channels that are inactive should be set
+ to 65535.
+ '''
+ def __init__(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, 'RC_CHANNELS_SCALED')
+ self._fieldnames = ['time_boot_ms', 'port', 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi']
+ self.time_boot_ms = time_boot_ms
+ self.port = port
+ self.chan1_scaled = chan1_scaled
+ self.chan2_scaled = chan2_scaled
+ self.chan3_scaled = chan3_scaled
+ self.chan4_scaled = chan4_scaled
+ self.chan5_scaled = chan5_scaled
+ self.chan6_scaled = chan6_scaled
+ self.chan7_scaled = chan7_scaled
+ self.chan8_scaled = chan8_scaled
+ self.rssi = rssi
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 237, struct.pack('<IhhhhhhhhBB', self.time_boot_ms, self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.port, self.rssi))
+
+class MAVLink_rc_channels_raw_message(MAVLink_message):
+ '''
+ The RAW values of the RC channels received. The standard PPM
+ modulation is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%. Individual receivers/transmitters might
+ violate this specification.
+ '''
+ def __init__(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_RAW, 'RC_CHANNELS_RAW')
+ self._fieldnames = ['time_boot_ms', 'port', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi']
+ self.time_boot_ms = time_boot_ms
+ self.port = port
+ self.chan1_raw = chan1_raw
+ self.chan2_raw = chan2_raw
+ self.chan3_raw = chan3_raw
+ self.chan4_raw = chan4_raw
+ self.chan5_raw = chan5_raw
+ self.chan6_raw = chan6_raw
+ self.chan7_raw = chan7_raw
+ self.chan8_raw = chan8_raw
+ self.rssi = rssi
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 244, struct.pack('<IHHHHHHHHBB', self.time_boot_ms, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.port, self.rssi))
+
+class MAVLink_servo_output_raw_message(MAVLink_message):
+ '''
+ The RAW values of the servo outputs (for RC input from the
+ remote, use the RC_CHANNELS messages). The standard PPM
+ modulation is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%.
+ '''
+ def __init__(self, time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 'SERVO_OUTPUT_RAW')
+ self._fieldnames = ['time_boot_ms', 'port', 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw']
+ self.time_boot_ms = time_boot_ms
+ self.port = port
+ self.servo1_raw = servo1_raw
+ self.servo2_raw = servo2_raw
+ self.servo3_raw = servo3_raw
+ self.servo4_raw = servo4_raw
+ self.servo5_raw = servo5_raw
+ self.servo6_raw = servo6_raw
+ self.servo7_raw = servo7_raw
+ self.servo8_raw = servo8_raw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 242, struct.pack('<IHHHHHHHHB', self.time_boot_ms, self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw, self.port))
+
+class MAVLink_mission_request_partial_list_message(MAVLink_message):
+ '''
+ Request a partial list of mission items from the
+ system/component.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol. If start
+ and end index are the same, just send one waypoint.
+ '''
+ def __init__(self, target_system, target_component, start_index, end_index):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, 'MISSION_REQUEST_PARTIAL_LIST')
+ self._fieldnames = ['target_system', 'target_component', 'start_index', 'end_index']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.start_index = start_index
+ self.end_index = end_index
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 212, struct.pack('<hhBB', self.start_index, self.end_index, self.target_system, self.target_component))
+
+class MAVLink_mission_write_partial_list_message(MAVLink_message):
+ '''
+ This message is sent to the MAV to write a partial list. If
+ start index == end index, only one item will be transmitted /
+ updated. If the start index is NOT 0 and above the current
+ list size, this request should be REJECTED!
+ '''
+ def __init__(self, target_system, target_component, start_index, end_index):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, 'MISSION_WRITE_PARTIAL_LIST')
+ self._fieldnames = ['target_system', 'target_component', 'start_index', 'end_index']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.start_index = start_index
+ self.end_index = end_index
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 9, struct.pack('<hhBB', self.start_index, self.end_index, self.target_system, self.target_component))
+
+class MAVLink_mission_item_message(MAVLink_message):
+ '''
+ Message encoding a mission item. This message is emitted to
+ announce the presence of a mission item and to
+ set a mission item on the system. The mission item can be
+ either in x, y, z meters (type: LOCAL) or x:lat, y:lon,
+ z:altitude. Local frame is Z-down, right handed (NED), global
+ frame is Z-up, right handed (ENU). See also
+ http://qgroundcontrol.org/mavlink/waypoint_protocol.
+ '''
+ def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_ITEM, 'MISSION_ITEM')
+ self._fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.seq = seq
+ self.frame = frame
+ self.command = command
+ self.current = current
+ self.autocontinue = autocontinue
+ self.param1 = param1
+ self.param2 = param2
+ self.param3 = param3
+ self.param4 = param4
+ self.x = x
+ self.y = y
+ self.z = z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 254, struct.pack('<fffffffHHBBBBB', self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z, self.seq, self.command, self.target_system, self.target_component, self.frame, self.current, self.autocontinue))
+
+class MAVLink_mission_request_message(MAVLink_message):
+ '''
+ Request the information of the mission item with the sequence
+ number seq. The response of the system to this message should
+ be a MISSION_ITEM message.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol
+ '''
+ def __init__(self, target_system, target_component, seq):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST, 'MISSION_REQUEST')
+ self._fieldnames = ['target_system', 'target_component', 'seq']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.seq = seq
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 230, struct.pack('<HBB', self.seq, self.target_system, self.target_component))
+
+class MAVLink_mission_set_current_message(MAVLink_message):
+ '''
+ Set the mission item with sequence number seq as current item.
+ This means that the MAV will continue to this mission item on
+ the shortest path (not following the mission items in-
+ between).
+ '''
+ def __init__(self, target_system, target_component, seq):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_SET_CURRENT, 'MISSION_SET_CURRENT')
+ self._fieldnames = ['target_system', 'target_component', 'seq']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.seq = seq
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 28, struct.pack('<HBB', self.seq, self.target_system, self.target_component))
+
+class MAVLink_mission_current_message(MAVLink_message):
+ '''
+ Message that announces the sequence number of the current
+ active mission item. The MAV will fly towards this mission
+ item.
+ '''
+ def __init__(self, seq):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_CURRENT, 'MISSION_CURRENT')
+ self._fieldnames = ['seq']
+ self.seq = seq
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 28, struct.pack('<H', self.seq))
+
+class MAVLink_mission_request_list_message(MAVLink_message):
+ '''
+ Request the overall list of mission items from the
+ system/component.
+ '''
+ def __init__(self, target_system, target_component):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, 'MISSION_REQUEST_LIST')
+ self._fieldnames = ['target_system', 'target_component']
+ self.target_system = target_system
+ self.target_component = target_component
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 132, struct.pack('<BB', self.target_system, self.target_component))
+
+class MAVLink_mission_count_message(MAVLink_message):
+ '''
+ This message is emitted as response to MISSION_REQUEST_LIST by
+ the MAV and to initiate a write transaction. The GCS can then
+ request the individual mission item based on the knowledge of
+ the total number of MISSIONs.
+ '''
+ def __init__(self, target_system, target_component, count):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_COUNT, 'MISSION_COUNT')
+ self._fieldnames = ['target_system', 'target_component', 'count']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.count = count
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 221, struct.pack('<HBB', self.count, self.target_system, self.target_component))
+
+class MAVLink_mission_clear_all_message(MAVLink_message):
+ '''
+ Delete all mission items at once.
+ '''
+ def __init__(self, target_system, target_component):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, 'MISSION_CLEAR_ALL')
+ self._fieldnames = ['target_system', 'target_component']
+ self.target_system = target_system
+ self.target_component = target_component
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 232, struct.pack('<BB', self.target_system, self.target_component))
+
+class MAVLink_mission_item_reached_message(MAVLink_message):
+ '''
+ A certain mission item has been reached. The system will
+ either hold this position (or circle on the orbit) or (if the
+ autocontinue on the WP was set) continue to the next MISSION.
+ '''
+ def __init__(self, seq):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, 'MISSION_ITEM_REACHED')
+ self._fieldnames = ['seq']
+ self.seq = seq
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 11, struct.pack('<H', self.seq))
+
+class MAVLink_mission_ack_message(MAVLink_message):
+ '''
+ Ack message during MISSION handling. The type field states if
+ this message is a positive ack (type=0) or if an error
+ happened (type=non-zero).
+ '''
+ def __init__(self, target_system, target_component, type):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_ACK, 'MISSION_ACK')
+ self._fieldnames = ['target_system', 'target_component', 'type']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.type = type
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 153, struct.pack('<BBB', self.target_system, self.target_component, self.type))
+
+class MAVLink_set_gps_global_origin_message(MAVLink_message):
+ '''
+ As local waypoints exist, the global MISSION reference allows
+ to transform between the local coordinate frame and the global
+ (GPS) coordinate frame. This can be necessary when e.g. in-
+ and outdoor settings are connected and the MAV should move
+ from in- to outdoor.
+ '''
+ def __init__(self, target_system, latitude, longitude, altitude):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, 'SET_GPS_GLOBAL_ORIGIN')
+ self._fieldnames = ['target_system', 'latitude', 'longitude', 'altitude']
+ self.target_system = target_system
+ self.latitude = latitude
+ self.longitude = longitude
+ self.altitude = altitude
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 41, struct.pack('<iiiB', self.latitude, self.longitude, self.altitude, self.target_system))
+
+class MAVLink_gps_global_origin_message(MAVLink_message):
+ '''
+ Once the MAV sets a new GPS-Local correspondence, this message
+ announces the origin (0,0,0) position
+ '''
+ def __init__(self, latitude, longitude, altitude):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, 'GPS_GLOBAL_ORIGIN')
+ self._fieldnames = ['latitude', 'longitude', 'altitude']
+ self.latitude = latitude
+ self.longitude = longitude
+ self.altitude = altitude
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 39, struct.pack('<iii', self.latitude, self.longitude, self.altitude))
+
+class MAVLink_set_local_position_setpoint_message(MAVLink_message):
+ '''
+ Set the setpoint for a local position controller. This is the
+ position in local coordinates the MAV should fly to. This
+ message is sent by the path/MISSION planner to the onboard
+ position controller. As some MAVs have a degree of freedom in
+ yaw (e.g. all helicopters/quadrotors), the desired yaw angle
+ is part of the message.
+ '''
+ def __init__(self, target_system, target_component, coordinate_frame, x, y, z, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, 'SET_LOCAL_POSITION_SETPOINT')
+ self._fieldnames = ['target_system', 'target_component', 'coordinate_frame', 'x', 'y', 'z', 'yaw']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.coordinate_frame = coordinate_frame
+ self.x = x
+ self.y = y
+ self.z = z
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 214, struct.pack('<ffffBBB', self.x, self.y, self.z, self.yaw, self.target_system, self.target_component, self.coordinate_frame))
+
+class MAVLink_local_position_setpoint_message(MAVLink_message):
+ '''
+ Transmit the current local setpoint of the controller to other
+ MAVs (collision avoidance) and to the GCS.
+ '''
+ def __init__(self, coordinate_frame, x, y, z, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, 'LOCAL_POSITION_SETPOINT')
+ self._fieldnames = ['coordinate_frame', 'x', 'y', 'z', 'yaw']
+ self.coordinate_frame = coordinate_frame
+ self.x = x
+ self.y = y
+ self.z = z
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 223, struct.pack('<ffffB', self.x, self.y, self.z, self.yaw, self.coordinate_frame))
+
+class MAVLink_global_position_setpoint_int_message(MAVLink_message):
+ '''
+ Transmit the current local setpoint of the controller to other
+ MAVs (collision avoidance) and to the GCS.
+ '''
+ def __init__(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, 'GLOBAL_POSITION_SETPOINT_INT')
+ self._fieldnames = ['coordinate_frame', 'latitude', 'longitude', 'altitude', 'yaw']
+ self.coordinate_frame = coordinate_frame
+ self.latitude = latitude
+ self.longitude = longitude
+ self.altitude = altitude
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 141, struct.pack('<iiihB', self.latitude, self.longitude, self.altitude, self.yaw, self.coordinate_frame))
+
+class MAVLink_set_global_position_setpoint_int_message(MAVLink_message):
+ '''
+ Set the current global position setpoint.
+ '''
+ def __init__(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, 'SET_GLOBAL_POSITION_SETPOINT_INT')
+ self._fieldnames = ['coordinate_frame', 'latitude', 'longitude', 'altitude', 'yaw']
+ self.coordinate_frame = coordinate_frame
+ self.latitude = latitude
+ self.longitude = longitude
+ self.altitude = altitude
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 33, struct.pack('<iiihB', self.latitude, self.longitude, self.altitude, self.yaw, self.coordinate_frame))
+
+class MAVLink_safety_set_allowed_area_message(MAVLink_message):
+ '''
+ Set a safety zone (volume), which is defined by two corners of
+ a cube. This message can be used to tell the MAV which
+ setpoints/MISSIONs to accept and which to reject. Safety areas
+ are often enforced by national or competition regulations.
+ '''
+ def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, 'SAFETY_SET_ALLOWED_AREA')
+ self._fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.frame = frame
+ self.p1x = p1x
+ self.p1y = p1y
+ self.p1z = p1z
+ self.p2x = p2x
+ self.p2y = p2y
+ self.p2z = p2z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 15, struct.pack('<ffffffBBB', self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z, self.target_system, self.target_component, self.frame))
+
+class MAVLink_safety_allowed_area_message(MAVLink_message):
+ '''
+ Read out the safety zone the MAV currently assumes.
+ '''
+ def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, 'SAFETY_ALLOWED_AREA')
+ self._fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z']
+ self.frame = frame
+ self.p1x = p1x
+ self.p1y = p1y
+ self.p1z = p1z
+ self.p2x = p2x
+ self.p2y = p2y
+ self.p2z = p2z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 3, struct.pack('<ffffffB', self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z, self.frame))
+
+class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message):
+ '''
+ Set roll, pitch and yaw.
+ '''
+ def __init__(self, target_system, target_component, roll, pitch, yaw, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, 'SET_ROLL_PITCH_YAW_THRUST')
+ self._fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 100, struct.pack('<ffffBB', self.roll, self.pitch, self.yaw, self.thrust, self.target_system, self.target_component))
+
+class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message):
+ '''
+ Set roll, pitch and yaw.
+ '''
+ def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, 'SET_ROLL_PITCH_YAW_SPEED_THRUST')
+ self._fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.roll_speed = roll_speed
+ self.pitch_speed = pitch_speed
+ self.yaw_speed = yaw_speed
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 24, struct.pack('<ffffBB', self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust, self.target_system, self.target_component))
+
+class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message):
+ '''
+ Setpoint in roll, pitch, yaw currently active on the system.
+ '''
+ def __init__(self, time_boot_ms, roll, pitch, yaw, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, 'ROLL_PITCH_YAW_THRUST_SETPOINT')
+ self._fieldnames = ['time_boot_ms', 'roll', 'pitch', 'yaw', 'thrust']
+ self.time_boot_ms = time_boot_ms
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 239, struct.pack('<Iffff', self.time_boot_ms, self.roll, self.pitch, self.yaw, self.thrust))
+
+class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message):
+ '''
+ Setpoint in rollspeed, pitchspeed, yawspeed currently active
+ on the system.
+ '''
+ def __init__(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT')
+ self._fieldnames = ['time_boot_ms', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust']
+ self.time_boot_ms = time_boot_ms
+ self.roll_speed = roll_speed
+ self.pitch_speed = pitch_speed
+ self.yaw_speed = yaw_speed
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 238, struct.pack('<Iffff', self.time_boot_ms, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust))
+
+class MAVLink_set_quad_motors_setpoint_message(MAVLink_message):
+ '''
+ Setpoint in the four motor speeds
+ '''
+ def __init__(self, target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, 'SET_QUAD_MOTORS_SETPOINT')
+ self._fieldnames = ['target_system', 'motor_front_nw', 'motor_right_ne', 'motor_back_se', 'motor_left_sw']
+ self.target_system = target_system
+ self.motor_front_nw = motor_front_nw
+ self.motor_right_ne = motor_right_ne
+ self.motor_back_se = motor_back_se
+ self.motor_left_sw = motor_left_sw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 30, struct.pack('<HHHHB', self.motor_front_nw, self.motor_right_ne, self.motor_back_se, self.motor_left_sw, self.target_system))
+
+class MAVLink_set_quad_swarm_roll_pitch_yaw_thrust_message(MAVLink_message):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+ '''
+ def __init__(self, group, mode, roll, pitch, yaw, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, 'SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST')
+ self._fieldnames = ['group', 'mode', 'roll', 'pitch', 'yaw', 'thrust']
+ self.group = group
+ self.mode = mode
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 240, struct.pack('<4h4h4h4HBB', self.roll, self.pitch, self.yaw, self.thrust, self.group, self.mode))
+
+class MAVLink_nav_controller_output_message(MAVLink_message):
+ '''
+ Outputs of the APM navigation controller. The primary use of
+ this message is to check the response and signs of the
+ controller before actual flight and to assist with tuning
+ controller parameters.
+ '''
+ def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, 'NAV_CONTROLLER_OUTPUT')
+ self._fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error']
+ self.nav_roll = nav_roll
+ self.nav_pitch = nav_pitch
+ self.nav_bearing = nav_bearing
+ self.target_bearing = target_bearing
+ self.wp_dist = wp_dist
+ self.alt_error = alt_error
+ self.aspd_error = aspd_error
+ self.xtrack_error = xtrack_error
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 183, struct.pack('<fffffhhH', self.nav_roll, self.nav_pitch, self.alt_error, self.aspd_error, self.xtrack_error, self.nav_bearing, self.target_bearing, self.wp_dist))
+
+class MAVLink_set_quad_swarm_led_roll_pitch_yaw_thrust_message(MAVLink_message):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+ '''
+ def __init__(self, group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, 'SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST')
+ self._fieldnames = ['group', 'mode', 'led_red', 'led_blue', 'led_green', 'roll', 'pitch', 'yaw', 'thrust']
+ self.group = group
+ self.mode = mode
+ self.led_red = led_red
+ self.led_blue = led_blue
+ self.led_green = led_green
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 130, struct.pack('<4h4h4h4HBB4s4s4s', self.roll, self.pitch, self.yaw, self.thrust, self.group, self.mode, self.led_red, self.led_blue, self.led_green))
+
+class MAVLink_state_correction_message(MAVLink_message):
+ '''
+ Corrects the systems state by adding an error correction term
+ to the position and velocity, and by rotating the attitude by
+ a correction angle.
+ '''
+ def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATE_CORRECTION, 'STATE_CORRECTION')
+ self._fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr']
+ self.xErr = xErr
+ self.yErr = yErr
+ self.zErr = zErr
+ self.rollErr = rollErr
+ self.pitchErr = pitchErr
+ self.yawErr = yawErr
+ self.vxErr = vxErr
+ self.vyErr = vyErr
+ self.vzErr = vzErr
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 130, struct.pack('<fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr))
+
+class MAVLink_request_data_stream_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, 'REQUEST_DATA_STREAM')
+ self._fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.req_stream_id = req_stream_id
+ self.req_message_rate = req_message_rate
+ self.start_stop = start_stop
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 148, struct.pack('<HBBBB', self.req_message_rate, self.target_system, self.target_component, self.req_stream_id, self.start_stop))
+
+class MAVLink_data_stream_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, stream_id, message_rate, on_off):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_DATA_STREAM, 'DATA_STREAM')
+ self._fieldnames = ['stream_id', 'message_rate', 'on_off']
+ self.stream_id = stream_id
+ self.message_rate = message_rate
+ self.on_off = on_off
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 21, struct.pack('<HBB', self.message_rate, self.stream_id, self.on_off))
+
+class MAVLink_manual_control_message(MAVLink_message):
+ '''
+ This message provides an API for manually controlling the
+ vehicle using standard joystick axes nomenclature, along with
+ a joystick-like input device. Unused axes can be disabled an
+ buttons are also transmit as boolean values of their
+ '''
+ def __init__(self, target, x, y, z, r, buttons):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MANUAL_CONTROL, 'MANUAL_CONTROL')
+ self._fieldnames = ['target', 'x', 'y', 'z', 'r', 'buttons']
+ self.target = target
+ self.x = x
+ self.y = y
+ self.z = z
+ self.r = r
+ self.buttons = buttons
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 243, struct.pack('<hhhhHB', self.x, self.y, self.z, self.r, self.buttons, self.target))
+
+class MAVLink_rc_channels_override_message(MAVLink_message):
+ '''
+ The RAW values of the RC channels sent to the MAV to override
+ info received from the RC radio. A value of -1 means no change
+ to that channel. A value of 0 means control of that channel
+ should be released back to the RC radio. The standard PPM
+ modulation is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%. Individual receivers/transmitters might
+ violate this specification.
+ '''
+ def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, 'RC_CHANNELS_OVERRIDE')
+ self._fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.chan1_raw = chan1_raw
+ self.chan2_raw = chan2_raw
+ self.chan3_raw = chan3_raw
+ self.chan4_raw = chan4_raw
+ self.chan5_raw = chan5_raw
+ self.chan6_raw = chan6_raw
+ self.chan7_raw = chan7_raw
+ self.chan8_raw = chan8_raw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 124, struct.pack('<HHHHHHHHBB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.target_system, self.target_component))
+
+class MAVLink_vfr_hud_message(MAVLink_message):
+ '''
+ Metrics typically displayed on a HUD for fixed wing aircraft
+ '''
+ def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_VFR_HUD, 'VFR_HUD')
+ self._fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb']
+ self.airspeed = airspeed
+ self.groundspeed = groundspeed
+ self.heading = heading
+ self.throttle = throttle
+ self.alt = alt
+ self.climb = climb
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 20, struct.pack('<ffffhH', self.airspeed, self.groundspeed, self.alt, self.climb, self.heading, self.throttle))
+
+class MAVLink_command_long_message(MAVLink_message):
+ '''
+ Send a command with up to four parameters to the MAV
+ '''
+ def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_LONG, 'COMMAND_LONG')
+ self._fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4', 'param5', 'param6', 'param7']
+ self.target_system = target_system
+ self.target_component = target_component
+ self.command = command
+ self.confirmation = confirmation
+ self.param1 = param1
+ self.param2 = param2
+ self.param3 = param3
+ self.param4 = param4
+ self.param5 = param5
+ self.param6 = param6
+ self.param7 = param7
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 152, struct.pack('<fffffffHBBB', self.param1, self.param2, self.param3, self.param4, self.param5, self.param6, self.param7, self.command, self.target_system, self.target_component, self.confirmation))
+
+class MAVLink_command_ack_message(MAVLink_message):
+ '''
+ Report status of a command. Includes feedback wether the
+ command was executed.
+ '''
+ def __init__(self, command, result):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_ACK, 'COMMAND_ACK')
+ self._fieldnames = ['command', 'result']
+ self.command = command
+ self.result = result
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 143, struct.pack('<HB', self.command, self.result))
+
+class MAVLink_roll_pitch_yaw_rates_thrust_setpoint_message(MAVLink_message):
+ '''
+ Setpoint in roll, pitch, yaw rates and thrust currently active
+ on the system.
+ '''
+ def __init__(self, time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, 'ROLL_PITCH_YAW_RATES_THRUST_SETPOINT')
+ self._fieldnames = ['time_boot_ms', 'roll_rate', 'pitch_rate', 'yaw_rate', 'thrust']
+ self.time_boot_ms = time_boot_ms
+ self.roll_rate = roll_rate
+ self.pitch_rate = pitch_rate
+ self.yaw_rate = yaw_rate
+ self.thrust = thrust
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 127, struct.pack('<Iffff', self.time_boot_ms, self.roll_rate, self.pitch_rate, self.yaw_rate, self.thrust))
+
+class MAVLink_manual_setpoint_message(MAVLink_message):
+ '''
+ Setpoint in roll, pitch, yaw and thrust from the operator
+ '''
+ def __init__(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MANUAL_SETPOINT, 'MANUAL_SETPOINT')
+ self._fieldnames = ['time_boot_ms', 'roll', 'pitch', 'yaw', 'thrust', 'mode_switch', 'manual_override_switch']
+ self.time_boot_ms = time_boot_ms
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.thrust = thrust
+ self.mode_switch = mode_switch
+ self.manual_override_switch = manual_override_switch
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 106, struct.pack('<IffffBB', self.time_boot_ms, self.roll, self.pitch, self.yaw, self.thrust, self.mode_switch, self.manual_override_switch))
+
+class MAVLink_local_position_ned_system_global_offset_message(MAVLink_message):
+ '''
+ The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED
+ messages of MAV X and the global coordinate frame in NED
+ coordinates. Coordinate frame is right-handed, Z-axis down
+ (aeronautical frame, NED / north-east-down convention)
+ '''
+ def __init__(self, time_boot_ms, x, y, z, roll, pitch, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, 'LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET')
+ self._fieldnames = ['time_boot_ms', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
+ self.time_boot_ms = time_boot_ms
+ self.x = x
+ self.y = y
+ self.z = z
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 231, struct.pack('<Iffffff', self.time_boot_ms, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
+
+class MAVLink_hil_state_message(MAVLink_message):
+ '''
+ Sent from simulation to autopilot. This packet is useful for
+ high throughput applications such as hardware in the loop
+ simulations.
+ '''
+ def __init__(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_STATE, 'HIL_STATE')
+ self._fieldnames = ['time_usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc']
+ self.time_usec = time_usec
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+ self.rollspeed = rollspeed
+ self.pitchspeed = pitchspeed
+ self.yawspeed = yawspeed
+ self.lat = lat
+ self.lon = lon
+ self.alt = alt
+ self.vx = vx
+ self.vy = vy
+ self.vz = vz
+ self.xacc = xacc
+ self.yacc = yacc
+ self.zacc = zacc
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 183, struct.pack('<Qffffffiiihhhhhh', self.time_usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc))
+
+class MAVLink_hil_controls_message(MAVLink_message):
+ '''
+ Sent from autopilot to simulation. Hardware in the loop
+ control outputs
+ '''
+ def __init__(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_CONTROLS, 'HIL_CONTROLS')
+ self._fieldnames = ['time_usec', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'aux1', 'aux2', 'aux3', 'aux4', 'mode', 'nav_mode']
+ self.time_usec = time_usec
+ self.roll_ailerons = roll_ailerons
+ self.pitch_elevator = pitch_elevator
+ self.yaw_rudder = yaw_rudder
+ self.throttle = throttle
+ self.aux1 = aux1
+ self.aux2 = aux2
+ self.aux3 = aux3
+ self.aux4 = aux4
+ self.mode = mode
+ self.nav_mode = nav_mode
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 63, struct.pack('<QffffffffBB', self.time_usec, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.aux1, self.aux2, self.aux3, self.aux4, self.mode, self.nav_mode))
+
+class MAVLink_hil_rc_inputs_raw_message(MAVLink_message):
+ '''
+ Sent from simulation to autopilot. The RAW values of the RC
+ channels received. The standard PPM modulation is as follows:
+ 1000 microseconds: 0%, 2000 microseconds: 100%. Individual
+ receivers/transmitters might violate this specification.
+ '''
+ def __init__(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, 'HIL_RC_INPUTS_RAW')
+ self._fieldnames = ['time_usec', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'chan9_raw', 'chan10_raw', 'chan11_raw', 'chan12_raw', 'rssi']
+ self.time_usec = time_usec
+ self.chan1_raw = chan1_raw
+ self.chan2_raw = chan2_raw
+ self.chan3_raw = chan3_raw
+ self.chan4_raw = chan4_raw
+ self.chan5_raw = chan5_raw
+ self.chan6_raw = chan6_raw
+ self.chan7_raw = chan7_raw
+ self.chan8_raw = chan8_raw
+ self.chan9_raw = chan9_raw
+ self.chan10_raw = chan10_raw
+ self.chan11_raw = chan11_raw
+ self.chan12_raw = chan12_raw
+ self.rssi = rssi
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 54, struct.pack('<QHHHHHHHHHHHHB', self.time_usec, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.chan9_raw, self.chan10_raw, self.chan11_raw, self.chan12_raw, self.rssi))
+
+class MAVLink_optical_flow_message(MAVLink_message):
+ '''
+ Optical flow from a flow sensor (e.g. optical mouse sensor)
+ '''
+ def __init__(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_OPTICAL_FLOW, 'OPTICAL_FLOW')
+ self._fieldnames = ['time_usec', 'sensor_id', 'flow_x', 'flow_y', 'flow_comp_m_x', 'flow_comp_m_y', 'quality', 'ground_distance']
+ self.time_usec = time_usec
+ self.sensor_id = sensor_id
+ self.flow_x = flow_x
+ self.flow_y = flow_y
+ self.flow_comp_m_x = flow_comp_m_x
+ self.flow_comp_m_y = flow_comp_m_y
+ self.quality = quality
+ self.ground_distance = ground_distance
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 175, struct.pack('<QfffhhBB', self.time_usec, self.flow_comp_m_x, self.flow_comp_m_y, self.ground_distance, self.flow_x, self.flow_y, self.sensor_id, self.quality))
+
+class MAVLink_global_vision_position_estimate_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, usec, x, y, z, roll, pitch, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, 'GLOBAL_VISION_POSITION_ESTIMATE')
+ self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
+ self.usec = usec
+ self.x = x
+ self.y = y
+ self.z = z
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 102, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
+
+class MAVLink_vision_position_estimate_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, usec, x, y, z, roll, pitch, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, 'VISION_POSITION_ESTIMATE')
+ self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
+ self.usec = usec
+ self.x = x
+ self.y = y
+ self.z = z
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 158, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
+
+class MAVLink_vision_speed_estimate_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, usec, x, y, z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, 'VISION_SPEED_ESTIMATE')
+ self._fieldnames = ['usec', 'x', 'y', 'z']
+ self.usec = usec
+ self.x = x
+ self.y = y
+ self.z = z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 208, struct.pack('<Qfff', self.usec, self.x, self.y, self.z))
+
+class MAVLink_vicon_position_estimate_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, usec, x, y, z, roll, pitch, yaw):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, 'VICON_POSITION_ESTIMATE')
+ self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
+ self.usec = usec
+ self.x = x
+ self.y = y
+ self.z = z
+ self.roll = roll
+ self.pitch = pitch
+ self.yaw = yaw
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 56, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
+
+class MAVLink_highres_imu_message(MAVLink_message):
+ '''
+ The IMU readings in SI units in NED body frame
+ '''
+ def __init__(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIGHRES_IMU, 'HIGHRES_IMU')
+ self._fieldnames = ['time_usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag', 'abs_pressure', 'diff_pressure', 'pressure_alt', 'temperature', 'fields_updated']
+ self.time_usec = time_usec
+ self.xacc = xacc
+ self.yacc = yacc
+ self.zacc = zacc
+ self.xgyro = xgyro
+ self.ygyro = ygyro
+ self.zgyro = zgyro
+ self.xmag = xmag
+ self.ymag = ymag
+ self.zmag = zmag
+ self.abs_pressure = abs_pressure
+ self.diff_pressure = diff_pressure
+ self.pressure_alt = pressure_alt
+ self.temperature = temperature
+ self.fields_updated = fields_updated
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 93, struct.pack('<QfffffffffffffH', self.time_usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag, self.abs_pressure, self.diff_pressure, self.pressure_alt, self.temperature, self.fields_updated))
+
+class MAVLink_file_transfer_start_message(MAVLink_message):
+ '''
+ Begin file transfer
+ '''
+ def __init__(self, transfer_uid, dest_path, direction, file_size, flags):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_FILE_TRANSFER_START, 'FILE_TRANSFER_START')
+ self._fieldnames = ['transfer_uid', 'dest_path', 'direction', 'file_size', 'flags']
+ self.transfer_uid = transfer_uid
+ self.dest_path = dest_path
+ self.direction = direction
+ self.file_size = file_size
+ self.flags = flags
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 235, struct.pack('<QI240sBB', self.transfer_uid, self.file_size, self.dest_path, self.direction, self.flags))
+
+class MAVLink_file_transfer_dir_list_message(MAVLink_message):
+ '''
+ Get directory listing
+ '''
+ def __init__(self, transfer_uid, dir_path, flags):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, 'FILE_TRANSFER_DIR_LIST')
+ self._fieldnames = ['transfer_uid', 'dir_path', 'flags']
+ self.transfer_uid = transfer_uid
+ self.dir_path = dir_path
+ self.flags = flags
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 93, struct.pack('<Q240sB', self.transfer_uid, self.dir_path, self.flags))
+
+class MAVLink_file_transfer_res_message(MAVLink_message):
+ '''
+ File transfer result
+ '''
+ def __init__(self, transfer_uid, result):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_FILE_TRANSFER_RES, 'FILE_TRANSFER_RES')
+ self._fieldnames = ['transfer_uid', 'result']
+ self.transfer_uid = transfer_uid
+ self.result = result
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 124, struct.pack('<QB', self.transfer_uid, self.result))
+
+class MAVLink_battery_status_message(MAVLink_message):
+ '''
+ Transmitte battery informations for a accu pack.
+ '''
+ def __init__(self, accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_BATTERY_STATUS, 'BATTERY_STATUS')
+ self._fieldnames = ['accu_id', 'voltage_cell_1', 'voltage_cell_2', 'voltage_cell_3', 'voltage_cell_4', 'voltage_cell_5', 'voltage_cell_6', 'current_battery', 'battery_remaining']
+ self.accu_id = accu_id
+ self.voltage_cell_1 = voltage_cell_1
+ self.voltage_cell_2 = voltage_cell_2
+ self.voltage_cell_3 = voltage_cell_3
+ self.voltage_cell_4 = voltage_cell_4
+ self.voltage_cell_5 = voltage_cell_5
+ self.voltage_cell_6 = voltage_cell_6
+ self.current_battery = current_battery
+ self.battery_remaining = battery_remaining
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 42, struct.pack('<HHHHHHhBb', self.voltage_cell_1, self.voltage_cell_2, self.voltage_cell_3, self.voltage_cell_4, self.voltage_cell_5, self.voltage_cell_6, self.current_battery, self.accu_id, self.battery_remaining))
+
+class MAVLink_setpoint_8dof_message(MAVLink_message):
+ '''
+ Set the 8 DOF setpoint for a controller.
+ '''
+ def __init__(self, target_system, val1, val2, val3, val4, val5, val6, val7, val8):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SETPOINT_8DOF, 'SETPOINT_8DOF')
+ self._fieldnames = ['target_system', 'val1', 'val2', 'val3', 'val4', 'val5', 'val6', 'val7', 'val8']
+ self.target_system = target_system
+ self.val1 = val1
+ self.val2 = val2
+ self.val3 = val3
+ self.val4 = val4
+ self.val5 = val5
+ self.val6 = val6
+ self.val7 = val7
+ self.val8 = val8
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 241, struct.pack('<ffffffffB', self.val1, self.val2, self.val3, self.val4, self.val5, self.val6, self.val7, self.val8, self.target_system))
+
+class MAVLink_setpoint_6dof_message(MAVLink_message):
+ '''
+ Set the 6 DOF setpoint for a attitude and position controller.
+ '''
+ def __init__(self, target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_SETPOINT_6DOF, 'SETPOINT_6DOF')
+ self._fieldnames = ['target_system', 'trans_x', 'trans_y', 'trans_z', 'rot_x', 'rot_y', 'rot_z']
+ self.target_system = target_system
+ self.trans_x = trans_x
+ self.trans_y = trans_y
+ self.trans_z = trans_z
+ self.rot_x = rot_x
+ self.rot_y = rot_y
+ self.rot_z = rot_z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 15, struct.pack('<ffffffB', self.trans_x, self.trans_y, self.trans_z, self.rot_x, self.rot_y, self.rot_z, self.target_system))
+
+class MAVLink_memory_vect_message(MAVLink_message):
+ '''
+ Send raw controller memory. The use of this message is
+ discouraged for normal packets, but a quite efficient way for
+ testing new messages and getting experimental debug output.
+ '''
+ def __init__(self, address, ver, type, value):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMORY_VECT, 'MEMORY_VECT')
+ self._fieldnames = ['address', 'ver', 'type', 'value']
+ self.address = address
+ self.ver = ver
+ self.type = type
+ self.value = value
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 204, struct.pack('<HBB32s', self.address, self.ver, self.type, self.value))
+
+class MAVLink_debug_vect_message(MAVLink_message):
+ '''
+
+ '''
+ def __init__(self, name, time_usec, x, y, z):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG_VECT, 'DEBUG_VECT')
+ self._fieldnames = ['name', 'time_usec', 'x', 'y', 'z']
+ self.name = name
+ self.time_usec = time_usec
+ self.x = x
+ self.y = y
+ self.z = z
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 49, struct.pack('<Qfff10s', self.time_usec, self.x, self.y, self.z, self.name))
+
+class MAVLink_named_value_float_message(MAVLink_message):
+ '''
+ Send a key-value pair as float. The use of this message is
+ discouraged for normal packets, but a quite efficient way for
+ testing new messages and getting experimental debug output.
+ '''
+ def __init__(self, time_boot_ms, name, value):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 'NAMED_VALUE_FLOAT')
+ self._fieldnames = ['time_boot_ms', 'name', 'value']
+ self.time_boot_ms = time_boot_ms
+ self.name = name
+ self.value = value
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 170, struct.pack('<If10s', self.time_boot_ms, self.value, self.name))
+
+class MAVLink_named_value_int_message(MAVLink_message):
+ '''
+ Send a key-value pair as integer. The use of this message is
+ discouraged for normal packets, but a quite efficient way for
+ testing new messages and getting experimental debug output.
+ '''
+ def __init__(self, time_boot_ms, name, value):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_INT, 'NAMED_VALUE_INT')
+ self._fieldnames = ['time_boot_ms', 'name', 'value']
+ self.time_boot_ms = time_boot_ms
+ self.name = name
+ self.value = value
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 44, struct.pack('<Ii10s', self.time_boot_ms, self.value, self.name))
+
+class MAVLink_statustext_message(MAVLink_message):
+ '''
+ Status text message. These messages are printed in yellow in
+ the COMM console of QGroundControl. WARNING: They consume
+ quite some bandwidth, so use only for important status and
+ error messages. If implemented wisely, these messages are
+ buffered on the MCU and sent only at a limited rate (e.g. 10
+ Hz).
+ '''
+ def __init__(self, severity, text):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATUSTEXT, 'STATUSTEXT')
+ self._fieldnames = ['severity', 'text']
+ self.severity = severity
+ self.text = text
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 83, struct.pack('<B50s', self.severity, self.text))
+
+class MAVLink_debug_message(MAVLink_message):
+ '''
+ Send a debug value. The index is used to discriminate between
+ values. These values show up in the plot of QGroundControl as
+ DEBUG N.
+ '''
+ def __init__(self, time_boot_ms, ind, value):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG, 'DEBUG')
+ self._fieldnames = ['time_boot_ms', 'ind', 'value']
+ self.time_boot_ms = time_boot_ms
+ self.ind = ind
+ self.value = value
+
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, 46, struct.pack('<IfB', self.time_boot_ms, self.value, self.ind))
+
+
+mavlink_map = {
+ MAVLINK_MSG_ID_HEARTBEAT : ( '<IBBBBB', MAVLink_heartbeat_message, [1, 2, 3, 0, 4, 5], 50 ),
+ MAVLINK_MSG_ID_SYS_STATUS : ( '<IIIHHhHHHHHHb', MAVLink_sys_status_message, [0, 1, 2, 3, 4, 5, 12, 6, 7, 8, 9, 10, 11], 124 ),
+ MAVLINK_MSG_ID_SYSTEM_TIME : ( '<QI', MAVLink_system_time_message, [0, 1], 137 ),
+ MAVLINK_MSG_ID_PING : ( '<QIBB', MAVLink_ping_message, [0, 1, 2, 3], 237 ),
+ MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : ( '<BBB25s', MAVLink_change_operator_control_message, [0, 1, 2, 3], 217 ),
+ MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : ( '<BBB', MAVLink_change_operator_control_ack_message, [0, 1, 2], 104 ),
+ MAVLINK_MSG_ID_AUTH_KEY : ( '<32s', MAVLink_auth_key_message, [0], 119 ),
+ MAVLINK_MSG_ID_SET_MODE : ( '<IBB', MAVLink_set_mode_message, [1, 2, 0], 89 ),
+ MAVLINK_MSG_ID_PARAM_REQUEST_READ : ( '<hBB16s', MAVLink_param_request_read_message, [1, 2, 3, 0], 214 ),
+ MAVLINK_MSG_ID_PARAM_REQUEST_LIST : ( '<BB', MAVLink_param_request_list_message, [0, 1], 159 ),
+ MAVLINK_MSG_ID_PARAM_VALUE : ( '<fHH16sB', MAVLink_param_value_message, [3, 0, 4, 1, 2], 220 ),
+ MAVLINK_MSG_ID_PARAM_SET : ( '<fBB16sB', MAVLink_param_set_message, [1, 2, 3, 0, 4], 168 ),
+ MAVLINK_MSG_ID_GPS_RAW_INT : ( '<QiiiHHHHBB', MAVLink_gps_raw_int_message, [0, 8, 1, 2, 3, 4, 5, 6, 7, 9], 24 ),
+ MAVLINK_MSG_ID_GPS_STATUS : ( '<B20s20s20s20s20s', MAVLink_gps_status_message, [0, 1, 2, 3, 4, 5], 23 ),
+ MAVLINK_MSG_ID_SCALED_IMU : ( '<Ihhhhhhhhh', MAVLink_scaled_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 170 ),
+ MAVLINK_MSG_ID_RAW_IMU : ( '<Qhhhhhhhhh', MAVLink_raw_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 144 ),
+ MAVLINK_MSG_ID_RAW_PRESSURE : ( '<Qhhhh', MAVLink_raw_pressure_message, [0, 1, 2, 3, 4], 67 ),
+ MAVLINK_MSG_ID_SCALED_PRESSURE : ( '<Iffh', MAVLink_scaled_pressure_message, [0, 1, 2, 3], 115 ),
+ MAVLINK_MSG_ID_ATTITUDE : ( '<Iffffff', MAVLink_attitude_message, [0, 1, 2, 3, 4, 5, 6], 39 ),
+ MAVLINK_MSG_ID_ATTITUDE_QUATERNION : ( '<Ifffffff', MAVLink_attitude_quaternion_message, [0, 1, 2, 3, 4, 5, 6, 7], 246 ),
+ MAVLINK_MSG_ID_LOCAL_POSITION_NED : ( '<Iffffff', MAVLink_local_position_ned_message, [0, 1, 2, 3, 4, 5, 6], 185 ),
+ MAVLINK_MSG_ID_GLOBAL_POSITION_INT : ( '<IiiiihhhH', MAVLink_global_position_int_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 104 ),
+ MAVLINK_MSG_ID_RC_CHANNELS_SCALED : ( '<IhhhhhhhhBB', MAVLink_rc_channels_scaled_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8, 10], 237 ),
+ MAVLINK_MSG_ID_RC_CHANNELS_RAW : ( '<IHHHHHHHHBB', MAVLink_rc_channels_raw_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8, 10], 244 ),
+ MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : ( '<IHHHHHHHHB', MAVLink_servo_output_raw_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8], 242 ),
+ MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST : ( '<hhBB', MAVLink_mission_request_partial_list_message, [2, 3, 0, 1], 212 ),
+ MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST : ( '<hhBB', MAVLink_mission_write_partial_list_message, [2, 3, 0, 1], 9 ),
+ MAVLINK_MSG_ID_MISSION_ITEM : ( '<fffffffHHBBBBB', MAVLink_mission_item_message, [9, 10, 7, 11, 8, 12, 13, 0, 1, 2, 3, 4, 5, 6], 254 ),
+ MAVLINK_MSG_ID_MISSION_REQUEST : ( '<HBB', MAVLink_mission_request_message, [1, 2, 0], 230 ),
+ MAVLINK_MSG_ID_MISSION_SET_CURRENT : ( '<HBB', MAVLink_mission_set_current_message, [1, 2, 0], 28 ),
+ MAVLINK_MSG_ID_MISSION_CURRENT : ( '<H', MAVLink_mission_current_message, [0], 28 ),
+ MAVLINK_MSG_ID_MISSION_REQUEST_LIST : ( '<BB', MAVLink_mission_request_list_message, [0, 1], 132 ),
+ MAVLINK_MSG_ID_MISSION_COUNT : ( '<HBB', MAVLink_mission_count_message, [1, 2, 0], 221 ),
+ MAVLINK_MSG_ID_MISSION_CLEAR_ALL : ( '<BB', MAVLink_mission_clear_all_message, [0, 1], 232 ),
+ MAVLINK_MSG_ID_MISSION_ITEM_REACHED : ( '<H', MAVLink_mission_item_reached_message, [0], 11 ),
+ MAVLINK_MSG_ID_MISSION_ACK : ( '<BBB', MAVLink_mission_ack_message, [0, 1, 2], 153 ),
+ MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN : ( '<iiiB', MAVLink_set_gps_global_origin_message, [3, 0, 1, 2], 41 ),
+ MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN : ( '<iii', MAVLink_gps_global_origin_message, [0, 1, 2], 39 ),
+ MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT : ( '<ffffBBB', MAVLink_set_local_position_setpoint_message, [4, 5, 6, 0, 1, 2, 3], 214 ),
+ MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : ( '<ffffB', MAVLink_local_position_setpoint_message, [4, 0, 1, 2, 3], 223 ),
+ MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT : ( '<iiihB', MAVLink_global_position_setpoint_int_message, [4, 0, 1, 2, 3], 141 ),
+ MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT : ( '<iiihB', MAVLink_set_global_position_setpoint_int_message, [4, 0, 1, 2, 3], 33 ),
+ MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : ( '<ffffffBBB', MAVLink_safety_set_allowed_area_message, [6, 7, 8, 0, 1, 2, 3, 4, 5], 15 ),
+ MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : ( '<ffffffB', MAVLink_safety_allowed_area_message, [6, 0, 1, 2, 3, 4, 5], 3 ),
+ MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : ( '<ffffBB', MAVLink_set_roll_pitch_yaw_thrust_message, [4, 5, 0, 1, 2, 3], 100 ),
+ MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : ( '<ffffBB', MAVLink_set_roll_pitch_yaw_speed_thrust_message, [4, 5, 0, 1, 2, 3], 24 ),
+ MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : ( '<Iffff', MAVLink_roll_pitch_yaw_thrust_setpoint_message, [0, 1, 2, 3, 4], 239 ),
+ MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : ( '<Iffff', MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, [0, 1, 2, 3, 4], 238 ),
+ MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT : ( '<HHHHB', MAVLink_set_quad_motors_setpoint_message, [4, 0, 1, 2, 3], 30 ),
+ MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST : ( '<4h4h4h4HBB', MAVLink_set_quad_swarm_roll_pitch_yaw_thrust_message, [4, 5, 0, 1, 2, 3], 240 ),
+ MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : ( '<fffffhhH', MAVLink_nav_controller_output_message, [0, 1, 5, 6, 7, 2, 3, 4], 183 ),
+ MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST : ( '<4h4h4h4HBB4s4s4s', MAVLink_set_quad_swarm_led_roll_pitch_yaw_thrust_message, [4, 5, 6, 7, 8, 0, 1, 2, 3], 130 ),
+ MAVLINK_MSG_ID_STATE_CORRECTION : ( '<fffffffff', MAVLink_state_correction_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 130 ),
+ MAVLINK_MSG_ID_REQUEST_DATA_STREAM : ( '<HBBBB', MAVLink_request_data_stream_message, [1, 2, 3, 0, 4], 148 ),
+ MAVLINK_MSG_ID_DATA_STREAM : ( '<HBB', MAVLink_data_stream_message, [1, 0, 2], 21 ),
+ MAVLINK_MSG_ID_MANUAL_CONTROL : ( '<hhhhHB', MAVLink_manual_control_message, [5, 0, 1, 2, 3, 4], 243 ),
+ MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : ( '<HHHHHHHHBB', MAVLink_rc_channels_override_message, [8, 9, 0, 1, 2, 3, 4, 5, 6, 7], 124 ),
+ MAVLINK_MSG_ID_VFR_HUD : ( '<ffffhH', MAVLink_vfr_hud_message, [0, 1, 4, 5, 2, 3], 20 ),
+ MAVLINK_MSG_ID_COMMAND_LONG : ( '<fffffffHBBB', MAVLink_command_long_message, [8, 9, 7, 10, 0, 1, 2, 3, 4, 5, 6], 152 ),
+ MAVLINK_MSG_ID_COMMAND_ACK : ( '<HB', MAVLink_command_ack_message, [0, 1], 143 ),
+ MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT : ( '<Iffff', MAVLink_roll_pitch_yaw_rates_thrust_setpoint_message, [0, 1, 2, 3, 4], 127 ),
+ MAVLINK_MSG_ID_MANUAL_SETPOINT : ( '<IffffBB', MAVLink_manual_setpoint_message, [0, 1, 2, 3, 4, 5, 6], 106 ),
+ MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET : ( '<Iffffff', MAVLink_local_position_ned_system_global_offset_message, [0, 1, 2, 3, 4, 5, 6], 231 ),
+ MAVLINK_MSG_ID_HIL_STATE : ( '<Qffffffiiihhhhhh', MAVLink_hil_state_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15], 183 ),
+ MAVLINK_MSG_ID_HIL_CONTROLS : ( '<QffffffffBB', MAVLink_hil_controls_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 63 ),
+ MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW : ( '<QHHHHHHHHHHHHB', MAVLink_hil_rc_inputs_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13], 54 ),
+ MAVLINK_MSG_ID_OPTICAL_FLOW : ( '<QfffhhBB', MAVLink_optical_flow_message, [0, 6, 4, 5, 1, 2, 7, 3], 175 ),
+ MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_global_vision_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 102 ),
+ MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_vision_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 158 ),
+ MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE : ( '<Qfff', MAVLink_vision_speed_estimate_message, [0, 1, 2, 3], 208 ),
+ MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_vicon_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 56 ),
+ MAVLINK_MSG_ID_HIGHRES_IMU : ( '<QfffffffffffffH', MAVLink_highres_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14], 93 ),
+ MAVLINK_MSG_ID_FILE_TRANSFER_START : ( '<QI240sBB', MAVLink_file_transfer_start_message, [0, 2, 3, 1, 4], 235 ),
+ MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST : ( '<Q240sB', MAVLink_file_transfer_dir_list_message, [0, 1, 2], 93 ),
+ MAVLINK_MSG_ID_FILE_TRANSFER_RES : ( '<QB', MAVLink_file_transfer_res_message, [0, 1], 124 ),
+ MAVLINK_MSG_ID_BATTERY_STATUS : ( '<HHHHHHhBb', MAVLink_battery_status_message, [7, 0, 1, 2, 3, 4, 5, 6, 8], 42 ),
+ MAVLINK_MSG_ID_SETPOINT_8DOF : ( '<ffffffffB', MAVLink_setpoint_8dof_message, [8, 0, 1, 2, 3, 4, 5, 6, 7], 241 ),
+ MAVLINK_MSG_ID_SETPOINT_6DOF : ( '<ffffffB', MAVLink_setpoint_6dof_message, [6, 0, 1, 2, 3, 4, 5], 15 ),
+ MAVLINK_MSG_ID_MEMORY_VECT : ( '<HBB32s', MAVLink_memory_vect_message, [0, 1, 2, 3], 204 ),
+ MAVLINK_MSG_ID_DEBUG_VECT : ( '<Qfff10s', MAVLink_debug_vect_message, [4, 0, 1, 2, 3], 49 ),
+ MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : ( '<If10s', MAVLink_named_value_float_message, [0, 2, 1], 170 ),
+ MAVLINK_MSG_ID_NAMED_VALUE_INT : ( '<Ii10s', MAVLink_named_value_int_message, [0, 2, 1], 44 ),
+ MAVLINK_MSG_ID_STATUSTEXT : ( '<B50s', MAVLink_statustext_message, [0, 1], 83 ),
+ MAVLINK_MSG_ID_DEBUG : ( '<IfB', MAVLink_debug_message, [0, 2, 1], 46 ),
+}
+
+class MAVError(Exception):
+ '''MAVLink error class'''
+ def __init__(self, msg):
+ Exception.__init__(self, msg)
+ self.message = msg
+
+class MAVString(str):
+ '''NUL terminated string'''
+ def __init__(self, s):
+ str.__init__(self)
+ def __str__(self):
+ i = self.find(chr(0))
+ if i == -1:
+ return self[:]
+ return self[0:i]
+
+class MAVLink_bad_data(MAVLink_message):
+ '''
+ a piece of bad data in a mavlink stream
+ '''
+ def __init__(self, data, reason):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA')
+ self._fieldnames = ['data', 'reason']
+ self.data = data
+ self.reason = reason
+ self._msgbuf = data
+
+class MAVLink(object):
+ '''MAVLink protocol handling class'''
+ def __init__(self, file, srcSystem=0, srcComponent=0):
+ self.seq = 0
+ self.file = file
+ self.srcSystem = srcSystem
+ self.srcComponent = srcComponent
+ self.callback = None
+ self.callback_args = None
+ self.callback_kwargs = None
+ self.buf = array.array('B')
+ self.expected_length = 6
+ self.have_prefix_error = False
+ self.robust_parsing = False
+ self.protocol_marker = 254
+ self.little_endian = True
+ self.crc_extra = True
+ self.sort_fields = True
+ self.total_packets_sent = 0
+ self.total_bytes_sent = 0
+ self.total_packets_received = 0
+ self.total_bytes_received = 0
+ self.total_receive_errors = 0
+ self.startup_time = time.time()
+
+ def set_callback(self, callback, *args, **kwargs):
+ self.callback = callback
+ self.callback_args = args
+ self.callback_kwargs = kwargs
+
+ def send(self, mavmsg):
+ '''send a MAVLink message'''
+ buf = mavmsg.pack(self)
+ self.file.write(buf)
+ self.seq = (self.seq + 1) % 255
+ self.total_packets_sent += 1
+ self.total_bytes_sent += len(buf)
+
+ def bytes_needed(self):
+ '''return number of bytes needed for next parsing stage'''
+ ret = self.expected_length - len(self.buf)
+ if ret <= 0:
+ return 1
+ return ret
+
+ def parse_char(self, c):
+ '''input some data bytes, possibly returning a new message'''
+ if isinstance(c, str):
+ self.buf.fromstring(c)
+ else:
+ self.buf.extend(c)
+ self.total_bytes_received += len(c)
+ if len(self.buf) >= 1 and self.buf[0] != 254:
+ magic = self.buf[0]
+ self.buf = self.buf[1:]
+ if self.robust_parsing:
+ m = MAVLink_bad_data(chr(magic), "Bad prefix")
+ if self.callback:
+ self.callback(m, *self.callback_args, **self.callback_kwargs)
+ self.expected_length = 6
+ self.total_receive_errors += 1
+ return m
+ if self.have_prefix_error:
+ return None
+ self.have_prefix_error = True
+ self.total_receive_errors += 1
+ raise MAVError("invalid MAVLink prefix '%s'" % magic)
+ self.have_prefix_error = False
+ if len(self.buf) >= 2:
+ (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2])
+ self.expected_length += 8
+ if self.expected_length >= 8 and len(self.buf) >= self.expected_length:
+ mbuf = self.buf[0:self.expected_length]
+ self.buf = self.buf[self.expected_length:]
+ self.expected_length = 6
+ if self.robust_parsing:
+ try:
+ m = self.decode(mbuf)
+ self.total_packets_received += 1
+ except MAVError as reason:
+ m = MAVLink_bad_data(mbuf, reason.message)
+ self.total_receive_errors += 1
+ else:
+ m = self.decode(mbuf)
+ self.total_packets_received += 1
+ if self.callback:
+ self.callback(m, *self.callback_args, **self.callback_kwargs)
+ return m
+ return None
+
+ def parse_buffer(self, s):
+ '''input some data bytes, possibly returning a list of new messages'''
+ m = self.parse_char(s)
+ if m is None:
+ return None
+ ret = [m]
+ while True:
+ m = self.parse_char("")
+ if m is None:
+ return ret
+ ret.append(m)
+ return ret
+
+ def decode(self, msgbuf):
+ '''decode a buffer as a MAVLink message'''
+ # decode the header
+ try:
+ magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
+ if ord(magic) != 254:
+ raise MAVError("invalid MAVLink prefix '%s'" % magic)
+ if mlen != len(msgbuf)-8:
+ raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId))
+
+ if not msgId in mavlink_map:
+ raise MAVError('unknown MAVLink message ID %u' % msgId)
+
+ # decode the payload
+ (fmt, type, order_map, crc_extra) = mavlink_map[msgId]
+
+ # decode the checksum
+ try:
+ crc, = struct.unpack('<H', msgbuf[-2:])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg)
+ crc2 = mavutil.x25crc(msgbuf[1:-2])
+ if True: # using CRC extra
+ crc2.accumulate(chr(crc_extra))
+ if crc != crc2.crc:
+ raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc))
+
+ try:
+ t = struct.unpack(fmt, msgbuf[6:-2])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % (
+ type, fmt, len(msgbuf[6:-2]), emsg))
+
+ tlist = list(t)
+ # handle sorted fields
+ if True:
+ t = tlist[:]
+ for i in range(0, len(tlist)):
+ tlist[i] = t[order_map[i]]
+
+ # terminate any strings
+ for i in range(0, len(tlist)):
+ if isinstance(tlist[i], str):
+ tlist[i] = MAVString(tlist[i])
+ t = tuple(tlist)
+ # construct the message object
+ try:
+ m = type(*t)
+ except Exception as emsg:
+ raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg))
+ m._msgbuf = msgbuf
+ m._payload = msgbuf[6:-2]
+ m._crc = crc
+ m._header = MAVLink_header(msgId, mlen, seq, srcSystem, srcComponent)
+ return m
+ def heartbeat_encode(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3):
+ '''
+ The heartbeat message shows that a system is present and responding.
+ The type of the MAV and Autopilot hardware allow the
+ receiving system to treat further messages from this
+ system appropriate (e.g. by laying out the user
+ interface based on the autopilot).
+
+ type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
+ autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t)
+ base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t)
+ custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t)
+ system_status : System status flag, see MAV_STATE ENUM (uint8_t)
+ mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t)
+
+ '''
+ msg = MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)
+ msg.pack(self)
+ return msg
+
+ def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3):
+ '''
+ The heartbeat message shows that a system is present and responding.
+ The type of the MAV and Autopilot hardware allow the
+ receiving system to treat further messages from this
+ system appropriate (e.g. by laying out the user
+ interface based on the autopilot).
+
+ type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
+ autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t)
+ base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t)
+ custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t)
+ system_status : System status flag, see MAV_STATE ENUM (uint8_t)
+ mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t)
+
+ '''
+ return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version))
+
+ def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
+ '''
+ The general system state. If the system is following the MAVLink
+ standard, the system state is mainly defined by three
+ orthogonal states/modes: The system mode, which is
+ either LOCKED (motors shut down and locked), MANUAL
+ (system under RC control), GUIDED (system with
+ autonomous position control, position setpoint
+ controlled manually) or AUTO (system guided by
+ path/waypoint planner). The NAV_MODE defined the
+ current flight state: LIFTOFF (often an open-loop
+ maneuver), LANDING, WAYPOINTS or VECTOR. This
+ represents the internal navigation state machine. The
+ system status shows wether the system is currently
+ active or not and if an emergency occured. During the
+ CRITICAL and EMERGENCY states the MAV is still
+ considered to be active, but should start emergency
+ procedures autonomously. After a failure occured it
+ should first move from active to critical to allow
+ manual intervention and then move to emergency after a
+ certain timeout.
+
+ 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)
+ 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) (uint16_t)
+ current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
+ battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t)
+ drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
+ errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
+ errors_count1 : Autopilot-specific errors (uint16_t)
+ errors_count2 : Autopilot-specific errors (uint16_t)
+ errors_count3 : Autopilot-specific errors (uint16_t)
+ errors_count4 : Autopilot-specific errors (uint16_t)
+
+ '''
+ msg = MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)
+ msg.pack(self)
+ return msg
+
+ def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
+ '''
+ The general system state. If the system is following the MAVLink
+ standard, the system state is mainly defined by three
+ orthogonal states/modes: The system mode, which is
+ either LOCKED (motors shut down and locked), MANUAL
+ (system under RC control), GUIDED (system with
+ autonomous position control, position setpoint
+ controlled manually) or AUTO (system guided by
+ path/waypoint planner). The NAV_MODE defined the
+ current flight state: LIFTOFF (often an open-loop
+ maneuver), LANDING, WAYPOINTS or VECTOR. This
+ represents the internal navigation state machine. The
+ system status shows wether the system is currently
+ active or not and if an emergency occured. During the
+ CRITICAL and EMERGENCY states the MAV is still
+ considered to be active, but should start emergency
+ procedures autonomously. After a failure occured it
+ should first move from active to critical to allow
+ manual intervention and then move to emergency after a
+ certain timeout.
+
+ 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)
+ 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) (uint16_t)
+ current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
+ battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t)
+ drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
+ errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
+ errors_count1 : Autopilot-specific errors (uint16_t)
+ errors_count2 : Autopilot-specific errors (uint16_t)
+ errors_count3 : Autopilot-specific errors (uint16_t)
+ errors_count4 : Autopilot-specific errors (uint16_t)
+
+ '''
+ return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4))
+
+ def system_time_encode(self, time_unix_usec, time_boot_ms):
+ '''
+ The system time is the time of the master clock, typically the
+ computer clock of the main onboard computer.
+
+ time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
+ time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t)
+
+ '''
+ msg = MAVLink_system_time_message(time_unix_usec, time_boot_ms)
+ msg.pack(self)
+ return msg
+
+ def system_time_send(self, time_unix_usec, time_boot_ms):
+ '''
+ The system time is the time of the master clock, typically the
+ computer clock of the main onboard computer.
+
+ time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
+ time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t)
+
+ '''
+ return self.send(self.system_time_encode(time_unix_usec, time_boot_ms))
+
+ def ping_encode(self, time_usec, seq, target_system, target_component):
+ '''
+ A ping message either requesting or responding to a ping. This allows
+ to measure the system latencies, including serial
+ port, radio modem and UDP connections.
+
+ time_usec : Unix timestamp in microseconds (uint64_t)
+ seq : PING sequence (uint32_t)
+ target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
+ target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
+
+ '''
+ msg = MAVLink_ping_message(time_usec, seq, target_system, target_component)
+ msg.pack(self)
+ return msg
+
+ def ping_send(self, time_usec, seq, target_system, target_component):
+ '''
+ A ping message either requesting or responding to a ping. This allows
+ to measure the system latencies, including serial
+ port, radio modem and UDP connections.
+
+ time_usec : Unix timestamp in microseconds (uint64_t)
+ seq : PING sequence (uint32_t)
+ target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
+ target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
+
+ '''
+ return self.send(self.ping_encode(time_usec, seq, target_system, target_component))
+
+ def change_operator_control_encode(self, target_system, control_request, version, passkey):
+ '''
+ Request to control this MAV
+
+ target_system : System the GCS requests control for (uint8_t)
+ control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
+ version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
+ passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
+
+ '''
+ msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey)
+ msg.pack(self)
+ return msg
+
+ def change_operator_control_send(self, target_system, control_request, version, passkey):
+ '''
+ Request to control this MAV
+
+ target_system : System the GCS requests control for (uint8_t)
+ control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
+ version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
+ passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
+
+ '''
+ return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey))
+
+ def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack):
+ '''
+ Accept / deny control of this MAV
+
+ gcs_system_id : ID of the GCS this message (uint8_t)
+ control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
+ ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
+
+ '''
+ msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack)
+ msg.pack(self)
+ return msg
+
+ def change_operator_control_ack_send(self, gcs_system_id, control_request, ack):
+ '''
+ Accept / deny control of this MAV
+
+ gcs_system_id : ID of the GCS this message (uint8_t)
+ control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
+ ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
+
+ '''
+ return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack))
+
+ def auth_key_encode(self, key):
+ '''
+ Emit an encrypted signature / key identifying this system. PLEASE
+ NOTE: This protocol has been kept simple, so
+ transmitting the key requires an encrypted channel for
+ true safety.
+
+ key : key (char)
+
+ '''
+ msg = MAVLink_auth_key_message(key)
+ msg.pack(self)
+ return msg
+
+ def auth_key_send(self, key):
+ '''
+ Emit an encrypted signature / key identifying this system. PLEASE
+ NOTE: This protocol has been kept simple, so
+ transmitting the key requires an encrypted channel for
+ true safety.
+
+ key : key (char)
+
+ '''
+ return self.send(self.auth_key_encode(key))
+
+ def set_mode_encode(self, target_system, base_mode, custom_mode):
+ '''
+ Set the system mode, as defined by enum MAV_MODE. There is no target
+ component id as the mode is by definition for the
+ overall aircraft, not only for one component.
+
+ target_system : The system setting the mode (uint8_t)
+ base_mode : The new base mode (uint8_t)
+ custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t)
+
+ '''
+ msg = MAVLink_set_mode_message(target_system, base_mode, custom_mode)
+ msg.pack(self)
+ return msg
+
+ def set_mode_send(self, target_system, base_mode, custom_mode):
+ '''
+ Set the system mode, as defined by enum MAV_MODE. There is no target
+ component id as the mode is by definition for the
+ overall aircraft, not only for one component.
+
+ target_system : The system setting the mode (uint8_t)
+ base_mode : The new base mode (uint8_t)
+ custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t)
+
+ '''
+ return self.send(self.set_mode_encode(target_system, base_mode, custom_mode))
+
+ def param_request_read_encode(self, target_system, target_component, param_id, param_index):
+ '''
+ Request to read the onboard parameter with the param_id string id.
+ Onboard parameters are stored as key[const char*] ->
+ value[float]. This allows to send a parameter to any
+ other component (such as the GCS) without the need of
+ previous knowledge of possible parameter names. Thus
+ the same GCS can store different parameters for
+ different autopilots. See also
+ http://qgroundcontrol.org/parameter_interface for a
+ full documentation of QGroundControl and IMU code.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t)
+
+ '''
+ msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index)
+ msg.pack(self)
+ return msg
+
+ def param_request_read_send(self, target_system, target_component, param_id, param_index):
+ '''
+ Request to read the onboard parameter with the param_id string id.
+ Onboard parameters are stored as key[const char*] ->
+ value[float]. This allows to send a parameter to any
+ other component (such as the GCS) without the need of
+ previous knowledge of possible parameter names. Thus
+ the same GCS can store different parameters for
+ different autopilots. See also
+ http://qgroundcontrol.org/parameter_interface for a
+ full documentation of QGroundControl and IMU code.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t)
+
+ '''
+ return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index))
+
+ def param_request_list_encode(self, target_system, target_component):
+ '''
+ Request all parameters of this component. After his request, all
+ parameters are emitted.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ msg = MAVLink_param_request_list_message(target_system, target_component)
+ msg.pack(self)
+ return msg
+
+ def param_request_list_send(self, target_system, target_component):
+ '''
+ Request all parameters of this component. After his request, all
+ parameters are emitted.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ return self.send(self.param_request_list_encode(target_system, target_component))
+
+ def param_value_encode(self, param_id, param_value, param_type, param_count, param_index):
+ '''
+ Emit the value of a onboard parameter. The inclusion of param_count
+ and param_index in the message allows the recipient to
+ keep track of received parameters and allows him to
+ re-request missing parameters after a loss or timeout.
+
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_value : Onboard parameter value (float)
+ param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t)
+ param_count : Total number of onboard parameters (uint16_t)
+ param_index : Index of this onboard parameter (uint16_t)
+
+ '''
+ msg = MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index)
+ msg.pack(self)
+ return msg
+
+ def param_value_send(self, param_id, param_value, param_type, param_count, param_index):
+ '''
+ Emit the value of a onboard parameter. The inclusion of param_count
+ and param_index in the message allows the recipient to
+ keep track of received parameters and allows him to
+ re-request missing parameters after a loss or timeout.
+
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_value : Onboard parameter value (float)
+ param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t)
+ param_count : Total number of onboard parameters (uint16_t)
+ param_index : Index of this onboard parameter (uint16_t)
+
+ '''
+ return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index))
+
+ def param_set_encode(self, target_system, target_component, param_id, param_value, param_type):
+ '''
+ Set a parameter value TEMPORARILY to RAM. It will be reset to default
+ on system reboot. Send the ACTION
+ MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM
+ contents to EEPROM. IMPORTANT: The receiving component
+ should acknowledge the new parameter value by sending
+ a param_value message to all communication partners.
+ This will also ensure that multiple GCS all have an
+ up-to-date list of all parameters. If the sending GCS
+ did not receive a PARAM_VALUE message within its
+ timeout time, it should re-send the PARAM_SET message.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_value : Onboard parameter value (float)
+ param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t)
+
+ '''
+ msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type)
+ msg.pack(self)
+ return msg
+
+ def param_set_send(self, target_system, target_component, param_id, param_value, param_type):
+ '''
+ Set a parameter value TEMPORARILY to RAM. It will be reset to default
+ on system reboot. Send the ACTION
+ MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM
+ contents to EEPROM. IMPORTANT: The receiving component
+ should acknowledge the new parameter value by sending
+ a param_value message to all communication partners.
+ This will also ensure that multiple GCS all have an
+ up-to-date list of all parameters. If the sending GCS
+ did not receive a PARAM_VALUE message within its
+ timeout time, it should re-send the PARAM_SET message.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char)
+ param_value : Onboard parameter value (float)
+ param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t)
+
+ '''
+ return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type))
+
+ def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
+ '''
+ The global position, as returned by the Global Positioning System
+ (GPS). This is NOT the global position
+ estimate of the sytem, but rather a RAW sensor value.
+ See message GLOBAL_POSITION for the global position
+ estimate. Coordinate frame is right-handed, Z-axis up
+ (GPS frame).
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_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. (uint8_t)
+ lat : Latitude in 1E7 degrees (int32_t)
+ lon : Longitude in 1E7 degrees (int32_t)
+ alt : Altitude in 1E3 meters (millimeters) above MSL (int32_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)
+ vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t)
+ cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
+ satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t)
+
+ '''
+ msg = MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)
+ msg.pack(self)
+ return msg
+
+ def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
+ '''
+ The global position, as returned by the Global Positioning System
+ (GPS). This is NOT the global position
+ estimate of the sytem, but rather a RAW sensor value.
+ See message GLOBAL_POSITION for the global position
+ estimate. Coordinate frame is right-handed, Z-axis up
+ (GPS frame).
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_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. (uint8_t)
+ lat : Latitude in 1E7 degrees (int32_t)
+ lon : Longitude in 1E7 degrees (int32_t)
+ alt : Altitude in 1E3 meters (millimeters) above MSL (int32_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)
+ vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t)
+ cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
+ satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t)
+
+ '''
+ return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible))
+
+ def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
+ '''
+ The positioning status, as reported by GPS. This message is intended
+ to display status information about each satellite
+ visible to the receiver. See message GLOBAL_POSITION
+ for the global position estimate. This message can
+ contain information for up to 20 satellites.
+
+ satellites_visible : Number of satellites visible (uint8_t)
+ satellite_prn : Global satellite ID (uint8_t)
+ satellite_used : 0: Satellite not used, 1: used for localization (uint8_t)
+ satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
+ satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
+ satellite_snr : Signal to noise ratio of satellite (uint8_t)
+
+ '''
+ msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)
+ msg.pack(self)
+ return msg
+
+ def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
+ '''
+ The positioning status, as reported by GPS. This message is intended
+ to display status information about each satellite
+ visible to the receiver. See message GLOBAL_POSITION
+ for the global position estimate. This message can
+ contain information for up to 20 satellites.
+
+ satellites_visible : Number of satellites visible (uint8_t)
+ satellite_prn : Global satellite ID (uint8_t)
+ satellite_used : 0: Satellite not used, 1: used for localization (uint8_t)
+ satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
+ satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
+ satellite_snr : Signal to noise ratio of satellite (uint8_t)
+
+ '''
+ return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr))
+
+ def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This message
+ should contain the scaled values to the described
+ units
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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) (int16_t)
+
+ '''
+ msg = MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
+ msg.pack(self)
+ return msg
+
+ def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This message
+ should contain the scaled values to the described
+ units
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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) (int16_t)
+
+ '''
+ return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
+
+ def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This message
+ should always contain the true raw values without any
+ scaling to allow data capture and system debugging.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ xacc : X acceleration (raw) (int16_t)
+ yacc : Y acceleration (raw) (int16_t)
+ zacc : Z acceleration (raw) (int16_t)
+ xgyro : Angular speed around X axis (raw) (int16_t)
+ ygyro : Angular speed around Y axis (raw) (int16_t)
+ zgyro : Angular speed around Z axis (raw) (int16_t)
+ xmag : X Magnetic field (raw) (int16_t)
+ ymag : Y Magnetic field (raw) (int16_t)
+ zmag : Z Magnetic field (raw) (int16_t)
+
+ '''
+ msg = MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
+ msg.pack(self)
+ return msg
+
+ def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
+ '''
+ The RAW IMU readings for the usual 9DOF sensor setup. This message
+ should always contain the true raw values without any
+ scaling to allow data capture and system debugging.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ xacc : X acceleration (raw) (int16_t)
+ yacc : Y acceleration (raw) (int16_t)
+ zacc : Z acceleration (raw) (int16_t)
+ xgyro : Angular speed around X axis (raw) (int16_t)
+ ygyro : Angular speed around Y axis (raw) (int16_t)
+ zgyro : Angular speed around Z axis (raw) (int16_t)
+ xmag : X Magnetic field (raw) (int16_t)
+ ymag : Y Magnetic field (raw) (int16_t)
+ zmag : Z Magnetic field (raw) (int16_t)
+
+ '''
+ return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
+
+ def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature):
+ '''
+ The RAW pressure readings for the typical setup of one absolute
+ pressure and one differential pressure sensor. The
+ sensor values should be the raw, UNSCALED ADC values.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ press_abs : Absolute pressure (raw) (int16_t)
+ press_diff1 : Differential pressure 1 (raw) (int16_t)
+ press_diff2 : Differential pressure 2 (raw) (int16_t)
+ temperature : Raw Temperature measurement (raw) (int16_t)
+
+ '''
+ msg = MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature)
+ msg.pack(self)
+ return msg
+
+ def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature):
+ '''
+ The RAW pressure readings for the typical setup of one absolute
+ pressure and one differential pressure sensor. The
+ sensor values should be the raw, UNSCALED ADC values.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ press_abs : Absolute pressure (raw) (int16_t)
+ press_diff1 : Differential pressure 1 (raw) (int16_t)
+ press_diff2 : Differential pressure 2 (raw) (int16_t)
+ temperature : Raw Temperature measurement (raw) (int16_t)
+
+ '''
+ return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature))
+
+ def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature):
+ '''
+ The pressure readings for the typical setup of one absolute and
+ differential pressure sensor. The units are as
+ specified in each field.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ press_abs : Absolute pressure (hectopascal) (float)
+ press_diff : Differential pressure 1 (hectopascal) (float)
+ temperature : Temperature measurement (0.01 degrees celsius) (int16_t)
+
+ '''
+ msg = MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature)
+ msg.pack(self)
+ return msg
+
+ def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature):
+ '''
+ The pressure readings for the typical setup of one absolute and
+ differential pressure sensor. The units are as
+ specified in each field.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ press_abs : Absolute pressure (hectopascal) (float)
+ press_diff : Differential pressure 1 (hectopascal) (float)
+ temperature : Temperature measurement (0.01 degrees celsius) (int16_t)
+
+ '''
+ return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature))
+
+ def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down, X-front,
+ Y-right).
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ roll : Roll angle (rad, -pi..+pi) (float)
+ pitch : Pitch angle (rad, -pi..+pi) (float)
+ yaw : Yaw angle (rad, -pi..+pi) (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+
+ '''
+ msg = MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)
+ msg.pack(self)
+ return msg
+
+ def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down, X-front,
+ Y-right).
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ roll : Roll angle (rad, -pi..+pi) (float)
+ pitch : Pitch angle (rad, -pi..+pi) (float)
+ yaw : Yaw angle (rad, -pi..+pi) (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+
+ '''
+ return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed))
+
+ def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down, X-front,
+ Y-right), expressed as quaternion.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ q1 : Quaternion component 1 (float)
+ q2 : Quaternion component 2 (float)
+ q3 : Quaternion component 3 (float)
+ q4 : Quaternion component 4 (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+
+ '''
+ msg = MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)
+ msg.pack(self)
+ return msg
+
+ def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
+ '''
+ The attitude in the aeronautical frame (right-handed, Z-down, X-front,
+ Y-right), expressed as quaternion.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ q1 : Quaternion component 1 (float)
+ q2 : Quaternion component 2 (float)
+ q3 : Quaternion component 3 (float)
+ q4 : Quaternion component 4 (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+
+ '''
+ return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed))
+
+ def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz):
+ '''
+ The filtered local position (e.g. fused computer vision and
+ accelerometers). Coordinate frame is right-handed,
+ Z-axis down (aeronautical frame, NED / north-east-down
+ convention)
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ x : X Position (float)
+ y : Y Position (float)
+ z : Z Position (float)
+ vx : X Speed (float)
+ vy : Y Speed (float)
+ vz : Z Speed (float)
+
+ '''
+ msg = MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz)
+ msg.pack(self)
+ return msg
+
+ def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz):
+ '''
+ The filtered local position (e.g. fused computer vision and
+ accelerometers). Coordinate frame is right-handed,
+ Z-axis down (aeronautical frame, NED / north-east-down
+ convention)
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ x : X Position (float)
+ y : Y Position (float)
+ z : Z Position (float)
+ vx : X Speed (float)
+ vy : Y Speed (float)
+ vz : Z Speed (float)
+
+ '''
+ return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz))
+
+ def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
+ '''
+ The filtered global position (e.g. fused GPS and accelerometers). The
+ position is in GPS-frame (right-handed, Z-up). It
+ is designed as scaled integer message since the
+ resolution of float is not sufficient.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ lat : Latitude, expressed as * 1E7 (int32_t)
+ lon : Longitude, expressed as * 1E7 (int32_t)
+ alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t)
+ relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t)
+ vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
+ vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
+ vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
+ hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
+
+ '''
+ msg = MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)
+ msg.pack(self)
+ return msg
+
+ def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
+ '''
+ The filtered global position (e.g. fused GPS and accelerometers). The
+ position is in GPS-frame (right-handed, Z-up). It
+ is designed as scaled integer message since the
+ resolution of float is not sufficient.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ lat : Latitude, expressed as * 1E7 (int32_t)
+ lon : Longitude, expressed as * 1E7 (int32_t)
+ alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t)
+ relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t)
+ vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
+ vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
+ vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
+ hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
+
+ '''
+ return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg))
+
+ def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
+ '''
+ The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
+ (100%) 10000. Channels that are inactive should be set
+ to 65535.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t)
+ chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t)
+
+ '''
+ msg = MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)
+ msg.pack(self)
+ return msg
+
+ def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
+ '''
+ The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
+ (100%) 10000. Channels that are inactive should be set
+ to 65535.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t)
+ chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. (int16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t)
+
+ '''
+ return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi))
+
+ def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
+ '''
+ The RAW values of the RC channels received. The standard PPM
+ modulation is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%. Individual receivers/transmitters
+ might violate this specification.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t)
+ chan1_raw : RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t)
+
+ '''
+ msg = MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)
+ msg.pack(self)
+ return msg
+
+ def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
+ '''
+ The RAW values of the RC channels received. The standard PPM
+ modulation is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%. Individual receivers/transmitters
+ might violate this specification.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t)
+ chan1_raw : RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused. (uint16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t)
+
+ '''
+ return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi))
+
+ def servo_output_raw_encode(self, time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
+ '''
+ The RAW values of the servo outputs (for RC input from the remote, use
+ the RC_CHANNELS messages). The standard PPM modulation
+ is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%.
+
+ time_boot_ms : Timestamp (microseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
+ servo1_raw : Servo output 1 value, in microseconds (uint16_t)
+ servo2_raw : Servo output 2 value, in microseconds (uint16_t)
+ servo3_raw : Servo output 3 value, in microseconds (uint16_t)
+ servo4_raw : Servo output 4 value, in microseconds (uint16_t)
+ servo5_raw : Servo output 5 value, in microseconds (uint16_t)
+ servo6_raw : Servo output 6 value, in microseconds (uint16_t)
+ servo7_raw : Servo output 7 value, in microseconds (uint16_t)
+ servo8_raw : Servo output 8 value, in microseconds (uint16_t)
+
+ '''
+ msg = MAVLink_servo_output_raw_message(time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)
+ msg.pack(self)
+ return msg
+
+ def servo_output_raw_send(self, time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
+ '''
+ The RAW values of the servo outputs (for RC input from the remote, use
+ the RC_CHANNELS messages). The standard PPM modulation
+ is as follows: 1000 microseconds: 0%, 2000
+ microseconds: 100%.
+
+ time_boot_ms : Timestamp (microseconds since system boot) (uint32_t)
+ port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
+ servo1_raw : Servo output 1 value, in microseconds (uint16_t)
+ servo2_raw : Servo output 2 value, in microseconds (uint16_t)
+ servo3_raw : Servo output 3 value, in microseconds (uint16_t)
+ servo4_raw : Servo output 4 value, in microseconds (uint16_t)
+ servo5_raw : Servo output 5 value, in microseconds (uint16_t)
+ servo6_raw : Servo output 6 value, in microseconds (uint16_t)
+ servo7_raw : Servo output 7 value, in microseconds (uint16_t)
+ servo8_raw : Servo output 8 value, in microseconds (uint16_t)
+
+ '''
+ return self.send(self.servo_output_raw_encode(time_boot_ms, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw))
+
+ def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index):
+ '''
+ Request a partial list of mission items from the system/component.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol.
+ If start and end index are the same, just send one
+ waypoint.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ start_index : Start index, 0 by default (int16_t)
+ end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t)
+
+ '''
+ msg = MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index)
+ msg.pack(self)
+ return msg
+
+ def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index):
+ '''
+ Request a partial list of mission items from the system/component.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol.
+ If start and end index are the same, just send one
+ waypoint.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ start_index : Start index, 0 by default (int16_t)
+ end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t)
+
+ '''
+ return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index))
+
+ def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index):
+ '''
+ This message is sent to the MAV to write a partial list. If start
+ index == end index, only one item will be transmitted
+ / updated. If the start index is NOT 0 and above the
+ current list size, this request should be REJECTED!
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t)
+ end_index : End index, equal or greater than start index. (int16_t)
+
+ '''
+ msg = MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index)
+ msg.pack(self)
+ return msg
+
+ def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index):
+ '''
+ This message is sent to the MAV to write a partial list. If start
+ index == end index, only one item will be transmitted
+ / updated. If the start index is NOT 0 and above the
+ current list size, this request should be REJECTED!
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t)
+ end_index : End index, equal or greater than start index. (int16_t)
+
+ '''
+ return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index))
+
+ def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
+ '''
+ Message encoding a mission item. This message is emitted to announce
+ the presence of a mission item and to set a mission
+ item on the system. The mission item can be either in
+ x, y, z meters (type: LOCAL) or x:lat, y:lon,
+ z:altitude. Local frame is Z-down, right handed (NED),
+ global frame is Z-up, right handed (ENU). See also
+ http://qgroundcontrol.org/mavlink/waypoint_protocol.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+ frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t)
+ command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t)
+ current : false:0, true:1 (uint8_t)
+ autocontinue : autocontinue to next wp (uint8_t)
+ 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)
+ x : PARAM5 / local: x position, global: latitude (float)
+ y : PARAM6 / y position: global: longitude (float)
+ z : PARAM7 / z position: global: altitude (float)
+
+ '''
+ msg = MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)
+ msg.pack(self)
+ return msg
+
+ def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
+ '''
+ Message encoding a mission item. This message is emitted to announce
+ the presence of a mission item and to set a mission
+ item on the system. The mission item can be either in
+ x, y, z meters (type: LOCAL) or x:lat, y:lon,
+ z:altitude. Local frame is Z-down, right handed (NED),
+ global frame is Z-up, right handed (ENU). See also
+ http://qgroundcontrol.org/mavlink/waypoint_protocol.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+ frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t)
+ command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t)
+ current : false:0, true:1 (uint8_t)
+ autocontinue : autocontinue to next wp (uint8_t)
+ 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)
+ x : PARAM5 / local: x position, global: latitude (float)
+ y : PARAM6 / y position: global: longitude (float)
+ z : PARAM7 / z position: global: altitude (float)
+
+ '''
+ return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z))
+
+ def mission_request_encode(self, target_system, target_component, seq):
+ '''
+ Request the information of the mission item with the sequence number
+ seq. The response of the system to this message should
+ be a MISSION_ITEM message.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+
+ '''
+ msg = MAVLink_mission_request_message(target_system, target_component, seq)
+ msg.pack(self)
+ return msg
+
+ def mission_request_send(self, target_system, target_component, seq):
+ '''
+ Request the information of the mission item with the sequence number
+ seq. The response of the system to this message should
+ be a MISSION_ITEM message.
+ http://qgroundcontrol.org/mavlink/waypoint_protocol
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+
+ '''
+ return self.send(self.mission_request_encode(target_system, target_component, seq))
+
+ def mission_set_current_encode(self, target_system, target_component, seq):
+ '''
+ Set the mission item with sequence number seq as current item. This
+ means that the MAV will continue to this mission item
+ on the shortest path (not following the mission items
+ in-between).
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+
+ '''
+ msg = MAVLink_mission_set_current_message(target_system, target_component, seq)
+ msg.pack(self)
+ return msg
+
+ def mission_set_current_send(self, target_system, target_component, seq):
+ '''
+ Set the mission item with sequence number seq as current item. This
+ means that the MAV will continue to this mission item
+ on the shortest path (not following the mission items
+ in-between).
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ seq : Sequence (uint16_t)
+
+ '''
+ return self.send(self.mission_set_current_encode(target_system, target_component, seq))
+
+ def mission_current_encode(self, seq):
+ '''
+ Message that announces the sequence number of the current active
+ mission item. The MAV will fly towards this mission
+ item.
+
+ seq : Sequence (uint16_t)
+
+ '''
+ msg = MAVLink_mission_current_message(seq)
+ msg.pack(self)
+ return msg
+
+ def mission_current_send(self, seq):
+ '''
+ Message that announces the sequence number of the current active
+ mission item. The MAV will fly towards this mission
+ item.
+
+ seq : Sequence (uint16_t)
+
+ '''
+ return self.send(self.mission_current_encode(seq))
+
+ def mission_request_list_encode(self, target_system, target_component):
+ '''
+ Request the overall list of mission items from the system/component.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ msg = MAVLink_mission_request_list_message(target_system, target_component)
+ msg.pack(self)
+ return msg
+
+ def mission_request_list_send(self, target_system, target_component):
+ '''
+ Request the overall list of mission items from the system/component.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ return self.send(self.mission_request_list_encode(target_system, target_component))
+
+ def mission_count_encode(self, target_system, target_component, count):
+ '''
+ This message is emitted as response to MISSION_REQUEST_LIST by the MAV
+ and to initiate a write transaction. The GCS can then
+ request the individual mission item based on the
+ knowledge of the total number of MISSIONs.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ count : Number of mission items in the sequence (uint16_t)
+
+ '''
+ msg = MAVLink_mission_count_message(target_system, target_component, count)
+ msg.pack(self)
+ return msg
+
+ def mission_count_send(self, target_system, target_component, count):
+ '''
+ This message is emitted as response to MISSION_REQUEST_LIST by the MAV
+ and to initiate a write transaction. The GCS can then
+ request the individual mission item based on the
+ knowledge of the total number of MISSIONs.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ count : Number of mission items in the sequence (uint16_t)
+
+ '''
+ return self.send(self.mission_count_encode(target_system, target_component, count))
+
+ def mission_clear_all_encode(self, target_system, target_component):
+ '''
+ Delete all mission items at once.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ msg = MAVLink_mission_clear_all_message(target_system, target_component)
+ msg.pack(self)
+ return msg
+
+ def mission_clear_all_send(self, target_system, target_component):
+ '''
+ Delete all mission items at once.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+
+ '''
+ return self.send(self.mission_clear_all_encode(target_system, target_component))
+
+ def mission_item_reached_encode(self, seq):
+ '''
+ A certain mission item has been reached. The system will either hold
+ this position (or circle on the orbit) or (if the
+ autocontinue on the WP was set) continue to the next
+ MISSION.
+
+ seq : Sequence (uint16_t)
+
+ '''
+ msg = MAVLink_mission_item_reached_message(seq)
+ msg.pack(self)
+ return msg
+
+ def mission_item_reached_send(self, seq):
+ '''
+ A certain mission item has been reached. The system will either hold
+ this position (or circle on the orbit) or (if the
+ autocontinue on the WP was set) continue to the next
+ MISSION.
+
+ seq : Sequence (uint16_t)
+
+ '''
+ return self.send(self.mission_item_reached_encode(seq))
+
+ def mission_ack_encode(self, target_system, target_component, type):
+ '''
+ Ack message during MISSION handling. The type field states if this
+ message is a positive ack (type=0) or if an error
+ happened (type=non-zero).
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ type : See MAV_MISSION_RESULT enum (uint8_t)
+
+ '''
+ msg = MAVLink_mission_ack_message(target_system, target_component, type)
+ msg.pack(self)
+ return msg
+
+ def mission_ack_send(self, target_system, target_component, type):
+ '''
+ Ack message during MISSION handling. The type field states if this
+ message is a positive ack (type=0) or if an error
+ happened (type=non-zero).
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ type : See MAV_MISSION_RESULT enum (uint8_t)
+
+ '''
+ return self.send(self.mission_ack_encode(target_system, target_component, type))
+
+ def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude):
+ '''
+ As local waypoints exist, the global MISSION reference allows to
+ transform between the local coordinate frame and the
+ global (GPS) coordinate frame. This can be necessary
+ when e.g. in- and outdoor settings are connected and
+ the MAV should move from in- to outdoor.
+
+ target_system : System ID (uint8_t)
+ latitude : global position * 1E7 (int32_t)
+ longitude : global position * 1E7 (int32_t)
+ altitude : global position * 1000 (int32_t)
+
+ '''
+ msg = MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude)
+ msg.pack(self)
+ return msg
+
+ def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude):
+ '''
+ As local waypoints exist, the global MISSION reference allows to
+ transform between the local coordinate frame and the
+ global (GPS) coordinate frame. This can be necessary
+ when e.g. in- and outdoor settings are connected and
+ the MAV should move from in- to outdoor.
+
+ target_system : System ID (uint8_t)
+ latitude : global position * 1E7 (int32_t)
+ longitude : global position * 1E7 (int32_t)
+ altitude : global position * 1000 (int32_t)
+
+ '''
+ return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude))
+
+ def gps_global_origin_encode(self, latitude, longitude, altitude):
+ '''
+ Once the MAV sets a new GPS-Local correspondence, this message
+ announces the origin (0,0,0) position
+
+ latitude : Latitude (WGS84), expressed as * 1E7 (int32_t)
+ longitude : Longitude (WGS84), expressed as * 1E7 (int32_t)
+ altitude : Altitude(WGS84), expressed as * 1000 (int32_t)
+
+ '''
+ msg = MAVLink_gps_global_origin_message(latitude, longitude, altitude)
+ msg.pack(self)
+ return msg
+
+ def gps_global_origin_send(self, latitude, longitude, altitude):
+ '''
+ Once the MAV sets a new GPS-Local correspondence, this message
+ announces the origin (0,0,0) position
+
+ latitude : Latitude (WGS84), expressed as * 1E7 (int32_t)
+ longitude : Longitude (WGS84), expressed as * 1E7 (int32_t)
+ altitude : Altitude(WGS84), expressed as * 1000 (int32_t)
+
+ '''
+ return self.send(self.gps_global_origin_encode(latitude, longitude, altitude))
+
+ def set_local_position_setpoint_encode(self, target_system, target_component, coordinate_frame, x, y, z, yaw):
+ '''
+ Set the setpoint for a local position controller. This is the position
+ in local coordinates the MAV should fly to. This
+ message is sent by the path/MISSION planner to the
+ onboard position controller. As some MAVs have a
+ degree of freedom in yaw (e.g. all
+ helicopters/quadrotors), the desired yaw angle is part
+ of the message.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
+ x : x position (float)
+ y : y position (float)
+ z : z position (float)
+ yaw : Desired yaw angle (float)
+
+ '''
+ msg = MAVLink_set_local_position_setpoint_message(target_system, target_component, coordinate_frame, x, y, z, yaw)
+ msg.pack(self)
+ return msg
+
+ def set_local_position_setpoint_send(self, target_system, target_component, coordinate_frame, x, y, z, yaw):
+ '''
+ Set the setpoint for a local position controller. This is the position
+ in local coordinates the MAV should fly to. This
+ message is sent by the path/MISSION planner to the
+ onboard position controller. As some MAVs have a
+ degree of freedom in yaw (e.g. all
+ helicopters/quadrotors), the desired yaw angle is part
+ of the message.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
+ x : x position (float)
+ y : y position (float)
+ z : z position (float)
+ yaw : Desired yaw angle (float)
+
+ '''
+ return self.send(self.set_local_position_setpoint_encode(target_system, target_component, coordinate_frame, x, y, z, yaw))
+
+ def local_position_setpoint_encode(self, coordinate_frame, x, y, z, yaw):
+ '''
+ Transmit the current local setpoint of the controller to other MAVs
+ (collision avoidance) and to the GCS.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
+ x : x position (float)
+ y : y position (float)
+ z : z position (float)
+ yaw : Desired yaw angle (float)
+
+ '''
+ msg = MAVLink_local_position_setpoint_message(coordinate_frame, x, y, z, yaw)
+ msg.pack(self)
+ return msg
+
+ def local_position_setpoint_send(self, coordinate_frame, x, y, z, yaw):
+ '''
+ Transmit the current local setpoint of the controller to other MAVs
+ (collision avoidance) and to the GCS.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
+ x : x position (float)
+ y : y position (float)
+ z : z position (float)
+ yaw : Desired yaw angle (float)
+
+ '''
+ return self.send(self.local_position_setpoint_encode(coordinate_frame, x, y, z, yaw))
+
+ def global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ '''
+ Transmit the current local setpoint of the controller to other MAVs
+ (collision avoidance) and to the GCS.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
+ latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
+ longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
+ altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
+ yaw : Desired yaw angle in degrees * 100 (int16_t)
+
+ '''
+ msg = MAVLink_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw)
+ msg.pack(self)
+ return msg
+
+ def global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ '''
+ Transmit the current local setpoint of the controller to other MAVs
+ (collision avoidance) and to the GCS.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
+ latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
+ longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
+ altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
+ yaw : Desired yaw angle in degrees * 100 (int16_t)
+
+ '''
+ return self.send(self.global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw))
+
+ def set_global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ '''
+ Set the current global position setpoint.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
+ latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
+ longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
+ altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
+ yaw : Desired yaw angle in degrees * 100 (int16_t)
+
+ '''
+ msg = MAVLink_set_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw)
+ msg.pack(self)
+ return msg
+
+ def set_global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw):
+ '''
+ Set the current global position setpoint.
+
+ coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
+ latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
+ longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
+ altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
+ yaw : Desired yaw angle in degrees * 100 (int16_t)
+
+ '''
+ return self.send(self.set_global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw))
+
+ def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ '''
+ Set a safety zone (volume), which is defined by two corners of a cube.
+ This message can be used to tell the MAV which
+ setpoints/MISSIONs to accept and which to reject.
+ Safety areas are often enforced by national or
+ competition regulations.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
+ p1x : x position 1 / Latitude 1 (float)
+ p1y : y position 1 / Longitude 1 (float)
+ p1z : z position 1 / Altitude 1 (float)
+ p2x : x position 2 / Latitude 2 (float)
+ p2y : y position 2 / Longitude 2 (float)
+ p2z : z position 2 / Altitude 2 (float)
+
+ '''
+ msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)
+ msg.pack(self)
+ return msg
+
+ def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ '''
+ Set a safety zone (volume), which is defined by two corners of a cube.
+ This message can be used to tell the MAV which
+ setpoints/MISSIONs to accept and which to reject.
+ Safety areas are often enforced by national or
+ competition regulations.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
+ p1x : x position 1 / Latitude 1 (float)
+ p1y : y position 1 / Longitude 1 (float)
+ p1z : z position 1 / Altitude 1 (float)
+ p2x : x position 2 / Latitude 2 (float)
+ p2y : y position 2 / Longitude 2 (float)
+ p2z : z position 2 / Altitude 2 (float)
+
+ '''
+ return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z))
+
+ def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ '''
+ Read out the safety zone the MAV currently assumes.
+
+ frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
+ p1x : x position 1 / Latitude 1 (float)
+ p1y : y position 1 / Longitude 1 (float)
+ p1z : z position 1 / Altitude 1 (float)
+ p2x : x position 2 / Latitude 2 (float)
+ p2y : y position 2 / Longitude 2 (float)
+ p2z : z position 2 / Altitude 2 (float)
+
+ '''
+ msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z)
+ msg.pack(self)
+ return msg
+
+ def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
+ '''
+ Read out the safety zone the MAV currently assumes.
+
+ frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
+ p1x : x position 1 / Latitude 1 (float)
+ p1y : y position 1 / Longitude 1 (float)
+ p1z : z position 1 / Altitude 1 (float)
+ p2x : x position 2 / Latitude 2 (float)
+ p2y : y position 2 / Longitude 2 (float)
+ p2z : z position 2 / Altitude 2 (float)
+
+ '''
+ return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z))
+
+ def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust):
+ '''
+ Set roll, pitch and yaw.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ roll : Desired roll angle in radians (float)
+ pitch : Desired pitch angle in radians (float)
+ yaw : Desired yaw angle in radians (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust)
+ msg.pack(self)
+ return msg
+
+ def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust):
+ '''
+ Set roll, pitch and yaw.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ roll : Desired roll angle in radians (float)
+ pitch : Desired pitch angle in radians (float)
+ yaw : Desired yaw angle in radians (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust))
+
+ def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
+ '''
+ Set roll, pitch and yaw.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ roll_speed : Desired roll angular speed in rad/s (float)
+ pitch_speed : Desired pitch angular speed in rad/s (float)
+ yaw_speed : Desired yaw angular speed in rad/s (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)
+ msg.pack(self)
+ return msg
+
+ def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
+ '''
+ Set roll, pitch and yaw.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ roll_speed : Desired roll angular speed in rad/s (float)
+ pitch_speed : Desired pitch angular speed in rad/s (float)
+ yaw_speed : Desired yaw angular speed in rad/s (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust))
+
+ def roll_pitch_yaw_thrust_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust):
+ '''
+ Setpoint in roll, pitch, yaw currently active on the system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll : Desired roll angle in radians (float)
+ pitch : Desired pitch angle in radians (float)
+ yaw : Desired yaw angle in radians (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust)
+ msg.pack(self)
+ return msg
+
+ def roll_pitch_yaw_thrust_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust):
+ '''
+ Setpoint in roll, pitch, yaw currently active on the system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll : Desired roll angle in radians (float)
+ pitch : Desired pitch angle in radians (float)
+ yaw : Desired yaw angle in radians (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust))
+
+ def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust):
+ '''
+ Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
+ system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll_speed : Desired roll angular speed in rad/s (float)
+ pitch_speed : Desired pitch angular speed in rad/s (float)
+ yaw_speed : Desired yaw angular speed in rad/s (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust)
+ msg.pack(self)
+ return msg
+
+ def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust):
+ '''
+ Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
+ system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll_speed : Desired roll angular speed in rad/s (float)
+ pitch_speed : Desired pitch angular speed in rad/s (float)
+ yaw_speed : Desired yaw angular speed in rad/s (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust))
+
+ def set_quad_motors_setpoint_encode(self, target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw):
+ '''
+ Setpoint in the four motor speeds
+
+ target_system : System ID of the system that should set these motor commands (uint8_t)
+ motor_front_nw : Front motor in + configuration, front left motor in x configuration (uint16_t)
+ motor_right_ne : Right motor in + configuration, front right motor in x configuration (uint16_t)
+ motor_back_se : Back motor in + configuration, back right motor in x configuration (uint16_t)
+ motor_left_sw : Left motor in + configuration, back left motor in x configuration (uint16_t)
+
+ '''
+ msg = MAVLink_set_quad_motors_setpoint_message(target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw)
+ msg.pack(self)
+ return msg
+
+ def set_quad_motors_setpoint_send(self, target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw):
+ '''
+ Setpoint in the four motor speeds
+
+ target_system : System ID of the system that should set these motor commands (uint8_t)
+ motor_front_nw : Front motor in + configuration, front left motor in x configuration (uint16_t)
+ motor_right_ne : Right motor in + configuration, front right motor in x configuration (uint16_t)
+ motor_back_se : Back motor in + configuration, back right motor in x configuration (uint16_t)
+ motor_left_sw : Left motor in + configuration, back left motor in x configuration (uint16_t)
+
+ '''
+ return self.send(self.set_quad_motors_setpoint_encode(target_system, motor_front_nw, motor_right_ne, motor_back_se, motor_left_sw))
+
+ def set_quad_swarm_roll_pitch_yaw_thrust_encode(self, group, mode, roll, pitch, yaw, thrust):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+
+ group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t)
+ mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t)
+ roll : Desired roll angle in radians +-PI (+-32767) (int16_t)
+ pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t)
+ yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t)
+ thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t)
+
+ '''
+ msg = MAVLink_set_quad_swarm_roll_pitch_yaw_thrust_message(group, mode, roll, pitch, yaw, thrust)
+ msg.pack(self)
+ return msg
+
+ def set_quad_swarm_roll_pitch_yaw_thrust_send(self, group, mode, roll, pitch, yaw, thrust):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+
+ group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t)
+ mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t)
+ roll : Desired roll angle in radians +-PI (+-32767) (int16_t)
+ pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t)
+ yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t)
+ thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t)
+
+ '''
+ return self.send(self.set_quad_swarm_roll_pitch_yaw_thrust_encode(group, mode, roll, pitch, yaw, thrust))
+
+ def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
+ '''
+ Outputs of the APM navigation controller. The primary use of this
+ message is to check the response and signs of the
+ controller before actual flight and to assist with
+ tuning controller parameters.
+
+ nav_roll : Current desired roll in degrees (float)
+ nav_pitch : Current desired pitch in degrees (float)
+ nav_bearing : Current desired heading in degrees (int16_t)
+ target_bearing : Bearing to current MISSION/target in degrees (int16_t)
+ wp_dist : Distance to active MISSION in meters (uint16_t)
+ alt_error : Current altitude error in meters (float)
+ aspd_error : Current airspeed error in meters/second (float)
+ xtrack_error : Current crosstrack error on x-y plane in meters (float)
+
+ '''
+ msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)
+ msg.pack(self)
+ return msg
+
+ def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
+ '''
+ Outputs of the APM navigation controller. The primary use of this
+ message is to check the response and signs of the
+ controller before actual flight and to assist with
+ tuning controller parameters.
+
+ nav_roll : Current desired roll in degrees (float)
+ nav_pitch : Current desired pitch in degrees (float)
+ nav_bearing : Current desired heading in degrees (int16_t)
+ target_bearing : Bearing to current MISSION/target in degrees (int16_t)
+ wp_dist : Distance to active MISSION in meters (uint16_t)
+ alt_error : Current altitude error in meters (float)
+ aspd_error : Current airspeed error in meters/second (float)
+ xtrack_error : Current crosstrack error on x-y plane in meters (float)
+
+ '''
+ return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error))
+
+ def set_quad_swarm_led_roll_pitch_yaw_thrust_encode(self, group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+
+ group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t)
+ mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t)
+ led_red : RGB red channel (0-255) (uint8_t)
+ led_blue : RGB green channel (0-255) (uint8_t)
+ led_green : RGB blue channel (0-255) (uint8_t)
+ roll : Desired roll angle in radians +-PI (+-32767) (int16_t)
+ pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t)
+ yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t)
+ thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t)
+
+ '''
+ msg = MAVLink_set_quad_swarm_led_roll_pitch_yaw_thrust_message(group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust)
+ msg.pack(self)
+ return msg
+
+ def set_quad_swarm_led_roll_pitch_yaw_thrust_send(self, group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust):
+ '''
+ Setpoint for up to four quadrotors in a group / wing
+
+ group : ID of the quadrotor group (0 - 255, up to 256 groups supported) (uint8_t)
+ mode : ID of the flight mode (0 - 255, up to 256 modes supported) (uint8_t)
+ led_red : RGB red channel (0-255) (uint8_t)
+ led_blue : RGB green channel (0-255) (uint8_t)
+ led_green : RGB blue channel (0-255) (uint8_t)
+ roll : Desired roll angle in radians +-PI (+-32767) (int16_t)
+ pitch : Desired pitch angle in radians +-PI (+-32767) (int16_t)
+ yaw : Desired yaw angle in radians, scaled to int16 +-PI (+-32767) (int16_t)
+ thrust : Collective thrust, scaled to uint16 (0..65535) (uint16_t)
+
+ '''
+ return self.send(self.set_quad_swarm_led_roll_pitch_yaw_thrust_encode(group, mode, led_red, led_blue, led_green, roll, pitch, yaw, thrust))
+
+ def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
+ '''
+ Corrects the systems state by adding an error correction term to the
+ position and velocity, and by rotating the attitude by
+ a correction angle.
+
+ xErr : x position error (float)
+ yErr : y position error (float)
+ zErr : z position error (float)
+ rollErr : roll error (radians) (float)
+ pitchErr : pitch error (radians) (float)
+ yawErr : yaw error (radians) (float)
+ vxErr : x velocity (float)
+ vyErr : y velocity (float)
+ vzErr : z velocity (float)
+
+ '''
+ msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)
+ msg.pack(self)
+ return msg
+
+ def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
+ '''
+ Corrects the systems state by adding an error correction term to the
+ position and velocity, and by rotating the attitude by
+ a correction angle.
+
+ xErr : x position error (float)
+ yErr : y position error (float)
+ zErr : z position error (float)
+ rollErr : roll error (radians) (float)
+ pitchErr : pitch error (radians) (float)
+ yawErr : yaw error (radians) (float)
+ vxErr : x velocity (float)
+ vyErr : y velocity (float)
+ vzErr : z velocity (float)
+
+ '''
+ return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr))
+
+ def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
+ '''
+
+
+ target_system : The target requested to send the message stream. (uint8_t)
+ target_component : The target requested to send the message stream. (uint8_t)
+ req_stream_id : The ID of the requested data stream (uint8_t)
+ req_message_rate : The requested interval between two messages of this type (uint16_t)
+ start_stop : 1 to start sending, 0 to stop sending. (uint8_t)
+
+ '''
+ msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop)
+ msg.pack(self)
+ return msg
+
+ def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
+ '''
+
+
+ target_system : The target requested to send the message stream. (uint8_t)
+ target_component : The target requested to send the message stream. (uint8_t)
+ req_stream_id : The ID of the requested data stream (uint8_t)
+ req_message_rate : The requested interval between two messages of this type (uint16_t)
+ start_stop : 1 to start sending, 0 to stop sending. (uint8_t)
+
+ '''
+ return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop))
+
+ def data_stream_encode(self, stream_id, message_rate, on_off):
+ '''
+
+
+ stream_id : The ID of the requested data stream (uint8_t)
+ message_rate : The requested interval between two messages of this type (uint16_t)
+ on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t)
+
+ '''
+ msg = MAVLink_data_stream_message(stream_id, message_rate, on_off)
+ msg.pack(self)
+ return msg
+
+ def data_stream_send(self, stream_id, message_rate, on_off):
+ '''
+
+
+ stream_id : The ID of the requested data stream (uint8_t)
+ message_rate : The requested interval between two messages of this type (uint16_t)
+ on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t)
+
+ '''
+ return self.send(self.data_stream_encode(stream_id, message_rate, on_off))
+
+ def manual_control_encode(self, target, x, y, z, r, buttons):
+ '''
+ This message provides an API for manually controlling the vehicle
+ using standard joystick axes nomenclature, along with
+ a joystick-like input device. Unused axes can be
+ disabled an buttons are also transmit as boolean
+ values of their
+
+ target : The system to be controlled. (uint8_t)
+ x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t)
+ y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t)
+ z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. (int16_t)
+ r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t)
+ buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t)
+
+ '''
+ msg = MAVLink_manual_control_message(target, x, y, z, r, buttons)
+ msg.pack(self)
+ return msg
+
+ def manual_control_send(self, target, x, y, z, r, buttons):
+ '''
+ This message provides an API for manually controlling the vehicle
+ using standard joystick axes nomenclature, along with
+ a joystick-like input device. Unused axes can be
+ disabled an buttons are also transmit as boolean
+ values of their
+
+ target : The system to be controlled. (uint8_t)
+ x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t)
+ y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t)
+ z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. (int16_t)
+ r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t)
+ buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t)
+
+ '''
+ return self.send(self.manual_control_encode(target, x, y, z, r, buttons))
+
+ def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
+ '''
+ The RAW values of the RC channels sent to the MAV to override info
+ received from the RC radio. A value of -1 means no
+ change to that channel. A value of 0 means control of
+ that channel should be released back to the RC radio.
+ The standard PPM modulation is as follows: 1000
+ microseconds: 0%, 2000 microseconds: 100%. Individual
+ receivers/transmitters might violate this
+ specification.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ chan1_raw : RC channel 1 value, in microseconds (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds (uint16_t)
+
+ '''
+ msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)
+ msg.pack(self)
+ return msg
+
+ def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
+ '''
+ The RAW values of the RC channels sent to the MAV to override info
+ received from the RC radio. A value of -1 means no
+ change to that channel. A value of 0 means control of
+ that channel should be released back to the RC radio.
+ The standard PPM modulation is as follows: 1000
+ microseconds: 0%, 2000 microseconds: 100%. Individual
+ receivers/transmitters might violate this
+ specification.
+
+ target_system : System ID (uint8_t)
+ target_component : Component ID (uint8_t)
+ chan1_raw : RC channel 1 value, in microseconds (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds (uint16_t)
+
+ '''
+ return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw))
+
+ def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb):
+ '''
+ Metrics typically displayed on a HUD for fixed wing aircraft
+
+ airspeed : Current airspeed in m/s (float)
+ groundspeed : Current ground speed in m/s (float)
+ heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
+ throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t)
+ alt : Current altitude (MSL), in meters (float)
+ climb : Current climb rate in meters/second (float)
+
+ '''
+ msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb)
+ msg.pack(self)
+ return msg
+
+ def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb):
+ '''
+ Metrics typically displayed on a HUD for fixed wing aircraft
+
+ airspeed : Current airspeed in m/s (float)
+ groundspeed : Current ground speed in m/s (float)
+ heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
+ throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t)
+ alt : Current altitude (MSL), in meters (float)
+ climb : Current climb rate in meters/second (float)
+
+ '''
+ return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb))
+
+ def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7):
+ '''
+ Send a command with up to four parameters to the MAV
+
+ target_system : System which should execute the command (uint8_t)
+ target_component : Component which should execute the command, 0 for all components (uint8_t)
+ command : Command ID, as defined by MAV_CMD enum. (uint16_t)
+ confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
+ param1 : Parameter 1, as defined by MAV_CMD enum. (float)
+ param2 : Parameter 2, as defined by MAV_CMD enum. (float)
+ param3 : Parameter 3, as defined by MAV_CMD enum. (float)
+ param4 : Parameter 4, as defined by MAV_CMD enum. (float)
+ param5 : Parameter 5, as defined by MAV_CMD enum. (float)
+ param6 : Parameter 6, as defined by MAV_CMD enum. (float)
+ param7 : Parameter 7, as defined by MAV_CMD enum. (float)
+
+ '''
+ msg = MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)
+ msg.pack(self)
+ return msg
+
+ def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7):
+ '''
+ Send a command with up to four parameters to the MAV
+
+ target_system : System which should execute the command (uint8_t)
+ target_component : Component which should execute the command, 0 for all components (uint8_t)
+ command : Command ID, as defined by MAV_CMD enum. (uint16_t)
+ confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
+ param1 : Parameter 1, as defined by MAV_CMD enum. (float)
+ param2 : Parameter 2, as defined by MAV_CMD enum. (float)
+ param3 : Parameter 3, as defined by MAV_CMD enum. (float)
+ param4 : Parameter 4, as defined by MAV_CMD enum. (float)
+ param5 : Parameter 5, as defined by MAV_CMD enum. (float)
+ param6 : Parameter 6, as defined by MAV_CMD enum. (float)
+ param7 : Parameter 7, as defined by MAV_CMD enum. (float)
+
+ '''
+ return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7))
+
+ def command_ack_encode(self, command, result):
+ '''
+ Report status of a command. Includes feedback wether the command was
+ executed.
+
+ command : Command ID, as defined by MAV_CMD enum. (uint16_t)
+ result : See MAV_RESULT enum (uint8_t)
+
+ '''
+ msg = MAVLink_command_ack_message(command, result)
+ msg.pack(self)
+ return msg
+
+ def command_ack_send(self, command, result):
+ '''
+ Report status of a command. Includes feedback wether the command was
+ executed.
+
+ command : Command ID, as defined by MAV_CMD enum. (uint16_t)
+ result : See MAV_RESULT enum (uint8_t)
+
+ '''
+ return self.send(self.command_ack_encode(command, result))
+
+ def roll_pitch_yaw_rates_thrust_setpoint_encode(self, time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust):
+ '''
+ Setpoint in roll, pitch, yaw rates and thrust currently active on the
+ system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll_rate : Desired roll rate in radians per second (float)
+ pitch_rate : Desired pitch rate in radians per second (float)
+ yaw_rate : Desired yaw rate in radians per second (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ msg = MAVLink_roll_pitch_yaw_rates_thrust_setpoint_message(time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust)
+ msg.pack(self)
+ return msg
+
+ def roll_pitch_yaw_rates_thrust_setpoint_send(self, time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust):
+ '''
+ Setpoint in roll, pitch, yaw rates and thrust currently active on the
+ system.
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll_rate : Desired roll rate in radians per second (float)
+ pitch_rate : Desired pitch rate in radians per second (float)
+ yaw_rate : Desired yaw rate in radians per second (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+
+ '''
+ return self.send(self.roll_pitch_yaw_rates_thrust_setpoint_encode(time_boot_ms, roll_rate, pitch_rate, yaw_rate, thrust))
+
+ def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch):
+ '''
+ Setpoint in roll, pitch, yaw and thrust from the operator
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll : Desired roll rate in radians per second (float)
+ pitch : Desired pitch rate in radians per second (float)
+ yaw : Desired yaw rate in radians per second (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+ mode_switch : Flight mode switch position, 0.. 255 (uint8_t)
+ manual_override_switch : Override mode switch position, 0.. 255 (uint8_t)
+
+ '''
+ msg = MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)
+ msg.pack(self)
+ return msg
+
+ def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch):
+ '''
+ Setpoint in roll, pitch, yaw and thrust from the operator
+
+ time_boot_ms : Timestamp in milliseconds since system boot (uint32_t)
+ roll : Desired roll rate in radians per second (float)
+ pitch : Desired pitch rate in radians per second (float)
+ yaw : Desired yaw rate in radians per second (float)
+ thrust : Collective thrust, normalized to 0 .. 1 (float)
+ mode_switch : Flight mode switch position, 0.. 255 (uint8_t)
+ manual_override_switch : Override mode switch position, 0.. 255 (uint8_t)
+
+ '''
+ return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch))
+
+ def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw):
+ '''
+ The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages
+ of MAV X and the global coordinate frame in NED
+ coordinates. Coordinate frame is right-handed, Z-axis
+ down (aeronautical frame, NED / north-east-down
+ convention)
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ x : X Position (float)
+ y : Y Position (float)
+ z : Z Position (float)
+ roll : Roll (float)
+ pitch : Pitch (float)
+ yaw : Yaw (float)
+
+ '''
+ msg = MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw)
+ msg.pack(self)
+ return msg
+
+ def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw):
+ '''
+ The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages
+ of MAV X and the global coordinate frame in NED
+ coordinates. Coordinate frame is right-handed, Z-axis
+ down (aeronautical frame, NED / north-east-down
+ convention)
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ x : X Position (float)
+ y : Y Position (float)
+ z : Z Position (float)
+ roll : Roll (float)
+ pitch : Pitch (float)
+ yaw : Yaw (float)
+
+ '''
+ return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw))
+
+ def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
+ '''
+ Sent from simulation to autopilot. This packet is useful for high
+ throughput applications such as hardware in the loop
+ simulations.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ roll : Roll angle (rad) (float)
+ pitch : Pitch angle (rad) (float)
+ yaw : Yaw angle (rad) (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+ lat : Latitude, expressed as * 1E7 (int32_t)
+ lon : Longitude, expressed as * 1E7 (int32_t)
+ alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
+ vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
+ vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
+ vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
+ xacc : X acceleration (mg) (int16_t)
+ yacc : Y acceleration (mg) (int16_t)
+ zacc : Z acceleration (mg) (int16_t)
+
+ '''
+ msg = MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)
+ msg.pack(self)
+ return msg
+
+ def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
+ '''
+ Sent from simulation to autopilot. This packet is useful for high
+ throughput applications such as hardware in the loop
+ simulations.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ roll : Roll angle (rad) (float)
+ pitch : Pitch angle (rad) (float)
+ yaw : Yaw angle (rad) (float)
+ rollspeed : Roll angular speed (rad/s) (float)
+ pitchspeed : Pitch angular speed (rad/s) (float)
+ yawspeed : Yaw angular speed (rad/s) (float)
+ lat : Latitude, expressed as * 1E7 (int32_t)
+ lon : Longitude, expressed as * 1E7 (int32_t)
+ alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
+ vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
+ vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
+ vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
+ xacc : X acceleration (mg) (int16_t)
+ yacc : Y acceleration (mg) (int16_t)
+ zacc : Z acceleration (mg) (int16_t)
+
+ '''
+ return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc))
+
+ def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
+ '''
+ Sent from autopilot to simulation. Hardware in the loop control
+ outputs
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ roll_ailerons : Control output -1 .. 1 (float)
+ pitch_elevator : Control output -1 .. 1 (float)
+ yaw_rudder : Control output -1 .. 1 (float)
+ throttle : Throttle 0 .. 1 (float)
+ aux1 : Aux 1, -1 .. 1 (float)
+ aux2 : Aux 2, -1 .. 1 (float)
+ aux3 : Aux 3, -1 .. 1 (float)
+ aux4 : Aux 4, -1 .. 1 (float)
+ mode : System mode (MAV_MODE) (uint8_t)
+ nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t)
+
+ '''
+ msg = MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)
+ msg.pack(self)
+ return msg
+
+ def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
+ '''
+ Sent from autopilot to simulation. Hardware in the loop control
+ outputs
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ roll_ailerons : Control output -1 .. 1 (float)
+ pitch_elevator : Control output -1 .. 1 (float)
+ yaw_rudder : Control output -1 .. 1 (float)
+ throttle : Throttle 0 .. 1 (float)
+ aux1 : Aux 1, -1 .. 1 (float)
+ aux2 : Aux 2, -1 .. 1 (float)
+ aux3 : Aux 3, -1 .. 1 (float)
+ aux4 : Aux 4, -1 .. 1 (float)
+ mode : System mode (MAV_MODE) (uint8_t)
+ nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t)
+
+ '''
+ return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode))
+
+ def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
+ '''
+ Sent from simulation to autopilot. The RAW values of the RC channels
+ received. The standard PPM modulation is as follows:
+ 1000 microseconds: 0%, 2000 microseconds: 100%.
+ Individual receivers/transmitters might violate this
+ specification.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ chan1_raw : RC channel 1 value, in microseconds (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds (uint16_t)
+ chan9_raw : RC channel 9 value, in microseconds (uint16_t)
+ chan10_raw : RC channel 10 value, in microseconds (uint16_t)
+ chan11_raw : RC channel 11 value, in microseconds (uint16_t)
+ chan12_raw : RC channel 12 value, in microseconds (uint16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
+
+ '''
+ msg = MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)
+ msg.pack(self)
+ return msg
+
+ def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
+ '''
+ Sent from simulation to autopilot. The RAW values of the RC channels
+ received. The standard PPM modulation is as follows:
+ 1000 microseconds: 0%, 2000 microseconds: 100%.
+ Individual receivers/transmitters might violate this
+ specification.
+
+ time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
+ chan1_raw : RC channel 1 value, in microseconds (uint16_t)
+ chan2_raw : RC channel 2 value, in microseconds (uint16_t)
+ chan3_raw : RC channel 3 value, in microseconds (uint16_t)
+ chan4_raw : RC channel 4 value, in microseconds (uint16_t)
+ chan5_raw : RC channel 5 value, in microseconds (uint16_t)
+ chan6_raw : RC channel 6 value, in microseconds (uint16_t)
+ chan7_raw : RC channel 7 value, in microseconds (uint16_t)
+ chan8_raw : RC channel 8 value, in microseconds (uint16_t)
+ chan9_raw : RC channel 9 value, in microseconds (uint16_t)
+ chan10_raw : RC channel 10 value, in microseconds (uint16_t)
+ chan11_raw : RC channel 11 value, in microseconds (uint16_t)
+ chan12_raw : RC channel 12 value, in microseconds (uint16_t)
+ rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
+
+ '''
+ return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi))
+
+ def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance):
+ '''
+ Optical flow from a flow sensor (e.g. optical mouse sensor)
+
+ time_usec : Timestamp (UNIX) (uint64_t)
+ sensor_id : Sensor ID (uint8_t)
+ flow_x : Flow in pixels in x-sensor direction (int16_t)
+ flow_y : Flow in pixels in y-sensor direction (int16_t)
+ flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float)
+ flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float)
+ quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
+ ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float)
+
+ '''
+ msg = MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)
+ msg.pack(self)
+ return msg
+
+ def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance):
+ '''
+ Optical flow from a flow sensor (e.g. optical mouse sensor)
+
+ time_usec : Timestamp (UNIX) (uint64_t)
+ sensor_id : Sensor ID (uint8_t)
+ flow_x : Flow in pixels in x-sensor direction (int16_t)
+ flow_y : Flow in pixels in y-sensor direction (int16_t)
+ flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float)
+ flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float)
+ quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
+ ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float)
+
+ '''
+ return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance))
+
+ def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ msg = MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
+ msg.pack(self)
+ return msg
+
+ def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
+
+ def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ msg = MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
+ msg.pack(self)
+ return msg
+
+ def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
+
+ def vision_speed_estimate_encode(self, usec, x, y, z):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X speed (float)
+ y : Global Y speed (float)
+ z : Global Z speed (float)
+
+ '''
+ msg = MAVLink_vision_speed_estimate_message(usec, x, y, z)
+ msg.pack(self)
+ return msg
+
+ def vision_speed_estimate_send(self, usec, x, y, z):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X speed (float)
+ y : Global Y speed (float)
+ z : Global Z speed (float)
+
+ '''
+ return self.send(self.vision_speed_estimate_encode(usec, x, y, z))
+
+ def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ msg = MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
+ msg.pack(self)
+ return msg
+
+ def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
+ '''
+
+
+ usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ x : Global X position (float)
+ y : Global Y position (float)
+ z : Global Z position (float)
+ roll : Roll angle in rad (float)
+ pitch : Pitch angle in rad (float)
+ yaw : Yaw angle in rad (float)
+
+ '''
+ return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
+
+ def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated):
+ '''
+ The IMU readings in SI units in NED body frame
+
+ time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ xacc : X acceleration (m/s^2) (float)
+ yacc : Y acceleration (m/s^2) (float)
+ zacc : Z acceleration (m/s^2) (float)
+ xgyro : Angular speed around X axis (rad / sec) (float)
+ ygyro : Angular speed around Y axis (rad / sec) (float)
+ zgyro : Angular speed around Z axis (rad / sec) (float)
+ xmag : X Magnetic field (Gauss) (float)
+ ymag : Y Magnetic field (Gauss) (float)
+ zmag : Z Magnetic field (Gauss) (float)
+ abs_pressure : Absolute pressure in millibar (float)
+ diff_pressure : Differential pressure in millibar (float)
+ pressure_alt : Altitude calculated from pressure (float)
+ temperature : Temperature in degrees celsius (float)
+ fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t)
+
+ '''
+ msg = MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)
+ msg.pack(self)
+ return msg
+
+ def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated):
+ '''
+ The IMU readings in SI units in NED body frame
+
+ time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t)
+ xacc : X acceleration (m/s^2) (float)
+ yacc : Y acceleration (m/s^2) (float)
+ zacc : Z acceleration (m/s^2) (float)
+ xgyro : Angular speed around X axis (rad / sec) (float)
+ ygyro : Angular speed around Y axis (rad / sec) (float)
+ zgyro : Angular speed around Z axis (rad / sec) (float)
+ xmag : X Magnetic field (Gauss) (float)
+ ymag : Y Magnetic field (Gauss) (float)
+ zmag : Z Magnetic field (Gauss) (float)
+ abs_pressure : Absolute pressure in millibar (float)
+ diff_pressure : Differential pressure in millibar (float)
+ pressure_alt : Altitude calculated from pressure (float)
+ temperature : Temperature in degrees celsius (float)
+ fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t)
+
+ '''
+ return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated))
+
+ def file_transfer_start_encode(self, transfer_uid, dest_path, direction, file_size, flags):
+ '''
+ Begin file transfer
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ dest_path : Destination path (char)
+ direction : Transfer direction: 0: from requester, 1: to requester (uint8_t)
+ file_size : File size in bytes (uint32_t)
+ flags : RESERVED (uint8_t)
+
+ '''
+ msg = MAVLink_file_transfer_start_message(transfer_uid, dest_path, direction, file_size, flags)
+ msg.pack(self)
+ return msg
+
+ def file_transfer_start_send(self, transfer_uid, dest_path, direction, file_size, flags):
+ '''
+ Begin file transfer
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ dest_path : Destination path (char)
+ direction : Transfer direction: 0: from requester, 1: to requester (uint8_t)
+ file_size : File size in bytes (uint32_t)
+ flags : RESERVED (uint8_t)
+
+ '''
+ return self.send(self.file_transfer_start_encode(transfer_uid, dest_path, direction, file_size, flags))
+
+ def file_transfer_dir_list_encode(self, transfer_uid, dir_path, flags):
+ '''
+ Get directory listing
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ dir_path : Directory path to list (char)
+ flags : RESERVED (uint8_t)
+
+ '''
+ msg = MAVLink_file_transfer_dir_list_message(transfer_uid, dir_path, flags)
+ msg.pack(self)
+ return msg
+
+ def file_transfer_dir_list_send(self, transfer_uid, dir_path, flags):
+ '''
+ Get directory listing
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ dir_path : Directory path to list (char)
+ flags : RESERVED (uint8_t)
+
+ '''
+ return self.send(self.file_transfer_dir_list_encode(transfer_uid, dir_path, flags))
+
+ def file_transfer_res_encode(self, transfer_uid, result):
+ '''
+ File transfer result
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ result : 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device (uint8_t)
+
+ '''
+ msg = MAVLink_file_transfer_res_message(transfer_uid, result)
+ msg.pack(self)
+ return msg
+
+ def file_transfer_res_send(self, transfer_uid, result):
+ '''
+ File transfer result
+
+ transfer_uid : Unique transfer ID (uint64_t)
+ result : 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device (uint8_t)
+
+ '''
+ return self.send(self.file_transfer_res_encode(transfer_uid, result))
+
+ def battery_status_encode(self, accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining):
+ '''
+ Transmitte battery informations for a accu pack.
+
+ accu_id : Accupack ID (uint8_t)
+ voltage_cell_1 : Battery voltage of cell 1, in millivolts (1 = 1 millivolt) (uint16_t)
+ voltage_cell_2 : Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_3 : Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_4 : Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_5 : Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_6 : Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
+ battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t)
+
+ '''
+ msg = MAVLink_battery_status_message(accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining)
+ msg.pack(self)
+ return msg
+
+ def battery_status_send(self, accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining):
+ '''
+ Transmitte battery informations for a accu pack.
+
+ accu_id : Accupack ID (uint8_t)
+ voltage_cell_1 : Battery voltage of cell 1, in millivolts (1 = 1 millivolt) (uint16_t)
+ voltage_cell_2 : Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_3 : Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_4 : Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_5 : Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ voltage_cell_6 : Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell (uint16_t)
+ current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
+ battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t)
+
+ '''
+ return self.send(self.battery_status_encode(accu_id, voltage_cell_1, voltage_cell_2, voltage_cell_3, voltage_cell_4, voltage_cell_5, voltage_cell_6, current_battery, battery_remaining))
+
+ def setpoint_8dof_encode(self, target_system, val1, val2, val3, val4, val5, val6, val7, val8):
+ '''
+ Set the 8 DOF setpoint for a controller.
+
+ target_system : System ID (uint8_t)
+ val1 : Value 1 (float)
+ val2 : Value 2 (float)
+ val3 : Value 3 (float)
+ val4 : Value 4 (float)
+ val5 : Value 5 (float)
+ val6 : Value 6 (float)
+ val7 : Value 7 (float)
+ val8 : Value 8 (float)
+
+ '''
+ msg = MAVLink_setpoint_8dof_message(target_system, val1, val2, val3, val4, val5, val6, val7, val8)
+ msg.pack(self)
+ return msg
+
+ def setpoint_8dof_send(self, target_system, val1, val2, val3, val4, val5, val6, val7, val8):
+ '''
+ Set the 8 DOF setpoint for a controller.
+
+ target_system : System ID (uint8_t)
+ val1 : Value 1 (float)
+ val2 : Value 2 (float)
+ val3 : Value 3 (float)
+ val4 : Value 4 (float)
+ val5 : Value 5 (float)
+ val6 : Value 6 (float)
+ val7 : Value 7 (float)
+ val8 : Value 8 (float)
+
+ '''
+ return self.send(self.setpoint_8dof_encode(target_system, val1, val2, val3, val4, val5, val6, val7, val8))
+
+ def setpoint_6dof_encode(self, target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z):
+ '''
+ Set the 6 DOF setpoint for a attitude and position controller.
+
+ target_system : System ID (uint8_t)
+ trans_x : Translational Component in x (float)
+ trans_y : Translational Component in y (float)
+ trans_z : Translational Component in z (float)
+ rot_x : Rotational Component in x (float)
+ rot_y : Rotational Component in y (float)
+ rot_z : Rotational Component in z (float)
+
+ '''
+ msg = MAVLink_setpoint_6dof_message(target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z)
+ msg.pack(self)
+ return msg
+
+ def setpoint_6dof_send(self, target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z):
+ '''
+ Set the 6 DOF setpoint for a attitude and position controller.
+
+ target_system : System ID (uint8_t)
+ trans_x : Translational Component in x (float)
+ trans_y : Translational Component in y (float)
+ trans_z : Translational Component in z (float)
+ rot_x : Rotational Component in x (float)
+ rot_y : Rotational Component in y (float)
+ rot_z : Rotational Component in z (float)
+
+ '''
+ return self.send(self.setpoint_6dof_encode(target_system, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z))
+
+ def memory_vect_encode(self, address, ver, type, value):
+ '''
+ Send raw controller memory. The use of this message is discouraged for
+ normal packets, but a quite efficient way for testing
+ new messages and getting experimental debug output.
+
+ address : Starting address of the debug variables (uint16_t)
+ ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t)
+ type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t)
+ value : Memory contents at specified address (int8_t)
+
+ '''
+ msg = MAVLink_memory_vect_message(address, ver, type, value)
+ msg.pack(self)
+ return msg
+
+ def memory_vect_send(self, address, ver, type, value):
+ '''
+ Send raw controller memory. The use of this message is discouraged for
+ normal packets, but a quite efficient way for testing
+ new messages and getting experimental debug output.
+
+ address : Starting address of the debug variables (uint16_t)
+ ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t)
+ type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t)
+ value : Memory contents at specified address (int8_t)
+
+ '''
+ return self.send(self.memory_vect_encode(address, ver, type, value))
+
+ def debug_vect_encode(self, name, time_usec, x, y, z):
+ '''
+
+
+ name : Name (char)
+ time_usec : Timestamp (uint64_t)
+ x : x (float)
+ y : y (float)
+ z : z (float)
+
+ '''
+ msg = MAVLink_debug_vect_message(name, time_usec, x, y, z)
+ msg.pack(self)
+ return msg
+
+ def debug_vect_send(self, name, time_usec, x, y, z):
+ '''
+
+
+ name : Name (char)
+ time_usec : Timestamp (uint64_t)
+ x : x (float)
+ y : y (float)
+ z : z (float)
+
+ '''
+ return self.send(self.debug_vect_encode(name, time_usec, x, y, z))
+
+ def named_value_float_encode(self, time_boot_ms, name, value):
+ '''
+ Send a key-value pair as float. The use of this message is discouraged
+ for normal packets, but a quite efficient way for
+ testing new messages and getting experimental debug
+ output.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ name : Name of the debug variable (char)
+ value : Floating point value (float)
+
+ '''
+ msg = MAVLink_named_value_float_message(time_boot_ms, name, value)
+ msg.pack(self)
+ return msg
+
+ def named_value_float_send(self, time_boot_ms, name, value):
+ '''
+ Send a key-value pair as float. The use of this message is discouraged
+ for normal packets, but a quite efficient way for
+ testing new messages and getting experimental debug
+ output.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ name : Name of the debug variable (char)
+ value : Floating point value (float)
+
+ '''
+ return self.send(self.named_value_float_encode(time_boot_ms, name, value))
+
+ def named_value_int_encode(self, time_boot_ms, name, value):
+ '''
+ Send a key-value pair as integer. The use of this message is
+ discouraged for normal packets, but a quite efficient
+ way for testing new messages and getting experimental
+ debug output.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ name : Name of the debug variable (char)
+ value : Signed integer value (int32_t)
+
+ '''
+ msg = MAVLink_named_value_int_message(time_boot_ms, name, value)
+ msg.pack(self)
+ return msg
+
+ def named_value_int_send(self, time_boot_ms, name, value):
+ '''
+ Send a key-value pair as integer. The use of this message is
+ discouraged for normal packets, but a quite efficient
+ way for testing new messages and getting experimental
+ debug output.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ name : Name of the debug variable (char)
+ value : Signed integer value (int32_t)
+
+ '''
+ return self.send(self.named_value_int_encode(time_boot_ms, name, value))
+
+ def statustext_encode(self, severity, text):
+ '''
+ Status text message. These messages are printed in yellow in the COMM
+ console of QGroundControl. WARNING: They consume quite
+ some bandwidth, so use only for important status and
+ error messages. If implemented wisely, these messages
+ are buffered on the MCU and sent only at a limited
+ rate (e.g. 10 Hz).
+
+ severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t)
+ text : Status text message, without null termination character (char)
+
+ '''
+ msg = MAVLink_statustext_message(severity, text)
+ msg.pack(self)
+ return msg
+
+ def statustext_send(self, severity, text):
+ '''
+ Status text message. These messages are printed in yellow in the COMM
+ console of QGroundControl. WARNING: They consume quite
+ some bandwidth, so use only for important status and
+ error messages. If implemented wisely, these messages
+ are buffered on the MCU and sent only at a limited
+ rate (e.g. 10 Hz).
+
+ severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t)
+ text : Status text message, without null termination character (char)
+
+ '''
+ return self.send(self.statustext_encode(severity, text))
+
+ def debug_encode(self, time_boot_ms, ind, value):
+ '''
+ Send a debug value. The index is used to discriminate between values.
+ These values show up in the plot of QGroundControl as
+ DEBUG N.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ ind : index of debug variable (uint8_t)
+ value : DEBUG value (float)
+
+ '''
+ msg = MAVLink_debug_message(time_boot_ms, ind, value)
+ msg.pack(self)
+ return msg
+
+ def debug_send(self, time_boot_ms, ind, value):
+ '''
+ Send a debug value. The index is used to discriminate between values.
+ These values show up in the plot of QGroundControl as
+ DEBUG N.
+
+ time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
+ ind : index of debug variable (uint8_t)
+ value : DEBUG value (float)
+
+ '''
+ return self.send(self.debug_encode(time_boot_ms, ind, value))
+
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index 296de721b..3b23f4f83 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -330,7 +330,7 @@ class uploader(object):
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
- raise RuntimeError("Firmware not suitable for this board")
+ raise RuntimeError("Firmware not suitable for this board (run 'make configure_px4fmu && make clean' or 'make configure_px4io && make clean' to reconfigure).")
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
diff --git a/apps/drivers/blinkm/Makefile b/apps/drivers/blinkm/Makefile
new file mode 100644
index 000000000..5a623693d
--- /dev/null
+++ b/apps/drivers/blinkm/Makefile
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# BlinkM I2C LED driver
+#
+
+APPNAME = blinkm
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 2048
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp
new file mode 100644
index 000000000..d589025cc
--- /dev/null
+++ b/apps/drivers/blinkm/blinkm.cpp
@@ -0,0 +1,465 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file blinkm.cpp
+ *
+ * Driver for the BlinkM LED controller connected via I2C.
+ */
+
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include <drivers/drv_blinkm.h>
+
+#include <nuttx/wqueue.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+class BlinkM : public device::I2C
+{
+public:
+ BlinkM(int bus);
+ ~BlinkM();
+
+ virtual int init();
+ virtual int probe();
+
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ static const char *script_names[];
+
+private:
+ enum ScriptID {
+ USER = 0,
+ RGB,
+ WHITE_FLASH,
+ RED_FLASH,
+ GREEN_FLASH,
+ BLUE_FLASH,
+ CYAN_FLASH,
+ MAGENTA_FLASH,
+ YELLOW_FLASH,
+ BLACK,
+ HUE_CYCLE,
+ MOOD_LIGHT,
+ VIRTUAL_CANDLE,
+ WATER_REFLECTIONS,
+ OLD_NEON,
+ THE_SEASONS,
+ THUNDERSTORM,
+ STOP_LIGHT,
+ MORSE_CODE
+ };
+
+ work_s _work;
+ static const unsigned _monitor_interval = 250;
+
+ static void monitor_trampoline(void *arg);
+ void monitor();
+
+ int set_rgb(uint8_t r, uint8_t g, uint8_t b);
+
+ int fade_rgb(uint8_t r, uint8_t g, uint8_t b);
+ int fade_hsb(uint8_t h, uint8_t s, uint8_t b);
+
+ int fade_rgb_random(uint8_t r, uint8_t g, uint8_t b);
+ int fade_hsb_random(uint8_t h, uint8_t s, uint8_t b);
+
+ int set_fade_speed(uint8_t s);
+
+ int play_script(uint8_t script_id);
+ int play_script(const char *script_name);
+ int stop_script();
+
+ int write_script_line(uint8_t line, uint8_t ticks, uint8_t cmd, uint8_t arg1, uint8_t arg2, uint8_t arg3);
+ int read_script_line(uint8_t line, uint8_t &ticks, uint8_t cmd[4]);
+ int set_script(uint8_t length, uint8_t repeats);
+
+ int get_rgb(uint8_t &r, uint8_t &g, uint8_t &b);
+
+ int get_firmware_version(uint8_t version[2]);
+};
+
+/* for now, we only support one BlinkM */
+namespace
+{
+BlinkM *g_blinkm;
+
+}
+
+/* list of script names, must match script ID numbers */
+const char *BlinkM::script_names[] = {
+ "USER",
+ "RGB",
+ "WHITE_FLASH",
+ "RED_FLASH",
+ "GREEN_FLASH",
+ "BLUE_FLASH",
+ "CYAN_FLASH",
+ "MAGENTA_FLASH",
+ "YELLOW_FLASH",
+ "BLACK",
+ "HUE_CYCLE",
+ "MOOD_LIGHT",
+ "VIRTUAL_CANDLE",
+ "WATER_REFLECTIONS",
+ "OLD_NEON",
+ "THE_SEASONS",
+ "THUNDERSTORM",
+ "STOP_LIGHT",
+ "MORSE_CODE",
+ nullptr
+};
+
+extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
+
+BlinkM::BlinkM(int bus) :
+ I2C("blinkm", BLINKM_DEVICE_PATH, bus, 0x09, 100000)
+{
+}
+
+BlinkM::~BlinkM()
+{
+}
+
+int
+BlinkM::init()
+{
+ int ret;
+
+ ret = I2C::init();
+
+ if (ret != OK) {
+ warnx("I2C init failed");
+ return ret;
+ }
+
+ /* set some sensible defaults */
+ set_fade_speed(25);
+
+ /* turn off by default */
+ play_script(BLACK);
+
+ /* start the system monitor as a low-priority workqueue entry */
+ work_queue(LPWORK, &_work, (worker_t)&BlinkM::monitor_trampoline, this, 1);
+
+ return OK;
+}
+
+int
+BlinkM::probe()
+{
+ uint8_t version[2];
+ int ret;
+
+ ret = get_firmware_version(version);
+
+ if (ret == OK)
+ log("found BlinkM firmware version %c%c", version[1], version[0]);
+
+ return ret;
+}
+
+int
+BlinkM::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = ENOTTY;
+
+ switch (cmd) {
+ case BLINKM_PLAY_SCRIPT_NAMED:
+ if (arg == 0) {
+ ret = EINVAL;
+ break;
+ }
+ ret = play_script((const char *)arg);
+ break;
+
+ case BLINKM_PLAY_SCRIPT:
+ ret = play_script(arg);
+ break;
+
+ case BLINKM_SET_USER_SCRIPT: {
+ if (arg == 0) {
+ ret = EINVAL;
+ break;
+ }
+
+ unsigned lines = 0;
+ const uint8_t *script = (const uint8_t *)arg;
+
+ while ((lines < 50) && (script[1] != 0)) {
+ ret = write_script_line(lines, script[0], script[1], script[2], script[3], script[4]);
+ if (ret != OK)
+ break;
+ script += 5;
+ }
+ if (ret == OK)
+ ret = set_script(lines, 0);
+ break;
+ }
+
+ default:
+ break;
+ }
+
+ return ret;
+}
+
+void
+BlinkM::monitor_trampoline(void *arg)
+{
+ BlinkM *bm = (BlinkM *)arg;
+
+ bm->monitor();
+}
+
+void
+BlinkM::monitor()
+{
+ /* check system state, possibly update LED to suit */
+
+ /* re-queue ourselves to run again later */
+ work_queue(LPWORK, &_work, (worker_t)&BlinkM::monitor_trampoline, this, _monitor_interval);
+}
+
+int
+BlinkM::set_rgb(uint8_t r, uint8_t g, uint8_t b)
+{
+ const uint8_t msg[4] = { 'n', r, g, b };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::fade_rgb(uint8_t r, uint8_t g, uint8_t b)
+{
+ const uint8_t msg[4] = { 'c', r, g, b };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::fade_hsb(uint8_t h, uint8_t s, uint8_t b)
+{
+ const uint8_t msg[4] = { 'h', h, s, b };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::fade_rgb_random(uint8_t r, uint8_t g, uint8_t b)
+{
+ const uint8_t msg[4] = { 'C', r, g, b };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::fade_hsb_random(uint8_t h, uint8_t s, uint8_t b)
+{
+ const uint8_t msg[4] = { 'H', h, s, b };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::set_fade_speed(uint8_t s)
+{
+ const uint8_t msg[2] = { 'f', s };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::play_script(uint8_t script_id)
+{
+ const uint8_t msg[4] = { 'p', script_id, 0, 0 };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::play_script(const char *script_name)
+{
+ /* handle HTML colour encoding */
+ if (isxdigit(script_name[0]) && (strlen(script_name) == 6)) {
+ char code[3];
+ uint8_t r, g, b;
+
+ code[2] = '\0';
+
+ code[0] = script_name[1];
+ code[1] = script_name[2];
+ r = strtol(code, 0, 16);
+ code[0] = script_name[3];
+ code[1] = script_name[4];
+ g = strtol(code, 0, 16);
+ code[0] = script_name[5];
+ code[1] = script_name[6];
+ b = strtol(code, 0, 16);
+
+ stop_script();
+ return set_rgb(r, g, b);
+ }
+
+ for (unsigned i = 0; script_names[i] != nullptr; i++)
+ if (!strcasecmp(script_name, script_names[i]))
+ return play_script(i);
+
+ return -1;
+}
+
+int
+BlinkM::stop_script()
+{
+ const uint8_t msg[1] = { 'o' };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::write_script_line(uint8_t line, uint8_t ticks, uint8_t cmd, uint8_t arg1, uint8_t arg2, uint8_t arg3)
+{
+ const uint8_t msg[8] = { 'W', 0, line, ticks, cmd, arg1, arg2, arg3 };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::read_script_line(uint8_t line, uint8_t &ticks, uint8_t cmd[4])
+{
+ const uint8_t msg[3] = { 'R', 0, line };
+ uint8_t result[5];
+
+ int ret = transfer(msg, sizeof(msg), result, sizeof(result));
+
+ if (ret == OK) {
+ ticks = result[0];
+ cmd[0] = result[1];
+ cmd[1] = result[2];
+ cmd[2] = result[3];
+ cmd[3] = result[4];
+ }
+
+ return ret;
+}
+
+int
+BlinkM::set_script(uint8_t len, uint8_t repeats)
+{
+ const uint8_t msg[4] = { 'L', 0, len, repeats };
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+BlinkM::get_rgb(uint8_t &r, uint8_t &g, uint8_t &b)
+{
+ const uint8_t msg = 'g';
+ uint8_t result[3];
+
+ int ret = transfer(&msg, sizeof(msg), result, sizeof(result));
+
+ if (ret == OK) {
+ r = result[0];
+ g = result[1];
+ b = result[2];
+ }
+
+ return ret;
+}
+
+
+int
+BlinkM::get_firmware_version(uint8_t version[2])
+{
+ const uint8_t msg = 'Z';
+
+ return transfer(&msg, sizeof(msg), version, sizeof(version));
+}
+
+int
+blinkm_main(int argc, char *argv[])
+{
+ if (!strcmp(argv[1], "start")) {
+ if (g_blinkm != nullptr)
+ errx(1, "already started");
+
+ g_blinkm = new BlinkM(3);
+
+ if (g_blinkm == nullptr)
+ errx(1, "new failed");
+
+ if (OK != g_blinkm->init()) {
+ delete g_blinkm;
+ g_blinkm = nullptr;
+ errx(1, "init failed");
+ }
+
+ exit(0);
+ }
+
+ if (g_blinkm == nullptr)
+ errx(1, "not started");
+
+ if (!strcmp(argv[1], "list")) {
+ for (unsigned i = 0; BlinkM::script_names[i] != nullptr; i++)
+ fprintf(stderr, " %s\n", BlinkM::script_names[i]);
+ fprintf(stderr, " <html color number>\n");
+ exit(0);
+ }
+
+ /* things that require access to the device */
+ int fd = open(BLINKM_DEVICE_PATH, 0);
+ if (fd < 0)
+ err(1, "can't open BlinkM device");
+
+ if (ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK)
+ exit(0);
+
+ errx(1, "missing command, try 'start', 'list' or a script name");
+} \ No newline at end of file
diff --git a/apps/drivers/device/i2c.cpp b/apps/drivers/device/i2c.cpp
index 56112d767..474190d83 100644
--- a/apps/drivers/device/i2c.cpp
+++ b/apps/drivers/device/i2c.cpp
@@ -115,7 +115,7 @@ I2C::probe()
}
int
-I2C::transfer(uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
+I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
{
struct i2c_msg_s msgv[2];
unsigned msgs;
@@ -130,7 +130,7 @@ I2C::transfer(uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len
if (send_len > 0) {
msgv[msgs].addr = _address;
msgv[msgs].flags = 0;
- msgv[msgs].buffer = send;
+ msgv[msgs].buffer = const_cast<uint8_t *>(send);
msgv[msgs].length = send_len;
msgs++;
}
diff --git a/apps/drivers/device/i2c.h b/apps/drivers/device/i2c.h
index 3112e8e37..4d630b8a8 100644
--- a/apps/drivers/device/i2c.h
+++ b/apps/drivers/device/i2c.h
@@ -97,7 +97,7 @@ protected:
* @return OK if the transfer was successful, -errno
* otherwise.
*/
- int transfer(uint8_t *send, unsigned send_len,
+ int transfer(const uint8_t *send, unsigned send_len,
uint8_t *recv, unsigned recv_len);
/**
diff --git a/apps/drivers/drv_blinkm.h b/apps/drivers/drv_blinkm.h
new file mode 100644
index 000000000..9c278f6c5
--- /dev/null
+++ b/apps/drivers/drv_blinkm.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_blinkm.h
+ *
+ * BlinkM driver API
+ *
+ * This could probably become a more generalised API for multi-colour LED
+ * driver systems, or be merged with the generic LED driver.
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#define BLINKM_DEVICE_PATH "/dev/blinkm"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _BLINKMIOCBASE (0x2900)
+#define _BLINKMIOC(_n) (_IOC(_BLINKMIOCBASE, _n))
+
+/** play the named script in *(char *)arg, repeating forever */
+#define BLINKM_PLAY_SCRIPT_NAMED _BLINKMIOC(1)
+
+/** play the numbered script in (arg), repeating forever */
+#define BLINKM_PLAY_SCRIPT _BLINKMIOC(2)
+
+/**
+ * Set the user script; (arg) is a pointer to an array of script lines,
+ * where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
+ *
+ * The script is terminated by a zero command.
+ */
+#define BLINKM_SET_USER_SCRIPT _BLINKMIOC(3)
diff --git a/apps/drivers/drv_pwm_output.h b/apps/drivers/drv_pwm_output.h
index 97033f2cd..b2fee65ac 100644
--- a/apps/drivers/drv_pwm_output.h
+++ b/apps/drivers/drv_pwm_output.h
@@ -95,7 +95,7 @@ ORB_DECLARE(output_pwm);
* Note that ioctls and ObjDev updates should not be mixed, as the
* behaviour of the system in this case is not defined.
*/
-#define _PWM_SERVO_BASE 0x2700
+#define _PWM_SERVO_BASE 0x2a00
/** arm all servo outputs handle by this driver */
#define PWM_SERVO_ARM _IOC(_PWM_SERVO_BASE, 0)
diff --git a/apps/drivers/hmc5883/hmc5883.cpp b/apps/drivers/hmc5883/hmc5883.cpp
index 3849a2e05..3734d7755 100644
--- a/apps/drivers/hmc5883/hmc5883.cpp
+++ b/apps/drivers/hmc5883/hmc5883.cpp
@@ -288,6 +288,20 @@ private:
*/
int check_calibration();
+ /**
+ * Check the current scale calibration
+ *
+ * @return 0 if scale calibration is ok, 1 else
+ */
+ int check_scale();
+
+ /**
+ * Check the current offset calibration
+ *
+ * @return 0 if offset calibration is ok, 1 else
+ */
+ int check_offset();
+
};
/* helper macro for handling report buffer indices */
@@ -1016,11 +1030,11 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
out:
if (ret == OK) {
- if (!check_calibration()) {
+ if (!check_scale()) {
warnx("mag scale calibration successfully finished.");
} else {
warnx("mag scale calibration finished with invalid results.");
- ret == ERROR;
+ ret = ERROR;
}
} else {
@@ -1030,9 +1044,9 @@ out:
return ret;
}
-int HMC5883::check_calibration()
+int HMC5883::check_scale()
{
- bool scale_valid, offset_valid;
+ bool scale_valid;
if ((-FLT_EPSILON + 1.0f < _scale.x_scale && _scale.x_scale < FLT_EPSILON + 1.0f) &&
(-FLT_EPSILON + 1.0f < _scale.y_scale && _scale.y_scale < FLT_EPSILON + 1.0f) &&
@@ -1043,6 +1057,14 @@ int HMC5883::check_calibration()
scale_valid = true;
}
+ /* return 0 if calibrated, 1 else */
+ return !scale_valid;
+}
+
+int HMC5883::check_offset()
+{
+ bool offset_valid;
+
if ((-2.0f * FLT_EPSILON < _scale.x_offset && _scale.x_offset < 2.0f * FLT_EPSILON) &&
(-2.0f * FLT_EPSILON < _scale.y_offset && _scale.y_offset < 2.0f * FLT_EPSILON) &&
(-2.0f * FLT_EPSILON < _scale.z_offset && _scale.z_offset < 2.0f * FLT_EPSILON)) {
@@ -1052,17 +1074,36 @@ int HMC5883::check_calibration()
offset_valid = true;
}
+ /* return 0 if calibrated, 1 else */
+ return !offset_valid;
+}
+
+int HMC5883::check_calibration()
+{
+ bool offset_valid = (check_offset() == OK);
+ bool scale_valid = (check_scale() == OK);
+
if (_calibrated != (offset_valid && scale_valid)) {
warnx("mag cal status changed %s%s", (scale_valid) ? "" : "scale invalid ",
(offset_valid) ? "" : "offset invalid");
_calibrated = (offset_valid && scale_valid);
+
+
+ // XXX Change advertisement
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
_calibrated,
SUBSYSTEM_TYPE_MAG};
- orb_advert_t pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
}
/* return 0 if calibrated, 1 else */
diff --git a/apps/drivers/mpu6000/mpu6000.cpp b/apps/drivers/mpu6000/mpu6000.cpp
index ed79440cc..55b7cfa85 100644
--- a/apps/drivers/mpu6000/mpu6000.cpp
+++ b/apps/drivers/mpu6000/mpu6000.cpp
@@ -446,8 +446,12 @@ MPU6000::init()
// write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
usleep(1000);
- /* do CDev init for the gyro device node */
- ret = _gyro->init();
+ /* do CDev init for the gyro device node, keep it optional */
+ int gyro_ret = _gyro->init();
+
+ if (gyro_ret != OK) {
+ _gyro_topic = -1;
+ }
return ret;
}
@@ -938,7 +942,9 @@ MPU6000::measure()
/* and publish for subscribers */
orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report);
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report);
+ if (_gyro_topic != -1) {
+ orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report);
+ }
/* stop measuring */
perf_end(_sample_perf);
diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp
index 3eb4a9ef2..a995f6214 100644
--- a/apps/drivers/px4fmu/fmu.cpp
+++ b/apps/drivers/px4fmu/fmu.cpp
@@ -60,6 +60,7 @@
#include <drivers/boards/px4fmu/px4fmu_internal.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <systemlib/mixer/mixer.h>
#include <drivers/drv_mixer.h>
@@ -110,9 +111,9 @@ private:
void task_main() __attribute__((noreturn));
static int control_callback(uintptr_t handle,
- uint8_t control_group,
- uint8_t control_index,
- float &input);
+ uint8_t control_group,
+ uint8_t control_index,
+ float &input);
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
@@ -177,6 +178,7 @@ PX4FMU::~PX4FMU()
_task_should_exit = true;
unsigned i = 10;
+
do {
/* wait 50ms - it should wake every 100ms or so worst-case */
usleep(50000);
@@ -212,6 +214,7 @@ PX4FMU::init()
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
+
if (ret == OK) {
log("default PWM output device");
_primary_pwm_device = true;
@@ -245,7 +248,7 @@ PX4FMU::task_main_trampoline(int argc, char *argv[])
int
PX4FMU::set_mode(Mode mode)
{
- /*
+ /*
* Configure for PWM output.
*
* Note that regardless of the configured mode, the task is always
@@ -279,6 +282,7 @@ PX4FMU::set_mode(Mode mode)
default:
return -EINVAL;
}
+
_mode = mode;
return OK;
}
@@ -331,8 +335,10 @@ PX4FMU::task_main()
/* handle update rate changes */
if (_current_update_rate != _update_rate) {
int update_rate_in_ms = int(1000 / _update_rate);
+
if (update_rate_in_ms < 2)
update_rate_in_ms = 2;
+
orb_set_interval(_t_actuators, update_rate_in_ms);
up_pwm_servo_set_rate(_update_rate);
_current_update_rate = _update_rate;
@@ -382,8 +388,8 @@ PX4FMU::task_main()
/* get new value */
orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
- /* update PWM servo armed status */
- up_pwm_servo_arm(aa.armed);
+ /* update PWM servo armed status if armed and not locked down */
+ up_pwm_servo_arm(aa.armed && !aa.lockdown);
}
}
@@ -404,9 +410,9 @@ PX4FMU::task_main()
int
PX4FMU::control_callback(uintptr_t handle,
- uint8_t control_group,
- uint8_t control_index,
- float &input)
+ uint8_t control_group,
+ uint8_t control_index,
+ float &input)
{
const actuator_controls_s *controls = (actuator_controls_s *)handle;
@@ -424,15 +430,17 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
/* try it as a GPIO ioctl first */
ret = gpio_ioctl(filp, cmd, arg);
+
if (ret != -ENOTTY)
return ret;
/* if we are in valid PWM mode, try it as a PWM ioctl as well */
- switch(_mode) {
+ switch (_mode) {
case MODE_2PWM:
case MODE_4PWM:
ret = pwm_ioctl(filp, cmd, arg);
break;
+
default:
debug("not in a PWM mode");
break;
@@ -550,8 +558,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
}
_mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
+
if (_mixers == nullptr) {
ret = -ENOMEM;
+
} else {
debug("loading mixers from %s", path);
@@ -582,7 +592,7 @@ void
PX4FMU::gpio_reset(void)
{
/*
- * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
+ * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
* to input mode.
*/
for (unsigned i = 0; i < _ngpio; i++)
@@ -609,17 +619,20 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
/* configure selected GPIOs as required */
for (unsigned i = 0; i < _ngpio; i++) {
- if (gpios & (1<<i)) {
+ if (gpios & (1 << i)) {
switch (function) {
case GPIO_SET_INPUT:
stm32_configgpio(_gpio_tab[i].input);
break;
+
case GPIO_SET_OUTPUT:
stm32_configgpio(_gpio_tab[i].output);
break;
+
case GPIO_SET_ALT_1:
if (_gpio_tab[i].alt != 0)
stm32_configgpio(_gpio_tab[i].alt);
+
break;
}
}
@@ -636,7 +649,7 @@ PX4FMU::gpio_write(uint32_t gpios, int function)
int value = (function == GPIO_SET) ? 1 : 0;
for (unsigned i = 0; i < _ngpio; i++)
- if (gpios & (1<<i))
+ if (gpios & (1 << i))
stm32_gpiowrite(_gpio_tab[i].output, value);
}
@@ -660,7 +673,7 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
lock();
switch (cmd) {
-
+
case GPIO_RESET:
gpio_reset();
break;
@@ -762,6 +775,7 @@ fmu_new_mode(PortMode new_mode, int update_rate)
/* (re)set the PWM output mode */
g_fmu->set_mode(servo_mode);
+
if ((servo_mode != PX4FMU::MODE_NONE) && (update_rate != 0))
g_fmu->set_pwm_rate(update_rate);
@@ -800,13 +814,18 @@ test(void)
fd = open(PWM_OUTPUT_DEVICE_PATH, 0);
- if (fd < 0) {
- puts("open fail");
- exit(1);
- }
+ if (fd < 0)
+ errx(1, "open fail");
+
+ if (ioctl(fd, PWM_SERVO_ARM, 0) < 0) err(1, "servo arm failed");
+
+ if (ioctl(fd, PWM_SERVO_SET(0), 1000) < 0) err(1, "servo 1 set failed");
- ioctl(fd, PWM_SERVO_ARM, 0);
- ioctl(fd, PWM_SERVO_SET(0), 1000);
+ if (ioctl(fd, PWM_SERVO_SET(1), 1200) < 0) err(1, "servo 2 set failed");
+
+ if (ioctl(fd, PWM_SERVO_SET(2), 1400) < 0) err(1, "servo 3 set failed");
+
+ if (ioctl(fd, PWM_SERVO_SET(3), 1600) < 0) err(1, "servo 4 set failed");
close(fd);
@@ -816,10 +835,8 @@ test(void)
void
fake(int argc, char *argv[])
{
- if (argc < 5) {
- puts("fmu fake <roll> <pitch> <yaw> <thrust> (values -100 .. 100)");
- exit(1);
- }
+ if (argc < 5)
+ errx(1, "fmu fake <roll> <pitch> <yaw> <thrust> (values -100 .. 100)");
actuator_controls_s ac;
@@ -833,10 +850,18 @@ fake(int argc, char *argv[])
orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac);
- if (handle < 0) {
- puts("advertise failed");
- exit(1);
- }
+ if (handle < 0)
+ errx(1, "advertise failed");
+
+ actuator_armed_s aa;
+
+ aa.armed = true;
+ aa.lockdown = false;
+
+ handle = orb_advertise(ORB_ID(actuator_armed), &aa);
+
+ if (handle < 0)
+ errx(1, "advertise failed 2");
exit(0);
}
@@ -890,15 +915,17 @@ fmu_main(int argc, char *argv[])
if (new_mode == PORT_FULL_PWM || new_mode == PORT_PWM_AND_GPIO) {
if (argc > i + 1) {
pwm_update_rate_in_hz = atoi(argv[i + 1]);
+
} else {
- fprintf(stderr, "missing argument for pwm update rate (-u)\n");
+ errx(1, "missing argument for pwm update rate (-u)");
return 1;
}
+
} else {
- fprintf(stderr, "pwm update rate currently only supported for mode_pwm, mode_pwm_gpio\n");
+ errx(1, "pwm update rate currently only supported for mode_pwm, mode_pwm_gpio");
}
}
- }
+ }
/* was a new mode set? */
if (new_mode != PORT_MODE_UNSET) {
@@ -915,5 +942,5 @@ fmu_main(int argc, char *argv[])
fprintf(stderr, "FMU: unrecognised command, try:\n");
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm [-u pwm_update_rate_in_hz], mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio\n");
- return -EINVAL;
+ exit(1);
}
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index f2c87473c..9f3dba047 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -53,6 +53,7 @@
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
+#include <termios.h>
#include <fcntl.h>
#include <arch/board/board.h>
@@ -87,7 +88,7 @@ public:
virtual int ioctl(file *filp, int cmd, unsigned long arg);
- void set_rx_mode(unsigned mode);
+ bool dump_one;
private:
static const unsigned _max_actuators = PX4IO_OUTPUT_CHANNELS;
@@ -95,7 +96,7 @@ private:
int _serial_fd; ///< serial interface to PX4IO
hx_stream_t _io_stream; ///< HX protocol stream
- int _task; ///< worker task
+ volatile int _task; ///< worker task
volatile bool _task_should_exit;
volatile bool _connected; ///< true once we have received a valid frame
@@ -121,8 +122,6 @@ private:
bool _send_needed; ///< If true, we need to send a packet to IO
bool _config_needed; ///< if true, we need to set a config update to IO
- uint8_t _rx_mode; ///< the current RX mode on IO
-
/**
* Trampoline to the worker task
*/
@@ -178,6 +177,7 @@ PX4IO *g_dev;
PX4IO::PX4IO() :
CDev("px4io", "/dev/px4io"),
+ dump_one(false),
_serial_fd(-1),
_io_stream(nullptr),
_task(-1),
@@ -190,8 +190,7 @@ PX4IO::PX4IO() :
_primary_pwm_device(false),
_switch_armed(false),
_send_needed(false),
- _config_needed(false),
- _rx_mode(RX_MODE_PPM_ONLY)
+ _config_needed(false)
{
/* we need this potentially before it could be set in task_main */
g_dev = this;
@@ -201,33 +200,17 @@ PX4IO::PX4IO() :
PX4IO::~PX4IO()
{
- if (_task != -1) {
- /* tell the task we want it to go away */
- _task_should_exit = true;
-
- /* spin waiting for the thread to stop */
- unsigned i = 10;
+ /* tell the task we want it to go away */
+ _task_should_exit = true;
- do {
- /* wait 50ms - it should wake every 100ms or so worst-case */
- usleep(50000);
-
- /* if we have given up, kill it */
- if (--i == 0) {
- task_delete(_task);
- break;
- }
-
- } while (_task != -1);
+ /* spin waiting for the task to stop */
+ for (unsigned i = 0; (i < 10) && (_task != -1); i++) {
+ /* give it another 100ms */
+ usleep(100000);
}
-
- /* clean up the alternate device node */
- if (_primary_pwm_device)
- unregister_driver(PWM_OUTPUT_DEVICE_PATH);
-
- /* kill the HX stream */
- if (_io_stream != nullptr)
- hx_stream_free(_io_stream);
+ /* well, kill it anyway, though this will probably crash */
+ if (_task != -1)
+ task_delete(_task);
g_dev = nullptr;
}
@@ -295,6 +278,16 @@ PX4IO::task_main()
goto out;
}
+ /* 115200bps, no parity, one stop bit */
+ {
+ struct termios t;
+
+ tcgetattr(_serial_fd, &t);
+ cfsetspeed(&t, 115200);
+ t.c_cflag &= ~(CSTOPB | PARENB);
+ tcsetattr(_serial_fd, TCSANOW, &t);
+ }
+
/* protocol stream */
_io_stream = hx_stream_init(_serial_fd, &PX4IO::rx_callback_trampoline, this);
if (_io_stream == nullptr) {
@@ -348,7 +341,6 @@ PX4IO::task_main()
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
- usleep(1000000);
continue;
}
@@ -402,8 +394,16 @@ PX4IO::task_main()
}
out:
+ debug("exiting");
+
+ /* kill the HX stream */
if (_io_stream != nullptr)
hx_stream_free(_io_stream);
+ ::close(_serial_fd);
+
+ /* clean up the alternate device node */
+ if (_primary_pwm_device)
+ unregister_driver(PWM_OUTPUT_DEVICE_PATH);
/* tell the dtor that we are exiting */
_task = -1;
@@ -464,21 +464,33 @@ PX4IO::rx_callback(const uint8_t *buffer, size_t bytes_received)
}
_connected = true;
- /* publish raw rc channel values from IO */
- _input_rc.timestamp = hrt_absolute_time();
- _input_rc.channel_count = rep->channel_count;
- for (int i = 0; i < rep->channel_count; i++)
- {
- _input_rc.values[i] = rep->rc_channel[i];
- }
+ /* publish raw rc channel values from IO if valid channels are present */
+ if (rep->channel_count > 0) {
+ _input_rc.timestamp = hrt_absolute_time();
+ _input_rc.channel_count = rep->channel_count;
+ for (int i = 0; i < rep->channel_count; i++)
+ {
+ _input_rc.values[i] = rep->rc_channel[i];
+ }
- orb_publish(ORB_ID(input_rc), _to_input_rc, &_input_rc);
+ orb_publish(ORB_ID(input_rc), _to_input_rc, &_input_rc);
+ }
/* remember the latched arming switch state */
_switch_armed = rep->armed;
_send_needed = true;
+ /* if monitoring, dump the received info */
+ if (dump_one) {
+ dump_one = false;
+
+ printf("IO: %s armed ", rep->armed ? "" : "not");
+ for (unsigned i = 0; i < rep->channel_count; i++)
+ printf("%d: %d ", i, rep->rc_channel[i]);
+ printf("\n");
+ }
+
out:
unlock();
}
@@ -500,7 +512,8 @@ PX4IO::io_send()
// XXX relays
- cmd.arm_ok = _armed.armed;
+ /* armed and not locked down */
+ cmd.arm_ok = (_armed.armed && !_armed.lockdown);
ret = hx_stream_send(_io_stream, &cmd, sizeof(cmd));
if (ret)
@@ -514,7 +527,6 @@ PX4IO::config_send()
int ret;
cfg.f2i_config_magic = F2I_CONFIG_MAGIC;
- cfg.serial_rx_mode = _rx_mode;
ret = hx_stream_send(_io_stream, &cfg, sizeof(cfg));
if (ret)
@@ -634,15 +646,6 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
return ret;
}
-void
-PX4IO::set_rx_mode(unsigned mode)
-{
- if (mode != _rx_mode) {
- _rx_mode = mode;
- _config_needed = true;
- }
-}
-
extern "C" __EXPORT int px4io_main(int argc, char *argv[]);
namespace
@@ -675,6 +678,30 @@ test(void)
exit(0);
}
+void
+monitor(void)
+{
+ unsigned cancels = 4;
+ printf("Hit <enter> three times to exit monitor mode\n");
+
+ for (;;) {
+ pollfd fds[1];
+
+ fds[0].fd = 0;
+ fds[0].events = POLLIN;
+ poll(fds, 1, 500);
+
+ if (fds[0].revents == POLLIN) {
+ int c;
+ read(0, &c, 1);
+ if (cancels-- == 0)
+ exit(0);
+ }
+
+ if (g_dev != nullptr)
+ g_dev->dump_one = true;
+ }
+}
}
int
@@ -744,25 +771,17 @@ px4io_main(int argc, char *argv[])
return ret;
}
- if (!strcmp(argv[1], "rx_dsm_10bit")) {
- if (g_dev == nullptr)
- errx(1, "not started");
- g_dev->set_rx_mode(RX_MODE_DSM_10BIT);
- }
- if (!strcmp(argv[1], "rx_dsm_11bit")) {
- if (g_dev == nullptr)
- errx(1, "not started");
- g_dev->set_rx_mode(RX_MODE_DSM_11BIT);
- }
- if (!strcmp(argv[1], "rx_sbus")) {
- if (g_dev == nullptr)
- errx(1, "not started");
- g_dev->set_rx_mode(RX_MODE_FUTABA_SBUS);
- }
+ if (!strcmp(argv[1], "rx_dsm") ||
+ !strcmp(argv[1], "rx_dsm_10bit") ||
+ !strcmp(argv[1], "rx_dsm_11bit") ||
+ !strcmp(argv[1], "rx_sbus") ||
+ !strcmp(argv[1], "rx_ppm"))
+ errx(0, "receiver type is automatically detected, option '%s' is deprecated", argv[1]);
if (!strcmp(argv[1], "test"))
test();
+ if (!strcmp(argv[1], "monitor"))
+ monitor();
-
- errx(1, "need a command, try 'start', 'test', 'rx_dsm_10bit', 'rx_dsm_11bit', 'rx_sbus' or 'update'");
+ errx(1, "need a command, try 'start', 'test', 'monitor' or 'update'");
}
diff --git a/apps/drivers/px4io/uploader.cpp b/apps/drivers/px4io/uploader.cpp
index 5669aeb01..8b354ff60 100644
--- a/apps/drivers/px4io/uploader.cpp
+++ b/apps/drivers/px4io/uploader.cpp
@@ -189,8 +189,10 @@ PX4IO_Uploader::drain()
int ret;
do {
- ret = recv(c, 10);
- //log("discard 0x%02x", c);
+ ret = recv(c, 250);
+ if (ret == OK) {
+ //log("discard 0x%02x", c);
+ }
} while (ret == OK);
}
diff --git a/apps/drivers/stm32/drv_pwm_servo.c b/apps/drivers/stm32/drv_pwm_servo.c
index 50aa34d81..954b458f5 100644
--- a/apps/drivers/stm32/drv_pwm_servo.c
+++ b/apps/drivers/stm32/drv_pwm_servo.c
@@ -60,13 +60,13 @@
#include "drv_pwm_servo.h"
-#include "chip.h"
-#include "up_internal.h"
-#include "up_arch.h"
+#include <chip.h>
+#include <up_internal.h>
+#include <up_arch.h>
-#include "stm32_internal.h"
-#include "stm32_gpio.h"
-#include "stm32_tim.h"
+#include <stm32_internal.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
/* default rate (in Hz) of PWM updates */
@@ -143,27 +143,27 @@ pwm_channel_init(unsigned channel)
/* configure the channel */
switch (pwm_channels[channel].timer_channel) {
case 1:
- rCCMR1(timer) |= (6 << 4);
+ rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC1M_SHIFT) | GTIM_CCMR1_OC1PE;
rCCR1(timer) = pwm_channels[channel].default_value;
- rCCER(timer) |= (1 << 0);
+ rCCER(timer) |= GTIM_CCER_CC1E;
break;
case 2:
- rCCMR1(timer) |= (6 << 12);
+ rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC2M_SHIFT) | GTIM_CCMR1_OC2PE;
rCCR2(timer) = pwm_channels[channel].default_value;
- rCCER(timer) |= (1 << 4);
+ rCCER(timer) |= GTIM_CCER_CC2E;
break;
case 3:
- rCCMR2(timer) |= (6 << 4);
+ rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC3M_SHIFT) | GTIM_CCMR2_OC3PE;
rCCR3(timer) = pwm_channels[channel].default_value;
- rCCER(timer) |= (1 << 8);
+ rCCER(timer) |= GTIM_CCER_CC3E;
break;
case 4:
- rCCMR2(timer) |= (6 << 12);
+ rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC4M_SHIFT) | GTIM_CCMR2_OC4PE;
rCCR4(timer) = pwm_channels[channel].default_value;
- rCCER(timer) |= (1 << 12);
+ rCCER(timer) |= GTIM_CCER_CC4E;
break;
}
}
@@ -288,17 +288,20 @@ up_pwm_servo_set_rate(unsigned rate)
void
up_pwm_servo_arm(bool armed)
{
- /*
- * XXX this is inelgant and in particular will either jam outputs at whatever level
- * they happen to be at at the time the timers stop or generate runts.
- * The right thing is almost certainly to kill auto-reload on the timers so that
- * they just stop at the end of their count for disable, and to reset/restart them
- * for enable.
- */
-
/* iterate timers and arm/disarm appropriately */
for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
- if (pwm_timers[i].base != 0)
- rCR1(i) = armed ? GTIM_CR1_CEN : 0;
+ if (pwm_timers[i].base != 0) {
+ if (armed) {
+ /* force an update to preload all registers */
+ rEGR(i) = GTIM_EGR_UG;
+
+ /* arm requires the timer be enabled */
+ rCR1(i) |= GTIM_CR1_CEN | GTIM_CR1_ARPE;
+
+ } else {
+ /* on disarm, just stop auto-reload so we don't generate runts */
+ rCR1(i) &= ~GTIM_CR1_ARPE;
+ }
+ }
}
}
diff --git a/apps/gps/mtk.c b/apps/gps/mtk.c
index 7ba4f52b0..3b0ee4565 100644
--- a/apps/gps/mtk.c
+++ b/apps/gps/mtk.c
@@ -128,7 +128,7 @@ int mtk_parse(uint8_t b, char *gps_rx_buffer)
mtk_gps->eph = packet->hdop;
mtk_gps->epv = 65535; //unknown in mtk custom mode
mtk_gps->vel = packet->ground_speed;
- mtk_gps->cog = 65535; //unknown in mtk custom mode
+ mtk_gps->cog = (uint16_t)packet->heading; //mtk: degrees *1e2, mavlink/ubx: degrees *1e2
mtk_gps->satellites_visible = packet->satellites;
/* convert time and date information to unix timestamp */
diff --git a/apps/gps/nmea_helper.c b/apps/gps/nmea_helper.c
index 577a3a01c..1a50371c1 100644
--- a/apps/gps/nmea_helper.c
+++ b/apps/gps/nmea_helper.c
@@ -214,7 +214,7 @@ void *nmea_loop(void *args)
nmea_gps->eph = (uint16_t)(info->HDOP * 100); //TODO:test scaling
nmea_gps->epv = (uint16_t)(info->VDOP * 100); //TODO:test scaling
nmea_gps->vel = (uint16_t)(info->speed * 1000 / 36); //*1000/3600*100
- nmea_gps->cog = 65535;
+ nmea_gps->cog = (uint16_t)info->direction*100; //nmea: degrees float, ubx/mavlink: degrees*1e2
nmea_gps->satellites_visible = (uint8_t)info->satinfo.inview;
int i = 0;
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index b393620e2..81b907bcd 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -735,7 +735,7 @@ int mavlink_main(int argc, char *argv[])
mavlink_task = task_spawn("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 6000,
+ 2048,
mavlink_thread_main,
(const char**)argv);
exit(0);
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 6b4375445..dd011aeed 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -202,6 +202,8 @@ handle_message(mavlink_message_t *msg)
mavlink_vicon_position_estimate_t pos;
mavlink_msg_vicon_position_estimate_decode(msg, &pos);
+ vicon_position.timestamp = hrt_absolute_time();
+
vicon_position.x = pos.x;
vicon_position.y = pos.y;
vicon_position.z = pos.z;
@@ -427,4 +429,4 @@ receive_start(int uart)
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
-} \ No newline at end of file
+}
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 82f8a1534..e6ec77bf6 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -754,8 +754,8 @@ uorb_receive_start(void)
pthread_attr_t uorb_attr;
pthread_attr_init(&uorb_attr);
- /* Set stack size, needs more than 8000 bytes */
- pthread_attr_setstacksize(&uorb_attr, 4096);
+ /* Set stack size, needs less than 2k */
+ pthread_attr_setstacksize(&uorb_attr, 2048);
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);
diff --git a/apps/mavlink/orb_topics.h b/apps/mavlink/orb_topics.h
index 61ed8cbfe..4650c4991 100644
--- a/apps/mavlink/orb_topics.h
+++ b/apps/mavlink/orb_topics.h
@@ -55,6 +55,7 @@
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/debug_key_value.h>
diff --git a/apps/px4/tests/test_bson.c b/apps/px4/tests/test_bson.c
index d03a8d332..e2a10ec29 100644
--- a/apps/px4/tests/test_bson.c
+++ b/apps/px4/tests/test_bson.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/apps/px4/tests/tests_param.c b/apps/px4/tests/tests_param.c
index 88eff30f1..13f17bc43 100644
--- a/apps/px4/tests/tests_param.c
+++ b/apps/px4/tests/tests_param.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/apps/px4io/comms.c b/apps/px4io/comms.c
index f1dac433f..83a006d43 100644
--- a/apps/px4io/comms.c
+++ b/apps/px4io/comms.c
@@ -32,10 +32,11 @@
****************************************************************************/
/**
- * @file FMU communication for the PX4IO module.
+ * @file comms.c
+ *
+ * FMU communication for the PX4IO module.
*/
-
#include <nuttx/config.h>
#include <stdio.h>
#include <stdbool.h>
@@ -44,9 +45,9 @@
#include <debug.h>
#include <stdlib.h>
#include <errno.h>
-#include <termios.h>
#include <string.h>
#include <poll.h>
+#include <termios.h>
#include <nuttx/clock.h>
@@ -54,103 +55,59 @@
#include <systemlib/hx_stream.h>
#include <systemlib/perf_counter.h>
+#define DEBUG
#include "px4io.h"
#define FMU_MIN_REPORT_INTERVAL 5000 /* 5ms */
#define FMU_MAX_REPORT_INTERVAL 100000 /* 100ms */
+int frame_rx;
+int frame_bad;
+
static int fmu_fd;
static hx_stream_t stream;
-static int rx_fd;
static struct px4io_report report;
static void comms_handle_frame(void *arg, const void *buffer, size_t length);
-static struct pollfd pollfds[2];
-static int pollcount;
-
-void
+static void
comms_init(void)
{
/* initialise the FMU interface */
- fmu_fd = open("/dev/ttyS1", O_RDWR | O_NONBLOCK);
- if (fmu_fd < 0)
- lib_lowprintf("COMMS: fmu open failed %d\n", errno);
+ fmu_fd = open("/dev/ttyS1", O_RDWR);
stream = hx_stream_init(fmu_fd, comms_handle_frame, NULL);
- pollfds[0].fd = fmu_fd;
- pollfds[0].events = POLLIN;
- pollcount = 1;
/* default state in the report to FMU */
report.i2f_magic = I2F_MAGIC;
-}
-
-static void
-serial_rx_init(unsigned serial_mode)
-{
- if (serial_mode == system_state.serial_rx_mode)
- return;
- system_state.serial_rx_mode = serial_mode;
-
- if (serial_mode == RX_MODE_PPM_ONLY) {
- if (rx_fd != -1) {
- pollcount = 1;
- close(rx_fd);
- rx_fd = -1;
- }
- return;
- }
-
- /* open the serial port used for DSM and S.bus communication */
- rx_fd = open("/dev/ttyS0", O_RDONLY | O_NONBLOCK);
- pollfds[1].fd = rx_fd;
- pollfds[1].events = POLLIN;
- pollcount = 2;
-
struct termios t;
- tcgetattr(rx_fd, &t);
-
- switch (serial_mode) {
- case RX_MODE_DSM_10BIT:
- case RX_MODE_DSM_11BIT:
-
- /* 115200, no parity, one stop bit */
- cfsetspeed(&t, 115200);
- t.c_cflag &= ~(CSTOPB | PARENB);
-
- dsm_init(serial_mode);
- break;
-
- case RX_MODE_FUTABA_SBUS:
- /* 100000, even parity, two stop bits */
- cfsetspeed(&t, 100000);
- t.c_cflag |= (CSTOPB | PARENB);
-
- sbus_init(serial_mode);
- break;
-
- default:
- break;
- }
- tcsetattr(rx_fd, TCSANOW, &t);
+ /* 115200bps, no parity, one stop bit */
+ tcgetattr(fmu_fd, &t);
+ cfsetspeed(&t, 115200);
+ t.c_cflag &= ~(CSTOPB | PARENB);
+ tcsetattr(fmu_fd, TCSANOW, &t);
}
void
-comms_check(void)
+comms_main(void)
{
- /*
- * Check for serial data
- */
- int ret = poll(pollfds, pollcount, 0);
+ comms_init();
+
+ struct pollfd fds;
+ fds.fd = fmu_fd;
+ fds.events = POLLIN;
+ debug("FMU: ready");
+
+ for (;;) {
+ /* wait for serial data, but no more than 10ms */
+ poll(&fds, 1, 10);
- if (ret > 0) {
/*
* Pull bytes from FMU and feed them to the HX engine.
* Limit the number of bytes we actually process on any one iteration.
*/
- if (pollfds[0].revents & POLLIN) {
+ if (fds.revents & POLLIN) {
char buf[32];
ssize_t count = read(fmu_fd, buf, sizeof(buf));
for (int i = 0; i < count; i++)
@@ -158,55 +115,32 @@ comms_check(void)
}
/*
- * Pull bytes from the serial RX port and feed them to the decoder
- * if we care about serial RX data.
+ * Decide if it's time to send an update to the FMU.
*/
- if ((pollcount > 1) && (pollfds[1].revents & POLLIN)) {
- switch (system_state.serial_rx_mode) {
- case RX_MODE_DSM_10BIT:
- case RX_MODE_DSM_11BIT:
- dsm_input(rx_fd);
- break;
-
- case RX_MODE_FUTABA_SBUS:
- sbus_input(rx_fd);
- break;
-
- default:
- break;
- }
+ static hrt_abstime last_report_time;
+ hrt_abstime now, delta;
+
+ /* should we send a report to the FMU? */
+ now = hrt_absolute_time();
+ delta = now - last_report_time;
+ if ((delta > FMU_MIN_REPORT_INTERVAL) &&
+ (system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) {
+
+ system_state.fmu_report_due = false;
+ last_report_time = now;
+
+ /* populate the report */
+ for (unsigned i = 0; i < system_state.rc_channels; i++)
+ report.rc_channel[i] = system_state.rc_channel_data[i];
+ report.channel_count = system_state.rc_channels;
+ report.armed = system_state.armed;
+
+ /* and send it */
+ hx_stream_send(stream, &report, sizeof(report));
}
}
-
- /*
- * Decide if it's time to send an update to the FMU.
- */
- static hrt_abstime last_report_time;
- hrt_abstime now, delta;
-
- /* should we send a report to the FMU? */
- now = hrt_absolute_time();
- delta = now - last_report_time;
- if ((delta > FMU_MIN_REPORT_INTERVAL) &&
- (system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) {
-
- system_state.fmu_report_due = false;
- last_report_time = now;
-
- /* populate the report */
- for (int i = 0; i < system_state.rc_channels; i++)
- report.rc_channel[i] = system_state.rc_channel_data[i];
- report.channel_count = system_state.rc_channels;
- report.armed = system_state.armed;
-
- /* and send it */
- hx_stream_send(stream, &report, sizeof(report));
- }
}
-int frame_rx;
-int frame_bad;
-
static void
comms_handle_config(const void *buffer, size_t length)
{
@@ -218,8 +152,6 @@ comms_handle_config(const void *buffer, size_t length)
}
frame_rx++;
-
- serial_rx_init(cfg->serial_rx_mode);
}
static void
@@ -277,9 +209,9 @@ comms_handle_frame(void *arg, const void *buffer, size_t length)
comms_handle_config(buffer, length);
break;
default:
+ frame_bad++;
break;
}
}
- frame_bad++;
}
diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c
new file mode 100644
index 000000000..3b3782918
--- /dev/null
+++ b/apps/px4io/controls.c
@@ -0,0 +1,154 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file controls.c
+ *
+ * R/C inputs and servo outputs.
+ */
+
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <debug.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <termios.h>
+#include <string.h>
+#include <poll.h>
+
+#include <nuttx/clock.h>
+
+#include <drivers/drv_hrt.h>
+#include <systemlib/hx_stream.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/ppm_decode.h>
+
+#define DEBUG
+#include "px4io.h"
+
+static void ppm_input(void);
+
+void
+controls_main(void)
+{
+ struct pollfd fds[2];
+
+ /* DSM input */
+ fds[0].fd = dsm_init("/dev/ttyS0");
+ fds[0].events = POLLIN;
+
+ /* S.bus input */
+ fds[1].fd = sbus_init("/dev/ttyS2");
+ fds[1].events = POLLIN;
+
+ for (;;) {
+ /* run this loop at ~100Hz */
+ poll(fds, 2, 10);
+
+ /*
+ * Gather R/C control inputs from supported sources.
+ *
+ * Note that if you're silly enough to connect more than
+ * one control input source, they're going to fight each
+ * other. Don't do that.
+ */
+ bool locked = false;
+
+ if (fds[0].revents & POLLIN)
+ locked |= dsm_input();
+ if (fds[1].revents & POLLIN)
+ locked |= sbus_input();
+
+ /*
+ * If we don't have lock from one of the serial receivers,
+ * look for PPM. It shares an input with S.bus, so there's
+ * a possibility it will mis-parse an S.bus frame.
+ *
+ * XXX each S.bus frame will cause a PPM decoder interrupt
+ * storm (lots of edges). It might be sensible to actually
+ * disable the PPM decoder completely if we have an alternate
+ * receiver lock.
+ */
+ if (!locked)
+ ppm_input();
+
+ /*
+ * If we haven't seen any new control data in 200ms, assume we
+ * have lost input and tell FMU.
+ */
+ if ((hrt_absolute_time() - system_state.rc_channels_timestamp) > 200000) {
+
+ /* set the number of channels to zero - no inputs */
+ system_state.rc_channels = 0;
+
+ /* trigger an immediate report to the FMU */
+ system_state.fmu_report_due = true;
+ }
+
+ /* XXX do bypass mode, etc. here */
+
+ /* do PWM output updates */
+ mixer_tick();
+ }
+}
+
+static void
+ppm_input(void)
+{
+ /*
+ * Look for new PPM input.
+ */
+ if (ppm_last_valid_decode != 0) {
+
+ /* avoid racing with PPM updates */
+ irqstate_t state = irqsave();
+
+ /* PPM data exists, copy it */
+ system_state.rc_channels = ppm_decoded_channels;
+ for (unsigned i = 0; i < ppm_decoded_channels; i++)
+ system_state.rc_channel_data[i] = ppm_buffer[i];
+
+ /* copy the timestamp and clear it */
+ system_state.rc_channels_timestamp = ppm_last_valid_decode;
+ ppm_last_valid_decode = 0;
+
+ irqrestore(state);
+
+ /* trigger an immediate report to the FMU */
+ system_state.fmu_report_due = true;
+ }
+}
diff --git a/apps/px4io/dsm.c b/apps/px4io/dsm.c
index 79b6301c7..2611f3a03 100644
--- a/apps/px4io/dsm.c
+++ b/apps/px4io/dsm.c
@@ -44,46 +44,69 @@
#include <fcntl.h>
#include <unistd.h>
#include <string.h>
+#include <termios.h>
#include <systemlib/ppm_decode.h>
#include <drivers/drv_hrt.h>
+#define DEBUG
+
#include "px4io.h"
#include "protocol.h"
#define DSM_FRAME_SIZE 16
#define DSM_FRAME_CHANNELS 7
+static int dsm_fd = -1;
+
+static hrt_abstime last_rx_time;
static hrt_abstime last_frame_time;
static uint8_t frame[DSM_FRAME_SIZE];
static unsigned partial_frame_count;
-static bool insync;
static unsigned channel_shift;
-static void dsm_decode(void);
+unsigned dsm_frame_drops;
+
+static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
+static void dsm_guess_format(bool reset);
+static void dsm_decode(hrt_abstime now);
-void
-dsm_init(unsigned mode)
+int
+dsm_init(const char *device)
{
- insync = false;
- partial_frame_count = 0;
+ if (dsm_fd < 0)
+ dsm_fd = open(device, O_RDONLY);
- if (mode == RX_MODE_DSM_10BIT) {
- channel_shift = 10;
+ if (dsm_fd >= 0) {
+ struct termios t;
+
+ /* 115200bps, no parity, one stop bit */
+ tcgetattr(dsm_fd, &t);
+ cfsetspeed(&t, 115200);
+ t.c_cflag &= ~(CSTOPB | PARENB);
+ tcsetattr(dsm_fd, TCSANOW, &t);
+
+ /* initialise the decoder */
+ partial_frame_count = 0;
+ last_rx_time = hrt_absolute_time();
+
+ /* reset the format detector */
+ dsm_guess_format(true);
+
+ debug("DSM: ready");
} else {
- channel_shift = 11;
+ debug("DSM: open failed");
}
- last_frame_time = hrt_absolute_time();
+ return dsm_fd;
}
-void
-dsm_input(int fd)
+bool
+dsm_input(void)
{
- uint8_t buf[DSM_FRAME_SIZE];
ssize_t ret;
hrt_abstime now;
@@ -97,56 +120,180 @@ dsm_input(int fd)
* We expect to only be called when bytes arrive for processing,
* and if an interval of more than 5ms passes between calls,
* the first byte we read will be the first byte of a frame.
+ *
+ * In the case where byte(s) are dropped from a frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
*/
now = hrt_absolute_time();
- if ((now - last_frame_time) > 5000)
- partial_frame_count = 0;
+ if ((now - last_rx_time) > 5000) {
+ if (partial_frame_count > 0) {
+ dsm_frame_drops++;
+ partial_frame_count = 0;
+ }
+ }
/*
* Fetch bytes, but no more than we would need to complete
* the current frame.
*/
- ret = read(fd, buf, DSM_FRAME_SIZE - partial_frame_count);
+ ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count);
/* if the read failed for any reason, just give up here */
if (ret < 1)
- return;
+ goto out;
+ last_rx_time = now;
/*
* Add bytes to the current frame
*/
- memcpy(&frame[partial_frame_count], buf, ret);
partial_frame_count += ret;
/*
* If we don't have a full frame, return
*/
if (partial_frame_count < DSM_FRAME_SIZE)
- return;
- last_frame_time = now;
+ goto out;
/*
* Great, it looks like we might have a frame. Go ahead and
* decode it.
*/
- dsm_decode();
+ dsm_decode(now);
partial_frame_count = 0;
+
+out:
+ /*
+ * If we have seen a frame in the last 200ms, we consider ourselves 'locked'
+ */
+ return (now - last_frame_time) < 200000;
+}
+
+static bool
+dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
+{
+
+ if (raw == 0xffff)
+ return false;
+
+ *channel = (raw >> shift) & 0xf;
+
+ uint16_t data_mask = (1 << shift) - 1;
+ *value = raw & data_mask;
+
+ //debug("DSM: %d 0x%04x -> %d %d", shift, raw, *channel, *value);
+
+ return true;
}
static void
-dsm_decode(void)
+dsm_guess_format(bool reset)
{
- uint16_t data_mask = (1 << channel_shift) - 1;
+ static uint32_t cs10;
+ static uint32_t cs11;
+ static unsigned samples;
- /*
- * The encoding of the first byte is uncertain, so we're going
- * to ignore it for now.
+ /* reset the 10/11 bit sniffed channel masks */
+ if (reset) {
+ cs10 = 0;
+ cs11 = 0;
+ samples = 0;
+ channel_shift = 0;
+ return;
+ }
+
+ /* scan the channels in the current frame in both 10- and 11-bit mode */
+ for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
+
+ uint8_t *dp = &frame[2 + (2 * i)];
+ uint16_t raw = (dp[0] << 8) | dp[1];
+ unsigned channel, value;
+
+ /* if the channel decodes, remember the assigned number */
+ if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31))
+ cs10 |= (1 << channel);
+ if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
+ cs11 |= (1 << channel);
+
+ /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */
+ }
+
+ /* wait until we have seen plenty of frames - 2 should normally be enough */
+ if (samples++ < 5)
+ return;
+
+ /*
+ * Iterate the set of sensible sniffed channel sets and see whether
+ * decoding in 10 or 11-bit mode has yielded anything we recognise.
*
- * The second byte may tell us about the protocol, but it's not
- * actually very interesting since what we really want to know
- * is how the channel data is formatted, and there doesn't seem
- * to be a reliable way to determine this from the protocol ID
- * alone.
+ * XXX Note that due to what seem to be bugs in the DSM2 high-resolution
+ * stream, we may want to sniff for longer in some cases when we think we
+ * are talking to a DSM2 receiver in high-resolution mode (so that we can
+ * reject it, ideally).
+ * See e.g. http://git.openpilot.org/cru/OPReview-116 for a discussion
+ * of this issue.
+ */
+ static uint32_t masks[] = {
+ 0x3f, /* 6 channels (DX6) */
+ 0x7f, /* 7 channels (DX7) */
+ 0xff, /* 8 channels (DX8) */
+ 0x3ff, /* 10 channels (DX10) */
+ 0x3fff /* 18 channels (DX10) */
+ };
+ unsigned votes10 = 0;
+ unsigned votes11 = 0;
+
+ for (unsigned i = 0; i < (sizeof(masks) / sizeof(masks[0])); i++) {
+
+ if (cs10 == masks[i])
+ votes10++;
+ if (cs11 == masks[i])
+ votes11++;
+ }
+ if ((votes11 == 1) && (votes10 == 0)) {
+ channel_shift = 11;
+ debug("DSM: detected 11-bit format");
+ return;
+ }
+ if ((votes10 == 1) && (votes11 == 0)) {
+ channel_shift = 10;
+ debug("DSM: detected 10-bit format");
+ return;
+ }
+
+ /* call ourselves to reset our state ... we have to try again */
+ debug("DSM: format detector failed, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
+ dsm_guess_format(true);
+}
+
+static void
+dsm_decode(hrt_abstime frame_time)
+{
+
+/*
+ debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
+ frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7],
+ frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]);
+*/
+ /*
+ * If we have lost signal for at least a second, reset the
+ * format guessing heuristic.
+ */
+ if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0))
+ dsm_guess_format(true);
+
+ /* we have received something we think is a frame */
+ last_frame_time = frame_time;
+
+ /* if we don't know the frame format, update the guessing state machine */
+ if (channel_shift == 0) {
+ dsm_guess_format(false);
+ return;
+ }
+
+ /*
+ * The encoding of the first two bytes is uncertain, so we're
+ * going to ignore them for now.
*
* Each channel is a 16-bit unsigned value containing either a 10-
* or 11-bit channel value and a 4-bit channel number, shifted
@@ -159,26 +306,50 @@ dsm_decode(void)
uint8_t *dp = &frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
+ unsigned channel, value;
- /* ignore pad channels */
- if (raw == 0xffff)
+ if (!dsm_decode_channel(raw, channel_shift, &channel, &value))
continue;
- unsigned channel = (raw >> channel_shift) & 0xf;
-
/* ignore channels out of range */
if (channel >= PX4IO_INPUT_CHANNELS)
continue;
- if (channel > ppm_decoded_channels)
- ppm_decoded_channels = channel;
+ /* update the decoded channel count */
+ if (channel >= system_state.rc_channels)
+ system_state.rc_channels = channel + 1;
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- unsigned data = raw & data_mask;
if (channel_shift == 11)
- data /= 2;
- ppm_buffer[channel] = 988 + data;
+ value /= 2;
+ value += 998;
+ /*
+ * Store the decoded channel into the R/C input buffer, taking into
+ * account the different ideas about channel assignement that we have.
+ *
+ * Specifically, the first four channels in rc_channel_data are roll, pitch, thrust, yaw,
+ * but the first four channels from the DSM receiver are thrust, roll, pitch, yaw.
+ */
+ switch (channel) {
+ case 0:
+ channel = 2;
+ break;
+ case 1:
+ channel = 0;
+ break;
+ case 2:
+ channel = 1;
+ default:
+ break;
+ }
+ system_state.rc_channel_data[channel] = value;
}
- ppm_last_valid_decode = hrt_absolute_time();
+
+ /* and note that we have received data from the R/C controller */
+ /* XXX failsafe will cause problems here - need a strategy for detecting it */
+ system_state.rc_channels_timestamp = frame_time;
+
+ /* trigger an immediate report to the FMU */
+ system_state.fmu_report_due = true;
}
diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c
index 572344d00..f02e98ae4 100644
--- a/apps/px4io/mixer.c
+++ b/apps/px4io/mixer.c
@@ -49,9 +49,6 @@
#include <fcntl.h>
#include <drivers/drv_pwm_output.h>
-#include <drivers/drv_hrt.h>
-
-#include <systemlib/ppm_decode.h>
#include "px4io.h"
@@ -62,21 +59,6 @@ static unsigned fmu_input_drops;
#define FMU_INPUT_DROP_LIMIT 20
/*
- * HRT periodic call used to check for control input data.
- */
-static struct hrt_call mixer_input_call;
-
-/*
- * Mixer periodic tick.
- */
-static void mixer_tick(void *arg);
-
-/*
- * Collect RC input data from the controller source(s).
- */
-static void mixer_get_rc_input(void);
-
-/*
* Update a mixer based on the current control signals.
*/
static void mixer_update(int mixer, uint16_t *inputs, int input_count);
@@ -92,20 +74,8 @@ struct mixer {
/* XXX more config here */
} mixers[IO_SERVO_COUNT];
-int
-mixer_init(void)
-{
-
-
- /* look for control data at 50Hz */
- hrt_call_every(&mixer_input_call, 1000, 20000, mixer_tick, NULL);
-
- return 0;
-}
-
-
-static void
-mixer_tick(void *arg)
+void
+mixer_tick(void)
{
uint16_t *control_values;
int control_count;
@@ -113,12 +83,6 @@ mixer_tick(void *arg)
bool should_arm;
/*
- * Start by looking for R/C control inputs.
- * This updates system_state with any control inputs received.
- */
- mixer_get_rc_input();
-
- /*
* Decide which set of inputs we're using.
*/
if (system_state.mixer_use_fmu) {
@@ -146,6 +110,7 @@ mixer_tick(void *arg)
} else {
/* we have no control input */
+ /* XXX builtin failsafe would activate here */
control_count = 0;
}
@@ -153,7 +118,7 @@ mixer_tick(void *arg)
* Tickle each mixer, if we have control data.
*/
if (control_count > 0) {
- for (i = 0; i < PX4IO_OUTPUT_CHANNELS; i++) {
+ for (i = 0; i < IO_SERVO_COUNT; i++) {
mixer_update(i, control_values, control_count);
/*
@@ -167,8 +132,7 @@ mixer_tick(void *arg)
/*
* Decide whether the servos should be armed right now.
*/
-
- should_arm = system_state.armed && system_state.arm_ok && (control_count > 0) && system_state.mixer_use_fmu;
+ should_arm = system_state.armed && system_state.arm_ok && (control_count > 0);
if (should_arm && !mixer_servos_armed) {
/* need to arm, but not armed */
up_pwm_servo_arm(true);
@@ -191,21 +155,3 @@ mixer_update(int mixer, uint16_t *inputs, int input_count)
mixers[mixer].current_value = 0;
}
}
-
-static void
-mixer_get_rc_input(void)
-{
-
- /* if we haven't seen any new data in 200ms, assume we have lost input and tell FMU */
- if ((hrt_absolute_time() - ppm_last_valid_decode) > 200000) {
- system_state.rc_channels = 0;
- system_state.fmu_report_due = true;
- return;
- }
-
- /* otherwise, copy channel data */
- system_state.rc_channels = ppm_decoded_channels;
- for (unsigned i = 0; i < ppm_decoded_channels; i++)
- system_state.rc_channel_data[i] = ppm_buffer[i];
- system_state.fmu_report_due = true;
-}
diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h
index 660eed12b..c704b1201 100644
--- a/apps/px4io/protocol.h
+++ b/apps/px4io/protocol.h
@@ -62,11 +62,7 @@ struct px4io_config {
uint16_t f2i_config_magic;
#define F2I_CONFIG_MAGIC 0x6366
- uint8_t serial_rx_mode;
-#define RX_MODE_PPM_ONLY 0
-#define RX_MODE_DSM_10BIT 1
-#define RX_MODE_DSM_11BIT 2
-#define RX_MODE_FUTABA_SBUS 3
+ /* XXX currently nothing here */
};
/* report from IO to FMU */
diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c
index dec2cdde6..a3ac9e3e7 100644
--- a/apps/px4io/px4io.c
+++ b/apps/px4io/px4io.c
@@ -44,6 +44,7 @@
#include <debug.h>
#include <stdlib.h>
#include <errno.h>
+#include <string.h>
#include <nuttx/clock.h>
@@ -55,37 +56,17 @@
__EXPORT int user_start(int argc, char *argv[]);
struct sys_state_s system_state;
-int gpio_fd;
-
-static const char cursor[] = {'|', '/', '-', '\\'};
-
-static struct hrt_call timer_tick_call;
-volatile int timers[TIMER_NUM_TIMERS];
-static void timer_tick(void *arg);
int user_start(int argc, char *argv[])
{
- int cycle = 0;
- bool heartbeat = false;
- bool failsafe = false;
+ /* reset all to zero */
+ memset(&system_state, 0, sizeof(system_state));
/* configure the high-resolution time/callout interface */
hrt_init();
- /* init the FMU and receiver links */
- comms_init();
-
- /* configure the first 8 PWM outputs (i.e. all of them) */
- /* note, must do this after comms init to steal back PA0, which is CTS otherwise */
- up_pwm_servo_init(0xff);
-
/* print some startup info */
lib_lowprintf("\nPX4IO: starting\n");
- struct mallinfo minfo = mallinfo();
- lib_lowprintf("free %u largest %u\n", minfo.mxordblk, minfo.fordblks);
-
- /* start the software timer service */
- hrt_call_every(&timer_tick_call, 1000, 1000, timer_tick, NULL);
/* default all the LEDs to off while we start */
LED_AMBER(false);
@@ -95,64 +76,23 @@ int user_start(int argc, char *argv[])
/* turn on servo power */
POWER_SERVO(true);
- /* start the mixer */
- mixer_init();
-
/* start the safety switch handler */
safety_init();
- /* set up some timers for the main loop */
- timers[TIMER_BLINK_BLUE] = 250; /* heartbeat blink @ 2Hz */
- timers[TIMER_STATUS_PRINT] = 1000; /* print status message @ 1Hz */
-
- /*
- * Main loop servicing communication with FMU
- */
- while(true) {
-
- /* check for communication from FMU, send updates */
- comms_check();
-
- /* blink the heartbeat LED */
- if (timers[TIMER_BLINK_BLUE] == 0) {
- timers[TIMER_BLINK_BLUE] = 250;
- LED_BLUE(heartbeat = !heartbeat);
- }
-
- /* blink the failsafe LED if we don't have FMU input */
- if (!system_state.mixer_use_fmu) {
- if (timers[TIMER_BLINK_AMBER] == 0) {
- timers[TIMER_BLINK_AMBER] = 125;
- failsafe = !failsafe;
- }
- } else {
- failsafe = false;
- }
- LED_AMBER(failsafe);
-
- /* print some simple status */
- if (timers[TIMER_STATUS_PRINT] == 0) {
- timers[TIMER_STATUS_PRINT] = 1000;
- lib_lowprintf("%c %s | %s | %s | %s | C=%d F=%d B=%d \r",
- cursor[cycle++ & 3],
- (system_state.arm_ok ? "FMU_ARMED" : "FMU_SAFE"),
- (system_state.armed ? "ARMED" : "SAFE"),
- (system_state.rc_channels ? "RC OK" : "NO RC"),
- (system_state.mixer_use_fmu ? "FMU OK" : "NO FMU"),
- system_state.rc_channels,
- frame_rx, frame_bad
- );
- }
- }
-
- /* Should never reach here */
- return ERROR;
-}
-
-static void
-timer_tick(void *arg)
-{
- for (unsigned i = 0; i < TIMER_NUM_TIMERS; i++)
- if (timers[i] > 0)
- timers[i]--;
-}
+ /* configure the first 8 PWM outputs (i.e. all of them) */
+ up_pwm_servo_init(0xff);
+
+ /* start the flight control signal handler */
+ task_create("FCon",
+ SCHED_PRIORITY_DEFAULT,
+ 1024,
+ (main_t)controls_main,
+ NULL);
+
+
+ struct mallinfo minfo = mallinfo();
+ lib_lowprintf("free %u largest %u\n", minfo.mxordblk, minfo.fordblks);
+
+ /* we're done here, go run the communications loop */
+ comms_main();
+} \ No newline at end of file
diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h
index f50e29252..45b7cf847 100644
--- a/apps/px4io/px4io.h
+++ b/apps/px4io/px4io.h
@@ -56,10 +56,11 @@
* Debug logging
*/
-#if 1
-# define debug(fmt, ...) lib_lowprintf(fmt "\n", ##args)
+#ifdef DEBUG
+# include <debug.h>
+# define debug(fmt, args...) lib_lowprintf(fmt "\n", ##args)
#else
-# define debug(fmt, ...) do {} while(0)
+# define debug(fmt, args...) do {} while(0)
#endif
/*
@@ -68,14 +69,15 @@
struct sys_state_s
{
- bool armed; /* IO armed */
- bool arm_ok; /* FMU says OK to arm */
+ bool armed; /* IO armed */
+ bool arm_ok; /* FMU says OK to arm */
/*
* Data from the remote control input(s)
*/
- int rc_channels;
+ unsigned rc_channels;
uint16_t rc_channel_data[PX4IO_INPUT_CHANNELS];
+ uint64_t rc_channels_timestamp;
/*
* Control signals from FMU.
@@ -146,7 +148,7 @@ extern volatile int timers[TIMER_NUM_TIMERS];
/*
* Mixer
*/
-extern int mixer_init(void);
+extern void mixer_tick(void);
/*
* Safety switch/LED.
@@ -156,16 +158,16 @@ extern void safety_init(void);
/*
* FMU communications
*/
-extern void comms_init(void);
-extern void comms_check(void);
+extern void comms_main(void) __attribute__((noreturn));
/*
- * Serial receiver decoders.
+ * R/C receiver handling.
*/
-extern void dsm_init(unsigned mode);
-extern void dsm_input(int fd);
-extern void sbus_init(unsigned mode);
-extern void sbus_input(int fd);
+extern void controls_main(void);
+extern int dsm_init(const char *device);
+extern bool dsm_input(void);
+extern int sbus_init(const char *device);
+extern bool sbus_input(void);
/*
* Assertion codes
diff --git a/apps/px4io/safety.c b/apps/px4io/safety.c
index 24fc9951a..60d20905a 100644
--- a/apps/px4io/safety.c
+++ b/apps/px4io/safety.c
@@ -51,6 +51,8 @@
#include "px4io.h"
static struct hrt_call arming_call;
+static struct hrt_call heartbeat_call;
+static struct hrt_call failsafe_call;
/*
* Count the number of times in a row that we see the arming button
@@ -58,18 +60,36 @@ static struct hrt_call arming_call;
*/
static unsigned counter;
+/*
+ * Define the various LED flash sequences for each system state.
+ */
+#define LED_PATTERN_SAFE 0xffff // always on
+#define LED_PATTERN_FMU_ARMED 0x4444 // slow blinking
+#define LED_PATTERN_IO_ARMED 0x5555 // fast blinking
+#define LED_PATTERN_IO_FMU_ARMED 0x5050 // long off then double blink
+
+static unsigned blink_counter = 0;
+
#define ARM_COUNTER_THRESHOLD 10
#define DISARM_COUNTER_THRESHOLD 2
-static bool safety_led_state;
static bool safety_button_pressed;
+
static void safety_check_button(void *arg);
+static void heartbeat_blink(void *arg);
+static void failsafe_blink(void *arg);
void
safety_init(void)
{
/* arrange for the button handler to be called at 10Hz */
hrt_call_every(&arming_call, 1000, 100000, safety_check_button, NULL);
+
+ /* arrange for the heartbeat handler to be called at 4Hz */
+ hrt_call_every(&heartbeat_call, 1000, 250000, heartbeat_blink, NULL);
+
+ /* arrange for the failsafe blinker to be called at 8Hz */
+ hrt_call_every(&failsafe_call, 1000, 125000, failsafe_blink, NULL);
}
static void
@@ -109,11 +129,46 @@ safety_check_button(void *arg)
counter = 0;
}
- /* when armed, toggle the LED; when safe, leave it on */
+ /* Select the appropriate LED flash pattern depending on the current IO/FMU arm state */
+ uint16_t pattern = LED_PATTERN_SAFE;
if (system_state.armed) {
- safety_led_state = !safety_led_state;
- } else {
- safety_led_state = true;
+ if (system_state.arm_ok) {
+ pattern = LED_PATTERN_IO_FMU_ARMED;
+ } else {
+ pattern = LED_PATTERN_IO_ARMED;
+ }
+ } else if (system_state.arm_ok) {
+ pattern = LED_PATTERN_FMU_ARMED;
+ }
+
+ /* Turn the LED on if we have a 1 at the current bit position */
+ LED_SAFETY(pattern & (1 << blink_counter++));
+
+ if (blink_counter > 15) {
+ blink_counter = 0;
}
- LED_SAFETY(safety_led_state);
}
+
+static void
+heartbeat_blink(void *arg)
+{
+ static bool heartbeat = false;
+
+ /* XXX add flags here that need to be frobbed by various loops */
+
+ LED_BLUE(heartbeat = !heartbeat);
+}
+
+static void
+failsafe_blink(void *arg)
+{
+ static bool failsafe = false;
+
+ /* blink the failsafe LED if we don't have FMU input */
+ if (!system_state.mixer_use_fmu) {
+ failsafe = !failsafe;
+ } else {
+ failsafe = false;
+ }
+ LED_AMBER(failsafe);
+} \ No newline at end of file
diff --git a/apps/px4io/sbus.c b/apps/px4io/sbus.c
index e363a0a78..a8f628a84 100644
--- a/apps/px4io/sbus.c
+++ b/apps/px4io/sbus.c
@@ -41,18 +41,212 @@
#include <fcntl.h>
#include <unistd.h>
+#include <termios.h>
+
+#include <systemlib/ppm_decode.h>
#include <drivers/drv_hrt.h>
+#define DEBUG
#include "px4io.h"
#include "protocol.h"
+#include "debug.h"
+
+#define SBUS_FRAME_SIZE 25
+#define SBUS_INPUT_CHANNELS 16
+
+static int sbus_fd = -1;
+
+static hrt_abstime last_rx_time;
+static hrt_abstime last_frame_time;
+
+static uint8_t frame[SBUS_FRAME_SIZE];
-void
-sbus_init(unsigned mode)
+static unsigned partial_frame_count;
+
+unsigned sbus_frame_drops;
+
+static void sbus_decode(hrt_abstime frame_time);
+
+int
+sbus_init(const char *device)
{
+ if (sbus_fd < 0)
+ sbus_fd = open(device, O_RDONLY);
+
+ if (sbus_fd >= 0) {
+ struct termios t;
+
+ /* 100000bps, even parity, two stop bits */
+ tcgetattr(sbus_fd, &t);
+ cfsetspeed(&t, 100000);
+ t.c_cflag |= (CSTOPB | PARENB);
+ tcsetattr(sbus_fd, TCSANOW, &t);
+
+ /* initialise the decoder */
+ partial_frame_count = 0;
+ last_rx_time = hrt_absolute_time();
+
+ debug("Sbus: ready");
+ } else {
+ debug("Sbus: open failed");
+ }
+
+ return sbus_fd;
+}
+
+bool
+sbus_input(void)
+{
+ ssize_t ret;
+ hrt_abstime now;
+
+ /*
+ * The S.bus protocol doesn't provide reliable framing,
+ * so we detect frame boundaries by the inter-frame delay.
+ *
+ * The minimum frame spacing is 7ms; with 25 bytes at 100000bps
+ * frame transmission time is ~2ms.
+ *
+ * We expect to only be called when bytes arrive for processing,
+ * and if an interval of more than 3ms passes between calls,
+ * the first byte we read will be the first byte of a frame.
+ *
+ * In the case where byte(s) are dropped from a frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
+ */
+ now = hrt_absolute_time();
+ if ((now - last_rx_time) > 3000) {
+ if (partial_frame_count > 0) {
+ sbus_frame_drops++;
+ partial_frame_count = 0;
+ }
+ }
+
+ /*
+ * Fetch bytes, but no more than we would need to complete
+ * the current frame.
+ */
+ ret = read(sbus_fd, &frame[partial_frame_count], SBUS_FRAME_SIZE - partial_frame_count);
+
+ /* if the read failed for any reason, just give up here */
+ if (ret < 1)
+ goto out;
+ last_rx_time = now;
+
+ /*
+ * Add bytes to the current frame
+ */
+ partial_frame_count += ret;
+
+ /*
+ * If we don't have a full frame, return
+ */
+ if (partial_frame_count < SBUS_FRAME_SIZE)
+ goto out;
+
+ /*
+ * Great, it looks like we might have a frame. Go ahead and
+ * decode it.
+ */
+ sbus_decode(now);
+ partial_frame_count = 0;
+
+out:
+ /*
+ * If we have seen a frame in the last 200ms, we consider ourselves 'locked'
+ */
+ return (now - last_frame_time) < 200000;
}
-void
-sbus_input(int fd)
+/*
+ * S.bus decoder matrix.
+ *
+ * Each channel value can come from up to 3 input bytes. Each row in the
+ * matrix describes up to three bytes, and each entry gives:
+ *
+ * - byte offset in the data portion of the frame
+ * - right shift applied to the data byte
+ * - mask for the data byte
+ * - left shift applied to the result into the channel value
+ */
+struct sbus_bit_pick {
+ uint8_t byte;
+ uint8_t rshift;
+ uint8_t mask;
+ uint8_t lshift;
+};
+static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
+/* 0 */ { { 0, 0, 0xff, 0},{ 1, 0, 0x07, 8},{ 0, 0, 0x00, 0} },
+/* 1 */ { { 1, 3, 0x1f, 0},{ 2, 0, 0x3f, 5},{ 0, 0, 0x00, 0} },
+/* 2 */ { { 2, 6, 0x03, 0},{ 3, 0, 0xff, 2},{ 4, 0, 0x01, 10} },
+/* 3 */ { { 4, 1, 0x7f, 0},{ 5, 0, 0x0f, 7},{ 0, 0, 0x00, 0} },
+/* 4 */ { { 5, 4, 0x0f, 0},{ 6, 0, 0x7f, 4},{ 0, 0, 0x00, 0} },
+/* 5 */ { { 6, 7, 0x01, 0},{ 7, 0, 0xff, 1},{ 8, 0, 0x03, 9} },
+/* 6 */ { { 8, 2, 0x3f, 0},{ 9, 0, 0x1f, 6},{ 0, 0, 0x00, 0} },
+/* 7 */ { { 9, 5, 0x07, 0},{10, 0, 0xff, 3},{ 0, 0, 0x00, 0} },
+/* 8 */ { {11, 0, 0xff, 0},{12, 0, 0x07, 8},{ 0, 0, 0x00, 0} },
+/* 9 */ { {12, 3, 0x1f, 0},{13, 0, 0x3f, 5},{ 0, 0, 0x00, 0} },
+/* 10 */ { {13, 6, 0x03, 0},{14, 0, 0xff, 2},{15, 0, 0x01, 10} },
+/* 11 */ { {15, 1, 0x7f, 0},{16, 0, 0x0f, 7},{ 0, 0, 0x00, 0} },
+/* 12 */ { {16, 4, 0x0f, 0},{17, 0, 0x7f, 4},{ 0, 0, 0x00, 0} },
+/* 13 */ { {17, 7, 0x01, 0},{18, 0, 0xff, 1},{19, 0, 0x03, 9} },
+/* 14 */ { {19, 2, 0x3f, 0},{20, 0, 0x1f, 6},{ 0, 0, 0x00, 0} },
+/* 15 */ { {20, 5, 0x07, 0},{21, 0, 0xff, 3},{ 0, 0, 0x00, 0} }
+};
+
+static void
+sbus_decode(hrt_abstime frame_time)
{
+ /* check frame boundary markers to avoid out-of-sync cases */
+ if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
+ sbus_frame_drops++;
+ return;
+ }
+
+ /* if the failsafe bit is set, we consider the frame invalid */
+ if (frame[23] & (1 << 4)) {
+ return;
+ }
+
+ /* we have received something we think is a frame */
+ last_frame_time = frame_time;
+
+ unsigned chancount = (PX4IO_INPUT_CHANNELS > SBUS_INPUT_CHANNELS) ?
+ SBUS_INPUT_CHANNELS : PX4IO_INPUT_CHANNELS;
+
+ /* use the decoder matrix to extract channel data */
+ for (unsigned channel = 0; channel < chancount; channel++) {
+ unsigned value = 0;
+
+ for (unsigned pick = 0; pick < 3; pick++) {
+ const struct sbus_bit_pick *decode = &sbus_decoder[channel][pick];
+
+ if (decode->mask != 0) {
+ unsigned piece = frame[1 + decode->byte];
+ piece >>= decode->rshift;
+ piece &= decode->mask;
+ piece <<= decode->lshift;
+
+ value |= piece;
+ }
+ }
+ /* convert 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
+ system_state.rc_channel_data[channel] = (value / 2) + 998;
+ }
+
+ if (PX4IO_INPUT_CHANNELS >= 18) {
+ chancount = 18;
+ /* XXX decode the two switch channels */
+ }
+
+ /* note the number of channels decoded */
+ system_state.rc_channels = chancount;
+
+ /* and note that we have received data from the R/C controller */
+ system_state.rc_channels_timestamp = frame_time;
+
+ /* trigger an immediate report to the FMU */
+ system_state.fmu_report_due = true;
}
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index 466284a1b..07a9015fe 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -1147,7 +1147,7 @@ Sensors::start()
_sensors_task = task_spawn("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 6000, /* XXX may be excesssive */
+ 2048,
(main_t)&Sensors::task_main_trampoline,
nullptr);
diff --git a/apps/systemcmds/bl_update/bl_update.c b/apps/systemcmds/bl_update/bl_update.c
index 745f76852..45715b791 100644
--- a/apps/systemcmds/bl_update/bl_update.c
+++ b/apps/systemcmds/bl_update/bl_update.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/apps/systemcmds/boardinfo/boardinfo.c b/apps/systemcmds/boardinfo/boardinfo.c
index 2328ebdb2..fb8b07ef4 100644
--- a/apps/systemcmds/boardinfo/boardinfo.c
+++ b/apps/systemcmds/boardinfo/boardinfo.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/apps/systemcmds/delay_test/Makefile b/apps/systemcmds/delay_test/Makefile
new file mode 100644
index 000000000..d30fcba27
--- /dev/null
+++ b/apps/systemcmds/delay_test/Makefile
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Delay test
+#
+
+APPNAME = delay_test
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 2048
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/systemcmds/delay_test/delay_test.c b/apps/systemcmds/delay_test/delay_test.c
new file mode 100644
index 000000000..51cce38fc
--- /dev/null
+++ b/apps/systemcmds/delay_test/delay_test.c
@@ -0,0 +1,160 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file delay_test.c
+ *
+ * Simple but effective delay test using leds and a scope to measure
+ * communication delays end-to-end accurately.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <poll.h>
+#include <string.h>
+
+#include <systemlib/err.h>
+
+#include <drivers/drv_led.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vehicle_command.h>
+
+__EXPORT int delay_test_main(int argc, char *argv[]);
+static int led_on(int leds, int led);
+static int led_off(int leds, int led);
+
+int delay_test_main(int argc, char *argv[])
+{
+ bool vicon_msg = false;
+ bool command_msg = false;
+
+ if (argc > 1 && !strcmp(argv[1], "--help")) {
+ warnx("usage: delay_test [vicon] [command]\n");
+ exit(1);
+ }
+
+ if (argc > 1 && !strcmp(argv[1], "vicon")) {
+ vicon_msg = true;
+ }
+
+ if (argc > 1 && !strcmp(argv[1], "command")) {
+ command_msg = true;
+ }
+
+ int buzzer = open("/dev/tone_alarm", O_WRONLY);
+ int leds = open(LED_DEVICE_PATH, 0);
+
+ /* prepare use of amber led */
+ led_off(leds, LED_AMBER);
+
+ int topic;
+
+ /* subscribe to topic */
+ if (vicon_msg) {
+ topic = orb_subscribe(ORB_ID(vehicle_vicon_position));
+ } else if (command_msg) {
+ topic = orb_subscribe(ORB_ID(vehicle_command));
+ } else {
+ errx(1, "No topic selected for delay test, use --help for a list of topics.");
+ }
+
+ const int testcount = 20;
+
+ warnx("running %d iterations..\n", testcount);
+
+ struct pollfd fds[1];
+ fds[0].fd = topic;
+ fds[0].events = POLLIN;
+
+ /* display and sound error */
+ for (int i = 0; i < testcount; i++)
+ {
+ /* wait for topic */
+ int ret = poll(&fds[0], 1, 2000);
+
+ /* this would be bad... */
+ if (ret < 0) {
+ warnx("poll error %d", errno);
+ usleep(1000000);
+ continue;
+ }
+
+ /* do we have a topic update? */
+ if (fds[0].revents & POLLIN) {
+
+ /* copy object to disable poll ready state */
+ if (vicon_msg) {
+ struct vehicle_vicon_position_s vicon_position;
+ orb_copy(ORB_ID(vehicle_vicon_position), topic, &vicon_position);
+ } else if (command_msg) {
+ struct vehicle_command_s vehicle_command;
+ orb_copy(ORB_ID(vehicle_command), topic, &vehicle_command);
+ }
+
+ led_on(leds, LED_AMBER);
+ ioctl(buzzer, TONE_SET_ALARM, 4);
+ /* keep led on for 50 ms to make it barely visible */
+ usleep(50000);
+ led_off(leds, LED_AMBER);
+ }
+ }
+
+ /* stop alarm */
+ ioctl(buzzer, TONE_SET_ALARM, 0);
+
+ /* switch on leds */
+ led_on(leds, LED_BLUE);
+ led_on(leds, LED_AMBER);
+
+ exit(0);
+}
+
+static int led_off(int leds, int led)
+{
+ return ioctl(leds, LED_OFF, led);
+}
+
+static int led_on(int leds, int led)
+{
+ return ioctl(leds, LED_ON, led);
+} \ No newline at end of file
diff --git a/apps/systemcmds/perf/perf.c b/apps/systemcmds/perf/perf.c
index 72406e9c7..ced942fd6 100644
--- a/apps/systemcmds/perf/perf.c
+++ b/apps/systemcmds/perf/perf.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 Lorenz Meier. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -13,7 +12,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
+ * 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
diff --git a/apps/uORB/topics/actuator_controls_effective.h b/apps/uORB/topics/actuator_controls_effective.h
index 3c72e4cb7..aad2c4d9b 100644
--- a/apps/uORB/topics/actuator_controls_effective.h
+++ b/apps/uORB/topics/actuator_controls_effective.h
@@ -48,13 +48,14 @@
#include <stdint.h>
#include "../uORB.h"
+#include "actuator_controls.h"
-#define NUM_ACTUATOR_CONTROLS 8
-#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
+#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
+#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
struct actuator_controls_effective_s {
uint64_t timestamp;
- float control_effective[NUM_ACTUATOR_CONTROLS];
+ float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
};
/* actuator control sets; this list can be expanded as more controllers emerge */
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
index c42ea36eb..754ca44e1 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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"
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h
index 9420ee62f..37d021095 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h
@@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Mon Nov 26 18:29:46 2012"
+#define MAVLINK_BUILD_DATE "Sat Dec 1 02:05:58 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H
diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h
index cce983c05..06f4ed711 100644
--- a/mavlink/include/mavlink/v1.0/common/common.h
+++ b/mavlink/include/mavlink/v1.0/common/common.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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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"
@@ -484,6 +484,9 @@ enum MAV_SEVERITY
#include "./mavlink_msg_vision_speed_estimate.h"
#include "./mavlink_msg_vicon_position_estimate.h"
#include "./mavlink_msg_highres_imu.h"
+#include "./mavlink_msg_file_transfer_start.h"
+#include "./mavlink_msg_file_transfer_dir_list.h"
+#include "./mavlink_msg_file_transfer_res.h"
#include "./mavlink_msg_battery_status.h"
#include "./mavlink_msg_setpoint_8dof.h"
#include "./mavlink_msg_setpoint_6dof.h"
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
new file mode 100644
index 000000000..27f5a91db
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
@@ -0,0 +1,182 @@
+// MESSAGE FILE_TRANSFER_DIR_LIST PACKING
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111
+
+typedef struct __mavlink_file_transfer_dir_list_t
+{
+ uint64_t transfer_uid; ///< Unique transfer ID
+ char dir_path[240]; ///< Directory path to list
+ uint8_t flags; ///< RESERVED
+} mavlink_file_transfer_dir_list_t;
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249
+#define MAVLINK_MSG_ID_111_LEN 249
+
+#define MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_DIR_PATH_LEN 240
+
+#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST { \
+ "FILE_TRANSFER_DIR_LIST", \
+ 3, \
+ { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_dir_list_t, transfer_uid) }, \
+ { "dir_path", NULL, MAVLINK_TYPE_CHAR, 240, 8, offsetof(mavlink_file_transfer_dir_list_t, dir_path) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 248, offsetof(mavlink_file_transfer_dir_list_t, flags) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a file_transfer_dir_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 transfer_uid Unique transfer ID
+ * @param dir_path Directory path to list
+ * @param flags RESERVED
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t transfer_uid, const char *dir_path, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[249];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 248, flags);
+ _mav_put_char_array(buf, 8, dir_path, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249);
+#else
+ mavlink_file_transfer_dir_list_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST;
+ return mavlink_finalize_message(msg, system_id, component_id, 249, 93);
+}
+
+/**
+ * @brief Pack a file_transfer_dir_list message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param transfer_uid Unique transfer ID
+ * @param dir_path Directory path to list
+ * @param flags RESERVED
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t transfer_uid,const char *dir_path,uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[249];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 248, flags);
+ _mav_put_char_array(buf, 8, dir_path, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249);
+#else
+ mavlink_file_transfer_dir_list_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 249, 93);
+}
+
+/**
+ * @brief Encode a file_transfer_dir_list struct into a message
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param file_transfer_dir_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
+{
+ return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
+}
+
+/**
+ * @brief Send a file_transfer_dir_list message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param transfer_uid Unique transfer ID
+ * @param dir_path Directory path to list
+ * @param flags RESERVED
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[249];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 248, flags);
+ _mav_put_char_array(buf, 8, dir_path, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, 249, 93);
+#else
+ mavlink_file_transfer_dir_list_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, 249, 93);
+#endif
+}
+
+#endif
+
+// MESSAGE FILE_TRANSFER_DIR_LIST UNPACKING
+
+
+/**
+ * @brief Get field transfer_uid from file_transfer_dir_list message
+ *
+ * @return Unique transfer ID
+ */
+static inline uint64_t mavlink_msg_file_transfer_dir_list_get_transfer_uid(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field dir_path from file_transfer_dir_list message
+ *
+ * @return Directory path to list
+ */
+static inline uint16_t mavlink_msg_file_transfer_dir_list_get_dir_path(const mavlink_message_t* msg, char *dir_path)
+{
+ return _MAV_RETURN_char_array(msg, dir_path, 240, 8);
+}
+
+/**
+ * @brief Get field flags from file_transfer_dir_list message
+ *
+ * @return RESERVED
+ */
+static inline uint8_t mavlink_msg_file_transfer_dir_list_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 248);
+}
+
+/**
+ * @brief Decode a file_transfer_dir_list message into a struct
+ *
+ * @param msg The message to decode
+ * @param file_transfer_dir_list C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_file_transfer_dir_list_decode(const mavlink_message_t* msg, mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ file_transfer_dir_list->transfer_uid = mavlink_msg_file_transfer_dir_list_get_transfer_uid(msg);
+ mavlink_msg_file_transfer_dir_list_get_dir_path(msg, file_transfer_dir_list->dir_path);
+ file_transfer_dir_list->flags = mavlink_msg_file_transfer_dir_list_get_flags(msg);
+#else
+ memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), 249);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
new file mode 100644
index 000000000..f7035ec9e
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
@@ -0,0 +1,166 @@
+// MESSAGE FILE_TRANSFER_RES PACKING
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_RES 112
+
+typedef struct __mavlink_file_transfer_res_t
+{
+ uint64_t transfer_uid; ///< Unique transfer ID
+ uint8_t result; ///< 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
+} mavlink_file_transfer_res_t;
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9
+#define MAVLINK_MSG_ID_112_LEN 9
+
+
+
+#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES { \
+ "FILE_TRANSFER_RES", \
+ 2, \
+ { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_res_t, transfer_uid) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_file_transfer_res_t, result) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a file_transfer_res 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 transfer_uid Unique transfer ID
+ * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t transfer_uid, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[9];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 8, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
+#else
+ mavlink_file_transfer_res_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES;
+ return mavlink_finalize_message(msg, system_id, component_id, 9, 124);
+}
+
+/**
+ * @brief Pack a file_transfer_res message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param transfer_uid Unique transfer ID
+ * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t transfer_uid,uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[9];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 8, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
+#else
+ mavlink_file_transfer_res_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 124);
+}
+
+/**
+ * @brief Encode a file_transfer_res struct into a message
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param file_transfer_res C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res)
+{
+ return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
+}
+
+/**
+ * @brief Send a file_transfer_res message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param transfer_uid Unique transfer ID
+ * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[9];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 8, result);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, 9, 124);
+#else
+ mavlink_file_transfer_res_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.result = result;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, 9, 124);
+#endif
+}
+
+#endif
+
+// MESSAGE FILE_TRANSFER_RES UNPACKING
+
+
+/**
+ * @brief Get field transfer_uid from file_transfer_res message
+ *
+ * @return Unique transfer ID
+ */
+static inline uint64_t mavlink_msg_file_transfer_res_get_transfer_uid(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field result from file_transfer_res message
+ *
+ * @return 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
+ */
+static inline uint8_t mavlink_msg_file_transfer_res_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Decode a file_transfer_res message into a struct
+ *
+ * @param msg The message to decode
+ * @param file_transfer_res C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_file_transfer_res_decode(const mavlink_message_t* msg, mavlink_file_transfer_res_t* file_transfer_res)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ file_transfer_res->transfer_uid = mavlink_msg_file_transfer_res_get_transfer_uid(msg);
+ file_transfer_res->result = mavlink_msg_file_transfer_res_get_result(msg);
+#else
+ memcpy(file_transfer_res, _MAV_PAYLOAD(msg), 9);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
new file mode 100644
index 000000000..5eaa9b220
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
@@ -0,0 +1,226 @@
+// MESSAGE FILE_TRANSFER_START PACKING
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_START 110
+
+typedef struct __mavlink_file_transfer_start_t
+{
+ uint64_t transfer_uid; ///< Unique transfer ID
+ uint32_t file_size; ///< File size in bytes
+ char dest_path[240]; ///< Destination path
+ uint8_t direction; ///< Transfer direction: 0: from requester, 1: to requester
+ uint8_t flags; ///< RESERVED
+} mavlink_file_transfer_start_t;
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254
+#define MAVLINK_MSG_ID_110_LEN 254
+
+#define MAVLINK_MSG_FILE_TRANSFER_START_FIELD_DEST_PATH_LEN 240
+
+#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START { \
+ "FILE_TRANSFER_START", \
+ 5, \
+ { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_start_t, transfer_uid) }, \
+ { "file_size", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_file_transfer_start_t, file_size) }, \
+ { "dest_path", NULL, MAVLINK_TYPE_CHAR, 240, 12, offsetof(mavlink_file_transfer_start_t, dest_path) }, \
+ { "direction", NULL, MAVLINK_TYPE_UINT8_T, 0, 252, offsetof(mavlink_file_transfer_start_t, direction) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 253, offsetof(mavlink_file_transfer_start_t, flags) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a file_transfer_start 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 transfer_uid Unique transfer ID
+ * @param dest_path Destination path
+ * @param direction Transfer direction: 0: from requester, 1: to requester
+ * @param file_size File size in bytes
+ * @param flags RESERVED
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[254];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint32_t(buf, 8, file_size);
+ _mav_put_uint8_t(buf, 252, direction);
+ _mav_put_uint8_t(buf, 253, flags);
+ _mav_put_char_array(buf, 12, dest_path, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254);
+#else
+ mavlink_file_transfer_start_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.file_size = file_size;
+ packet.direction = direction;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START;
+ return mavlink_finalize_message(msg, system_id, component_id, 254, 235);
+}
+
+/**
+ * @brief Pack a file_transfer_start message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message was sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param transfer_uid Unique transfer ID
+ * @param dest_path Destination path
+ * @param direction Transfer direction: 0: from requester, 1: to requester
+ * @param file_size File size in bytes
+ * @param flags RESERVED
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t transfer_uid,const char *dest_path,uint8_t direction,uint32_t file_size,uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[254];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint32_t(buf, 8, file_size);
+ _mav_put_uint8_t(buf, 252, direction);
+ _mav_put_uint8_t(buf, 253, flags);
+ _mav_put_char_array(buf, 12, dest_path, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254);
+#else
+ mavlink_file_transfer_start_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.file_size = file_size;
+ packet.direction = direction;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 254, 235);
+}
+
+/**
+ * @brief Encode a file_transfer_start struct into a message
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param file_transfer_start C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start)
+{
+ return mavlink_msg_file_transfer_start_pack(system_id, component_id, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags);
+}
+
+/**
+ * @brief Send a file_transfer_start message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param transfer_uid Unique transfer ID
+ * @param dest_path Destination path
+ * @param direction Transfer direction: 0: from requester, 1: to requester
+ * @param file_size File size in bytes
+ * @param flags RESERVED
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[254];
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint32_t(buf, 8, file_size);
+ _mav_put_uint8_t(buf, 252, direction);
+ _mav_put_uint8_t(buf, 253, flags);
+ _mav_put_char_array(buf, 12, dest_path, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, 254, 235);
+#else
+ mavlink_file_transfer_start_t packet;
+ packet.transfer_uid = transfer_uid;
+ packet.file_size = file_size;
+ packet.direction = direction;
+ packet.flags = flags;
+ mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, 254, 235);
+#endif
+}
+
+#endif
+
+// MESSAGE FILE_TRANSFER_START UNPACKING
+
+
+/**
+ * @brief Get field transfer_uid from file_transfer_start message
+ *
+ * @return Unique transfer ID
+ */
+static inline uint64_t mavlink_msg_file_transfer_start_get_transfer_uid(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field dest_path from file_transfer_start message
+ *
+ * @return Destination path
+ */
+static inline uint16_t mavlink_msg_file_transfer_start_get_dest_path(const mavlink_message_t* msg, char *dest_path)
+{
+ return _MAV_RETURN_char_array(msg, dest_path, 240, 12);
+}
+
+/**
+ * @brief Get field direction from file_transfer_start message
+ *
+ * @return Transfer direction: 0: from requester, 1: to requester
+ */
+static inline uint8_t mavlink_msg_file_transfer_start_get_direction(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 252);
+}
+
+/**
+ * @brief Get field file_size from file_transfer_start message
+ *
+ * @return File size in bytes
+ */
+static inline uint32_t mavlink_msg_file_transfer_start_get_file_size(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field flags from file_transfer_start message
+ *
+ * @return RESERVED
+ */
+static inline uint8_t mavlink_msg_file_transfer_start_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 253);
+}
+
+/**
+ * @brief Decode a file_transfer_start message into a struct
+ *
+ * @param msg The message to decode
+ * @param file_transfer_start C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_file_transfer_start_decode(const mavlink_message_t* msg, mavlink_file_transfer_start_t* file_transfer_start)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ file_transfer_start->transfer_uid = mavlink_msg_file_transfer_start_get_transfer_uid(msg);
+ file_transfer_start->file_size = mavlink_msg_file_transfer_start_get_file_size(msg);
+ mavlink_msg_file_transfer_start_get_dest_path(msg, file_transfer_start->dest_path);
+ file_transfer_start->direction = mavlink_msg_file_transfer_start_get_direction(msg);
+ file_transfer_start->flags = mavlink_msg_file_transfer_start_get_flags(msg);
+#else
+ memcpy(file_transfer_start, _MAV_PAYLOAD(msg), 254);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h
index ae133521d..ef70550c0 100644
--- a/mavlink/include/mavlink/v1.0/common/testsuite.h
+++ b/mavlink/include/mavlink/v1.0/common/testsuite.h
@@ -3886,6 +3886,149 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_file_transfer_start(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_file_transfer_start_t packet_in = {
+ 93372036854775807ULL,
+ 963497880,
+ "MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",
+ 249,
+ 60,
+ };
+ mavlink_file_transfer_start_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.transfer_uid = packet_in.transfer_uid;
+ packet1.file_size = packet_in.file_size;
+ packet1.direction = packet_in.direction;
+ packet1.flags = packet_in.flags;
+
+ mav_array_memcpy(packet1.dest_path, packet_in.dest_path, sizeof(char)*240);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_start_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_file_transfer_start_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_start_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
+ mavlink_msg_file_transfer_start_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_start_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
+ mavlink_msg_file_transfer_start_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_file_transfer_start_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_start_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
+ mavlink_msg_file_transfer_start_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_file_transfer_dir_list(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_file_transfer_dir_list_t packet_in = {
+ 93372036854775807ULL,
+ "IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",
+ 237,
+ };
+ mavlink_file_transfer_dir_list_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.transfer_uid = packet_in.transfer_uid;
+ packet1.flags = packet_in.flags;
+
+ mav_array_memcpy(packet1.dir_path, packet_in.dir_path, sizeof(char)*240);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_dir_list_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.dir_path , packet1.flags );
+ mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_dir_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.dir_path , packet1.flags );
+ mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_file_transfer_dir_list_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_dir_list_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.dir_path , packet1.flags );
+ mavlink_msg_file_transfer_dir_list_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_file_transfer_res(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_file_transfer_res_t packet_in = {
+ 93372036854775807ULL,
+ 29,
+ };
+ mavlink_file_transfer_res_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.transfer_uid = packet_in.transfer_uid;
+ packet1.result = packet_in.result;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_res_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_file_transfer_res_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_res_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.result );
+ mavlink_msg_file_transfer_res_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_res_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.result );
+ mavlink_msg_file_transfer_res_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_file_transfer_res_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_res_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.result );
+ mavlink_msg_file_transfer_res_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@@ -4419,6 +4562,9 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_highres_imu(system_id, component_id, last_msg);
+ mavlink_test_file_transfer_start(system_id, component_id, last_msg);
+ mavlink_test_file_transfer_dir_list(system_id, component_id, last_msg);
+ mavlink_test_file_transfer_res(system_id, component_id, last_msg);
mavlink_test_battery_status(system_id, component_id, last_msg);
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);
diff --git a/mavlink/include/mavlink/v1.0/common/version.h b/mavlink/include/mavlink/v1.0/common/version.h
index 91eb80309..41b9416ee 100644
--- a/mavlink/include/mavlink/v1.0/common/version.h
+++ b/mavlink/include/mavlink/v1.0/common/version.h
@@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:26 2012"
+#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h b/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
index e6125469f..d53b53319 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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"
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/version.h b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
index 9a1b4f179..a64a4fae7 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/version.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
@@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:03 2012"
+#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:23 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
index b3f255991..58ec25f1a 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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"
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/version.h b/mavlink/include/mavlink/v1.0/pixhawk/version.h
index 332cd9758..6e63f4bc7 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/version.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:17 2012"
+#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:36 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
index 0d0f378ad..94270f757 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 242, 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, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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"
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/version.h b/mavlink/include/mavlink/v1.0/sensesoar/version.h
index fc6760aba..0d33c77b6 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/version.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/version.h
@@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Mon Nov 26 18:30:26 2012"
+#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index ff18d208b..0868c3cd3 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -185,11 +185,15 @@ struct up_dev_s
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (7 or 8) */
bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
+ bool iflow; /* input flow control (RTS) enabled */
+ bool oflow; /* output flow control (CTS) enabled */
uint32_t baud; /* Configured baud */
#else
const uint8_t parity; /* 0=none, 1=odd, 2=even */
const uint8_t bits; /* Number of bits (7 or 8) */
const bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
+ const bool iflow; /* input flow control (RTS) enabled */
+ const bool oflow; /* output flow control (CTS) enabled */
const uint32_t baud; /* Configured baud */
#endif
@@ -221,7 +225,7 @@ struct up_dev_s
* Private Function Prototypes
****************************************************************************/
-static void up_setspeed(struct uart_dev_s *dev);
+static void up_set_format(struct uart_dev_s *dev);
static int up_setup(struct uart_dev_s *dev);
static void up_shutdown(struct uart_dev_s *dev);
static int up_attach(struct uart_dev_s *dev);
@@ -393,6 +397,8 @@ static struct up_dev_s g_usart1priv =
.parity = CONFIG_USART1_PARITY,
.bits = CONFIG_USART1_BITS,
.stopbits2 = CONFIG_USART1_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART1_BAUD,
.apbclock = STM32_PCLK2_FREQUENCY,
.usartbase = STM32_USART1_BASE,
@@ -444,6 +450,8 @@ static struct up_dev_s g_usart2priv =
.parity = CONFIG_USART2_PARITY,
.bits = CONFIG_USART2_BITS,
.stopbits2 = CONFIG_USART2_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART2_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_USART2_BASE,
@@ -495,6 +503,8 @@ static struct up_dev_s g_usart3priv =
.parity = CONFIG_USART3_PARITY,
.bits = CONFIG_USART3_BITS,
.stopbits2 = CONFIG_USART3_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART3_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_USART3_BASE,
@@ -546,17 +556,15 @@ static struct up_dev_s g_uart4priv =
.parity = CONFIG_UART4_PARITY,
.bits = CONFIG_UART4_BITS,
.stopbits2 = CONFIG_UART4_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_UART4_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART4_BASE,
.tx_gpio = GPIO_UART4_TX,
.rx_gpio = GPIO_UART4_RX,
-#ifdef GPIO_UART4_CTS
- .cts_gpio = GPIO_UART4_CTS,
-#endif
-#ifdef GPIO_UART4_RTS
- .rts_gpio = GPIO_UART4_RTS,
-#endif
+ .cts_gpio = 0, /* flow control not supported on this port */
+ .rts_gpio = 0, /* flow control not supported on this port */
#ifdef CONFIG_UART4_RXDMA
.rxdma_channel = DMAMAP_UART4_RX,
.rxfifo = g_uart4rxfifo,
@@ -597,17 +605,15 @@ static struct up_dev_s g_uart5priv =
.parity = CONFIG_UART5_PARITY,
.bits = CONFIG_UART5_BITS,
.stopbits2 = CONFIG_UART5_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_UART5_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART5_BASE,
.tx_gpio = GPIO_UART5_TX,
.rx_gpio = GPIO_UART5_RX,
-#ifdef GPIO_UART5_CTS
- .cts_gpio = GPIO_UART5_CTS,
-#endif
-#ifdef GPIO_UART5_RTS
- .rts_gpio = GPIO_UART5_RTS,
-#endif
+ .cts_gpio = 0, /* flow control not supported on this port */
+ .rts_gpio = 0, /* flow control not supported on this port */
#ifdef CONFIG_UART5_RXDMA
.rxdma_channel = DMAMAP_UART5_RX,
.rxfifo = g_uart5rxfifo,
@@ -648,6 +654,8 @@ static struct up_dev_s g_usart6priv =
.parity = CONFIG_USART6_PARITY,
.bits = CONFIG_USART6_BITS,
.stopbits2 = CONFIG_USART6_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART6_BAUD,
.apbclock = STM32_PCLK2_FREQUENCY,
.usartbase = STM32_USART6_BASE,
@@ -812,21 +820,22 @@ static int up_dma_nextrx(struct up_dev_s *priv)
#endif
/****************************************************************************
- * Name: up_setspeed
+ * Name: up_set_format
*
* Description:
- * Set the serial line speed.
+ * Set the serial line format and speed.
*
****************************************************************************/
#ifndef CONFIG_SUPPRESS_UART_CONFIG
-static void up_setspeed(struct uart_dev_s *dev)
+static void up_set_format(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint32_t usartdiv32;
uint32_t mantissa;
uint32_t fraction;
uint32_t brr;
+ uint32_t regval;
/* Configure the USART Baud Rate. The baud rate for the receiver and
* transmitter (Rx and Tx) are both set to the same value as programmed
@@ -844,20 +853,64 @@ static void up_setspeed(struct uart_dev_s *dev)
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
*/
- usartdiv32 = priv->apbclock / (priv->baud >> 1);
+ usartdiv32 = priv->apbclock / (priv->baud >> 1);
+
+ /* The mantissa part is then */
+
+ mantissa = usartdiv32 >> 5;
+ brr = mantissa << USART_BRR_MANT_SHIFT;
+
+ /* The fractional remainder (with rounding) */
+
+ fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ brr |= fraction << USART_BRR_FRAC_SHIFT;
+ up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
+
+ /* Configure parity mode */
- /* The mantissa part is then */
+ regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
+ regval &= ~(USART_CR1_PCE|USART_CR1_PS);
- mantissa = usartdiv32 >> 5;
- brr = mantissa << USART_BRR_MANT_SHIFT;
+ if (priv->parity == 1) /* Odd parity */
+ {
+ regval |= (USART_CR1_PCE|USART_CR1_PS);
+ }
+ else if (priv->parity == 2) /* Even parity */
+ {
+ regval |= USART_CR1_PCE;
+ }
- /* The fractional remainder (with rounding) */
+ up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
+
+ /* Configure STOP bits */
+
+ regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
+ regval &= ~(USART_CR2_STOP_MASK);
+
+ if (priv->stopbits2)
+ {
+ regval |= USART_CR2_STOP2;
+ }
+ up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
+
+ /* Configure hardware flow control */
+
+ regval = up_serialin(priv, STM32_USART_CR3_OFFSET);
+ regval &= ~(USART_CR3_CTSE|USART_CR3_RTSE);
+
+ if (priv->iflow && (priv->rts_gpio != 0))
+ {
+ regval |= USART_CR3_RTSE;
+ }
+ if (priv->oflow && (priv->cts_gpio != 0))
+ {
+ regval |= USART_CR3_CTSE;
+ }
+
+ up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
- fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
- brr |= fraction << USART_BRR_FRAC_SHIFT;
- up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
}
-#endif
+#endif /* CONFIG_SUPPRESS_UART_CONFIG */
/****************************************************************************
* Name: up_setup
@@ -894,43 +947,28 @@ static int up_setup(struct uart_dev_s *dev)
}
/* Configure CR2 */
- /* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
+ /* Clear CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
- regval &= ~(USART_CR2_STOP_MASK|USART_CR2_CLKEN|USART_CR2_CPOL|
+ regval &= ~(USART_CR2_CLKEN|USART_CR2_CPOL|
USART_CR2_CPHA|USART_CR2_LBCL|USART_CR2_LBDIE);
- /* Configure STOP bits */
-
- if (priv->stopbits2)
- {
- regval |= USART_CR2_STOP2;
- }
up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
/* Configure CR1 */
- /* Clear M, PCE, PS, TE, REm and all interrupt enable bits */
+ /* Clear M, TE, REm and all interrupt enable bits */
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
- regval &= ~(USART_CR1_M|USART_CR1_PCE|USART_CR1_PS|USART_CR1_TE|
+ regval &= ~(USART_CR1_M|USART_CR1_TE|
USART_CR1_RE|USART_CR1_ALLINTS);
- /* Configure word length and parity mode */
+ /* Configure word length */
if (priv->bits == 9) /* Default: 1 start, 8 data, n stop */
{
regval |= USART_CR1_M; /* 1 start, 9 data, n stop */
}
- if (priv->parity == 1) /* Odd parity */
- {
- regval |= (USART_CR1_PCE|USART_CR1_PS);
- }
- else if (priv->parity == 2) /* Even parity */
- {
- regval |= USART_CR1_PCE;
- }
-
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
/* Configure CR3 */
@@ -943,16 +981,17 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
- /* Configure the USART Baud Rate. */
+ /* Configure the USART line format and speed. */
- up_setspeed(dev);
+ up_set_format(dev);
/* Enable Rx, Tx, and the USART */
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
-#endif
+
+#endif /* CONFIG_SUPPRESS_UART_CONFIG */
/* Set up the cached interrupt enables value */
@@ -1279,12 +1318,21 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break;
}
- /* TODO: Other termios fields are not yet returned.
- * Note that only cfsetospeed is not necessary because we have
- * knowledge that only one speed is supported.
+ cfsetispeed(termiosp, priv->baud);
+
+ /* Note that since we only support 8/9 bit modes and
+ * there is no way to report 9-bit mode, we always claim 8.
*/
- cfsetispeed(termiosp, priv->baud);
+ termiosp->c_cflag =
+ ((priv->parity != 0) ? PARENB : 0) |
+ ((priv->parity == 1) ? PARODD : 0) |
+ ((priv->stopbits2) ? CSTOPB : 0) |
+ ((priv->oflow) ? CCTS_OFLOW : 0) |
+ ((priv->iflow) ? CRTS_IFLOW : 0) |
+ CS8;
+
+ /* TODO: CCTS_IFLOW, CCTS_OFLOW */
}
break;
@@ -1298,16 +1346,48 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break;
}
- /* TODO: Handle other termios settings.
- * Note that only cfgetispeed is used besued we have knowledge
+ /* Perform some sanity checks before accepting any changes */
+
+ if (((termiosp->c_cflag & CSIZE) != CS8) ||
+ ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) ||
+ ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)))
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ if (termiosp->c_cflag & PARENB)
+ {
+ priv->parity = (termiosp->c_cflag & PARODD) ? 1 : 2;
+ }
+ else
+ {
+ priv->parity = 0;
+ }
+
+ priv->stopbits2 = (termiosp->c_cflag & CSTOPB) != 0;
+ priv->oflow = (termiosp->c_cflag & CCTS_OFLOW) != 0;
+ priv->iflow = (termiosp->c_cflag & CRTS_IFLOW) != 0;
+
+ /* Note that since there is no way to request 9-bit mode
+ * and no way to support 5/6/7-bit modes, we ignore them
+ * all here.
+ */
+
+ /* Note that only cfgetispeed is used because we have knowledge
* that only one speed is supported.
*/
priv->baud = cfgetispeed(termiosp);
- up_setspeed(dev);
+
+ /* effect the changes immediately - note that we do not implement
+ * TCSADRAIN / TCSAFLUSH
+ */
+
+ up_set_format(dev);
}
break;
-#endif
+#endif /* CONFIG_SERIAL_TERMIOS */
#ifdef CONFIG_USART_BREAKS
case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
@@ -1945,10 +2025,10 @@ void stm32_serial_dma_poll(void)
int up_putc(int ch)
{
#if CONSOLE_UART > 0
-// struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
-// uint16_t ie;
+ struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
+ uint16_t ie;
-// up_disableusartint(priv, &ie);
+ up_disableusartint(priv, &ie);
/* Check for LF */
@@ -1960,7 +2040,7 @@ int up_putc(int ch)
}
up_lowputc(ch);
-// up_restoreusartint(priv, ie);
+ up_restoreusartint(priv, ie);
#endif
return ch;
}
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 5833e3575..0959687de 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -55,7 +55,7 @@ CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/bl_update
CONFIGURED_APPS += systemcmds/preflight_check
-#CONFIGURED_APPS += systemcmds/calibration
+CONFIGURED_APPS += systemcmds/delay_test
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/hello_sky
@@ -98,6 +98,7 @@ CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += drivers/led
+CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index 9d61cae5b..bc724c006 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -692,7 +692,7 @@ CONFIG_ARCH_BZERO=n
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=8
CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=25
+CONFIG_NFILE_DESCRIPTORS=32
CONFIG_NFILE_STREAMS=25
CONFIG_NAME_MAX=32
CONFIG_STDIO_BUFFER_SIZE=256
diff --git a/nuttx/configs/px4io/include/board.h b/nuttx/configs/px4io/include/board.h
index e9181baf1..d941985b4 100755
--- a/nuttx/configs/px4io/include/board.h
+++ b/nuttx/configs/px4io/include/board.h
@@ -96,6 +96,18 @@
#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
+/*
+ * Some of the USART pins are not available; override the GPIO
+ * definitions with an invalid pin configuration.
+ */
+#define GPIO_USART2_CTS 0xffffffff
+#define GPIO_USART2_RTS 0xffffffff
+#define GPIO_USART2_CK 0xffffffff
+#define GPIO_USART3_TX 0xffffffff
+#define GPIO_USART3_CK 0xffffffff
+#define GPIO_USART3_CTS 0xffffffff
+#define GPIO_USART3_RTS 0xffffffff
+
/*
* High-resolution timer
*/
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index e90e7ce62..1ac70f8ab 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -124,7 +124,7 @@ CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_USART2=y
-CONFIG_STM32_USART3=n
+CONFIG_STM32_USART3=y
CONFIG_STM32_I2C1=y
CONFIG_STM32_I2C2=n
CONFIG_STM32_BKP=n
@@ -161,13 +161,13 @@ CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
-CONFIG_USART1_TXBUFSIZE=32
-CONFIG_USART2_TXBUFSIZE=32
-CONFIG_USART3_TXBUFSIZE=32
+CONFIG_USART1_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=64
+CONFIG_USART3_TXBUFSIZE=64
CONFIG_USART1_RXBUFSIZE=64
-CONFIG_USART2_RXBUFSIZE=128
-CONFIG_USART3_RXBUFSIZE=32
+CONFIG_USART2_RXBUFSIZE=64
+CONFIG_USART3_RXBUFSIZE=64
CONFIG_USART1_BAUD=115200
CONFIG_USART2_BAUD=115200
@@ -341,26 +341,28 @@ CONFIG_DEBUG_CAN=n
CONFIG_DEBUG_I2C=n
CONFIG_DEBUG_INPUT=n
+CONFIG_MSEC_PER_TICK=1
CONFIG_HAVE_CXX=n
CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=1
CONFIG_MM_SMALL=y
CONFIG_ARCH_LOWPUTC=y
-CONFIG_RR_INTERVAL=200
+CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=n
-CONFIG_TASK_NAME_SIZE=0
+CONFIG_TASK_NAME_SIZE=8
CONFIG_START_YEAR=1970
CONFIG_START_MONTH=1
CONFIG_START_DAY=1
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
+# this eats ~1KiB of RAM ... work out why
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=n
CONFIG_MUTEX_TYPES=n
CONFIG_PRIORITY_INHERITANCE=n
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_NNESTPRIO=0
-CONFIG_FDCLONE_DISABLE=n
+CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WORKQUEUE=n
@@ -469,7 +471,7 @@ CONFIG_NPTHREAD_KEYS=4
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=32
-CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STDIO_LINEBUFFER=n
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 40011199b..c650da5db 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -252,7 +252,7 @@ static inline ssize_t uart_irqwrite(FAR uart_dev_t *dev, FAR const char *buffer,
{
int ch = *buffer++;
- /* If this is the console, then we should replace LF with CR-LF */
+ /* assume that this is console text output and always do \n -> \r\n conversion */
if (ch == '\n')
{
@@ -277,6 +277,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
FAR uart_dev_t *dev = inode->i_private;
ssize_t nread = buflen;
int ret;
+ char ch;
/* We may receive console writes through this path from interrupt handlers and
* from debug output in the IDLE task! In these cases, we will need to do things
@@ -308,8 +309,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
if (ret < 0)
{
/* A signal received while waiting for access to the xmit.head will
- * abort the transfer. After the transfer has started, we are committed
- * and signals will be ignored.
+ * abort the transfer.
*/
return ret;
@@ -323,53 +323,64 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
uart_disabletxint(dev);
for (; buflen; buflen--)
{
- int ch = *buffer++;
+ ch = *buffer++;
- /* If the ONLCR flag is set, we should translate \n to \r\n */
+ /* Do output post-processing */
- ret = OK;
- if ((ch == '\n') && (dev->termios_s.c_oflag & ONLCR))
- {
- ret = uart_putxmitchar(dev, '\r');
- }
+#ifdef CONFIG_SERIAL_TERMIOS
- /* Put the character into the transmit buffer */
+ if (dev->tc_oflag & OPOST)
+ {
- if (ret == OK)
- {
- ret = uart_putxmitchar(dev, ch);
- }
+ /* Mapping CR to NL? */
- /* Were we awakened by a signal? That should be the only condition that
- * uart_putxmitchar() should return an error.
- */
+ if ((ch == '\r') && (dev->tc_oflag & OCRNL))
+ {
+ ch = '\n';
+ }
- if (ret < 0)
- {
- /* POSIX requires that we return -1 and errno set if no data was
- * transferred. Otherwise, we return the number of bytes in the
- * interrupted transfer.
- */
+ /* Are we interested in newline processing? */
- if (buflen < nread)
+ if ((ch == '\n') && (dev->tc_oflag & (ONLCR | ONLRET)))
{
- /* Some data was transferred. Return the number of bytes that were
- * successfully transferred.
- */
+ ret = uart_putxmitchar(dev, '\r');
- nread -= buflen;
- }
- else
- {
- /* No data was transferred. Return -EINTR. The VFS layer will
- * set the errno value appropriately).
- */
-
- nread = -EINTR;
+ if (ret != OK)
+ {
+ break;
+ }
}
+ /* Specifically not handled:
+ *
+ * OXTABS - primarily a full-screen terminal optimisation
+ * ONOEOT - Unix interoperability hack
+ * OLCUC - Not specified by Posix
+ * ONOCR - low-speed interactive optimisation
+ */
+
+ }
+
+#else /* !CONFIG_SERIAL_TERMIOS */
+
+ /* If this is the console, convert \n -> \r\n */
+
+ if (dev->isconsole && ch == '\n')
+ {
+ ret = uart_putxmitchar(dev, '\r');
+ }
+
+#endif
+
+ /* Put the character into the transmit buffer */
+
+ ret = uart_putxmitchar(dev, ch);
+
+ if (ret != OK)
+ {
break;
}
+
}
if (dev->xmit.head != dev->xmit.tail)
@@ -378,6 +389,36 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
}
uart_givesem(&dev->xmit.sem);
+
+ /* Were we interrupted by a signal? That should be the only condition that
+ * uart_putxmitchar() should return an error.
+ */
+
+ if (ret < 0)
+ {
+ /* POSIX requires that we return -1 and errno set if no data was
+ * transferred. Otherwise, we return the number of bytes in the
+ * interrupted transfer.
+ */
+
+ if (buflen < nread)
+ {
+ /* Some data was transferred. Return the number of bytes that were
+ * successfully transferred.
+ */
+
+ nread -= buflen;
+ }
+ else
+ {
+ /* No data was transferred. Return -EINTR. The VFS layer will
+ * set the errno value appropriately).
+ */
+
+ nread = -EINTR;
+ }
+ }
+
return nread;
}
@@ -393,6 +434,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
ssize_t recvd = 0;
int16_t tail;
int ret;
+ char ch;
/* Only one user can access dev->recv.tail at a time */
@@ -430,8 +472,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
{
/* Take the next character from the tail of the buffer */
- *buffer++ = dev->recv.buffer[tail];
- recvd++;
+ ch = dev->recv.buffer[tail];
/* Increment the tail index. Most operations are done using the
* local variable 'tail' so that the final dev->recv.tail update
@@ -444,6 +485,49 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
}
dev->recv.tail = tail;
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
+ /* Do input processing if any is enabled */
+
+ if (dev->tc_iflag & (INLCR | IGNCR | ICRNL))
+ {
+
+ /* \n -> \r or \r -> \n translation? */
+
+ if ((ch == '\n') && (dev->tc_iflag & INLCR))
+ {
+ ch = '\r';
+ }
+ else if ((ch == '\r') && (dev->tc_iflag & ICRNL))
+ {
+ ch = '\n';
+ }
+
+ /* discarding \r ? */
+ if ((ch == '\r') & (dev->tc_iflag & IGNCR))
+ {
+ continue;
+ }
+
+ }
+
+ /* Specifically not handled:
+ *
+ * All of the local modes; echo, line editing, etc.
+ * Anything to do with break or parity errors.
+ * ISTRIP - we should be 8-bit clean.
+ * IUCLC - Not Posix
+ * IXON/OXOFF - no xon/xoff flow control.
+ */
+
+#endif
+
+ /* store the received character */
+
+ *buffer++ = ch;
+ recvd++;
+
}
#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS
@@ -573,43 +657,77 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
/* Handle TTY-level IOCTLs here */
/* Let low-level driver handle the call first */
+
int ret = dev->ops->ioctl(filep, cmd, arg);
+
/* Append any higher level TTY flags */
- switch (cmd)
+
+ if (ret == OK)
{
- case TCGETS:
- {
- struct termios *termiosp = (struct termios*)arg;
+ switch (cmd)
+ {
- if (!termiosp)
- {
- ret = -EINVAL;
- break;
- }
+ case FIONREAD:
+ {
+ int count;
+ irqstate_t state = irqsave();
- /* Fetch the out flags */
- termiosp->c_oflag = dev->termios_s.c_oflag;
- /* Fetch the in flags */
- termiosp->c_iflag = dev->termios_s.c_iflag;
- }
- break;
+ /* determine the number of bytes available in the buffer */
- case TCSETS:
- {
- struct termios *termiosp = (struct termios*)arg;
+ if (dev->recv.tail <= dev->recv.head)
+ {
+ count = dev->recv.head - dev->recv.tail;
+ }
+ else
+ {
+ count = dev->recv.size - (dev->recv.tail - dev->recv.head);
+ }
- if (!termiosp)
- {
- ret = -EINVAL;
- break;
- }
+ irqrestore(state);
+
+ *(int *)arg = count;
+ }
+
+#ifdef CONFIG_SERIAL_TERMIOS
+ case TCGETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* and update with flags from this layer */
- /* Set the out flags */
- dev->termios_s.c_oflag = termiosp->c_oflag;
- /* Set the in flags */
- dev->termios_s.c_iflag = termiosp->c_iflag;
- }
- break;
+ termiosp->c_iflag = dev->tc_iflag;
+ termiosp->c_oflag = dev->tc_oflag;
+ termiosp->c_lflag = dev->tc_lflag;
+ }
+
+ break;
+
+ case TCSETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* update the flags we keep at this layer */
+
+ dev->tc_iflag = termiosp->c_iflag;
+ dev->tc_oflag = termiosp->c_oflag;
+ dev->tc_lflag = termiosp->c_lflag;
+ }
+
+ break;
+#endif
+ }
}
return ret;
}
@@ -900,6 +1018,25 @@ static int uart_open(FAR struct file *filep)
dev->recv.head = 0;
dev->recv.tail = 0;
+ /* initialise termios state */
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
+ dev->tc_iflag = 0;
+ if (dev->isconsole == true)
+ {
+
+ /* enable \n -> \r\n translation for the console */
+
+ dev->tc_oflag = OPOST | ONLCR;
+ }
+ else
+ {
+ dev->tc_oflag = 0;
+ }
+
+#endif
+
/* Enable the RX interrupt */
uart_enablerxint(dev);
@@ -937,14 +1074,22 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
#ifndef CONFIG_DISABLE_POLL
sem_init(&dev->pollsem, 0, 1);
#endif
+
/* Setup termios flags */
- memset(&dev->termios_s, 0, sizeof(dev->termios_s));
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
if (dev->isconsole == true)
{
- /* Device is console, set up termios flags */
- dev->termios_s.c_oflag |= ONLCR;
+
+ /* enable \n -> \r\n translation for the console as early as possible */
+
+ dev->tc_oflag = OPOST | ONLCR;
+ dev->tc_iflag = 0;
}
+#endif
+
dbg("Registering %s\n", path);
return register_driver(path, &g_serialops, 0666, dev);
}
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index 19f29b1fb..08f62e164 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -106,6 +106,10 @@
* OUT: None
*/
+#define FIONREAD _FIOC(0x0004) /* IN: Location to return value (int *)
+ * OUT: Bytes readable from this fd
+ */
+
/* NuttX file system ioctl definitions **************************************/
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
diff --git a/nuttx/include/nuttx/serial/serial.h b/nuttx/include/nuttx/serial/serial.h
index 67a7f9d99..49dba3795 100644
--- a/nuttx/include/nuttx/serial/serial.h
+++ b/nuttx/include/nuttx/serial/serial.h
@@ -46,7 +46,9 @@
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
-#include <termios.h>
+#ifdef CONFIG_SERIAL_TERMIOS
+# include <termios.h>
+#endif
#include <nuttx/fs/fs.h>
/************************************************************************************
@@ -216,7 +218,12 @@ struct uart_dev_s
#endif
/* Terminal control flags */
- struct termios termios_s;
+
+#ifdef CONFIG_SERIAL_TERMIOS
+ tcflag_t tc_iflag; /* Input modes */
+ tcflag_t tc_oflag; /* Output modes */
+ tcflag_t tc_lflag; /* Local modes */
+#endif
};
typedef struct uart_dev_s uart_dev_t;
diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h
index e381814e3..c8f590a5b 100644
--- a/nuttx/include/termios.h
+++ b/nuttx/include/termios.h
@@ -58,7 +58,7 @@
#define INLCR (1 << 5) /* Bit 5: Map NL to CR on input */
#define INPCK (1 << 6) /* Bit 6: Enable input parity check */
#define ISTRIP (1 << 7) /* Bit 7: Strip character */
-#define IUCLC (1 << 8) /* Bit 8: Map upper-case to lower-case on input (LEGACY) */
+ /* Bit 8: unused */
#define IXANY (1 << 9) /* Bit 9: Enable any character to restart output */
#define IXOFF (1 << 10) /* Bit 10: Enable start/stop input control */
#define IXON (1 << 11) /* Bit 11: Enable start/stop output control */
@@ -67,7 +67,7 @@
/* Terminal output modes (c_oflag in the termios structure) */
#define OPOST (1 << 0) /* Bit 0: Post-process output */
-#define OLCUC (1 << 1) /* Bit 1: Map lower-case to upper-case on output (LEGACY) */
+ /* Bit 1: unused */
#define ONLCR (1 << 2) /* Bit 2: Map NL to CR-NL on output */
#define OCRNL (1 << 3) /* Bit 3: Map CR to NL on output */
#define ONOCR (1 << 4) /* Bit 4: No CR output at column 0 */
@@ -98,17 +98,20 @@
/* Control Modes (c_cflag in the termios structure) */
-#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
-# define CS5 (0 << 0) /* 5 bits */
-# define CS6 (1 << 0) /* 6 bits */
-# define CS7 (2 << 0) /* 7 bits */
-# define CS8 (3 << 0) /* 8 bits */
-#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
-#define CREAD (1 << 3) /* Bit 3: Enable receiver */
-#define PARENB (1 << 4) /* Bit 4: Parity enable */
-#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
-#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
-#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
+#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
+# define CS5 (0 << 0) /* 5 bits */
+# define CS6 (1 << 0) /* 6 bits */
+# define CS7 (2 << 0) /* 7 bits */
+# define CS8 (3 << 0) /* 8 bits */
+#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
+#define CREAD (1 << 3) /* Bit 3: Enable receiver */
+#define PARENB (1 << 4) /* Bit 4: Parity enable */
+#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
+#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
+#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
+#define CCTS_OFLOW (1 << 8) /* Bit 8: CTS flow control of output */
+#define CRTSCTS CCTS_OFLOW
+#define CRTS_IFLOW (1 << 9) /* Bit 9: RTS flow control of input */
/* Local Modes (c_lflag in the termios structure) */
@@ -121,7 +124,6 @@
#define ISIG (1 << 6) /* Bit 6: Enable signals */
#define NOFLSH (1 << 7) /* Bit 7: Disable flush after interrupt or quit */
#define TOSTOP (1 << 8) /* Bit 8: Send SIGTTOU for background output */
-#define XCASE (1 << 9) /* Bit 9: Canonical upper/lower presentation (LEGACY) */
/* The following are subscript names for the termios c_cc array */
@@ -230,7 +232,7 @@ struct termios
* cf[set|get][o|i]speed() POSIX interfaces.
*/
- const speed_t c_speed; /* Input/output speed (non-POSIX)*/
+ speed_t c_speed; /* Input/output speed (non-POSIX)*/
};
/****************************************************************************