aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/3035_viper10
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb8
-rwxr-xr-xROMFS/px4fmu_common/mixers/FMU_FX79.mix4
-rwxr-xr-xROMFS/px4fmu_common/mixers/Viper.mix72
6 files changed, 100 insertions, 3 deletions
diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper
new file mode 100644
index 000000000..a4c1e832d
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3035_viper
@@ -0,0 +1,10 @@
+#!nsh
+#
+# Viper
+#
+# Simon Wilks <sjwilks@gmail.com>
+#
+
+sh /etc/init.d/rc.fw_defaults
+
+set MIXER Viper
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 17541e680..9de7d9ecd 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -103,6 +103,11 @@ then
sh /etc/init.d/3034_fx79
fi
+if param compare SYS_AUTOSTART 3035 35
+then
+ sh /etc/init.d/3035_viper
+fi
+
if param compare SYS_AUTOSTART 3100
then
sh /etc/init.d/3100_tbs_caipirinha
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index 3a50fcf56..3c336f295 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -11,4 +11,8 @@ then
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50
+ param set FW_T_HRATE_P 0.01
+ param set FW_T_RLL2THR 15
+ param set FW_T_SRATE_P 0.01
+ param set FW_T_TIME_CONST 5
fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 1f8d8b862..f1c21f295 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,8 +3,12 @@
# USB MAVLink start
#
-mavlink start -r 10000 -d /dev/ttyACM0 -x
+mavlink start -r 20000 -d /dev/ttyACM0 -x
# Enable a number of interesting streams we want via USB
+mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
@@ -15,6 +19,8 @@ mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
usleep 100000
+mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20
diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
index 0a1dca98d..112d9b891 100755
--- a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
@@ -27,12 +27,12 @@ for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
-S: 0 0 5000 8000 0 -10000 10000
+S: 0 0 7500 7500 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 0 7500 7500 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
Output 2
diff --git a/ROMFS/px4fmu_common/mixers/Viper.mix b/ROMFS/px4fmu_common/mixers/Viper.mix
new file mode 100755
index 000000000..79c4447be
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/Viper.mix
@@ -0,0 +1,72 @@
+Viper Delta-wing mixer
+=================================
+
+Designed for Viper.
+
+TODO (sjwilks): Add mixers for flaps.
+
+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 7500 7500 0 -10000 10000
+S: 0 1 8000 8000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 7500 7500 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
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000