aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris6
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar2
-rw-r--r--ROMFS/px4fmu_common/init.d/4008_ardrone25
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults3
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS90
-rw-r--r--ROMFS/px4fmu_common/mixers/README154
8 files changed, 221 insertions, 63 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index f11aa704e..084dff140 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -18,9 +18,9 @@ then
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 0.5
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAW_P 2.5
+ param set MC_YAWRATE_P 0.25
+ param set MC_YAWRATE_I 0.25
param set MC_YAWRATE_D 0.0
param set BAT_V_SCALING 0.00989
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index df2e609bc..daa04a4de 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -1,7 +1,5 @@
#!nsh
#
-# UNTESTED UNTESTED!
-#
# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index db0e40fc2..3ab2ac3d1 100644
--- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
@@ -5,4 +5,4 @@
sh /etc/init.d/rc.fw_defaults
-set MIXER easystar.mix
+set MIXER easystar
diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index 14786f210..e6007db0e 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -14,19 +14,20 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
- param set MC_ROLL_P 5.0
- param set MC_ROLLRATE_P 0.13
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.0
- param set MC_PITCH_P 5.0
- param set MC_PITCHRATE_P 0.13
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.0
- param set MC_YAW_P 1.0
- param set MC_YAWRATE_P 0.15
- param set MC_YAWRATE_I 0.0
+ param set MC_ROLL_P 6.0
+ param set MC_ROLLRATE_P 0.14
+ param set MC_ROLLRATE_I 0.1
+ param set MC_ROLLRATE_D 0.002
+ param set MC_PITCH_P 6.0
+ param set MC_PITCHRATE_P 0.14
+ param set MC_PITCHRATE_I 0.1
+ param set MC_PITCHRATE_D 0.002
+ param set MC_YAW_P 2.0
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
- param set MC_YAW_FF 0.15
+ param set MC_YAW_FF 0.8
+
param set BAT_V_SCALING 0.00838095238
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 517e073af..25f31a7e0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -11,6 +11,6 @@ then
sdlog2 start -r 50 -a -b 4 -t
else
echo "Start sdlog2 at 200Hz"
- sdlog2 start -r 200 -a -b 16 -t
+ sdlog2 start -r 200 -a -b 22 -t
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index b6b0a5b4e..127e42164 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -37,10 +37,11 @@ then
param set MPC_LAND_SPEED 1.0
param set PE_VELNE_NOISE 0.5
- param set PE_VELNE_NOISE 0.7
+ param set PE_VELD_NOISE 0.7
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
+ param set NAV_ACCEPT_RAD 2.0
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 8c413e087..6d06f897a 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -65,12 +65,12 @@ then
# Start CDC/ACM serial driver
#
sercon
-
+
#
# Start the ORB (first app to start)
#
uorb start
-
+
#
# Load parameters
#
@@ -79,7 +79,7 @@ then
then
set PARAM_FILE /fs/mtd_params
fi
-
+
param select $PARAM_FILE
if param load
then
@@ -87,21 +87,25 @@ then
else
echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi
-
+
#
# Start system state indicator
#
if rgbled start
then
- echo "[init] Using external RGB Led"
+ echo "[init] RGB Led"
else
if blinkm start
then
- echo "[init] Using blinkm"
+ echo "[init] BlinkM"
blinkm systemstate
fi
fi
-
+
+ if pca8574 start
+ then
+ fi
+
#
# Set default values
#
@@ -122,7 +126,7 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
-
+
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
#
@@ -132,7 +136,7 @@ then
else
set DO_AUTOCONFIG no
fi
-
+
#
# Set USE_IO flag
#
@@ -142,7 +146,7 @@ then
else
set USE_IO no
fi
-
+
#
# Set parameters and env variables for selected AUTOSTART
#
@@ -172,9 +176,9 @@ then
param set SYS_AUTOCONFIG 0
param save
fi
-
+
set IO_PRESENT no
-
+
if [ $USE_IO == yes ]
then
#
@@ -186,19 +190,19 @@ then
else
set IO_FILE /etc/extras/px4io-v1_default.bin
fi
-
+
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $LOG_FILE
-
+
set IO_PRESENT yes
else
echo "[init] Trying to update"
echo "PX4IO Trying to update" >> $LOG_FILE
-
+
tone_alarm MLL32CP8MB
-
+
if px4io forceupdate 14662 $IO_FILE
then
usleep 500000
@@ -207,7 +211,7 @@ then
echo "[init] PX4IO CRC OK, update successful"
echo "PX4IO CRC OK after updating" >> $LOG_FILE
tone_alarm MLL8CDE
-
+
set IO_PRESENT yes
else
echo "[init] ERROR: PX4IO update failed"
@@ -220,14 +224,14 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $IO_PRESENT == no ]
then
echo "[init] ERROR: PX4IO not found"
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Set default output if not set
#
@@ -246,7 +250,7 @@ then
# Need IO for output but it not present, disable output
set OUTPUT_MODE none
echo "[init] ERROR: PX4IO not found, disabling output"
-
+
# Avoid using ttyS0 for MAVLink on FMUv1
if ver hwcmp PX4FMU_V1
then
@@ -270,17 +274,17 @@ then
# Try to get an USB console
nshterm /dev/ttyACM0 &
-
+
#
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
-
+
#
# Start primary output
#
set TTYS1_BUSY no
-
+
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
if [ $OUTPUT_MODE != none ]
then
@@ -296,7 +300,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
echo "[init] Use FMU as primary output"
@@ -307,7 +311,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -320,7 +324,7 @@ then
fi
fi
fi
-
+
if [ $OUTPUT_MODE == mkblctrl ]
then
echo "[init] Use MKBLCTRL as primary output"
@@ -333,7 +337,7 @@ then
then
set MKBLCTRL_ARG "-mkmode +"
fi
-
+
if mkblctrl $MKBLCTRL_ARG
then
echo "[init] MKBLCTRL started"
@@ -341,9 +345,9 @@ then
echo "[init] ERROR: MKBLCTRL start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
fi
-
+
if [ $OUTPUT_MODE == hil ]
then
echo "[init] Use HIL as primary output"
@@ -355,7 +359,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Start IO or FMU for RC PPM input if needed
#
@@ -382,7 +386,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -397,7 +401,7 @@ then
fi
fi
fi
-
+
#
# MAVLink
#
@@ -418,7 +422,7 @@ then
fi
mavlink start $MAVLINK_FLAGS
-
+
#
# Sensors, Logging, GPS
#
@@ -429,7 +433,7 @@ then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
fi
-
+
if [ $GPS == yes ]
then
echo "[init] Start GPS"
@@ -439,7 +443,7 @@ then
gps start -f
else
gps start
- fi
+ fi
fi
#
@@ -456,24 +460,24 @@ then
if [ $VEHICLE_TYPE == fw ]
then
echo "[init] Vehicle type: FIXED WING"
-
+
if [ $MIXER == none ]
then
# Set default mixer for fixed wing if not defined
set MIXER FMU_AERT
fi
-
+
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 1 (fixed wing) if not defined
set MAV_TYPE 1
fi
-
+
param set MAV_TYPE $MAV_TYPE
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard fixedwing apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
@@ -521,7 +525,7 @@ then
set MAV_TYPE 14
fi
fi
-
+
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
@@ -529,10 +533,10 @@ then
else
param set MAV_TYPE $MAV_TYPE
fi
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard multicopter apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
diff --git a/ROMFS/px4fmu_common/mixers/README b/ROMFS/px4fmu_common/mixers/README
new file mode 100644
index 000000000..60311232e
--- /dev/null
+++ b/ROMFS/px4fmu_common/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. \ No newline at end of file