aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d')
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults2
-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/rc.usb1
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS10
5 files changed, 16 insertions, 3 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index fab2a7f18..e6de64054 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -10,7 +10,7 @@ then
param set NAV_LAND_ALT 90
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
- param set NAV_ACCEPT_RAD 50
+ param set NAV_ACC_RAD 50
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 307a64c4d..24d9650a0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -41,7 +41,9 @@ then
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
- param set NAV_ACCEPT_RAD 2.0
+ param set NAV_ACC_RAD 2.0
+ param set RTL_RETURN_ALT 30.0
+ param set RTL_DESCEND_ALT 10.0
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index e6fc535a6..973db9017 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -56,7 +56,6 @@ fi
if meas_airspeed start
then
- echo "[i] Using MEAS airspeed sensor"
else
if ets_airspeed start
then
@@ -67,6 +66,7 @@ else
fi
fi
+# Check for flow sensor
if px4flow start
then
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index ee040a706..b3de8e590 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -25,6 +25,7 @@ mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
usleep 100000
+mavlink stream -d /dev/ttyACM0 -s LOCAL_POSITION_NED -r 30
# Exit shell to make it available to MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 14fc8d2b4..26b729aad 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -430,6 +430,16 @@ then
unset MAVLINK_F
#
+ # MAVLink onboard / TELEM2
+ #
+ if ver hwcmp PX4FMU_V2
+ then
+ if param compare SYS_COMPANION 921600
+ then
+ mavlink start -d /dev/ttyS2 -b 921600 -m onboard
+ fi
+ fi
+
# UAVCAN
#
sh /etc/init.d/rc.uavcan