aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-08-01 12:09:16 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-08-01 12:09:16 +0200
commitf78ea38d982006389e83382a44baa672834acb6d (patch)
treee429b408296920f02156c07ccf1952513c5a401e /ROMFS
parentdb5d668439be63e4c8fd7dab49b81c5e162ee095 (diff)
parent2d4dd0d5c03a7ef3d696f40b6a6988e08e991034 (diff)
downloadpx4-firmware-f78ea38d982006389e83382a44baa672834acb6d.tar.gz
px4-firmware-f78ea38d982006389e83382a44baa672834acb6d.tar.bz2
px4-firmware-f78ea38d982006389e83382a44baa672834acb6d.zip
Merge remote-tracking branch 'upstream/master' into obcfailsafe
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb8
2 files changed, 11 insertions, 1 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index 3a50fcf56..3c336f295 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -11,4 +11,8 @@ then
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50
+ param set FW_T_HRATE_P 0.01
+ param set FW_T_RLL2THR 15
+ param set FW_T_SRATE_P 0.01
+ param set FW_T_TIME_CONST 5
fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 1f8d8b862..f1c21f295 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,8 +3,12 @@
# USB MAVLink start
#
-mavlink start -r 10000 -d /dev/ttyACM0 -x
+mavlink start -r 20000 -d /dev/ttyACM0 -x
# Enable a number of interesting streams we want via USB
+mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
@@ -15,6 +19,8 @@ mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
usleep 100000
+mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20