aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_default
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_default')
-rwxr-xr-xROMFS/px4fmu_default/logging/logconv.m224
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_AERT.mix64
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_AET.mix60
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_Q.mix52
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_RET.mix53
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_X5.mix50
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_delta.mix50
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_hex_+.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_hex_x.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_octo_+.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_octo_x.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_pass.mix23
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_quad_+.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_quad_x.mix7
-rw-r--r--ROMFS/px4fmu_default/mixers/README154
15 files changed, 772 insertions, 0 deletions
diff --git a/ROMFS/px4fmu_default/logging/logconv.m b/ROMFS/px4fmu_default/logging/logconv.m
new file mode 100755
index 000000000..5ea2aeb95
--- /dev/null
+++ b/ROMFS/px4fmu_default/logging/logconv.m
@@ -0,0 +1,224 @@
+% 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';
+
+% Work around a Matlab bug (not related to PX4)
+% where timestamps from 1.1.1970 do not allow to
+% read the file's size
+if ismac
+ system('touch -t 201212121212.12 sysvector.bin');
+end
+
+%%%%%%%%%%%%%%%%%%%%%%%
+% SYSTEM VECTOR
+%
+% //All measurements in NED frame
+%
+% uint64_t timestamp; //[us]
+% float gyro[3]; //[rad/s]
+% float accel[3]; //[m/s^2]
+% float mag[3]; //[gauss]
+% float baro; //pressure [millibar]
+% float baro_alt; //altitude above MSL [meter]
+% float baro_temp; //[degree celcius]
+% float control[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
+% float actuators[8]; //motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512)
+% float vbat; //battery voltage in [volt]
+% float bat_current - current drawn from battery at this time instant
+% float bat_discharged - discharged energy in mAh
+% float adc[3]; //remaining auxiliary ADC ports [volt]
+% float local_position[3]; //tangent plane mapping into x,y,z [m]
+% 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]
+% float diff_pressure; - pressure difference in millibar
+% float ind_airspeed;
+% float true_airspeed;
+
+% 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', 'bat_current', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{12} = struct('name', 'bat_discharged', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{13} = struct('name', 'adc', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{14} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{15} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le');
+logFormat{16} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, '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
+
+
+if exist(filePath, 'file')
+
+ fileInfo = dir(filePath);
+ fileSize = fileInfo.bytes;
+
+ elements = int64(fileSize./(lineLength));
+
+ 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
+
+ % 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
+
+%% Plot GPS RAW measurements
+
+% Only plot GPS data if available
+if cumsum(double(sysvector.gps_raw_position(200:end,1))) > 0
+ figure('units','normalized','outerposition',[0 0 1 1])
+ plot3(sysvector.gps_raw_position(200:end,1), sysvector.gps_raw_position(200:end,2), sysvector.gps_raw_position(200:end,3));
+end
+
+
+%% Plot optical flow trajectory
+
+flow_sz = size(sysvector.timestamp);
+flow_elements = flow_sz(1);
+
+xt(1:flow_elements,1) = sysvector.timestamp(:,1); % time column [ms]
+
+
+%calc dt
+dt = zeros(flow_elements,1);
+for i = 1:flow_elements-1
+ dt(i+1,1) = double(xt(i+1,1)-xt(i,1)) * 10^(-6); % timestep [s]
+end
+dt(1,1) = mean(dt);
+
+
+global_speed = zeros(flow_elements,3);
+
+%calc global speed (with rot matrix)
+for i = 1:flow_elements
+ rotM = [sysvector.rot_matrix(i,1:3);sysvector.rot_matrix(i,4:6);sysvector.rot_matrix(i,7:9)]';
+ speedX = sysvector.optical_flow(i,3);
+ speedY = sysvector.optical_flow(i,4);
+
+ relSpeed = [-speedY,speedX,0];
+ global_speed(i,:) = relSpeed * rotM;
+end
+
+
+
+px = zeros(flow_elements,1);
+py = zeros(flow_elements,1);
+distance = 0;
+
+last_vx = 0;
+last_vy = 0;
+elem_cnt = 0;
+
+% Very basic accumulation, stops on bad flow quality
+for i = 1:flow_elements
+ if sysvector.optical_flow(i,6) > 5
+ px(i,1) = global_speed(i,1)*dt(i,1);
+ py(i,1) = global_speed(i,2)*dt(i,1);
+ distance = distance + norm([px(i,1) py(i,1)]);
+ last_vx = px(i,1);
+ last_vy = py(i,1);
+ else
+ px(i,1) = last_vx;
+ py(i,1) = last_vy;
+ last_vx = last_vx*0.95;
+ last_vy = last_vy*0.95;
+ end
+end
+
+px_sum = cumsum(px);
+py_sum = cumsum(py);
+time = cumsum(dt);
+
+figure()
+set(gca, 'Units','normal');
+
+plot(py_sum, px_sum, '-blue', 'LineWidth',2);
+axis equal;
+% set title and axis captions
+xlabel('X position (meters)','fontsize',14)
+ylabel('Y position (meters)','fontsize',14)
+% mark begin and end
+hold on
+plot(py_sum(1,1),px_sum(1,1),'ks','LineWidth',2,...
+'MarkerEdgeColor','k',...
+'MarkerFaceColor','g',...
+'MarkerSize',10)
+hold on
+plot(py_sum(end,1),px_sum(end,1),'kv','LineWidth',2,...
+'MarkerEdgeColor','k',...
+'MarkerFaceColor','b',...
+'MarkerSize',10)
+% add total length as annotation
+set(gca,'fontsize',13);
+legend('Trajectory', 'START', sprintf('END\n(%.2f m, %.0f:%.0f s)', distance, time_m, time_s - time_m*60));
+title('Optical Flow Position Integration', 'fontsize', 15);
+
+figure()
+plot(time, sysvector.optical_flow(:,5), 'blue');
+axis([time(1,1) time(end,1) 0 (max(sysvector.optical_flow(i,5))+0.2)]);
+xlabel('seconds','fontsize',14);
+ylabel('m','fontsize',14);
+set(gca,'fontsize',13);
+title('Ultrasound Altitude', 'fontsize', 15);
+
+
+figure()
+plot(time, global_speed(:,2), 'red');
+hold on;
+plot(time, global_speed(:,1), 'blue');
+legend('y velocity (m/s)', 'x velocity (m/s)');
+xlabel('seconds','fontsize',14);
+ylabel('m/s','fontsize',14);
+set(gca,'fontsize',13);
+title('Optical Flow Velocity', 'fontsize', 15);
diff --git a/ROMFS/px4fmu_default/mixers/FMU_AERT.mix b/ROMFS/px4fmu_default/mixers/FMU_AERT.mix
new file mode 100644
index 000000000..75e82bb00
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_AERT.mix
@@ -0,0 +1,64 @@
+Aileron/rudder/elevator/throttle mixer for PX4FMU
+==================================================
+
+This file defines mixers suitable for controlling a fixed wing aircraft with
+aileron, rudder, elevator and throttle controls using PX4FMU. The configuration
+assumes the aileron servo(s) are connected to PX4FMU servo output 0, the
+elevator to output 1, the rudder to output 2 and the throttle to output 3.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+Aileron mixer
+-------------
+Two scalers total (output, roll).
+
+This mixer assumes that the aileron servos are set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+As there is only one output, if using two servos adjustments to compensate for
+differences between the servos must be made mechanically. To obtain the correct
+motion using a Y cable, the servos can be positioned reversed from one another.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+Elevator mixer
+------------
+Two scalers total (output, roll).
+
+This mixer assumes that the elevator servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
+
+Rudder mixer
+------------
+Two scalers total (output, yaw).
+
+This mixer assumes that the rudder servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 10000 10000 0 -10000 10000
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
diff --git a/ROMFS/px4fmu_default/mixers/FMU_AET.mix b/ROMFS/px4fmu_default/mixers/FMU_AET.mix
new file mode 100644
index 000000000..20cb88b91
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_AET.mix
@@ -0,0 +1,60 @@
+Aileron/elevator/throttle mixer for PX4FMU
+==================================================
+
+This file defines mixers suitable for controlling a fixed wing aircraft with
+aileron, elevator and throttle controls using PX4FMU. The configuration assumes
+the aileron servo(s) are connected to PX4FMU servo output 0, the elevator to
+output 1 and the throttle to output 3.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+Aileron mixer
+-------------
+Two scalers total (output, roll).
+
+This mixer assumes that the aileron servos are set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+As there is only one output, if using two servos adjustments to compensate for
+differences between the servos must be made mechanically. To obtain the correct
+motion using a Y cable, the servos can be positioned reversed from one another.
+
+Alternatively, output 2 could be used as a second aileron servo output with
+separate mixing.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+Elevator mixer
+------------
+Two scalers total (output, roll).
+
+This mixer assumes that the elevator servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
diff --git a/ROMFS/px4fmu_default/mixers/FMU_Q.mix b/ROMFS/px4fmu_default/mixers/FMU_Q.mix
new file mode 100644
index 000000000..a35d299fd
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_Q.mix
@@ -0,0 +1,52 @@
+Delta-wing mixer for PX4FMU
+===========================
+
+Designed for Bormatec Camflyer Q
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -5000 -8000 0 -10000 10000
+S: 0 1 -8000 -8000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -8000 -5000 0 -10000 10000
+S: 0 1 8000 8000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
diff --git a/ROMFS/px4fmu_default/mixers/FMU_RET.mix b/ROMFS/px4fmu_default/mixers/FMU_RET.mix
new file mode 100644
index 000000000..95beb8927
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_RET.mix
@@ -0,0 +1,53 @@
+Rudder/elevator/throttle mixer for PX4FMU
+=========================================
+
+This file defines mixers suitable for controlling a fixed wing aircraft with
+rudder, elevator and throttle controls using PX4FMU. The configuration assumes
+the rudder servo is connected to PX4FMU servo output 0, the elevator to output 1
+and the throttle to output 3.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+Rudder mixer
+------------
+Two scalers total (output, roll).
+
+This mixer assumes that the rudder servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+Elevator mixer
+------------
+Two scalers total (output, roll).
+
+This mixer assumes that the elevator servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
diff --git a/ROMFS/px4fmu_default/mixers/FMU_X5.mix b/ROMFS/px4fmu_default/mixers/FMU_X5.mix
new file mode 100644
index 000000000..981466704
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_X5.mix
@@ -0,0 +1,50 @@
+Delta-wing mixer for PX4FMU
+===========================
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 3000 5000 0 -10000 10000
+S: 0 1 5000 5000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 5000 3000 0 -10000 10000
+S: 0 1 -5000 -5000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
diff --git a/ROMFS/px4fmu_default/mixers/FMU_delta.mix b/ROMFS/px4fmu_default/mixers/FMU_delta.mix
new file mode 100644
index 000000000..981466704
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_delta.mix
@@ -0,0 +1,50 @@
+Delta-wing mixer for PX4FMU
+===========================
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 3000 5000 0 -10000 10000
+S: 0 1 5000 5000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 5000 3000 0 -10000 10000
+S: 0 1 -5000 -5000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
diff --git a/ROMFS/px4fmu_default/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_default/mixers/FMU_hex_+.mix
new file mode 100644
index 000000000..b5e38ce9e
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_hex_+.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a hexacopter in the + configuration. All controls
+are mixed 100%.
+
+R: 6+ 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_default/mixers/FMU_hex_x.mix
new file mode 100644
index 000000000..8e8d122ad
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_hex_x.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a hexacopter in the X configuration. All controls
+are mixed 100%.
+
+R: 6x 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/FMU_octo_+.mix b/ROMFS/px4fmu_default/mixers/FMU_octo_+.mix
new file mode 100644
index 000000000..2cb70e814
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_octo_+.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a octocopter in the + configuration. All controls
+are mixed 100%.
+
+R: 8+ 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/FMU_octo_x.mix b/ROMFS/px4fmu_default/mixers/FMU_octo_x.mix
new file mode 100644
index 000000000..edc71f013
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_octo_x.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a octocopter in the X configuration. All controls
+are mixed 100%.
+
+R: 8x 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/FMU_pass.mix b/ROMFS/px4fmu_default/mixers/FMU_pass.mix
new file mode 100644
index 000000000..e9a81f2bb
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_pass.mix
@@ -0,0 +1,23 @@
+Passthrough mixer for PX4FMU
+============================
+
+This file defines passthrough mixers suitable for testing.
+
+Channel group 0, channels 0-3 are passed directly through to the outputs.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 10000 10000 0 -10000 10000
+
diff --git a/ROMFS/px4fmu_default/mixers/FMU_quad_+.mix b/ROMFS/px4fmu_default/mixers/FMU_quad_+.mix
new file mode 100644
index 000000000..dfdf1d58e
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_quad_+.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a quadrotor in the + configuration. All controls
+are mixed 100%.
+
+R: 4+ 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/FMU_quad_x.mix b/ROMFS/px4fmu_default/mixers/FMU_quad_x.mix
new file mode 100644
index 000000000..12a3bee20
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_quad_x.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a quadrotor in the X configuration. All controls
+are mixed 100%.
+
+R: 4x 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_default/mixers/README b/ROMFS/px4fmu_default/mixers/README
new file mode 100644
index 000000000..6649c53c2
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/README
@@ -0,0 +1,154 @@
+PX4 mixer definitions
+=====================
+
+Files in this directory implement example mixers that can be used as a basis
+for customisation, or for general testing purposes.
+
+Mixer basics
+------------
+
+Mixers combine control values from various sources (control tasks, user inputs,
+etc.) and produce output values suitable for controlling actuators; servos,
+motors, switches and so on.
+
+An actuator derives its value from the combination of one or more control
+values. Each of the control values is scaled according to the actuator's
+configuration and then combined to produce the actuator value, which may then be
+further scaled to suit the specific output type.
+
+Internally, all scaling is performed using floating point values. Inputs and
+outputs are clamped to the range -1.0 to 1.0.
+
+control control control
+ | | |
+ v v v
+ scale scale scale
+ | | |
+ | v |
+ +-------> mix <------+
+ |
+ scale
+ |
+ v
+ out
+
+Scaling
+-------
+
+Basic scalers provide linear scaling of the input to the output.
+
+Each scaler allows the input value to be scaled independently for inputs
+greater/less than zero. An offset can be applied to the output, and lower and
+upper boundary constraints can be applied. Negative scaling factors cause the
+output to be inverted (negative input produces positive output).
+
+Scaler pseudocode:
+
+if (input < 0)
+ output = (input * NEGATIVE_SCALE) + OFFSET
+else
+ output = (input * POSITIVE_SCALE) + OFFSET
+
+if (output < LOWER_LIMIT)
+ output = LOWER_LIMIT
+if (output > UPPER_LIMIT)
+ output = UPPER_LIMIT
+
+Syntax
+------
+
+Mixer definitions are text files; lines beginning with a single capital letter
+followed by a colon are significant. All other lines are ignored, meaning that
+explanatory text can be freely mixed with the definitions.
+
+Each file may define more than one mixer; the allocation of mixers to actuators
+is specific to the device reading the mixer definition, and the number of
+actuator outputs generated by a mixer is specific to the mixer.
+
+A mixer begins with a line of the form
+
+ <tag>: <mixer arguments>
+
+The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
+multirotor mixer, etc.
+
+Null Mixer
+..........
+
+A null mixer consumes no controls and generates a single actuator output whose
+value is always zero. Typically a null mixer is used as a placeholder in a
+collection of mixers in order to achieve a specific pattern of actuator outputs.
+
+The null mixer definition has the form:
+
+ Z:
+
+Simple Mixer
+............
+
+A simple mixer combines zero or more control inputs into a single actuator
+output. Inputs are scaled, and the mixing function sums the result before
+applying an output scaler.
+
+A simple mixer definition begins with:
+
+ M: <control count>
+ O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
+
+If <control count> is zero, the sum is effectively zero and the mixer will
+output a fixed value that is <offset> constrained by <lower limit> and <upper
+limit>.
+
+The second line defines the output scaler with scaler parameters as discussed
+above. Whilst the calculations are performed as floating-point operations, the
+values stored in the definition file are scaled by a factor of 10000; i.e. an
+offset of -0.5 is encoded as -5000.
+
+The definition continues with <control count> entries describing the control
+inputs and their scaling, in the form:
+
+ S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
+
+The <group> value identifies the control group from which the scaler will read,
+and the <index> value an offset within that group. These values are specific to
+the device reading the mixer definition.
+
+When used to mix vehicle controls, mixer group zero is the vehicle attitude
+control group, and index values zero through three are normally roll, pitch,
+yaw and thrust respectively.
+
+The remaining fields on the line configure the control scaler with parameters as
+discussed above. Whilst the calculations are performed as floating-point
+operations, the values stored in the definition file are scaled by a factor of
+10000; i.e. an offset of -0.5 is encoded as -5000.
+
+Multirotor Mixer
+................
+
+The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
+into a set of actuator outputs intended to drive motor speed controllers.
+
+The mixer definition is a single line of the form:
+
+R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
+
+The supported geometries include:
+
+ 4x - quadrotor in X configuration
+ 4+ - quadrotor in + configuration
+ 6x - hexcopter in X configuration
+ 6+ - hexcopter in + configuration
+ 8x - octocopter in X configuration
+ 8+ - octocopter in + configuration
+
+Each of the roll, pitch and yaw scale values determine scaling of the roll,
+pitch and yaw controls relative to the thrust control. Whilst the calculations
+are performed as floating-point operations, the values stored in the definition
+file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
+
+Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
+thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
+range -1.0 to 1.0.
+
+In the case where an actuator saturates, all actuator values are rescaled so that
+the saturating actuator is limited to 1.0.