Skip to content
Snippets Groups Projects
Commit 5fe3c49b authored by Lorenz Meier's avatar Lorenz Meier
Browse files

Merged multirotor branch

parents e44d134c 66c61fbe
No related branches found
No related tags found
No related merge requests found
Showing
with 270 additions and 395 deletions
......@@ -19,14 +19,19 @@ Archives/*
Build/*
core
cscope.out
dot.gdbinit
Firmware.sublime-workspace
Images/*.bin
Images/*.px4
mavlink/include/mavlink/v0.9/
/nuttx-configs/px4io-v2/src/.depend
/nuttx-configs/px4io-v2/src/Make.dep
/nuttx-configs/px4io-v2/src/libboard.a
/nuttx-configs/px4io-v1/src/.depend
/nuttx-configs/px4io-v1/src/Make.dep
/nuttx-configs/px4io-v1/src/libboard.a
/NuttX
/Documentation/doxy.log
/Documentation/html/
/Documentation/doxygen*objdb*tmp
.tags
.tags_sorted_by_file
\ No newline at end of file
.tags_sorted_by_file
......@@ -27,7 +27,7 @@ define _perf_print
# PC_COUNT
if $hdr->type == 0
set $count = (struct perf_ctr_count *)$hdr
printf "%llu events,\n", $count->event_count;
printf "%llu events\n", $count->event_count
end
# PC_ELPASED
if $hdr->type == 1
......
# copy the file to .gdbinit in your Firmware tree, and adjust the path
# below to match your system
# For example:
# target extended /dev/serial/by-id/usb-Black_Sphere_Technologies_Black_Magic_Probe_DDE5A1C4-if00
# target extended /dev/ttyACM4
monitor swdp_scan
attach 1
monitor vector_catch disable hard
set mem inaccessible-by-default off
set print pretty
source Debug/PX4
# program a bootable device load on a mavstation
# To run type openocd -f mavprogram.cfg
source [find interface/olimex-arm-usb-ocd-h.cfg]
source [find px4fmu-v1-board.cfg]
init
halt
# Find the flash inside this CPU
flash probe 0
# erase it (128 pages) then program and exit
#flash erase_sector 0 0 127
# stm32f1x mass_erase 0
# It seems that Pat's image has a start address offset of 0x1000 but the vectors need to be at zero, so fixbin.sh moves things around
#flash write_bank 0 fixed.bin 0
#flash write_image firmware.elf
#shutdown
target remote :3333
# Don't let GDB get confused while stepping
define hook-step
mon cortex_m maskisr on
end
define hookpost-step
mon cortex_m maskisr off
end
mon init
mon stm32_init
# mon reset halt
mon poll
mon cortex_m maskisr auto
set mem inaccessible-by-default off
set print pretty
source Debug/PX4
echo PX4 resumed, press ctrl-c to interrupt\n
continue
# The latest defaults in OpenOCD 0.7.0 are actually prettymuch correct for the px4fmu
# increase working area to 32KB for faster flash programming
set WORKAREASIZE 0x8000
source [find target/stm32f4x.cfg]
# needed for px4
reset_config trst_only
proc stm32_reset {} {
reset halt
# FIXME - needed to init periphs on reset
# 0x40023800 RCC base
# 0x24 RCC_APB2 0x75933
# RCC_APB2 0
}
# perform init that is required on each connection to the target
proc stm32_init {} {
# force jtag to not shutdown during sleep
#uint32_t cr = getreg32(STM32_DBGMCU_CR);
#cr |= DBGMCU_CR_STANDBY | DBGMCU_CR_STOP | DBGMCU_CR_SLEEP;
#putreg32(cr, STM32_DBGMCU_CR);
mww 0xe0042004 00000007
}
# if srst is not fitted use SYSRESETREQ to
# perform a soft reset
cortex_m reset_config sysresetreq
# Let GDB directly program elf binaries
gdb_memory_map enable
# doesn't work yet
gdb_flash_program disable
#!/bin/bash
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
openocd -f interface/olimex-arm-usb-ocd-h.cfg -f $DIR/px4fmu-v1-board.cfg
# script for stm32f2xxx
if { [info exists CHIPNAME] } {
set _CHIPNAME $CHIPNAME
} else {
set _CHIPNAME stm32f4xxx
}
if { [info exists ENDIAN] } {
set _ENDIAN $ENDIAN
} else {
set _ENDIAN little
}
# Work-area is a space in RAM used for flash programming
# By default use 64kB
if { [info exists WORKAREASIZE] } {
set _WORKAREASIZE $WORKAREASIZE
} else {
set _WORKAREASIZE 0x10000
}
# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz
#
# Since we may be running of an RC oscilator, we crank down the speed a
# bit more to be on the safe side. Perhaps superstition, but if are
# running off a crystal, we can run closer to the limit. Note
# that there can be a pretty wide band where things are more or less stable.
jtag_khz 1000
jtag_nsrst_delay 100
jtag_ntrst_delay 100
#jtag scan chain
if { [info exists CPUTAPID ] } {
set _CPUTAPID $CPUTAPID
} else {
# See STM Document RM0033
# Section 32.6.3 - corresponds to Cortex-M3 r2p0
set _CPUTAPID 0x4ba00477
}
jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
if { [info exists BSTAPID ] } {
set _BSTAPID $BSTAPID
} else {
# See STM Document RM0033
# Section 32.6.2
#
set _BSTAPID 0x06413041
}
jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME -rtos auto
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
set _FLASHNAME $_CHIPNAME.flash
flash bank $_FLASHNAME stm32f2x 0 0 0 0 $_TARGETNAME
# if srst is not fitted use SYSRESETREQ to
# perform a soft reset
cortex_m3 reset_config sysresetreq
No preview for this file type
No preview for this file type
No preview for this file type
{
"board_id": 9,
"magic": "PX4FWv1",
"description": "Firmware for the PX4FMUv2 board",
"image": "",
"build_time": 0,
"summary": "PX4FMUv2",
"version": "0.1",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}
{
"board_id": 10,
"magic": "PX4FWv2",
"description": "Firmware for the PX4IOv2 board",
"image": "",
"build_time": 0,
"summary": "PX4IOv2",
"version": "2.0",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}
{
"board_id": 10,
"magic": "PX4FWv2",
"description": "Firmware for the PX4IOv2 board",
"image": "",
"build_time": 0,
"summary": "PX4IOv2",
"version": "2.0",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}
......@@ -40,14 +40,16 @@ export PX4_BASE := $(realpath $(dir $(lastword $(MAKEFILE_LIST))))/
include $(PX4_BASE)makefiles/setup.mk
#
# Canned firmware configurations that we build.
# Canned firmware configurations that we (know how to) build.
#
CONFIGS ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
KNOWN_CONFIGS := $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
CONFIGS ?= $(KNOWN_CONFIGS)
#
# Boards that we build NuttX export kits for.
# Boards that we (know how to) build NuttX export kits for.
#
BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
BOARDS ?= $(KNOWN_BOARDS)
#
# Debugging
......@@ -87,10 +89,11 @@ endif
#
# Built products
#
STAGED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
DESIRED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
STAGED_FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(IMAGE_DIR)$(config).px4)
FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
all: $(STAGED_FIRMWARES)
all: $(DESIRED_FIRMWARES)
#
# Copy FIRMWARES into the image directory.
......@@ -114,13 +117,26 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
@$(ECHO) %%%%
@$(ECHO) %%%% Building $(config) in $(work_dir)
@$(ECHO) %%%%
$(Q) mkdir -p $(work_dir)
$(Q) make -r -C $(work_dir) \
$(Q) $(MKDIR) -p $(work_dir)
$(Q) $(MAKE) -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
$(FIRMWARE_GOAL)
#
# Make FMU firmwares depend on the corresponding IO firmware.
#
# This is a pretty vile hack, since it hard-codes knowledge of the FMU->IO dependency
# and forces the _default config in all cases. There has to be a better way to do this...
#
FMU_VERSION = $(patsubst px4fmu-%,%,$(word 1, $(subst _, ,$(1))))
define FMU_DEP
$(BUILD_DIR)$(1).build/firmware.px4: $(IMAGE_DIR)px4io-$(call FMU_VERSION,$(1))_default.px4
endef
FMU_CONFIGS := $(filter px4fmu%,$(CONFIGS))
$(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
#
# Build the NuttX export archives.
#
......@@ -147,12 +163,12 @@ $(ARCHIVE_DIR)%.export: configuration = nsh
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@$(ECHO) %% Exporting NuttX for $(board)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) mkdir -p $(dir $@)
$(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) $(MKDIR) -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
......@@ -168,11 +184,11 @@ BOARD = $(BOARDS)
menuconfig: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(BOARD)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
@$(ECHO) %% Running menuconfig for $(BOARD)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
$(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
@$(ECHO) %% Saving configuration file
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
else
......@@ -191,7 +207,7 @@ $(NUTTX_SRC):
# Testing targets
#
testbuild:
$(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
$(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
#
# Cleanup targets. 'clean' should remove all built products and force
......@@ -206,7 +222,8 @@ clean:
.PHONY: distclean
distclean: clean
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) $(MAKE) -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(FIND) . -maxdepth 1 -type l -delete)
#
# Print some help text
......@@ -228,9 +245,9 @@ help:
@$(ECHO) " A limited set of configs can be built with CONFIGS=<list-of-configs>"
@$(ECHO) ""
@for config in $(CONFIGS); do \
echo " $$config"; \
echo " Build just the $$config firmware configuration."; \
echo ""; \
$(ECHO) " $$config"; \
$(ECHO) " Build just the $$config firmware configuration."; \
$(ECHO) ""; \
done
@$(ECHO) " clean"
@$(ECHO) " Remove all firmware build pieces."
......
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# disable USB and autostart
set USB no
set MODE custom
echo "[init] doing PX4FMU Quad startup..."
#
# Start the ORB
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/params
fi
echo "[init] 01_fmu_quad_x: PX4FMU Quad X with PWM outputs"
#
# Load default params for this platform
......@@ -52,56 +30,35 @@ fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
#
# Start GPS interface (depends on orb)
# Start PWM output
#
gps start
fmu mode_pwm
#
# Start the attitude estimator
# Load mixer
#
attitude_estimator_ekf start
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
pwm -u 400 -m 0xff
#
# Start attitude control
# Set PWM output frequency
#
multirotor_att_control start
pwm -u 400 -m 0xff
#
# Start logging
# Start common for all multirotors apps
#
sdlog2 start -r 50 -a -b 14
sh /etc/init.d/rc.multirotor
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
#!nsh
#
# Flight startup script for PX4FMU+PX4IO
#
# disable USB and autostart
set USB no
set MODE custom
#
# Start the ORB (first app to start)
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/params
fi
echo "[init] 02_io_quad_x: PX4FMU+PX4IO Quad X with PWM outputs"
#
# Load default params for this platform
......@@ -28,74 +8,40 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start MAVLink (depends on orb)
# Start MAVLink
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander (depends on orb, mavlink)
#
commander start
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# Disable px4io topic limiting
#
px4io limit 200
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator (depends on orb)
# Start and configure PX4IO interface
#
attitude_estimator_ekf start
sh /etc/init.d/rc.io
#
# Load mixer and start controllers (depends on px4io)
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
pwm -u 400 -m 0xff
multirotor_att_control start
#
# Start logging
# Set PWM output frequency
#
sdlog2 start -r 50 -a -b 14
pwm -u 400 -m 0xff
#
# Start system state
# Start common for all multirotors apps
#
if blinkm start
then
blinkm systemstate
fi
sh /etc/init.d/rc.multirotor
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE ardrone
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
#
uorb start
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
# Load microSD params
# Load default params for this platform
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
if param compare SYS_AUTOCONFIG 1
then
param load /fs/microsd/params
# Set all params here, then disable autoconfig
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Fire up the multi rotor attitude controller
# Configure PX4FMU for operation with PX4IOAR
#
multirotor_att_control start
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start logging
#
sdlog start -s 10
#
# Start GPS capture
#
gps start
#
# Start system state
#
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
# use the same UART for telemetry
# Start common for all multirotors apps
#
echo "[init] startup done"
sh /etc/init.d/rc.multirotor
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
# Disable the USB interface
set USB no
echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
# Disable autostarting other apps
set MODE ardrone
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
# Load default params for this platform
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
if param compare SYS_AUTOCONFIG 1
then
param load /fs/microsd/params
# Set all params here, then disable autoconfig
# TODO
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink_onboard start -d /dev/ttyS3 -b 115200
usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink and MAVLink Onboard (Flow Sensor)
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink_onboard start -d /dev/ttyS3 -b 115200
usleep 5000
#
# Start the commander.
#
......@@ -79,16 +71,6 @@ flow_position_control start
# Fire up the flow speed controller
#
flow_speed_control start
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
#
echo "[init] startup done"
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
#!nsh
#
# Flight startup script for PX4FMU+PX4IO
#
# disable USB and autostart
set USB no
set MODE custom
echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame"
#
# Load default params for this platform
......@@ -15,27 +10,26 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
param set MC_ATTRATE_D 0.005
param set MC_ATTRATE_D 0.004
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.1
param set MC_ATTRATE_P 0.12
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 4.5
param set MC_ATT_P 7.0
param set MC_RCLOSS_THR 0.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.3
param set MC_YAWPOS_P 0.6
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_P 0.1
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWRATE_D 0.005
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_P 0.3
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
......@@ -44,73 +38,30 @@ param set MAV_TYPE 2
#
mavlink start
usleep 5000
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
pwm -u 400 -m 0xff
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# Disable px4io topic limiting
# Start and configure PX4IO interface
#
px4io limit 200
sh /etc/init.d/rc.io
#
# This sets a PWM right after startup (regardless of safety button)
# Set PWM values for DJI ESCs
#
px4io idle 900 900 900 900
#
# The values are for spinning motors when armed using DJI ESCs
#
px4io min 1200 1200 1200 1200
#
# Upper limits could be higher, this is on the safe side
#
px4io max 1800 1800 1800 1800
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start the commander (depends on orb, mavlink)
#
commander start
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator (depends on orb)
#
attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
multirotor_att_control start
#
# Start logging
# Set PWM output frequency
#
sdlog2 start -r 20 -a -b 16
pwm -u 400 -m 0xff
#
# Start system state
# Start common for all multirotors apps
#
if blinkm start
then
blinkm systemstate
fi
sh /etc/init.d/rc.multirotor
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment