Browse Source

Merge branch 'master' of github.com:PX4/Firmware into ekf_params

sbg
Lorenz Meier 11 years ago
parent
commit
2ecaab98f9
  1. 50
      ROMFS/px4fmu_common/init.d/rcS
  2. 5
      src/modules/mavlink/mavlink_main.cpp

50
ROMFS/px4fmu_common/init.d/rcS

@ -20,7 +20,7 @@ echo "[init] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd if mount -t vfat /dev/mmcsd0 /fs/microsd
then then
set LOG_FILE /fs/microsd/bootlog.txt set LOG_FILE /fs/microsd/bootlog.txt
echo "[init] microSD card mounted at /fs/microsd" echo "[init] microSD mounted: /fs/microsd"
# Start playing the startup tune # Start playing the startup tune
tone_alarm start tone_alarm start
else else
@ -83,9 +83,9 @@ then
param select $PARAM_FILE param select $PARAM_FILE
if param load if param load
then then
echo "[init] Parameters loaded: $PARAM_FILE" echo "[init] Params loaded: $PARAM_FILE"
else else
echo "[init] ERROR: Parameters loading failed: $PARAM_FILE" echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi fi
# #
@ -146,7 +146,7 @@ then
# #
if param compare SYS_AUTOSTART 0 if param compare SYS_AUTOSTART 0
then then
echo "[init] Don't try to find autostart script" echo "[init] No autostart"
else else
sh /etc/init.d/rc.autostart sh /etc/init.d/rc.autostart
fi fi
@ -156,10 +156,10 @@ then
# #
if [ -f $CONFIG_FILE ] if [ -f $CONFIG_FILE ]
then then
echo "[init] Reading config: $CONFIG_FILE" echo "[init] Config: $CONFIG_FILE"
sh $CONFIG_FILE sh $CONFIG_FILE
else else
echo "[init] Config file not found: $CONFIG_FILE" echo "[init] Config not found: $CONFIG_FILE"
fi fi
# #
@ -264,10 +264,10 @@ then
then then
set FMU_MODE serial set FMU_MODE serial
fi fi
else
# Try to get an USB console if not in HIL mode
nshterm /dev/ttyACM0 &
fi fi
# Try to get an USB console
nshterm /dev/ttyACM0 &
# #
# Start the Commander (needs to be this early for in-air-restarts) # Start the Commander (needs to be this early for in-air-restarts)
@ -401,23 +401,17 @@ then
# #
if [ $MAVLINK_FLAGS == default ] if [ $MAVLINK_FLAGS == default ]
then then
if [ $HIL == yes ] # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
if [ $TTYS1_BUSY == yes ]
then then
sleep 1 # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0" set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else else
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s # Start MAVLink on default port: ttyS1
if [ $TTYS1_BUSY == yes ] set MAVLINK_FLAGS "-r 1000"
then
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else
# Start MAVLink on default port: ttyS1
set MAVLINK_FLAGS "-r 1000"
fi
fi fi
fi fi
@ -436,17 +430,15 @@ then
# #
# Sensors, Logging, GPS # Sensors, Logging, GPS
# #
echo "[init] Start sensors"
sh /etc/init.d/rc.sensors sh /etc/init.d/rc.sensors
if [ $HIL == no ] if [ $HIL == no ]
then then
echo "[init] Start logging" echo "[init] Start logging"
sh /etc/init.d/rc.logging sh /etc/init.d/rc.logging
echo "[init] Start GPS"
gps start
fi fi
gps start
# #
# Start up ARDrone Motor interface # Start up ARDrone Motor interface
@ -561,7 +553,7 @@ then
echo "[init] Starting addons script: $EXTRAS_FILE" echo "[init] Starting addons script: $EXTRAS_FILE"
sh $EXTRAS_FILE sh $EXTRAS_FILE
else else
echo "[init] Addons script not found: $EXTRAS_FILE" echo "[init] No addons script: $EXTRAS_FILE"
fi fi
if [ $EXIT_ON_END == yes ] if [ $EXIT_ON_END == yes ]

5
src/modules/mavlink/mavlink_main.cpp

@ -583,6 +583,11 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
/* open uart */ /* open uart */
_uart_fd = open(uart_name, O_RDWR | O_NOCTTY); _uart_fd = open(uart_name, O_RDWR | O_NOCTTY);
if (_uart_fd < 0) {
return _uart_fd;
}
/* Try to set baud rate */ /* Try to set baud rate */
struct termios uart_config; struct termios uart_config;
int termios_state; int termios_state;

Loading…
Cancel
Save