aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery1
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom3
-rw-r--r--ROMFS/px4fmu_common/init.d/3035_viper11
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart11
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.interface5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.uavcan18
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb4
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS34
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_AERT.mix11
-rwxr-xr-xROMFS/px4fmu_common/mixers/FMU_FX79.mix17
-rwxr-xr-xROMFS/px4fmu_common/mixers/Viper.mix71
13 files changed, 163 insertions, 30 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index c4be16943..b1aa8c00b 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -27,3 +27,4 @@ fi
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
+set PWM_MIN 1200
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index 31dfe7100..53c48d8aa 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -30,6 +30,9 @@ then
param set FW_RR_P 0.08
param set FW_R_LIM 50
param set FW_R_RMAX 0
+ # Bottom of bay and nominal zero-pitch attitude differ
+ # the payload bay is pitched up about 7 degrees
+ param set SENS_BOARD_Y_OFF 7.0
fi
set MIXER phantom
diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper
new file mode 100644
index 000000000..f3b0e8418
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3035_viper
@@ -0,0 +1,11 @@
+#!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..78778d806 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -21,6 +21,12 @@
# Simulation setups
#
+if param compare SYS_AUTOSTART 901
+then
+ sh /etc/init.d/901_bottle_drop_test.hil
+ set MODE custom
+fi
+
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
@@ -103,6 +109,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_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 9aca3fc5f..c97b3477f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -13,3 +13,5 @@ ekf_att_pos_estimator start
#
fw_att_control start
fw_pos_control_l1 start
+
+bottle_drop start
diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface
index 1de0abb58..e44cd0953 100644
--- a/ROMFS/px4fmu_common/init.d/rc.interface
+++ b/ROMFS/px4fmu_common/init.d/rc.interface
@@ -77,4 +77,9 @@ then
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
fi
fi
+
+ if [ $FAILSAFE != none ]
+ then
+ pwm failsafe -d $OUTPUT_DEV $FAILSAFE
+ fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index ecb408a54..739df7ac0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -68,6 +68,11 @@ else
fi
fi
+# Check for flow sensor
+if px4flow start
+then
+fi
+
#
# Start the sensor collection task.
# IMPORTANT: this also loads param offsets
diff --git a/ROMFS/px4fmu_common/init.d/rc.uavcan b/ROMFS/px4fmu_common/init.d/rc.uavcan
new file mode 100644
index 000000000..9a470a6b8
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.uavcan
@@ -0,0 +1,18 @@
+#!nsh
+#
+# UAVCAN initialization script.
+#
+
+if param compare UAVCAN_ENABLE 1
+then
+ if uavcan start
+ then
+ # First sensor publisher to initialize takes lowest instance ID
+ # This delay ensures that UAVCAN-interfaced sensors would be allocated on lowest instance IDs
+ sleep 1
+ echo "[init] UAVCAN started"
+ else
+ echo "[init] ERROR: Could not start UAVCAN"
+ tone_alarm $TUNE_OUT_ERROR
+ fi
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index eb6039b4c..ee040a706 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,7 +3,7 @@
# 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
@@ -23,7 +23,7 @@ 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
+mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
usleep 100000
# Exit shell to make it available to MAVLink
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 24b2a299a..ea04ece34 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -66,6 +66,9 @@ then
#
sercon
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+
#
# Start the ORB (first app to start)
#
@@ -83,9 +86,12 @@ then
param select $PARAM_FILE
if param load
then
- echo "[init] Params loaded: $PARAM_FILE"
+ echo "[param] Loaded: $PARAM_FILE"
else
- echo "[init] ERROR: Params loading failed: $PARAM_FILE"
+ echo "[param] FAILED loading $PARAM_FILE"
+ if param reset
+ then
+ fi
fi
#
@@ -93,11 +99,9 @@ then
#
if rgbled start
then
- echo "[init] RGB Led"
else
if blinkm start
then
- echo "[init] BlinkM"
blinkm systemstate
fi
fi
@@ -126,6 +130,7 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
+ set FAILSAFE none
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -276,13 +281,12 @@ then
fi
fi
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
-
#
- # Start the datamanager
+ # Start the datamanager (and do not abort boot if it fails)
#
- dataman start
+ if dataman start
+ then
+ fi
#
# Start the Commander (needs to be this early for in-air-restarts)
@@ -299,11 +303,10 @@ then
then
if [ $OUTPUT_MODE == uavcan_esc ]
then
- if uavcan start 1
+ if param compare UAVCAN_ENABLE 0
then
- echo "CAN UP"
- else
- echo "CAN ERR"
+ echo "[init] OVERRIDING UAVCAN_ENABLE = 1"
+ param set UAVCAN_ENABLE 1
fi
fi
@@ -443,6 +446,11 @@ then
mavlink start $MAVLINK_FLAGS
#
+ # UAVCAN
+ #
+ sh /etc/init.d/rc.uavcan
+
+ #
# Sensors, Logging, GPS
#
sh /etc/init.d/rc.sensors
diff --git a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
index 0ec663e35..7fed488af 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
@@ -64,21 +64,22 @@ O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
-Gimbal / flaps / payload mixer for last four channels
+Gimbal / flaps / payload mixer for last four channels,
+using the payload control group
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 4 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 5 10000 10000 0 -10000 10000
+S: 2 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 6 10000 10000 0 -10000 10000
+S: 2 2 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 7 10000 10000 0 -10000 10000
+S: 2 3 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
index 0a1dca98d..b8879af9e 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
@@ -52,21 +52,18 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
-Gimbal / flaps / payload mixer for last four channels
+Inputs to the mixer come from channel group 2 (payload), channels 0
+(bay servo 1), 1 (bay servo 2) and 3 (drop release).
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 4 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 5 10000 10000 0 -10000 10000
+S: 2 1 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
+S: 2 2 -10000 -10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/Viper.mix b/ROMFS/px4fmu_common/mixers/Viper.mix
new file mode 100755
index 000000000..5aa3828f2
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/Viper.mix
@@ -0,0 +1,71 @@
+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
+
+Inputs to the mixer come from channel group 2 (payload), channels 0
+(bay servo 1), 1 (bay servo 2) and 3 (drop release).
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 1 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 2 -8000 -8000 0 -10000 10000
+
+