aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/15_tbs_discovery
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-08-28 15:50:06 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-08-28 15:50:06 +0200
commit0731d331bfbee88f91fa4737ec77c0a66ce171f6 (patch)
treeb6a25a74edcd3bc81ba5a64444bff1dfbd3aad89 /ROMFS/px4fmu_common/init.d/15_tbs_discovery
parentfeb4dad9e1c8e766cac93b55437c8234493ed71b (diff)
downloadpx4-firmware-0731d331bfbee88f91fa4737ec77c0a66ce171f6.tar.gz
px4-firmware-0731d331bfbee88f91fa4737ec77c0a66ce171f6.tar.bz2
px4-firmware-0731d331bfbee88f91fa4737ec77c0a66ce171f6.zip
ROMFS reshuffling / cleanup, in sync with QGC
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/15_tbs_discovery')
-rw-r--r--ROMFS/px4fmu_common/init.d/15_tbs_discovery78
1 files changed, 78 insertions, 0 deletions
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
new file mode 100644
index 000000000..4e7406b66
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -0,0 +1,78 @@
+#!nsh
+
+echo "[init] Team Blacksheep Discovery Quad"
+
+#
+# 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 set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_RCLOSS_THR 0.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+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
+
+ sh /etc/init.d/rc.io
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900
+ px4io min 1200 1200 1200 1200
+ px4io max 1800 1800 1800 1800
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ set EXIT_ON_END yes
+fi
+
+#
+# Load the mixer for a quad with wide arms
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+
+#
+# Set PWM output frequency
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi