aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-02-16 18:01:15 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-02-16 18:01:15 +0100
commit1c98343e7bdb27839ea9528854315e23b67c82e2 (patch)
treec8eb9b64a52cd356958dce5c69426e80ed57f29e /ROMFS
parenta0780a20b5e10eafa1ddf7e16bce788b94514bba (diff)
parent781845587cf98e5aafbccdb4ace45e014cc2d043 (diff)
downloadpx4-firmware-1c98343e7bdb27839ea9528854315e23b67c82e2.tar.gz
px4-firmware-1c98343e7bdb27839ea9528854315e23b67c82e2.tar.bz2
px4-firmware-1c98343e7bdb27839ea9528854315e23b67c82e2.zip
Merge branch 'master' of github.com:PX4/Firmware
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/Makefile3
-rwxr-xr-x[-rw-r--r--]ROMFS/logging/logconv.m163
-rw-r--r--ROMFS/mixers/FMU_Q.mix52
-rw-r--r--ROMFS/mixers/FMU_X5.mix (renamed from ROMFS/mixers/FMU_delta.mix)0
-rw-r--r--ROMFS/scripts/rc.boarddetect66
-rwxr-xr-xROMFS/scripts/rcS67
6 files changed, 257 insertions, 94 deletions
diff --git a/ROMFS/Makefile b/ROMFS/Makefile
index 3b024de06..d827fa491 100644
--- a/ROMFS/Makefile
+++ b/ROMFS/Makefile
@@ -23,7 +23,8 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
$(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
$(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \
$(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \
- $(SRCROOT)/mixers/FMU_delta.mix~mixers/FMU_delta.mix \
+ $(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \
+ $(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \
$(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
$(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
diff --git a/ROMFS/logging/logconv.m b/ROMFS/logging/logconv.m
index b53d0ae39..c405410de 100644..100755
--- a/ROMFS/logging/logconv.m
+++ b/ROMFS/logging/logconv.m
@@ -45,29 +45,30 @@ end
% 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');
+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', 'omnidirectional_flow', 'bytes', 4, 'array', 22,'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{22} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{23} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{24} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
% First get length of one line
columns = length(logFormat);
@@ -83,7 +84,7 @@ if exist(filePath, 'file')
fileInfo = dir(filePath);
fileSize = fileInfo.bytes;
- elements = int64(fileSize./(lineLength))
+ elements = int64(fileSize./(lineLength));
fid = fopen(filePath, 'r');
offset = 0;
@@ -102,8 +103,8 @@ if exist(filePath, 'file')
% shot the flight time
time_us = sysvector.timestamp(end) - sysvector.timestamp(1);
- time_s = time_us*1e-6
- time_m = time_s/60
+ time_s = time_us*1e-6;
+ time_m = time_s/60;
% close the logfile
fclose(fid);
@@ -112,3 +113,113 @@ if exist(filePath, 'file')
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/mixers/FMU_Q.mix b/ROMFS/mixers/FMU_Q.mix
new file mode 100644
index 000000000..a35d299fd
--- /dev/null
+++ b/ROMFS/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/mixers/FMU_delta.mix b/ROMFS/mixers/FMU_X5.mix
index 981466704..981466704 100644
--- a/ROMFS/mixers/FMU_delta.mix
+++ b/ROMFS/mixers/FMU_X5.mix
diff --git a/ROMFS/scripts/rc.boarddetect b/ROMFS/scripts/rc.boarddetect
new file mode 100644
index 000000000..f233e51df
--- /dev/null
+++ b/ROMFS/scripts/rc.boarddetect
@@ -0,0 +1,66 @@
+#!nsh
+#
+# If we are still in flight mode, work out what airframe
+# configuration we have and start up accordingly.
+#
+if [ $MODE != autostart ]
+then
+ echo "[init] automatic startup cancelled by user script"
+else
+ echo "[init] detecting attached hardware..."
+
+ #
+ # Assume that we are PX4FMU in standalone mode
+ #
+ set BOARD PX4FMU
+
+ #
+ # Are we attached to a PX4IOAR (AR.Drone carrier board)?
+ #
+ if boardinfo test name PX4IOAR
+ then
+ set BOARD PX4IOAR
+ if [ -f /etc/init.d/rc.PX4IOAR ]
+ then
+ echo "[init] reading /etc/init.d/rc.PX4IOAR"
+ usleep 500
+ sh /etc/init.d/rc.PX4IOAR
+ fi
+ else
+ echo "[init] PX4IOAR not detected"
+ fi
+
+ #
+ # Are we attached to a PX4IO?
+ #
+ if boardinfo test name PX4IO
+ then
+ set BOARD PX4IO
+ if [ -f /etc/init.d/rc.PX4IO ]
+ then
+ echo "[init] reading /etc/init.d/rc.PX4IO"
+ usleep 500
+ sh /etc/init.d/rc.PX4IO
+ fi
+ else
+ echo "[init] PX4IO not detected"
+ fi
+
+ #
+ # Looks like we are stand-alone
+ #
+ if [ $BOARD == PX4FMU ]
+ then
+ echo "[init] no expansion board detected"
+ if [ -f /etc/init.d/rc.standalone ]
+ then
+ echo "[init] reading /etc/init.d/rc.standalone"
+ sh /etc/init.d/rc.standalone
+ fi
+ fi
+
+ #
+ # We may not reach here if the airframe-specific script exits the shell.
+ #
+ echo "[init] startup done."
+fi \ No newline at end of file
diff --git a/ROMFS/scripts/rcS b/ROMFS/scripts/rcS
index 660bf61e9..89a767879 100755
--- a/ROMFS/scripts/rcS
+++ b/ROMFS/scripts/rcS
@@ -77,70 +77,3 @@ then
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi
-
-
-#
-# If we are still in flight mode, work out what airframe
-# configuration we have and start up accordingly.
-#
-if [ $MODE != autostart ]
-then
- echo "[init] automatic startup cancelled by user script"
-else
- echo "[init] detecting attached hardware..."
-
- #
- # Assume that we are PX4FMU in standalone mode
- #
- set BOARD PX4FMU
-
- #
- # Are we attached to a PX4IOAR (AR.Drone carrier board)?
- #
- if boardinfo test name PX4IOAR
- then
- set BOARD PX4IOAR
- if [ -f /etc/init.d/rc.PX4IOAR ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IOAR"
- usleep 500
- sh /etc/init.d/rc.PX4IOAR
- fi
- else
- echo "[init] PX4IOAR not detected"
- fi
-
- #
- # Are we attached to a PX4IO?
- #
- if boardinfo test name PX4IO
- then
- set BOARD PX4IO
- if [ -f /etc/init.d/rc.PX4IO ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IO"
- usleep 500
- sh /etc/init.d/rc.PX4IO
- fi
- else
- echo "[init] PX4IO not detected"
- fi
-
- #
- # Looks like we are stand-alone
- #
- if [ $BOARD == PX4FMU ]
- then
- echo "[init] no expansion board detected"
- if [ -f /etc/init.d/rc.standalone ]
- then
- echo "[init] reading /etc/init.d/rc.standalone"
- sh /etc/init.d/rc.standalone
- fi
- fi
-
- #
- # We may not reach here if the airframe-specific script exits the shell.
- #
- echo "[init] startup done."
-fi