#!nsh # Un comment and use set +e to ignore and set -e to enable 'exit on error control' set +e # Un comment the line below to help debug scripts by printing a trace of the script commands #set -x # PX4FMU startup script. # # NOTE: environment variable references: # If the dollar sign ('$') is followed by a left bracket ('{') then the # variable name is terminated with the right bracket character ('}'). # Otherwise, the variable name goes to the end of the argument. # # # NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS. # # # Set default paramter values # set AUX_MODE pwm set DATAMAN_OPT "" set FAILSAFE none set FAILSAFE_AUX none set FCONFIG /fs/microsd/etc/config.txt set FEXTRAS /fs/microsd/etc/extras.txt set FRC /fs/microsd/etc/rc.txt set FMU_ARGS "" set FMU_MODE pwm set IO_FILE "" set IO_PRESENT no set LOG_FILE /fs/microsd/bootlog.txt set LOGGER_BUF 14 set MAVLINK_F default set MAVLINK_COMPANION_DEVICE /dev/ttyS2 set MAV_TYPE none set MIXER none set MIXER_AUX none set MK_MODE none set MKBLCTRL_ARG "" set MODE autostart set OUTPUT_MODE none set PARAM_FILE /fs/microsd/params set PWM_OUT none set PWM_RATE p:PWM_RATE set PWM_DISARMED p:PWM_DISARMED set PWM_MIN p:PWM_MIN set PWM_MAX p:PWM_MAX set PWM_AUX_OUT none set PWM_AUX_RATE none set PWM_ACHDIS none set PWM_AUX_DISARMED p:PWM_AUX_DISARMED set PWM_AUX_MIN p:PWM_AUX_MIN set PWM_AUX_MAX p:PWM_AUX_MAX set TUNE_ERR "ML<> $LOG_FILE tone_alarm MLL8CDE set IO_PRESENT yes else echo "PX4IO update failed" >> $LOG_FILE tone_alarm ${TUNE_ERR} fi else echo "PX4IO update failed" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi fi fi if [ $USE_IO == yes -a $IO_PRESENT == no ] then echo "PX4IO not found" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi # # Set default output if not set # if [ $OUTPUT_MODE == none ] then if [ $USE_IO == yes ] then set OUTPUT_MODE io else set OUTPUT_MODE fmu fi fi if [ $OUTPUT_MODE == io -a $IO_PRESENT != yes ] then # Need IO for output but it not present, disable output set OUTPUT_MODE none fi if [ $OUTPUT_MODE == tap_esc ] then set FMU_MODE rcin fi if ver hwcmp AEROFC_V1 then set DATAMAN_OPT -i fi if ver hwcmp AEROCORE2 then set DATAMAN_OPT "-f /fs/mtd_dataman" fi # # waypoint storage # REBOOTWORK this needs to start in parallel # if dataman start $DATAMAN_OPT then fi # # Sensors System (start before Commander so Preflight checks are properly run) # commander Needs to be this early for in-air-restarts # if param compare SYS_HITL 1 then set OUTPUT_MODE hil sensors start -h commander start --hil else if ver hwcmp PX4_SAME70XPLAINED_V1 then gps start -d /dev/ttyS2 else gps start fi sh /etc/init.d/rc.sensors commander start fi send_event start load_mon start # # Check if UAVCAN is enabled, default to it for ESCs # if param greater UAVCAN_ENABLE 2 then set OUTPUT_MODE uavcan_esc fi # Sensors on the PWM interface bank if param compare SENS_EN_LL40LS 1 then # clear pins 5 and 6 set FMU_MODE pwm4 set AUX_MODE pwm4 fi if param greater TRIG_MODE 0 then # We ONLY support trigger on pins 5 and 6 when simultanously using AUX for actuator output if param compare TRIG_PINS 56 then # clear pins 5 and 6 set FMU_MODE pwm4 set AUX_MODE pwm4 else set FMU_MODE none set AUX_MODE none fi camera_trigger start param set CAM_FBACK_MODE 1 camera_feedback start fi # If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output if [ $OUTPUT_MODE != none ] then if [ $OUTPUT_MODE == uavcan_esc ] then if param compare UAVCAN_ENABLE 0 then param set UAVCAN_ENABLE 3 fi fi if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ] then if px4io start then sh /etc/init.d/rc.io else echo "PX4IO start failed" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi fi if [ $OUTPUT_MODE == fmu ] then if fmu mode_$FMU_MODE $FMU_ARGS then else echo "FMU start failed" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi fi if [ $OUTPUT_MODE == mkblctrl ] then if [ $MKBLCTRL_MODE == x ] then set MKBLCTRL_ARG "-mkmode x" fi if [ $MKBLCTRL_MODE == + ] then set MKBLCTRL_ARG "-mkmode +" fi if mkblctrl $MKBLCTRL_ARG then else tune_control play -m ${TUNE_ERR} fi fi if [ $OUTPUT_MODE == hil ] then if pwm_out_sim start then else tune_control play -m ${TUNE_ERR} fi fi # # Start IO or FMU for RC PPM input if needed # if [ $IO_PRESENT == yes ] then if [ $OUTPUT_MODE != io ] then if px4io start then sh /etc/init.d/rc.io else echo "PX4IO start failed" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi fi else if [ $OUTPUT_MODE != fmu ] then if fmu mode_${FMU_MODE} $FMU_ARGS then else echo "FMU mode_${FMU_MODE} start failed" >> $LOG_FILE tune_control play -m ${TUNE_ERR} fi fi fi fi # # Start mavlink streams. # sh /etc/init.d/rc.mavlink # # Starting stuff according to UAVCAN_ENABLE value # if param greater UAVCAN_ENABLE 0 then # Start core UAVCAN module if uavcan start then if param greater UAVCAN_ENABLE 1 then # Reduce logger buffer to free up some RAM for UAVCAN servers set LOGGER_BUF 6 # Start UAVCAN firmware update server and dynamic node ID allocation server uavcan start fw fi else tone_alarm ${TUNE_ERR} fi fi if ver hwcmp PX4FMU_V2 PX4FMU_V4 PX4FMU_V4PRO MINDPX_V2 PX4FMU_V5 OMNIBUS_F4SD then # Check for flow sensor - as it is a background task, launch it last px4flow start & fi # # Configure vehicle type specific parameters. # Note: rc.vehicle_setup is the entry point for rc.interface, # rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps. # sh /etc/init.d/rc.vehicle_setup # # Start the navigator. # navigator start # Start any custom addons. if [ -f $FEXTRAS ] then echo "Addons script: ${FEXTRAS}" sh $FEXTRAS fi # # Start a thermal calibration if required. # sh /etc/init.d/rc.thermal_cal # # vmount to control mounts such as gimbals, disabled by default. # if param compare MNT_MODE_IN -1 then else if vmount start then fi fi # # Start the logger. # sh /etc/init.d/rc.logging # End of autostart. fi # There is no further script processing, so we can free some RAM # XXX potentially unset all script variables. unset AUX_MODE unset DATAMAN_OPT unset FAILSAFE unset FAILSAFE_AUX unset FCONFIG unset FEXTRAS unset FRC unset FMU_ARGS unset FMU_MODE unset IO_FILE unset IO_PRESENT unset LOG_FILE unset LOGGER_BUF unset MAVLINK_F unset MAVLINK_COMPANION_DEVICE unset MAV_TYPE unset MIXER unset MIXER_AUX unset MK_MODE unset MKBLCTRL_ARG unset MODE unset OUTPUT_AUX_DEV unset OUTPUT_DEV unset OUTPUT_MODE unset PARAM_FILE unset PWM_ACHDIS unset PWM_OUT unset PWM_RATE unset PWM_DISARMED unset PWM_MIN unset PWM_MAX unset PWM_AUX_OUT unset PWM_AUX_RATE unset PWM_ACHDIS unset PWM_AUX_DISARMED unset PWM_AUX_MIN unset PWM_AUX_MAX unset TUNE_ERR unset USE_IO unset VEHICLE_TYPE # Boot is complete, inform MAVLink app(s) that the system is now fully up and running mavlink boot_complete