diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-03-11 21:14:54 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-03-11 21:14:54 +0100 |
commit | 5f847ff8a3df1ba303129a7a4938305a6901755c (patch) | |
tree | f99e41d3d35bc89337c3dd5a876ea149f0eda079 /ROMFS | |
parent | 4cee3614c7bc2e960ac52e59014bc4d08b8da11e (diff) | |
download | px4-firmware-5f847ff8a3df1ba303129a7a4938305a6901755c.tar.gz px4-firmware-5f847ff8a3df1ba303129a7a4938305a6901755c.tar.bz2 px4-firmware-5f847ff8a3df1ba303129a7a4938305a6901755c.zip |
Remove HIL flag on startup
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rcS | 2 |
1 files changed, 1 insertions, 1 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index eba18ddb1..8cb8f4dc7 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -392,7 +392,7 @@ then if [ $HIL == yes ] then sleep 1 - set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0 -m hil" + set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0" usleep 5000 else # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s |