Browse Source

Tweak startup order for memory

sbg
Lorenz Meier 9 years ago committed by Lorenz Meier
parent
commit
5786b73772
  1. 8
      ROMFS/tap_common/init.d/6001_hexa_x
  2. 27
      ROMFS/tap_common/init.d/rc.mc_defaults
  3. 10
      ROMFS/tap_common/init.d/rc.sensors
  4. 30
      ROMFS/tap_common/init.d/rcS

8
ROMFS/tap_common/init.d/6001_hexa_x

@ -13,7 +13,13 @@ @@ -13,7 +13,13 @@
sh /etc/init.d/rc.mc_defaults
tap_esc start -d /dev/ttyS4 -n 6
param set MAV_TYPE 13
param set MC_YAWRATE_P 0.12
param set CAL_MAG0_ROT 6
if tap_esc start -d /dev/ttyS4 -n 6
then
fi
set OUTPUT_MODE tap_esc
set MIXER hexa_x

27
ROMFS/tap_common/init.d/rc.mc_defaults

@ -9,16 +9,19 @@ then @@ -9,16 +9,19 @@ then
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.25
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set PWM_DISARMED 900
param set PWM_MIN 1075
param set PWM_MAX 1950
param set RTL_LAND_DELAY 0
fi
param set NAV_ACC_RAD 2.0
param set MIS_TAKEOFF_ALT 2.5
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set MPC_THR_MIN 0.10
param set MPC_MANTHR_MIN 0.04
# set environment variables (!= parameters)
set PWM_RATE 400
# tell the mixer to use parameters for these instead
@ -33,17 +36,3 @@ set PWM_AUX_OUT 1234 @@ -33,17 +36,3 @@ set PWM_AUX_OUT 1234
set PWM_AUX_DISARMED 1500
set PWM_AUX_MIN 1000
set PWM_AUX_MAX 2000
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1000
then
param set PWM_MIN 1075
fi
if param compare PWM_MAX 2000
then
param set PWM_MAX 1950
fi
if param compare PWM_DISARMED 0
then
param set PWM_DISARMED 900
fi

10
ROMFS/tap_common/init.d/rc.sensors

@ -16,17 +16,13 @@ if hmc5883 -C -T -X start @@ -16,17 +16,13 @@ if hmc5883 -C -T -X start
then
fi
# Internal I2C bus Rotation TBD
# Internal I2C bus
if mpu6000 -I -T 6000 start
then
fi
if meas_airspeed start
then
fi
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 20000
# Wait 50 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 50000
if sensors start
then
fi

30
ROMFS/tap_common/init.d/rcS

@ -21,8 +21,6 @@ sercon @@ -21,8 +21,6 @@ sercon
set TUNE_ERR ML<<CP4CP4CP4CP4CP4
set LOG_FILE /fs/microsd/bootlog.txt
tone_alarm start
#
# Try to mount the microSD card.
#
@ -68,6 +66,8 @@ else @@ -68,6 +66,8 @@ else
fi
fi
tone_alarm start
#
# Start system state indicator
#
@ -158,7 +158,10 @@ commander start @@ -158,7 +158,10 @@ commander start
load_mon start
# Start MAVLink on the gimbal port
mavlink start -r 1200 -d /dev/ttyS1
#mavlink start -r 1200 -d /dev/ttyS1
# Start MAVLink on USB, developers can use the MAVLink shell
mavlink start -r 60000 -d /dev/ttyACM0 -m config
#
# Logging
@ -336,30 +339,9 @@ if navigator start @@ -336,30 +339,9 @@ if navigator start
then
fi
#
# Generic setup (autostart ID not found)
#
if [ $VEHICLE_TYPE == none ]
then
echo "WARN [init] No autostart ID found"
fi
# Start any custom addons
set FEXTRAS /fs/microsd/etc/extras.txt
if [ -f $FEXTRAS ]
then
echo "INFO [init] Addons script: $FEXTRAS"
sh $FEXTRAS
fi
unset FEXTRAS
# There is no further script processing, so we can free some RAM
# XXX potentially unset all script variables.
unset TUNE_ERR
# Start MAVLink on USB, developers can use the MAVLink shell
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
mavlink boot_complete
echo "[boot complete]"

Loading…
Cancel
Save