Browse Source

Removed confusing non-error message, updated start scripts to match wiki and most recent SW revs

sbg
Lorenz Meier 12 years ago
parent
commit
3d3a68a7fb
  1. 83
      ROMFS/scripts/rc.FMU_quad_x
  2. 87
      ROMFS/scripts/rc.PX4IO
  3. 36
      ROMFS/scripts/rc.PX4IOAR
  4. 3
      apps/commander/commander.c

83
ROMFS/scripts/rc.FMU_quad_x

@ -1,40 +1,67 @@ @@ -1,40 +1,67 @@
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE custom
echo "[init] doing PX4FMU Quad startup..."
#
# Start the ORB
#
# Startup for X-quad on FMU1.5/1.6
#
echo "[init] uORB"
uorb start
echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters ]
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load
param load /fs/microsd/parameters
fi
echo "[init] sensors"
#bma180 start
#l3gd20 start
mpu6000 start
hmc5883 start
ms5611 start
sensors start
echo "[init] mavlink"
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
echo "[init] commander"
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
echo "[init] attitude control"
#
# Start the attitude estimator
#
attitude_estimator_ekf start
multirotor_att_control start
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Start attitude control
#
multirotor_att_control start
echo "[init] startup done, exiting"
exit
exit

87
ROMFS/scripts/rc.PX4IO

@ -1,73 +1,80 @@ @@ -1,73 +1,80 @@
#!nsh
# Disable USB and autostart
set USB no
set MODE camflyer
#
# Start the object request broker
# Start the ORB
#
uorb start
#
# Init the EEPROM
# Load microSD params
#
echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters ]
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load
param load /fs/microsd/parameters
fi
#
# Enable / connect to PX4IO
#
px4io start
#
# Load an appropriate mixer. FMU_pass.mix is a passthru mixer
# which is good for testing. See ROMFS/mixers for a full list of mixers.
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
mixer load /dev/pwm_output /etc/mixers/FMU_pass.mix
param set MAV_TYPE 1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink on UART1 (dev/ttyS0) at 57600 baud (CLI is now unusable)
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start GPS interface
#
gps start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
kalman_demo start
#
# Start the attitude and position controller
# Start PX4IO interface
#
fixedwing_att_control start
fixedwing_pos_control start
px4io start
#
# Start GPS capture. Comment this out if you do not have a GPS.
# Load mixer and start controllers
#
gps start
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
#
# Start logging
#
# Start logging to microSD if we can
#
sh /etc/init.d/rc.logging
sdlog start -s 10
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
# Start system state
#
echo "[init] startup done"
exit
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi

36
ROMFS/scripts/rc.PX4IOAR

@ -17,7 +17,7 @@ echo "[init] doing PX4IOAR startup..." @@ -17,7 +17,7 @@ echo "[init] doing PX4IOAR startup..."
uorb start
#
# Load microSD params
# Init the parameter storage
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
@ -27,16 +27,23 @@ then @@ -27,16 +27,23 @@ then
fi
#
# Start MAVLink
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
param set MAV_TYPE 2
#
# Start the sensors and test them.
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
#
@ -62,15 +69,26 @@ multirotor_att_control start @@ -62,15 +69,26 @@ multirotor_att_control start
#
ardrone_interface start -d /dev/ttyS1
#
# Start GPS capture
#
gps start
#
# Start logging
#
#sdlog start
sdlog start -s 10
#
# Start GPS capture
# Start system state
#
gps start
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi
#
# startup is done; we don't want the shell because we

3
apps/commander/commander.c

@ -1459,9 +1459,6 @@ int commander_thread_main(int argc, char *argv[]) @@ -1459,9 +1459,6 @@ int commander_thread_main(int argc, char *argv[])
} else {
current_status.flag_external_manual_override_ok = true;
}
} else {
warnx("ARMED, rejecting sys type change\n");
}
}

Loading…
Cancel
Save