Merged beta into master

This commit is contained in:
Lorenz Meier
2015-08-01 16:58:02 +02:00
87 changed files with 1386 additions and 545 deletions
@@ -1,7 +1,15 @@
#!nsh
#
# HILStar
# <lorenz@px4.io>
# @name HILStar (XPlane)
#
# @type Simulation
#
# @output MAIN1 aileron
# @output MAIN2 elevator
# @output MAIN3 rudder
# @output MAIN4 throttle
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# Team Blacksheep Discovery Quadcopter
# @name Team Blacksheep Discovery
#
# Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io>
# @type Quadrotor Wide
#
# @maintainer Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# 3DR Iris Quadcopter
# @name 3DR Iris Quadrotor
#
# Anton Babushkin <anton@px4.io>
# @type Quadrotor Wide
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# Steadidrone QU4D
# @name Steadidrone QU4D
#
# Thomas Gubler <thomas@px4.io>
# @type Quadrotor Wide
#
# @maintainer Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,10 +1,10 @@
#!nsh
#
# Team Blacksheep Discovery Long Range Quadcopter
#
# Setup: 15 x 5" Props, 6S 4000mAh TBS LiPo, TBS 30A ESCs, TBS 400kV Motors
# @name Team Blacksheep Discovery Endurance
#
# Simon Wilks <simon@px4.io>
# @type Quadrotor Wide
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# HobbyKing SK450 DeadCat modification
# @name HobbyKing SK450 DeadCat modification
#
# Anton Matosov <anton.matosov@gmail.com>
# @type Quadrotor Wide
#
# @maintainer Anton Matosov <anton.matosov@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# HIL Quadcopter X
# @name HIL Quadcopter X
#
# Anton Babushkin <anton@px4.io>
# @type Simulation
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+10 -17
View File
@@ -1,32 +1,25 @@
#!nsh
#
# @name 3DR Iris Quadrotor
# @name 3DR DIY Quad
#
# @type Quadrotor Wide
# @type Quadrotor x
#
# @maintainer Anton Babushkin <anton@px4.io>
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
if [ $AUTOCNF == yes ]
then
# TODO tune roll/pitch separately
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.05
param set MC_ROLL_P 6.5
param set MC_ROLLRATE_P 0.08
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.05
param set MC_PITCH_P 6.0
param set MC_PITCHRATE_P 0.16
param set MC_PITCHRATE_I 0.09
param set MC_PITCHRATE_D 0.004
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
param set BAT_C_SCALING 0.0124
param set MC_YAW_P 4
fi
set MIXER quad_x
@@ -1,8 +1,10 @@
#!nsh
#
# HIL Quadcopter +
# @name HIL Quadcopter +
#
# Anton Babushkin <anton@px4.io>
# @type Simulation
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# HIL Rascal 110 (Flightgear)
# @name HIL Rascal 110 (Flightgear)
#
# Thomas Gubler <thomas@px4.io>
# @type Simulation
#
# @maintainer Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# HIL Malolo 1 (Flightgear)
# @name HIL Malolo 1 (Flightgear)
#
# Thomas Gubler <thomas@px4.io>
# @type Simulation
#
# @maintainer Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# Generic 10" Hexa coaxial geometry
# @name Generic Hexa coaxial geometry
#
# Lorenz Meier <lorenz@px4.io>
# @type Hexarotor Coaxial
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# Generic 10" Octo coaxial geometry
# @name Generic 10" Octo coaxial geometry
#
# Lorenz Meier <lorenz@px4.io>
# @type Octorotor Coaxial
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
@@ -1,7 +1,10 @@
#!nsh
#
# Generic configuration file for caipirinha VTOL version
# @name Duorotor Tailsitter
#
# Roman Bapst <bapstr@gmail.com>
# @type VTOL Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#
sh /etc/init.d/rc.vtol_defaults
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# Generic configuration file for BirdsEyeView Aerobotics FireFly6
# @name BirdsEyeView Aerobotics FireFly6
#
# Roman Bapst <bapstroman@gmail.com>
# @type VTOL Tiltrotor
#
# @maintainer Roman Bapst <roman@px4.io>
#
sh /etc/init.d/rc.vtol_defaults
@@ -1,7 +1,10 @@
#!nsh
#
# Generic configuration file for a tailsitter with motors in X configuration.
# @name Quadrotor X Tailsitter
#
# Roman Bapst <bapstroman@gmail.com>
# @type VTOL Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#
sh /etc/init.d/rc.vtol_defaults
@@ -0,0 +1,21 @@
#!nsh
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#
sh /etc/init.d/rc.vtol_defaults
set MIXER quad_+_vtol
set PWM_OUT 1234
set PWM_MAX 2000
set PWM_RATE 400
set MAV_TYPE 20
param set VT_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 0
param set VT_ELEV_MC_LOCK 1
+4 -3
View File
@@ -1,9 +1,10 @@
#!nsh
#
# Generic Tricopter Y Geometry
# Yaw Servo +Output ==> +Yaw Vehicle Rotation
# @name Generic Tricopter Y+ Geometry
#
# Trent Lukaczyk <aerialhedgehog@gmail.com>
# @type Tricopter Y+
#
# @maintainer Trent Lukaczyk <aerialhedgehog@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
+4 -3
View File
@@ -1,9 +1,10 @@
#!nsh
#
# Generic Tricopter Y Geometry
# Yaw Servo +Output ==> -Yaw Vehicle Rotation
# @name Generic Tricopter Y- Geometry
#
# Trent Lukaczyk <aerialhedgehog@gmail.com>
# @type Tricopter Y-
#
# @maintainer Trent Lukaczyk <aerialhedgehog@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
+5 -1
View File
@@ -1,6 +1,10 @@
#!nsh
#
# MPX EasyStar Plane
# @name Multiplex Easystar
#
# @type Standard Plane
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+17
View File
@@ -1,4 +1,21 @@
#!nsh
#
# @name Standard AERT Plane
#
# @type Standard Plane
#
# @output MAIN1 aileron
# @output MAIN2 elevator
# @output MAIN4 rudder
# @output MAIN3 throttle
# @output MAIN5 flaps
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -1,4 +1,21 @@
#!nsh
#
# @name Skywalker (3DR Aero)
#
# @type Standard Plane
#
# @output MAIN1 aileron
# @output MAIN2 elevator
# @output MAIN4 rudder
# @output MAIN3 throttle
# @output MAIN5 flaps
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -1,4 +1,19 @@
#!nsh
#
# @name Skyhunter 1800
#
# @type Standard Plane
#
# @output MAIN1 aileron
# @output MAIN2 elevator
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+17
View File
@@ -1,4 +1,21 @@
#!nsh
#
# @name Standard AETR Plane
#
# @type Standard Plane
#
# @output MAIN1 aileron
# @output MAIN2 elevator
# @output MAIN3 throttle
# @output MAIN4 rudder
# @output MAIN5 flaps
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+17 -2
View File
@@ -1,4 +1,21 @@
#!nsh
#
# @name IO Camflyer
#
# @url https://pixhawk.org/platforms/planes/bormatec_camflyer_q
#
# @type Flying Wing
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -17,11 +34,9 @@ then
param set FW_LND_TLALT 5
param set FW_THR_LND_MAX 0
param set FW_PR_FF 0.35
param set FW_PR_I 0.005
param set FW_PR_IMAX 0.4
param set FW_PR_P 0.08
param set FW_RR_FF 0.6
param set FW_RR_I 0.005
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.04
fi
+14 -4
View File
@@ -1,8 +1,20 @@
#!nsh
#
# Phantom FPV Flying Wing
# @name Phantom FPV Flying Wing
#
# Simon Wilks <simon@px4.io>
# @url https://pixhawk.org/platforms/planes/z-84_wing_wing
#
# @type Flying Wing
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -16,14 +28,12 @@ then
param set FW_L1_DAMPING 0.75
param set FW_L1_PERIOD 15
param set FW_PR_FF 0.2
param set FW_PR_I 0.005
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
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 50
+14 -2
View File
@@ -1,8 +1,20 @@
#!nsh
#
# Skywalker X5 Flying Wing
# @name Skywalker X5 Flying Wing
#
# Thomas Gubler <thomas@px4.io>, Julian Oes <julian@px4.io>
# @url https://pixhawk.org/platforms/planes/skywalker_x5
#
# @type Flying Wing
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Thomas Gubler <thomas@px4.io>, Julian Oes <julian@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+14 -2
View File
@@ -1,8 +1,20 @@
#!nsh
#
# Wing Wing (aka Z-84) Flying Wing
# @name Wing Wing (aka Z-84) Flying Wing
#
# Simon Wilks <simon@px4.io>
# @url https://pixhawk.org/platforms/planes/z-84_wing_wing
#
# @type Flying Wing
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# FX-79 Buffalo Flying Wing
# @name FX-79 Buffalo Flying Wing
#
# Simon Wilks <simon@px4.io>
# @type Flying Wing
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
+5 -2
View File
@@ -1,8 +1,11 @@
#
#!nsh
#
# Viper
# @name Viper
#
# Simon Wilks <simon@px4.io>
# @type Flying Wing
#
# @maintainer Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -1,8 +1,10 @@
#!nsh
#
# TBS Caipirinha
# @name TBS Caipirinha
#
# Lorenz Meier <lorenz@px4.io>
# @type Flying Wing
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@@ -22,16 +24,17 @@ then
param set FW_LND_TLALT 5
param set FW_THR_LND_MAX 0
param set FW_PR_FF 0.35
param set FW_PR_I 0.01
param set FW_PR_IMAX 0.4
param set FW_PR_P 0.08
param set FW_RR_FF 0.6
param set FW_RR_I 0.01
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.04
param set SYS_COMPANION 157600
param set PWM_MAIN_REV0 1
param set PWM_MAIN_REV1 1
param set PWM_DISARMED 0
param set PWM_MIN 900
param set PWM_MAX 2100
fi
set PWM_DISARMED p:PWM_DISARMED
+8 -2
View File
@@ -1,8 +1,14 @@
#!nsh
#
# Generic 10" Quad X geometry
# @name Generic Quadrotor X config
#
# Lorenz Meier <lorenz@px4.io>
# @type Quadrotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+5 -1
View File
@@ -1,6 +1,10 @@
#!nsh
#
# ARDrone
# @name AR.Drone Frame
#
# @type Quadrotor x
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+15 -4
View File
@@ -1,8 +1,14 @@
#!nsh
#
# DJI Flame Wheel F330
# @name DJI Flame Wheel F330
#
# Anton Babushkin <anton@px4.io>
# @type Quadrotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/4001_quad_x
@@ -21,7 +27,12 @@ then
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
# DJI ESCs do not support calibration and need a higher min
param set PWM_MIN 1230
fi
set PWM_MIN 1200
set PWM_MAX 1950
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1075
then
param set PWM_MIN 1230
fi
+15 -4
View File
@@ -1,8 +1,14 @@
#!nsh
#
# DJI Flame Wheel F450
# @name DJI Flame Wheel F450
#
# Lorenz Meier <lorenz@px4.io>
# @type Quadrotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/4001_quad_x
@@ -22,7 +28,12 @@ then
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
# DJI ESCs do not support calibration and need a higher min
param set PWM_MIN 1230
fi
set PWM_MIN 1230
set PWM_MAX 1950
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1075
then
param set PWM_MIN 1230
fi
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# F450-sized quadrotor with CAN
# @name F450-sized quadrotor with CAN
#
# Pavel Kirienko <pavel@px4.io>
# @type Quadrotor x
#
# @maintainer Pavel Kirienko <pavel@px4.io>
#
sh /etc/init.d/4001_quad_x
+4 -4
View File
@@ -1,11 +1,11 @@
#!nsh
#
# Hobbyking Micro Integrated PCB Quadcopter
# with SimonK ESC firmware and Mystery A1510 motors
# @name Hobbyking Micro PCB
#
# Thomas Gubler <thomas@px4.io>
# @type Quadrotor x
#
# @maintainer Thomas Gubler <thomas@px4.io>
#
echo "HK Micro PCB Quad"
sh /etc/init.d/4001_quad_x
@@ -1,9 +1,10 @@
#!nsh
#
# loading default values for the axialracing ax10
# @name Axial Racing AX10
#
# @type Rover
#
#load some defaults e.g. PWM values
sh /etc/init.d/rc.axialracing_ax10_defaults
#choose a mixer, for rover control we need a plain passthrough to the servos
+4 -2
View File
@@ -1,8 +1,10 @@
#!nsh
#
# Generic 10" Quad + geometry
# @name Generic 10" Quad + geometry
#
# Anton Babushkin <anton@px4.io>
# @type Quadrotor +
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+8 -2
View File
@@ -1,8 +1,14 @@
#!nsh
#
# Generic 10" Hexa X geometry
# @name Generic Hexarotor x geometry
#
# Anton Babushkin <anton@px4.io>
# @type Hexarotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+8 -2
View File
@@ -1,8 +1,14 @@
#!nsh
#
# Generic 10" Hexa + geometry
# @name Generic Hexarotor + geometry
#
# Anton Babushkin <anton@px4.io>
# @type Hexarotor +
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+8 -2
View File
@@ -1,8 +1,14 @@
#!nsh
#
# Generic 10" Octo X geometry
# @name Generic Octocopter X geometry
#
# Anton Babushkin <anton@px4.io>
# @type Octorotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
+8 -2
View File
@@ -1,8 +1,14 @@
#!nsh
#
# Generic 10" Octo + geometry
# @name Generic Octocopter + geometry
#
# Anton Babushkin <anton@px4.io>
# @type Octorotor +
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
-310
View File
@@ -1,310 +0,0 @@
#
# SYS_AUTOSTART = 0 means no autostart (default)
#
# AUTOSTART PARTITION:
# 0 .. 999 Reserved (historical)
# 1000 .. 1999 Simulation setups
# 2000 .. 2999 Standard planes
# 3000 .. 3999 Flying wing
# 4000 .. 4999 Quad X
# 5000 .. 5999 Quad +
# 6000 .. 6999 Hexa X
# 7000 .. 7999 Hexa +
# 8000 .. 8999 Octo X
# 9000 .. 9999 Octo +
# 10000 .. 10999 Wide arm / H frame
# 11000 .. 11999 Hexa Cox
# 12000 .. 12999 Octo Cox
# 13000 .. 13999 VTOL
# 14000 .. 14999 Tri Y
#
# Simulation
#
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
fi
if param compare SYS_AUTOSTART 1001
then
sh /etc/init.d/1001_rc_quad_x.hil
fi
if param compare SYS_AUTOSTART 1003
then
sh /etc/init.d/1003_rc_quad_+.hil
fi
if param compare SYS_AUTOSTART 1004
then
sh /etc/init.d/1004_rc_fw_Rascal110.hil
fi
if param compare SYS_AUTOSTART 1005
then
sh /etc/init.d/1005_rc_fw_Malolo1.hil
fi
#
# Plane
#
if param compare SYS_AUTOSTART 2100 100
then
sh /etc/init.d/2100_mpx_easystar
set MODE custom
fi
if param compare SYS_AUTOSTART 2101 101
then
sh /etc/init.d/2101_fw_AERT
set MODE custom
fi
if param compare SYS_AUTOSTART 2102 102
then
sh /etc/init.d/2102_3dr_skywalker
set MODE custom
fi
if param compare SYS_AUTOSTART 2103 103
then
sh /etc/init.d/2103_skyhunter_1800
set MODE custom
fi
if param compare SYS_AUTOSTART 2104
then
sh /etc/init.d/2104_fw_AETR
set MODE custom
fi
#
# Flying wing
#
if param compare SYS_AUTOSTART 3030 30
then
sh /etc/init.d/3030_io_camflyer
fi
if param compare SYS_AUTOSTART 3031 31
then
sh /etc/init.d/3031_phantom
fi
if param compare SYS_AUTOSTART 3032 32
then
sh /etc/init.d/3032_skywalker_x5
fi
if param compare SYS_AUTOSTART 3033 33
then
sh /etc/init.d/3033_wingwing
fi
if param compare SYS_AUTOSTART 3034 34
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
fi
#
# Quad X
#
if param compare SYS_AUTOSTART 4001
then
sh /etc/init.d/4001_quad_x
fi
#
# ARDrone
#
if param compare SYS_AUTOSTART 4008 8
then
sh /etc/init.d/4008_ardrone
fi
if param compare SYS_AUTOSTART 4010 10
then
sh /etc/init.d/4010_dji_f330
fi
if param compare SYS_AUTOSTART 4011 11
then
sh /etc/init.d/4011_dji_f450
fi
if param compare SYS_AUTOSTART 4012
then
sh /etc/init.d/4012_quad_x_can
fi
if param compare SYS_AUTOSTART 4020
then
sh /etc/init.d/4020_hk_micro_pcb
fi
#
# Quad +
#
if param compare SYS_AUTOSTART 5001
then
sh /etc/init.d/5001_quad_+
fi
#
# Hexa X
#
if param compare SYS_AUTOSTART 6001
then
sh /etc/init.d/6001_hexa_x
fi
#
# Hexa +
#
if param compare SYS_AUTOSTART 7001
then
sh /etc/init.d/7001_hexa_+
fi
#
# Octo X
#
if param compare SYS_AUTOSTART 8001
then
sh /etc/init.d/8001_octo_x
fi
#
# Octo +
#
if param compare SYS_AUTOSTART 9001
then
sh /etc/init.d/9001_octo_+
fi
#
# Wide arm / H frame
#
if param compare SYS_AUTOSTART 10015 15
then
sh /etc/init.d/10015_tbs_discovery
fi
if param compare SYS_AUTOSTART 10016 16
then
sh /etc/init.d/10016_3dr_iris
fi
if param compare SYS_AUTOSTART 10017
then
sh /etc/init.d/10017_steadidrone_qu4d
fi
if param compare SYS_AUTOSTART 10018 18
then
sh /etc/init.d/10018_tbs_endurance
fi
if param compare SYS_AUTOSTART 10019
then
sh /etc/init.d/10019_sk450_deadcat
fi
#
# Hexa Coaxial
#
if param compare SYS_AUTOSTART 11001
then
sh /etc/init.d/11001_hexa_cox
fi
#
# Octo Coaxial
#
if param compare SYS_AUTOSTART 12001
then
sh /etc/init.d/12001_octo_cox
fi
# 13000 is historically reserved for the quadshot
#
# VTOL Caipririnha (Tailsitter)
#
if param compare SYS_AUTOSTART 13001
then
sh /etc/init.d/13001_caipirinha_vtol
fi
#
# VTOL BirdsEyeView FireFly x6 (Tilt-Rotor)
#
if param compare SYS_AUTOSTART 13002
then
sh /etc/init.d/13002_firefly6
fi
#
# Tailsitter with 4 motors in x config
#
if param compare SYS_AUTOSTART 13003
then
sh /etc/init.d/13003_quad_tailsitter
fi
#
# TriCopter Y Yaw+
#
if param compare SYS_AUTOSTART 14001
then
sh /etc/init.d/14001_tri_y_yaw+
fi
#
# TriCopter Y Yaw-
#
if param compare SYS_AUTOSTART 14002
then
sh /etc/init.d/14002_tri_y_yaw-
fi
#
# Ground Rover AxialRacing AX10
#
if param compare SYS_AUTOSTART 50001
then
sh /etc/init.d/50001_axialracing_ax10
fi
+22 -3
View File
@@ -14,12 +14,31 @@ then
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set PWM_DISARMED 900
param set PWM_MIN 1075
param set PWM_MAX 1950
fi
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1000
then
param set PWM_MIN 1075
fi
if param compare PWM_MAX 2000
then
param set PWM_MAX 1950
fi
if param compare PWM_DISARMED 0
then
param set PWM_DISARMED 900
fi
# set environment variables (!= parameters)
set PWM_RATE 400
set PWM_DISARMED 900
set PWM_MIN 1075
set PWM_MAX 2000
# tell the mixer to use parameters for these instead
set PWM_DISARMED p:PWM_DISARMED
set PWM_MIN p:PWM_MIN
set PWM_MAX p:PWM_MAX
# This is the gimbal pass mixer
set MIXER_AUX pass
+9 -2
View File
@@ -575,7 +575,7 @@ then
fi
if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
then
set MAV_TYPE 2
set MAV_TYPE 15
fi
if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
then
@@ -599,6 +599,7 @@ then
if [ $MAV_TYPE == none ]
then
echo "Unknown MAV_TYPE"
param set MAV_TYPE 2
else
param set MAV_TYPE $MAV_TYPE
fi
@@ -642,6 +643,7 @@ then
if [ $MAV_TYPE == none ]
then
echo "Unknown MAV_TYPE"
param set MAV_TYPE 19
else
param set MAV_TYPE $MAV_TYPE
fi
@@ -672,6 +674,8 @@ then
then
sh /etc/init.d/rc.axialracing_ax10_apps
fi
param set MAV_TYPE 10
fi
unset MIXER
@@ -708,7 +712,7 @@ then
fi
unset EXIT_ON_END
# Run no SD alarm last
# Run no SD alarm
if [ $LOG_FILE == /dev/null ]
then
echo "[i] No microSD card found"
@@ -716,6 +720,9 @@ then
tone_alarm error
fi
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
mavlink boot_complete
# End of autostart
fi
@@ -0,0 +1,28 @@
Mixer for Tailsitter with + motor configuration and elevons
===========================================================
This file defines a single mixer for tailsitter with motors in X configuration. All controls
are mixed 100%.
R: 4+ 10000 10000 10000 0
# mixer for the elevons
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 -10000 -10000 0 -10000 10000
# mixer for canard surface
M: 1
O: 10000 10000 0 -10000 10000
S: 1 1 -10000 -10000 0 -10000 10000
# mixer for rudder
M: 1
O: 10000 10000 0 -10000 10000
S: 1 2 -10000 -10000 0 -10000 10000