diff options
author | Anton Babushkin <anton.babushkin@me.com> | 2013-12-30 08:55:26 +0400 |
---|---|---|
committer | Anton Babushkin <anton.babushkin@me.com> | 2013-12-30 08:55:26 +0400 |
commit | a71b04775c435f53489e8a62c421131280ca093b (patch) | |
tree | 33391c7ab9127fdf4bf09cff08a774f80d792cff /ROMFS | |
parent | f084ddfeb05715efee2488e7bd9b51939b4142b8 (diff) | |
parent | 95bdc1a9bd364ce95abe06b097579cc8a9162e33 (diff) | |
download | px4-firmware-a71b04775c435f53489e8a62c421131280ca093b.tar.gz px4-firmware-a71b04775c435f53489e8a62c421131280ca093b.tar.bz2 px4-firmware-a71b04775c435f53489e8a62c421131280ca093b.zip |
Merge commit '95bdc1a9bd364ce95abe06b097579cc8a9162e33' into navigator_new_vector
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/31_io_phantom | 33 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/33_io_wingwing | 91 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/34_io_fx79 | 91 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/800_sdlogger | 60 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rcS | 18 | ||||
-rwxr-xr-x | ROMFS/px4fmu_common/mixers/FMU_FX79.mix | 72 |
6 files changed, 351 insertions, 14 deletions
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom index 63cd7f9b2..62cfe1a9c 100644 --- a/ROMFS/px4fmu_common/init.d/31_io_phantom +++ b/ROMFS/px4fmu_common/init.d/31_io_phantom @@ -8,30 +8,35 @@ echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV" if param compare SYS_AUTOCONFIG 1 then # Set all params here, then disable autoconfig + param set FW_AIRSPD_MIN 11.4 + param set FW_AIRSPD_TRIM 14 + param set FW_AIRSPD_MAX 22 + param set FW_L1_PERIOD 15 param set FW_P_D 0 param set FW_P_I 0 param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 + param set FW_P_LIM_MAX 45 + param set FW_P_LIM_MIN -45 param set FW_P_P 60 param set FW_P_RMAX_NEG 0 param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 + param set FW_P_ROLLFF 2 param set FW_R_D 0 param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 + param set FW_R_IMAX 15 + param set FW_R_P 80 + param set FW_R_RMAX 60 + param set FW_THR_CRUISE 0.8 + param set FW_THR_LND_MAX 0 param set FW_THR_MAX 1 - param set FW_THR_MIN 0 + param set FW_THR_MIN 0.5 param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 17 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 - + param set FW_T_SINK_MIN 2.0 + param set FW_Y_ROLLFF 1.0 + param set RC_SCALE_ROLL 0.6 + param set RC_SCALE_PITCH 0.6 + param set TRIM_PITCH 0.1 + param set SYS_AUTOCONFIG 0 param save fi diff --git a/ROMFS/px4fmu_common/init.d/33_io_wingwing b/ROMFS/px4fmu_common/init.d/33_io_wingwing new file mode 100644 index 000000000..538c69711 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/33_io_wingwing @@ -0,0 +1,91 @@ +#!nsh + +echo "[init] PX4FMU v1, v2 with or without IO on the Wing Wing (aka Z-84)" + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set FW_AIRSPD_MIN 7 + param set FW_AIRSPD_TRIM 9 + param set FW_AIRSPD_MAX 14 + param set FW_L1_PERIOD 10 + param set FW_P_D 0 + param set FW_P_I 0 + param set FW_P_IMAX 20 + param set FW_P_LIM_MAX 30 + param set FW_P_LIM_MIN -20 + param set FW_P_P 30 + param set FW_P_RMAX_NEG 0 + param set FW_P_RMAX_POS 0 + param set FW_P_ROLLFF 2 + param set FW_R_D 0 + param set FW_R_I 5 + param set FW_R_IMAX 20 + param set FW_R_P 60 + param set FW_R_RMAX 60 + param set FW_THR_CRUISE 0.65 + param set FW_THR_MAX 0.7 + param set FW_THR_MIN 0 + param set FW_T_SINK_MAX 5 + param set FW_T_SINK_MIN 2 + param set FW_T_TIME_CONST 9 + param set FW_Y_ROLLFF 2.0 + param set RC_SCALE_ROLL 1.0 + param set RC_SCALE_PITCH 1.0 + + param set SYS_AUTOCONFIG 0 + param save +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing +# +param set MAV_TYPE 1 + +set EXIT_ON_END no + +# +# Start and configure PX4IO or FMU interface +# +if px4io detect +then + # Start MAVLink (depends on orb) + mavlink start + + sh /etc/init.d/rc.io + # Limit to 100 Hz updates and (implicit) 50 Hz PWM + px4io limit 100 +else + # Start MAVLink (on UART1 / ttyS0) + mavlink start -d /dev/ttyS0 + + fmu mode_pwm + param set BAT_V_SCALING 0.004593 + set EXIT_ON_END yes +fi + +# +# Load mixer and start controllers (depends on px4io) +# +if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ] +then + echo "Using /fs/microsd/etc/mixers/FMU_Q.mix" + mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix +else + echo "Using /etc/mixers/FMU_Q.mix" + mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix +fi + +# +# Start common fixedwing apps +# +sh /etc/init.d/rc.fixedwing + +if [ $EXIT_ON_END == yes ] +then + exit +fi
\ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/34_io_fx79 b/ROMFS/px4fmu_common/init.d/34_io_fx79 new file mode 100644 index 000000000..989204952 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/34_io_fx79 @@ -0,0 +1,91 @@ +#!nsh + +echo "[init] PX4FMU v1, v2 with or without IO on FX-79 Buffalo" + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set FW_AIRSPD_MAX 20 + param set FW_AIRSPD_TRIM 12 + param set FW_AIRSPD_MIN 15 + param set FW_L1_PERIOD 12 + param set FW_P_D 0 + param set FW_P_I 0 + param set FW_P_IMAX 15 + param set FW_P_LIM_MAX 50 + param set FW_P_LIM_MIN -50 + param set FW_P_P 60 + param set FW_P_RMAX_NEG 0 + param set FW_P_RMAX_POS 0 + param set FW_P_ROLLFF 1.1 + param set FW_R_D 0 + param set FW_R_I 5 + param set FW_R_IMAX 20 + param set FW_R_P 80 + param set FW_R_RMAX 100 + param set FW_THR_CRUISE 0.75 + param set FW_THR_MAX 1 + param set FW_THR_MIN 0 + param set FW_T_SINK_MAX 5.0 + param set FW_T_SINK_MIN 4.0 + param set FW_T_TIME_CONST 9 + param set FW_Y_ROLLFF 1.1 + param set RC_SCALE_ROLL 1.0 + param set RC_SCALE_PITCH 1.0 + + param set SYS_AUTOCONFIG 0 + param save +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing +# +param set MAV_TYPE 1 + +set EXIT_ON_END no + +# +# Start and configure PX4IO or FMU interface +# +if px4io detect +then + # Start MAVLink (depends on orb) + mavlink start + + sh /etc/init.d/rc.io + # Limit to 100 Hz updates and (implicit) 50 Hz PWM + px4io limit 100 +else + # Start MAVLink (on UART1 / ttyS0) + mavlink start -d /dev/ttyS0 + + fmu mode_pwm + param set BAT_V_SCALING 0.004593 + set EXIT_ON_END yes +fi + +# +# Load mixer and start controllers (depends on px4io) +# +if [ -f /fs/microsd/etc/mixers/FMU_FX79.mix ] +then + echo "Using /fs/microsd/etc/mixers/FMU_FX79.mix" + mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_FX79.mix +else + echo "Using /etc/mixers/FMU_FX79.mix" + mixer load /dev/pwm_output /etc/mixers/FMU_FX79.mix +fi + +# +# Start common fixedwing apps +# +sh /etc/init.d/rc.fixedwing + +if [ $EXIT_ON_END == yes ] +then + exit +fi diff --git a/ROMFS/px4fmu_common/init.d/800_sdlogger b/ROMFS/px4fmu_common/init.d/800_sdlogger new file mode 100644 index 000000000..955fe0e2a --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/800_sdlogger @@ -0,0 +1,60 @@ +#!nsh + +echo "[init] PX4FMU v1, v2 init to log only + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set SYS_AUTOCONFIG 0 + + param save +fi + +set EXIT_ON_END no + +# +# Start and configure PX4IO or FMU interface +# +if px4io detect +then + # Start MAVLink (depends on orb) + mavlink start + usleep 5000 + + commander start + + sh /etc/init.d/rc.io + # Set PWM values for DJI ESCs +else + # Start MAVLink (on UART1 / ttyS0) + mavlink start -d /dev/ttyS0 + usleep 5000 + param set BAT_V_SCALING 0.004593 + set EXIT_ON_END yes +fi + +sh /etc/init.d/rc.sensors + +gps start + +attitude_estimator_ekf start + +position_estimator_inav start + +if [ -d /fs/microsd ] +then + if [ $BOARD == fmuv1 ] + then + sdlog2 start -r 50 -e -b 16 + else + sdlog2 start -r 200 -e -b 16 + fi +fi + +if [ $EXIT_ON_END == yes ] +then + exit +fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 14bb820fa..6eac00d0c 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -331,6 +331,18 @@ then set MODE custom fi + if param compare SYS_AUTOSTART 33 + then + sh /etc/init.d/33_io_wingwing + set MODE custom + fi + + if param compare SYS_AUTOSTART 34 + then + sh /etc/init.d/34_io_fx79 + set MODE custom + fi + if param compare SYS_AUTOSTART 40 then sh /etc/init.d/40_io_segway @@ -355,6 +367,12 @@ then set MODE custom fi + if param compare SYS_AUTOSTART 800 + then + sh /etc/init.d/800_sdlogger + set MODE custom + fi + # Start any custom extensions that might be missing if [ -f /fs/microsd/etc/rc.local ] then diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix new file mode 100755 index 000000000..0a1dca98d --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix @@ -0,0 +1,72 @@ +FX-79 Delta-wing mixer for PX4FMU +================================= + +Designed for FX-79. + +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 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 + +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 |