aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-05-12 09:58:55 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-05-12 09:58:55 +0200
commit01a54390e9ac1daa3af8c51ae3c35e39bf99cec6 (patch)
tree5bdb086ac86053baa69e9bb97f0472727d3e1e6d /ROMFS/px4fmu_common
parentd1bd4b0a45ec0f6f081560fbadf675e21ce53d83 (diff)
parent3f4c264050774e79add989cb85a80623038478c0 (diff)
downloadpx4-firmware-01a54390e9ac1daa3af8c51ae3c35e39bf99cec6.tar.gz
px4-firmware-01a54390e9ac1daa3af8c51ae3c35e39bf99cec6.tar.bz2
px4-firmware-01a54390e9ac1daa3af8c51ae3c35e39bf99cec6.zip
Merge remote-tracking branch 'upstream/master' into qu4d
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/12001_octo_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar2
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom8
-rw-r--r--ROMFS/px4fmu_common/init.d/3032_skywalker_x52
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.io2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors2
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS72
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_hexa_cox.mix (renamed from ROMFS/px4fmu_common/mixers/hexa_cox.mix)0
-rw-r--r--ROMFS/px4fmu_common/mixers/easystar.mix31
12 files changed, 82 insertions, 47 deletions
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index 38e65435b..df2e609bc 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -9,7 +9,7 @@
sh /etc/init.d/rc.mc_defaults
-set MIXER hexa_cox
+set MIXER FMU_hexa_cox
# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index 99f902a6d..8703f5f2f 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -7,6 +7,6 @@
sh /etc/init.d/rc.mc_defaults
-set MIXER octo_cox
+set MIXER FMU_octo_cox
set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index 465a22c53..db0e40fc2 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 FMU_RET
+set MIXER easystar.mix
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index 6cbd23643..24372bddc 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -10,8 +10,8 @@ sh /etc/init.d/rc.fw_defaults
if [ $DO_AUTOCONFIG == yes ]
then
param set FW_AIRSPD_MIN 13
- param set FW_AIRSPD_TRIM 18
- param set FW_AIRSPD_MAX 40
+ param set FW_AIRSPD_TRIM 15
+ param set FW_AIRSPD_MAX 25
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.75
param set FW_L1_PERIOD 15
@@ -23,12 +23,12 @@ then
param set FW_P_LIM_MIN -50
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
- param set FW_P_ROLLFF 0
+ param set FW_P_ROLLFF 1
param set FW_RR_FF 0.5
param set FW_RR_I 0.02
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.08
- param set FW_R_LIM 70
+ param set FW_R_LIM 50
param set FW_R_RMAX 0
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
index bf5a87068..465166f25 100644
--- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
+++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
@@ -23,7 +23,7 @@ then
param set FW_P_LIM_MIN -45
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
- param set FW_P_ROLLFF 0
+ param set FW_P_ROLLFF 1
param set FW_RR_FF 0.3
param set FW_RR_I 0
param set FW_RR_IMAX 0.2
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
index 6e8fdbc0f..e23aebd87 100644
--- a/ROMFS/px4fmu_common/init.d/rc.io
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -11,7 +11,7 @@ px4io recovery
# Adjust PX4IO update rate limit
#
set PX4IO_LIMIT 400
-if hw_ver compare PX4FMU_V1
+if ver hwcmp PX4FMU_V1
then
set PX4IO_LIMIT 200
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index c5aef8273..3469d5f5f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,7 +5,7 @@
if [ -d /fs/microsd ]
then
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 8 -t
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 4db62607a..a8c6dc811 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -32,9 +32,9 @@ then
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_MAX 3
param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
+ param set MPC_TILTMAX_AIR 45.0
+ param set MPC_TILTMAX_LND 15.0
param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 235be2431..1e14930fe 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -22,7 +22,7 @@ then
echo "[init] Using L3GD20(H)"
fi
-if hw_ver compare PX4FMU_V2
+if ver hwcmp PX4FMU_V2
then
if lsm303d start
then
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 0cb6d281a..756ee8ef8 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -20,7 +20,7 @@ echo "[init] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
set LOG_FILE /fs/microsd/bootlog.txt
- echo "[init] microSD card mounted at /fs/microsd"
+ echo "[init] microSD mounted: /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
@@ -83,9 +83,9 @@ then
param select $PARAM_FILE
if param load
then
- echo "[init] Parameters loaded: $PARAM_FILE"
+ echo "[init] Params loaded: $PARAM_FILE"
else
- echo "[init] ERROR: Parameters loading failed: $PARAM_FILE"
+ echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi
#
@@ -120,6 +120,8 @@ then
set EXIT_ON_END no
set MAV_TYPE none
set LOAD_DEFAULT_APPS yes
+ set GPS yes
+ set GPS_FAKE no
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -146,7 +148,7 @@ then
#
if param compare SYS_AUTOSTART 0
then
- echo "[init] Don't try to find autostart script"
+ echo "[init] No autostart"
else
sh /etc/init.d/rc.autostart
fi
@@ -156,10 +158,10 @@ then
#
if [ -f $CONFIG_FILE ]
then
- echo "[init] Reading config: $CONFIG_FILE"
+ echo "[init] Config: $CONFIG_FILE"
sh $CONFIG_FILE
else
- echo "[init] Config file not found: $CONFIG_FILE"
+ echo "[init] Config not found: $CONFIG_FILE"
fi
#
@@ -246,7 +248,7 @@ then
echo "[init] ERROR: PX4IO not found, disabling output"
# Avoid using ttyS0 for MAVLink on FMUv1
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
set FMU_MODE serial
fi
@@ -260,14 +262,14 @@ then
if [ $HIL == yes ]
then
set OUTPUT_MODE hil
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
set FMU_MODE serial
fi
- else
- # Try to get an USB console if not in HIL mode
- nshterm /dev/ttyACM0 &
fi
+
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
#
# Start the Commander (needs to be this early for in-air-restarts)
@@ -306,7 +308,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
@@ -381,7 +383,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
@@ -401,23 +403,17 @@ then
#
if [ $MAVLINK_FLAGS == default ]
then
- if [ $HIL == yes ]
+ # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
+ if [ $TTYS1_BUSY == yes ]
then
- sleep 1
- set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0"
+ # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
+ set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
+
+ # Exit from nsh to free port for mavlink
+ set EXIT_ON_END yes
else
- # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
- if [ $TTYS1_BUSY == yes ]
- then
- # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
- set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
-
- # Exit from nsh to free port for mavlink
- set EXIT_ON_END yes
- else
- # Start MAVLink on default port: ttyS1
- set MAVLINK_FLAGS "-r 1000"
- fi
+ # Start MAVLink on default port: ttyS1
+ set MAVLINK_FLAGS "-r 1000"
fi
fi
@@ -436,18 +432,26 @@ then
#
# Sensors, Logging, GPS
#
- echo "[init] Start sensors"
sh /etc/init.d/rc.sensors
if [ $HIL == no ]
then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
-
- echo "[init] Start GPS"
- gps start
fi
+ if [ $GPS == yes ]
+ then
+ echo "[init] Start GPS"
+ if [ $GPS_FAKE == yes ]
+ then
+ echo "[init] Faking GPS"
+ gps start -f
+ else
+ gps start
+ fi
+ fi
+
#
# Start up ARDrone Motor interface
#
@@ -514,7 +518,7 @@ then
then
set MAV_TYPE 13
fi
- if [ $MIXER == hexa_cox ]
+ if [ $MIXER == FMU_hexa_cox ]
then
set MAV_TYPE 13
fi
@@ -561,7 +565,7 @@ then
echo "[init] Starting addons script: $EXTRAS_FILE"
sh $EXTRAS_FILE
else
- echo "[init] Addons script not found: $EXTRAS_FILE"
+ echo "[init] No addons script: $EXTRAS_FILE"
fi
if [ $EXIT_ON_END == yes ]
diff --git a/ROMFS/px4fmu_common/mixers/hexa_cox.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_cox.mix
index 497786feb..497786feb 100644
--- a/ROMFS/px4fmu_common/mixers/hexa_cox.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_hexa_cox.mix
diff --git a/ROMFS/px4fmu_common/mixers/easystar.mix b/ROMFS/px4fmu_common/mixers/easystar.mix
new file mode 100644
index 000000000..0051ffdbb
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/easystar.mix
@@ -0,0 +1,31 @@
+EASYSTAR / EASYSTAR II MIXER
+============================
+
+Aileron mixer
+-------------
+One output - would be easy to add support for 2 servos
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+Elevator mixer
+------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
+
+Rudder mixer
+------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 -10000 -10000 0 -10000 10000
+
+Motor speed mixer
+-----------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000