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/4008_ardrone14
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS12
2 files changed, 16 insertions, 10 deletions
diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index fa9b9d18a..d6b2319f9 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -3,6 +3,8 @@
# ARDrone
#
+echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board"
+
# Just use the default multicopter settings.
sh /etc/init.d/rc.mc_defaults
@@ -29,12 +31,6 @@ then
param save
fi
-set FMU_MODE gpio
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-set MAV_TYPE 2
-set VEHICLE_TYPE mc
-param set BAT_V_SCALING 0.008381
+set FMU_MODE gpio_serial
+set OUTPUT_MODE fmu
+set ARDRONE yes \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 76f021e33..af78162ed 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -397,8 +397,10 @@ then
set EXIT_ON_END yes
else
# Start MAVLink on default port: ttyS1
- mavlink start
+ mavlink start -d /dev/ttyS0
usleep 5000
+
+ set EXIT_ON_END yes
fi
fi
@@ -428,6 +430,14 @@ then
fi
#
+ # Start up ARDrone Motor interface
+ #
+ if [ $ARDRONE == yes ]
+ then
+ ardrone_interface start -d /dev/ttyS1
+ fi
+
+ #
# Fixed wing setup
#
if [ $VEHICLE_TYPE == fw ]