Merged new repository layout from PX4/Firmware

This commit is contained in:
Simon Wilks 2013-05-15 20:11:13 +02:00
commit 6571629dca
804 changed files with 23946 additions and 3897 deletions

7
.gitignore vendored
View File

@ -1,4 +1,5 @@
.built
.context
*.context
*.bdat
*.pdat
@ -43,7 +44,6 @@ nuttx/nuttx.hex
.settings
Firmware.sublime-workspace
.DS_Store
nsh_romfsimg.h
cscope.out
.configX-e
nuttx-export.zip
@ -55,3 +55,8 @@ mavlink/include/mavlink/v0.9/
core
.gdbinit
mkdeps
Archives
Build
!ROMFS/*/*.d
!ROMFS/*/*/*.d
!ROMFS/*/*/*/*.d

File diff suppressed because it is too large Load Diff

282
Makefile
View File

@ -1,43 +1,53 @@
#
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#
# Top-level Makefile for building PX4 firmware images.
#
#
# Note that this is a transitional process; the eventual goal is for this
# project to slim down and simply generate PX4 link kits via the NuttX
# 'make export' mechanism.
#
#
#
# Some useful paths.
# Get path and tool configuration
#
export PX4BASE = $(realpath $(dir $(lastword $(MAKEFILE_LIST))))
export NUTTX_SRC = $(PX4BASE)/nuttx
export NUTTX_APPS = $(PX4BASE)/apps
export MAVLINK_SRC = $(PX4BASE)/mavlink
export ROMFS_SRC = $(PX4BASE)/ROMFS
export IMAGE_DIR = $(PX4BASE)/Images
export PX4_BASE := $(realpath $(dir $(lastword $(MAKEFILE_LIST))))/
include $(PX4_BASE)makefiles/setup.mk
#
# Tools
# Canned firmware configurations that we build.
#
MKFW = $(PX4BASE)/Tools/px_mkfw.py
UPLOADER = $(PX4BASE)/Tools/px_uploader.py
CONFIGS ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
#
# What are we currently configured for?
# Boards that we build NuttX export kits for.
#
CONFIGURED = $(PX4BASE)/.configured
ifneq ($(wildcard $(CONFIGURED)),)
export TARGET := $(shell cat $(CONFIGURED))
endif
#
# What we will build
#
FIRMWARE_BUNDLE = $(IMAGE_DIR)/$(TARGET).px4
FIRMWARE_BINARY = $(IMAGE_DIR)/$(TARGET).bin
FIRMWARE_PROTOTYPE = $(IMAGE_DIR)/$(TARGET).prototype
BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
#
# Debugging
@ -45,120 +55,156 @@ FIRMWARE_PROTOTYPE = $(IMAGE_DIR)/$(TARGET).prototype
MQUIET = --no-print-directory
#MQUIET = --print-directory
all: $(FIRMWARE_BUNDLE)
################################################################################
# No user-serviceable parts below
################################################################################
#
# Generate a wrapped .px4 file from the built binary
# If the user has listed a config as a target, strip it out and override CONFIGS.
#
$(FIRMWARE_BUNDLE): $(FIRMWARE_BINARY) $(MKFW) $(FIRMWARE_PROTOTYPE)
@echo Generating $@
@$(MKFW) --prototype $(FIRMWARE_PROTOTYPE) \
--git_identity $(PX4BASE) \
--image $(FIRMWARE_BINARY) > $@
FIRMWARE_GOAL = firmware
EXPLICIT_CONFIGS := $(filter $(CONFIGS),$(MAKECMDGOALS))
ifneq ($(EXPLICIT_CONFIGS),)
CONFIGS := $(EXPLICIT_CONFIGS)
.PHONY: $(EXPLICIT_CONFIGS)
$(EXPLICIT_CONFIGS): all
#
# Build the firmware binary.
# If the user has asked to upload, they must have also specified exactly one
# config.
#
.PHONY: $(FIRMWARE_BINARY)
$(FIRMWARE_BINARY): setup_$(TARGET) configure-check
@echo Building $@ for $(TARGET)
@make -C $(NUTTX_SRC) -r $(MQUIET) all
@cp $(NUTTX_SRC)/nuttx.bin $@
#
# The 'configure' targets select one particular firmware configuration
# and makes it current.
#
configure_px4fmu:
@echo Configuring for px4fmu
@make -C $(PX4BASE) distclean
@cd $(NUTTX_SRC)/tools && /bin/sh configure.sh px4fmu/nsh
@echo px4fmu > $(CONFIGURED)
configure_px4io:
@echo Configuring for px4io
@make -C $(PX4BASE) distclean
@cd $(NUTTX_SRC)/tools && /bin/sh configure.sh px4io/io
@echo px4io > $(CONFIGURED)
configure-check:
ifeq ($(wildcard $(CONFIGURED)),)
@echo
@echo "Not configured - use 'make configure_px4fmu' or 'make configure_px4io' first"
@echo
@exit 1
ifneq ($(filter upload,$(MAKECMDGOALS)),)
ifneq ($(words $(EXPLICIT_CONFIGS)),1)
$(error In order to upload, exactly one board config must be specified)
endif
FIRMWARE_GOAL = upload
.PHONY: upload
upload:
@:
endif
endif
#
# Built products
#
STAGED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
all: $(STAGED_FIRMWARES)
#
# Per-configuration additional targets
# Copy FIRMWARES into the image directory.
#
.PHONY: px4fmu_setup
setup_px4fmu:
@echo Generating ROMFS
@make -C $(ROMFS_SRC) all
setup_px4io:
# fake target to make configure-check happy if TARGET is not set
setup_:
$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
@echo %% Copying $@
$(Q) $(COPY) $< $@
#
# Firmware uploading.
# Generate FIRMWARES.
#
.PHONY: $(FIRMWARES)
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
$(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) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
$(FIRMWARE_GOAL)
# serial port defaults by operating system.
SYSTYPE = $(shell uname)
ifeq ($(SYSTYPE),Darwin)
SERIAL_PORTS ?= "/dev/tty.usbmodemPX1,/dev/tty.usbmodemPX2,/dev/tty.usbmodemPX3,/dev/tty.usbmodemPX4,/dev/tty.usbmodem1,/dev/tty.usbmodem2,/dev/tty.usbmodem3,/dev/tty.usbmodem4"
endif
ifeq ($(SYSTYPE),Linux)
SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
endif
ifeq ($(SERIAL_PORTS),)
SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
#
# Build the NuttX export archives.
#
# Note that there are no explicit dependencies extended from these
# archives. If NuttX is updated, the user is expected to rebuild the
# archives/build area manually. Likewise, when the 'archives' target is
# invoked, all archives are always rebuilt.
#
# XXX Should support fetching/unpacking from a separate directory to permit
# downloads of the prebuilt archives as well...
#
# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4"
#
NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
.PHONY: archives
archives: $(NUTTX_ARCHIVES)
# We cannot build these parallel; note that we also force -j1 for the
# sub-make invocations.
ifneq ($(filter archives,$(MAKECMDGOALS)),)
.NOTPARALLEL:
endif
upload: $(FIRMWARE_BUNDLE) $(UPLOADER)
$(UPLOADER) --port $(SERIAL_PORTS) $(FIRMWARE_BUNDLE)
#
# JTAG firmware uploading with OpenOCD
#
ifeq ($(JTAGCONFIG),)
JTAGCONFIG=interface/olimex-jtag-tiny.cfg
endif
upload-jtag-px4fmu:
@echo Attempting to flash PX4FMU board via JTAG
@openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
upload-jtag-px4io: all
@echo Attempting to flash PX4IO board via JTAG
@openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown
#
# Hacks and fixups
#
ifeq ($(SYSTYPE),Darwin)
# PATH inherited by Eclipse may not include toolchain install location
export PATH := $(PATH):/usr/local/bin
endif
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
$(ARCHIVE_DIR)%.export: configuration = $(if $(filter $(board),px4io),io,nsh)
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
@echo %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@echo %% Exporting NuttX for $(board)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
$(Q) mkdir -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
#
# Cleanup targets. 'clean' should remove all built products and force
# a complete re-compilation, 'distclean' should remove everything
# that's generated leaving only files that are in source control.
#
.PHONY: clean upload-jtag-px4fmu
.PHONY: clean
clean:
@make -C $(NUTTX_SRC) -r $(MQUIET) distclean
@make -C $(ROMFS_SRC) -r $(MQUIET) clean
$(Q) $(RMDIR) $(BUILD_DIR)*.build
$(Q) $(REMOVE) $(IMAGE_DIR)*.px4
.PHONY: distclean
distclean:
@rm -f $(CONFIGURED)
@make -C $(NUTTX_SRC) -r $(MQUIET) distclean
@make -C $(ROMFS_SRC) -r $(MQUIET) distclean
distclean: clean
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
#
# Print some help text
#
.PHONY: help
help:
@echo ""
@echo " PX4 firmware builder"
@echo " ===================="
@echo ""
@echo " Available targets:"
@echo " ------------------"
@echo ""
@echo " archives"
@echo " Build the NuttX RTOS archives that are used by the firmware build."
@echo ""
@echo " all"
@echo " Build all firmware configs: $(CONFIGS)"
@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 ""; \
done
@echo " clean"
@echo " Remove all firmware build pieces."
@echo ""
@echo " distclean"
@echo " Remove all compilation products, including NuttX RTOS archives."
@echo ""
@echo " upload"
@echo " When exactly one config is being built, add this target to upload the"
@echo " firmware to the board when the build is complete. Not supported for"
@echo " all configurations."
@echo ""
@echo " Common options:"
@echo " ---------------"
@echo ""
@echo " V=1"
@echo " If V is set, more verbose output is printed during the build. This can"
@echo " help when diagnosing issues with the build or toolchain."
@echo ""

1
ROMFS/.gitignore vendored
View File

@ -1 +0,0 @@
/img

View File

@ -1,123 +0,0 @@
#
# Makefile to generate a PX4FMU ROMFS image.
#
# In normal use, 'make install' will generate a new ROMFS header and place it
# into the px4fmu configuration in the appropriate location.
#
#
# Directories of interest
#
SRCROOT ?= $(dir $(lastword $(MAKEFILE_LIST)))
BUILDROOT ?= $(SRCROOT)/img
ROMFS_HEADER ?= $(SRCROOT)/../nuttx/configs/px4fmu/include/nsh_romfsimg.h
#
# List of files to install in the ROMFS, specified as <source>~<destination>
#
ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
$(SRCROOT)/scripts/rc.sensors~init.d/rc.sensors \
$(SRCROOT)/scripts/rc.logging~init.d/rc.logging \
$(SRCROOT)/scripts/rc.standalone~init.d/rc.standalone \
$(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \
$(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
$(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \
$(SRCROOT)/scripts/rc.usb~init.d/rc.usb \
$(SRCROOT)/scripts/rc.hil~init.d/rc.hil \
$(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \
$(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \
$(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \
$(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
$(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
$(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \
$(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \
$(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \
$(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
$(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
$(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \
$(SRCROOT)/mixers/FMU_octo_+.mix~mixers/FMU_octo_+.mix \
$(SRCROOT)/logging/logconv.m~logging/logconv.m
# the EXTERNAL_SCRIPTS variable is used to add out of tree scripts
# to ROMFS.
ROMFS_FSSPEC += $(EXTERNAL_SCRIPTS)
#
# Add the PX4IO firmware to the spec if someone has dropped it into the
# source directory, or otherwise specified its location.
#
# Normally this is only something you'd do when working on PX4IO; most
# users will upgrade with firmware off the microSD card.
#
PX4IO_FIRMWARE ?= $(SRCROOT)/px4io.bin
ifneq ($(wildcard $(PX4IO_FIRMWARE)),)
ROMFS_FSSPEC += $(PX4IO_FIRMWARE)~px4io.bin
endif
################################################################################
# No user-serviceable parts below
################################################################################
#
# Just the source files from the ROMFS spec, so that we can fail cleanly if they don't
# exist
#
ROMFS_SRCFILES = $(foreach spec,$(ROMFS_FSSPEC),$(firstword $(subst ~, ,$(spec))))
#
# Just the destination directories from the ROMFS spec
#
ROMFS_DIRS = $(sort $(dir $(foreach spec,$(ROMFS_FSSPEC),$(lastword $(subst ~, ,$(spec))))))
#
# Intermediate products
#
ROMFS_IMG = $(BUILDROOT)/romfs.img
ROMFS_WORKDIR = $(BUILDROOT)/romfs
#
# Convenience target for rebuilding the ROMFS header
#
all: $(ROMFS_HEADER)
$(ROMFS_HEADER): $(ROMFS_IMG) $(dir $(ROMFS_HEADER))
@echo Generating the ROMFS header...
@(cd $(dir $(ROMFS_IMG)) && xxd -i $(notdir $(ROMFS_IMG))) | sed -e 's/char/const char/' > $@
$(ROMFS_IMG): $(ROMFS_WORKDIR)
@echo Generating the ROMFS image...
@genromfs -f $@ -d $(ROMFS_WORKDIR) -V "NSHInitVol"
$(ROMFS_WORKDIR): $(ROMFS_SRCFILES)
@echo Rebuilding the ROMFS work area...
@rm -rf $(ROMFS_WORKDIR)
@mkdir -p $(ROMFS_WORKDIR)
@for dir in $(ROMFS_DIRS) ; do mkdir -p $(ROMFS_WORKDIR)/$$dir; done
@for spec in $(ROMFS_FSSPEC) ; do \
echo $$spec | sed -e 's%^.*~% %' ;\
`echo "cp $$spec" | sed -e 's%~% $(ROMFS_WORKDIR)/%'` ;\
done
$(BUILDROOT):
@mkdir -p $(BUILDROOT)
clean:
@rm -rf $(BUILDROOT)
distclean: clean
@rm -f $(PX4IO_FIRMWARE) $(ROMFS_HEADER)
.PHONY: all install clean distclean
#
# Hacks and fixups
#
SYSTYPE = $(shell uname)
ifeq ($(SYSTYPE),Darwin)
# PATH inherited by Eclipse may not include toolchain install location
export PATH := $(PATH):/usr/local/bin
endif

View File

@ -20,10 +20,10 @@ uorb start
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/parameters
param load /fs/microsd/params
fi
#

View File

@ -0,0 +1,107 @@
#!nsh
# Disable USB and autostart
set USB no
set MODE quad
#
# 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
#
# 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
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
echo "PX4IO Firmware found. Checking Upgrade.."
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
then
echo "No newer version, skipping upgrade."
else
echo "Loading /fs/microsd/px4io.bin"
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
then
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
else
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
fi
fi
fi
#
# Start MAVLink (depends on orb)
#
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
#
# 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)
#
attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
multirotor_att_control start
#
# Start logging
#
#sdlog start -s 4
#
# Start system state
#
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi

View File

@ -13,10 +13,10 @@ uorb start
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/parameters
param load /fs/microsd/params
fi
#
@ -104,4 +104,4 @@ then
blinkm systemstate
else
echo "no BlinkM found, OK."
fi
fi

View File

@ -17,13 +17,13 @@ echo "[init] doing PX4IOAR startup..."
uorb start
#
# Init the parameter storage
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/parameters
param load /fs/microsd/params
fi
#
@ -96,4 +96,4 @@ fi
#
echo "[init] startup done"
exit
exit

View File

@ -17,10 +17,10 @@ hil mode_pwm
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/parameters
param load /fs/microsd/params
fi
#

View File

@ -7,6 +7,14 @@
# Start sensor drivers here.
#
#
# Check for UORB
#
if uorb start
then
echo "uORB started"
fi
ms5611 start
adc start

View File

@ -0,0 +1,50 @@
Delta-wing mixer for PX4FMU
===========================
This file defines mixers suitable for controlling a delta wing aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).
See the README for more information on the scaler format.
Elevon mixers
-------------
Three scalers total (output, roll, pitch).
On the assumption that the two elevon servos are physically reversed, the pitch
input is inverted between the two servos.
The scaling factor for roll inputs is adjusted to implement differential travel
for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 3000 5000 0 -10000 10000
S: 0 1 5000 5000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 5000 3000 0 -10000 10000
S: 0 1 -5000 -5000 0 -10000 10000
Output 2
--------
This mixer is empty.
Z:
Motor speed mixer
-----------------
Two scalers total (output, thrust).
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
range. Inputs below zero are treated as zero.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000

View File

@ -0,0 +1,6 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor with a wide configuration. All controls are mixed 100%.
R: 4w 10000 10000 10000 0

View File

@ -41,20 +41,19 @@
# The uploader uses the following fields from the firmware file:
#
# image
# The firmware that will be uploaded.
# The firmware that will be uploaded.
# image_size
# The size of the firmware in bytes.
# The size of the firmware in bytes.
# board_id
# The board for which the firmware is intended.
# The board for which the firmware is intended.
# board_revision
# Currently only used for informational purposes.
# Currently only used for informational purposes.
#
import sys
import argparse
import binascii
import serial
import os
import struct
import json
import zlib
@ -64,292 +63,294 @@ import array
from sys import platform as _platform
class firmware(object):
'''Loads a firmware file'''
'''Loads a firmware file'''
desc = {}
image = bytes()
crctab = array.array('I', [
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d ])
crcpad = bytearray('\xff\xff\xff\xff')
desc = {}
image = bytes()
crctab = array.array('I', [
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d])
crcpad = bytearray('\xff\xff\xff\xff')
def __init__(self, path):
def __init__(self, path):
# read the file
f = open(path, "r")
self.desc = json.load(f)
f.close()
# read the file
f = open(path, "r")
self.desc = json.load(f)
f.close()
self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
# pad image to 4-byte length
while ((len(self.image) % 4) != 0):
self.image.append('\xff')
# pad image to 4-byte length
while ((len(self.image) % 4) != 0):
self.image.append('\xff')
def property(self, propname):
return self.desc[propname]
def property(self, propname):
return self.desc[propname]
def __crc32(self, bytes, state):
for byte in bytes:
index = (state ^ byte) & 0xff
state = self.crctab[index] ^ (state >> 8)
return state
def __crc32(self, bytes, state):
for byte in bytes:
index = (state ^ byte) & 0xff
state = self.crctab[index] ^ (state >> 8)
return state
def crc(self, padlen):
state = self.__crc32(self.image, int(0))
for i in range(len(self.image), (padlen - 1), 4):
state = self.__crc32(self.crcpad, state)
return state
def crc(self, padlen):
state = self.__crc32(self.image, int(0))
for i in range(len(self.image), (padlen - 1), 4):
state = self.__crc32(self.crcpad, state)
return state
class uploader(object):
'''Uploads a firmware file to the PX FMU bootloader'''
'''Uploads a firmware file to the PX FMU bootloader'''
# protocol bytes
INSYNC = chr(0x12)
EOC = chr(0x20)
# protocol bytes
INSYNC = chr(0x12)
EOC = chr(0x20)
# reply bytes
OK = chr(0x10)
FAILED = chr(0x11)
INVALID = chr(0x13) # rev3+
# reply bytes
OK = chr(0x10)
FAILED = chr(0x11)
INVALID = chr(0x13) # rev3+
# command bytes
NOP = chr(0x00) # guaranteed to be discarded by the bootloader
GET_SYNC = chr(0x21)
GET_DEVICE = chr(0x22)
CHIP_ERASE = chr(0x23)
CHIP_VERIFY = chr(0x24) # rev2 only
PROG_MULTI = chr(0x27)
READ_MULTI = chr(0x28) # rev2 only
GET_CRC = chr(0x29) # rev3+
REBOOT = chr(0x30)
INFO_BL_REV = chr(1) # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 3 # maximum supported bootloader protocol
INFO_BOARD_ID = chr(2) # board type
INFO_BOARD_REV = chr(3) # board revision
INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
# command bytes
NOP = chr(0x00) # guaranteed to be discarded by the bootloader
GET_SYNC = chr(0x21)
GET_DEVICE = chr(0x22)
CHIP_ERASE = chr(0x23)
CHIP_VERIFY = chr(0x24) # rev2 only
PROG_MULTI = chr(0x27)
READ_MULTI = chr(0x28) # rev2 only
GET_CRC = chr(0x29) # rev3+
REBOOT = chr(0x30)
INFO_BL_REV = chr(1) # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 3 # maximum supported bootloader protocol
INFO_BOARD_ID = chr(2) # board type
INFO_BOARD_REV = chr(3) # board revision
INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
self.port = serial.Serial(portname, baudrate, timeout=0.25)
def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
self.port = serial.Serial(portname, baudrate, timeout=0.5)
def close(self):
if self.port is not None:
self.port.close()
def close(self):
if self.port is not None:
self.port.close()
def __send(self, c):
# print("send " + binascii.hexlify(c))
self.port.write(str(c))
def __send(self, c):
# print("send " + binascii.hexlify(c))
self.port.write(str(c))
def __recv(self, count = 1):
c = self.port.read(count)
if len(c) < 1:
raise RuntimeError("timeout waiting for data")
# print("recv " + binascii.hexlify(c))
return c
def __recv(self, count=1):
c = self.port.read(count)
if len(c) < 1:
raise RuntimeError("timeout waiting for data")
# print("recv " + binascii.hexlify(c))
return c
def __recv_int(self):
raw = self.__recv(4)
val = struct.unpack("<I", raw)
return val[0]
def __recv_int(self):
raw = self.__recv(4)
val = struct.unpack("<I", raw)
return val[0]
def __getSync(self):
self.port.flush()
c = self.__recv()
if c is not self.INSYNC:
raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if c == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if c != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
def __getSync(self):
self.port.flush()
c = self.__recv()
if c is not self.INSYNC:
raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if c == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if c != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
# attempt to get back into sync with the bootloader
def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput()
self.__send(uploader.GET_SYNC
+ uploader.EOC)
self.__getSync()
# def __trySync(self):
# c = self.__recv()
# if (c != self.INSYNC):
# #print("unexpected 0x%x instead of INSYNC" % ord(c))
# return False;
# c = self.__recv()
# if (c != self.OK):
# #print("unexpected 0x%x instead of OK" % ord(c))
# return False
# return True
# attempt to get back into sync with the bootloader
def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput()
self.__send(uploader.GET_SYNC
+ uploader.EOC)
self.__getSync()
# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
self.__send(uploader.GET_DEVICE + param + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
# def __trySync(self):
# c = self.__recv()
# if (c != self.INSYNC):
# #print("unexpected 0x%x instead of INSYNC" % ord(c))
# return False;
# c = self.__recv()
# if (c != self.OK):
# #print("unexpected 0x%x instead of OK" % ord(c))
# return False
# return True
# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self):
self.__send(uploader.CHIP_ERASE
+ uploader.EOC)
# erase is very slow, give it 10s
deadline = time.time() + 10
while time.time() < deadline:
try:
self.__getSync()
return
except RuntimeError as ex:
# we timed out, that's OK
continue
# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
self.__send(uploader.GET_DEVICE + param + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
raise RuntimeError("timed out waiting for erase")
# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self):
self.__send(uploader.CHIP_ERASE
+ uploader.EOC)
# erase is very slow, give it 20s
deadline = time.time() + 20
while time.time() < deadline:
try:
self.__getSync()
return
except RuntimeError:
# we timed out, that's OK
continue
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data):
self.__send(uploader.PROG_MULTI
+ chr(len(data)))
self.__send(data)
self.__send(uploader.EOC)
self.__getSync()
# verify multiple bytes in flash
def __verify_multi(self, data):
self.__send(uploader.READ_MULTI
+ chr(len(data))
+ uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
print(("got " + binascii.hexlify(programmed)))
print(("expect " + binascii.hexlify(data)))
return False
self.__getSync()
return True
# send the reboot command
def __reboot(self):
self.__send(uploader.REBOOT
+ uploader.EOC)
self.port.flush()
raise RuntimeError("timed out waiting for erase")
# v3+ can report failure if the first word flash fails
if self.bl_rev >= 3:
self.__getSync()
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data):
self.__send(uploader.PROG_MULTI
+ chr(len(data)))
self.__send(data)
self.__send(uploader.EOC)
self.__getSync()
# split a sequence into a list of size-constrained pieces
def __split_len(self, seq, length):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# verify multiple bytes in flash
def __verify_multi(self, data):
self.__send(uploader.READ_MULTI
+ chr(len(data))
+ uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
print("got " + binascii.hexlify(programmed))
print("expect " + binascii.hexlify(data))
return False
self.__getSync()
return True
# upload code
def __program(self, fw):
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
for bytes in groups:
self.__program_multi(bytes)
# send the reboot command
def __reboot(self):
self.__send(uploader.REBOOT
+ uploader.EOC)
self.port.flush()
# verify code
def __verify_v2(self, fw):
self.__send(uploader.CHIP_VERIFY
+ uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
for bytes in groups:
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
# v3+ can report failure if the first word flash fails
if self.bl_rev >= 3:
self.__getSync()
def __verify_v3(self, fw):
expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC
+ uploader.EOC)
report_crc = self.__recv_int()
self.__getSync()
if report_crc != expect_crc:
print(("Expected 0x%x" % expect_crc))
print(("Got 0x%x" % report_crc))
raise RuntimeError("Program CRC failed")
# split a sequence into a list of size-constrained pieces
def __split_len(self, seq, length):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
self.__sync()
# upload code
def __program(self, fw):
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
for bytes in groups:
self.__program_multi(bytes)
# get the bootloader protocol ID first
self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
print(("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV))
raise RuntimeError("Bootloader protocol mismatch")
# verify code
def __verify_v2(self, fw):
self.__send(uploader.CHIP_VERIFY
+ uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
for bytes in groups:
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
def __verify_v3(self, fw):
expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC
+ uploader.EOC)
report_crc = self.__recv_int()
self.__getSync()
if report_crc != expect_crc:
print("Expected 0x%x" % expect_crc)
print("Got 0x%x" % report_crc)
raise RuntimeError("Program CRC failed")
# upload the firmware
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
raise RuntimeError("Firmware not suitable for this board (run 'make configure_px4fmu && make clean' or 'make configure_px4io && make clean' to reconfigure).")
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
self.__sync()
print("erase...")
self.__erase()
# get the bootloader protocol ID first
self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
print("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV)
raise RuntimeError("Bootloader protocol mismatch")
print("program...")
self.__program(fw)
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
print("verify...")
if self.bl_rev == 2:
self.__verify_v2(fw)
else:
self.__verify_v3(fw)
# upload the firmware
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
raise RuntimeError("Firmware not suitable for this board")
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
print("erase...")
self.__erase()
print("program...")
self.__program(fw)
print("verify...")
if self.bl_rev == 2:
self.__verify_v2(fw)
else:
self.__verify_v3(fw)
print("done, rebooting.")
self.__reboot()
self.port.close()
print("done, rebooting.")
self.__reboot()
self.port.close()
# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
@ -360,57 +361,57 @@ args = parser.parse_args()
# Load the firmware file
fw = firmware(args.firmware)
print(("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'))))
print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision')))
# Spin waiting for a device to show up
while True:
for port in args.port.split(","):
for port in args.port.split(","):
#print("Trying %s" % port)
#print("Trying %s" % port)
# create an uploader attached to the port
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if not "COM" in port and not "tty.usb" in port:
up = uploader(port, args.baud)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
if not "COM" in port and not "ACM" in port:
up = uploader(port, args.baud)
elif "win" in _platform:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
except:
# open failed, rate-limit our attempts
time.sleep(0.05)
# create an uploader attached to the port
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if not "COM" in port and not "tty.usb" in port:
up = uploader(port, args.baud)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
if not "COM" in port and not "ACM" in port:
up = uploader(port, args.baud)
elif "win" in _platform:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
except:
# open failed, rate-limit our attempts
time.sleep(0.05)
# and loop to the next port
continue
# and loop to the next port
continue
# port is open, try talking to it
try:
# identify the bootloader
up.identify()
print(("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port)))
# port is open, try talking to it
try:
# identify the bootloader
up.identify()
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
except:
# most probably a timeout talking to the port, no bootloader
continue
except:
# most probably a timeout talking to the port, no bootloader
continue
try:
# ok, we have a bootloader, try flashing it
up.upload(fw)
try:
# ok, we have a bootloader, try flashing it
up.upload(fw)
except RuntimeError as ex:
except RuntimeError as ex:
# print the error
print(("ERROR: %s" % ex.args))
# print the error
print("ERROR: %s" % ex.args)
finally:
# always close the port
up.close()
finally:
# always close the port
up.close()
# we could loop here if we wanted to wait for more boards...
sys.exit(0)
# we could loop here if we wanted to wait for more boards...
sys.exit(0)

View File

@ -1,41 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Board-specific startup code for the PX4FMU
#
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
LIBNAME = brd_px4fmu
include $(APPDIR)/mk/app.mk

View File

@ -1,41 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Board-specific startup code for the PX4IO
#
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
LIBNAME = brd_px4io
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Interface driver for the PX4FMU board
#
APPNAME = hil
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the L3GD20 driver.
#
APPNAME = l3gd20
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the BMA180 driver.
#
APPNAME = mpu6000
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk

View File

@ -1,43 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# STM32 ADC driver
#
APPNAME = adc
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
include $(APPDIR)/mk/app.mk

View File

@ -1,43 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Tone alarm driver
#
APPNAME = tone_alarm
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
include $(APPDIR)/mk/app.mk

View File

@ -38,7 +38,6 @@
# Sub-directories
SUBDIRS = adc can cdcacm nsh
SUBDIRS += math_demo control_demo kalman_demo px4_deamon_app
#SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc
#SUBDIRS += ftpd hello helloxx hidkbd igmp json keypadtest lcdrw mm modbus mount

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Basic example application
#
APPNAME = control_demo
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Basic example application
#
APPNAME = math_demo
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 8192
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Basic example application
#
APPNAME = px4_deamon_app
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Basic example application
#
APPNAME = px4_mavlink_debug
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Basic example application
#
APPNAME = px4_simple_app
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,45 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Fixedwing Control application
#
APPNAME = fixedwing_att_control
PRIORITY = SCHED_PRIORITY_MAX - 30
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

View File

@ -1,45 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Fixedwing Control application
#
APPNAME = fixedwing_pos_control
PRIORITY = SCHED_PRIORITY_MAX - 30
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

View File

@ -1,45 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Graupner HoTT Telemetry application.
#
# The following line is required for accessing UARTs directly.
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
APPNAME = hott_telemetry
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Mavlink Application
#
APPNAME = mavlink
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Mavlink Application
#
APPNAME = mavlink_onboard
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

View File

@ -1,237 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Common Makefile for nsh command modules and utility libraries; should be
# included by the module-specific Makefile.
#
# To build an app that appears as an nsh external command, the caller
# must define:
#
# APPNAME - the name of the application, defaults to the name
# of the parent directory.
#
# If APPNAME is not defined, a utility library is built instead. The library
# name is normally automatically determined, but it can be overridden by
# setting:
#
# LIBNAME - the name of the library, defaults to the name of the
# directory
#
# The calling makefile may also set:
#
# ASRCS - list of assembly source files, defaults to all .S
# files in the directory
#
# CSRCS - list of C source files, defaults to all .c files
# in the directory
#
# CXXSRCS - list of C++ source files, defaults to all .cpp
# files in the directory
#
# INCLUDES - list of directories to be added to the include
# search path
#
# PRIORITY - thread priority for the command (defaults to
# SCHED_PRIORITY_DEFAULT)
#
# STACKSIZE - stack size for the command (defaults to
# CONFIG_PTHREAD_STACK_DEFAULT)
#
# Symbols in the module are private to the module unless deliberately exported
# using the __EXPORT tag, or DEFAULT_VISIBILITY is set
#
############################################################################
# No user-serviceable parts below
############################################################################
############################################################################
# Work out who included us so we can report decent errors
#
THIS_MAKEFILE := $(lastword $(MAKEFILE_LIST))
ifeq ($(APP_MAKEFILE),)
APP_MAKEFILE := $(lastword $(filter-out $(THIS_MAKEFILE),$(MAKEFILE_LIST)))
endif
############################################################################
# Get configuration
#
-include $(TOPDIR)/.config
-include $(TOPDIR)/Make.defs
include $(APPDIR)/Make.defs
############################################################################
# Sanity-check the information we've been given and set any defaults
#
SRCDIR ?= $(dir $(APP_MAKEFILE))
PRIORITY ?= SCHED_PRIORITY_DEFAULT
STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
INCLUDES += $(APPDIR)
ASRCS ?= $(wildcard $(SRCDIR)/*.S)
CSRCS ?= $(wildcard $(SRCDIR)/*.c)
CHDRS ?= $(wildcard $(SRCDIR)/*.h)
CXXSRCS ?= $(wildcard $(SRCDIR)/*.cpp)
CXXHDRS ?= $(wildcard $(SRCDIR)/*.hpp)
# if APPNAME is not set, this is a library
ifeq ($(APPNAME),)
LIBNAME ?= $(lastword $(subst /, ,$(realpath $(SRCDIR))))
endif
# there has to be a source file
ifeq ($(ASRCS)$(CSRCS)$(CXXSRCS),)
$(error $(realpath $(APP_MAKEFILE)): at least one of ASRCS, CSRCS or CXXSRCS must be set)
endif
# check that C++ is configured if we have C++ source files and we are building
ifneq ($(CXXSRCS),)
ifneq ($(CONFIG_HAVE_CXX),y)
ifeq ($(MAKECMDGOALS),build)
$(error $(realpath $(APP_MAKEFILE)): cannot set CXXSRCS if CONFIG_HAVE_CXX not set in configuration)
endif
endif
endif
############################################################################
# Adjust compilation flags to implement EXPORT
#
ifeq ($(DEFAULT_VISIBILITY),)
DEFAULT_VISIBILITY = hidden
else
DEFAULT_VISIBILITY = default
endif
CFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(APPDIR)/systemlib/visibility.h
CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(APPDIR)/systemlib/visibility.h
############################################################################
# Add extra include directories
#
CFLAGS += $(addprefix -I,$(INCLUDES))
CXXFLAGS += $(addprefix -I,$(INCLUDES))
############################################################################
# Things we are going to build
#
SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS)
AOBJS = $(patsubst %.S,%.o,$(ASRCS))
COBJS = $(patsubst %.c,%.o,$(CSRCS))
CXXOBJS = $(patsubst %.cpp,%.o,$(CXXSRCS))
OBJS = $(AOBJS) $(COBJS) $(CXXOBJS)
# Automatic depdendency generation
DEPS = $(OBJS:$(OBJEXT)=.d)
CFLAGS += -MD
CXXFLAGS += -MD
# The prelinked object that we are ultimately going to build
ifneq ($(APPNAME),)
PRELINKOBJ = $(APPNAME).pre.o
else
PRELINKOBJ = $(LIBNAME).pre.o
endif
# The archive the prelinked object will be linked into
# XXX does WINTOOL ever get set?
ifeq ($(WINTOOL),y)
INCDIROPT = -w
BIN = "$(shell cygpath -w $(APPDIR)/libapps$(LIBEXT))"
else
BIN = "$(APPDIR)/libapps$(LIBEXT)"
endif
############################################################################
# Rules for building things
#
all: .built
.PHONY: clean depend distclean
#
# Top-level build; add prelinked object to the apps archive
#
.built: $(PRELINKOBJ)
@$(call ARCHIVE, $(BIN), $(PRELINKOBJ))
@touch $@
#
# Source dependencies
#
depend:
@exit 0
ifneq ($(APPNAME),)
#
# App registration
#
context: .context
.context: $(MAKEFILE_LIST)
$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
@touch $@
else
context:
@exit 0
endif
#
# Object files
#
$(PRELINKOBJ): $(OBJS)
$(call PRELINK, $@, $(OBJS))
$(AOBJS): %.o : %.S $(MAKEFILE_LIST)
$(call ASSEMBLE, $<, $@)
$(COBJS): %.o : %.c $(MAKEFILE_LIST)
$(call COMPILE, $<, $@)
$(CXXOBJS): %.o : %.cpp $(MAKEFILE_LIST)
$(call COMPILEXX, $<, $@)
#
# Tidying up
#
clean:
@rm -f $(OBJS) $(DEPS) $(PRELINKOBJ) .built
$(call CLEAN)
distclean: clean
@rm -f Make.dep .depend
-include $(DEPS)

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build uORB
#
APPNAME = multirotor_att_control
PRIORITY = SCHED_PRIORITY_MAX - 15
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build multirotor position control
#
APPNAME = multirotor_pos_control
PRIORITY = SCHED_PRIORITY_MAX - 25
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

View File

@ -66,7 +66,7 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
MAXOPTIMIZATION = -Os
# Build targets
# Build Targets
all: .built
.PHONY: context .depend depend clean distclean

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the calibration tool
#
APPNAME = calibration
PRIORITY = SCHED_PRIORITY_MAX - 1
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -1,147 +0,0 @@
/****************************************************************************
* calibration.c
*
* Copyright (C) 2012 Ivan Ovinnikov. All rights reserved.
* Authors: Nils Wenzler <wenzlern@ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "calibration.h"
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int calibrate_help(int argc, char *argv[]);
static int calibrate_all(int argc, char *argv[]);
__EXPORT int calibration_main(int argc, char *argv[]);
/****************************************************************************
* Private Data
****************************************************************************/
struct {
const char *name;
int (* fn)(int argc, char *argv[]);
unsigned options;
#define OPT_NOHELP (1<<0)
#define OPT_NOALLTEST (1<<1)
} calibrates[] = {
{"range", range_cal, 0},
{"servo", servo_cal, 0},
{"all", calibrate_all, OPT_NOALLTEST},
{"help", calibrate_help, OPT_NOALLTEST | OPT_NOHELP},
{NULL, NULL}
};
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
static int
calibrate_help(int argc, char *argv[])
{
unsigned i;
printf("Available calibration routines:\n");
for (i = 0; calibrates[i].name; i++)
printf(" %s\n", calibrates[i].name);
return 0;
}
static int
calibrate_all(int argc, char *argv[])
{
unsigned i;
char *args[2] = {"all", NULL};
printf("Running all calibration routines...\n\n");
for (i = 0; calibrates[i].name; i++) {
printf(" %s:\n", calibrates[i].name);
if (calibrates[i].fn(1, args)) {
printf(" FAIL\n");
} else {
printf(" DONE\n");
}
}
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
void press_enter(void)
{
int c;
printf("Press CTRL+ENTER to continue... \n");
fflush(stdout);
do c = getchar(); while ((c != '\n') && (c != EOF));
}
/****************************************************************************
* Name: calibrate_main
****************************************************************************/
int calibration_main(int argc, char *argv[])
{
unsigned i;
if (argc < 2) {
printf("calibration: missing name - 'calibration help' for a list of routines\n");
return 1;
}
for (i = 0; calibrates[i].name; i++) {
if (!strcmp(calibrates[i].name, argv[1]))
return calibrates[i].fn(argc - 1, argv + 1);
}
printf("calibrate: no routines called '%s' - 'calibration help' for a list of routines\n", argv[1]);
return 1;
}

View File

@ -1,196 +0,0 @@
/****************************************************************************
* channels_cal.c
*
* Copyright (C) 2012 Nils Wenzler. All rights reserved.
* Authors: Nils Wenzler <wenzlern@ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "calibration.h"
/****************************************************************************
* Defines
****************************************************************************/
#define ABS(a) (((a) < 0) ? -(a) : (a))
#define MIN(a,b) (((a)<(b))?(a):(b))
#define MAX(a,b) (((a)>(b))?(a):(b))
/****************************************************************************
* Private Data
****************************************************************************/
//Store the values here before writing them to global_data_rc_channels
uint16_t old_values[NR_CHANNELS];
uint16_t cur_values[NR_CHANNELS];
uint8_t function_map[NR_CHANNELS];
char names[12][9];
/****************************************************************************
* Private Functions
****************************************************************************/
void press_enter_2(void)
{
int c;
printf("Press CTRL+ENTER to continue... \n");
fflush(stdout);
do c = getchar(); while ((c != '\n') && (c != EOF));
}
/**This gets all current values and writes them to min or max
*/
uint8_t get_val(uint16_t *buffer)
{
if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
printf("Channel: %i\t RAW Value: %i: \n", i, global_data_rc_channels->chan[i].raw);
buffer[i] = global_data_rc_channels->chan[i].raw;
}
global_data_unlock(&global_data_rc_channels->access_conf);
return 0;
} else
return -1;
}
void set_channel(void)
{
static uint8_t j = 0;
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
if (ABS(old_values - cur_values) > 50) {
function_map[j] = i;
strcpy(names[i], global_data_rc_channels->function_names[j]);
j++;
}
}
}
void write_dat(void)
{
global_data_lock(&global_data_rc_channels->access_conf);
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
global_data_rc_channels->function[i] = function_map[i];
strcpy(global_data_rc_channels->chan[i].name, names[i]);
printf("Channel %i\t Function %s\n", i,
global_data_rc_channels->chan[i].name);
}
global_data_unlock(&global_data_rc_channels->access_conf);
}
/****************************************************************************
* Public Functions
****************************************************************************/
int channels_cal(int argc, char *argv[])
{
printf("This routine maps the input functions on the remote control\n");
printf("to the corresponding function (Throttle, Roll,..)\n");
printf("Always move the stick all the way\n");
press_enter_2();
printf("Pull the THROTTLE stick down\n");
press_enter_2();
while (get_val(old_values));
printf("Move the THROTTLE stick up\n ");
press_enter_2();
while (get_val(cur_values));
set_channel();
printf("Pull the PITCH stick down\n");
press_enter_2();
while (get_val(old_values));
printf("Move the PITCH stick up\n ");
press_enter_2();
while (get_val(cur_values));
set_channel();
printf("Put the ROLL stick to the left\n");
press_enter_2();
while (get_val(old_values));
printf("Put the ROLL stick to the right\n ");
press_enter_2();
while (get_val(cur_values));
set_channel();
printf("Put the YAW stick to the left\n");
press_enter_2();
while (get_val(old_values));
printf("Put the YAW stick to the right\n ");
press_enter_2();
while (get_val(cur_values));
set_channel();
uint8_t k;
for (k = 5; k < NR_CHANNELS; k++) {
function_map[k] = k;
strcpy(names[k], global_data_rc_channels->function_names[k]);
}
//write the values to global_data_rc_channels
write_dat();
return 0;
}

View File

@ -1,224 +0,0 @@
/****************************************************************************
* range_cal.c
*
* Copyright (C) 2012 Nils Wenzler. All rights reserved.
* Authors: Nils Wenzler <wenzlern@ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <stdlib.h>
#include "calibration.h"
/****************************************************************************
* Defines
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
//Store the values here before writing them to global_data_rc_channels
uint16_t max_values[NR_CHANNELS];
uint16_t min_values[NR_CHANNELS];
uint16_t mid_values[NR_CHANNELS];
/****************************************************************************
* Private Functions
****************************************************************************/
/**This sets the middle values
*/
uint8_t set_mid(void)
{
if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
if (i == global_data_rc_channels->function[ROLL] ||
i == global_data_rc_channels->function[YAW] ||
i == global_data_rc_channels->function[PITCH]) {
mid_values[i] = global_data_rc_channels->chan[i].raw;
} else {
mid_values[i] = (max_values[i] + min_values[i]) / 2;
}
}
global_data_unlock(&global_data_rc_channels->access_conf);
return 0;
} else
return -1;
}
/**This gets all current values and writes them to min or max
*/
uint8_t get_value(void)
{
if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
//see if the value is bigger or smaller than 1500 (roughly neutral)
//and write to the appropriate array
if (global_data_rc_channels->chan[i].raw != 0 &&
global_data_rc_channels->chan[i].raw < 1500) {
min_values[i] = global_data_rc_channels->chan[i].raw;
} else if (global_data_rc_channels->chan[i].raw != 0 &&
global_data_rc_channels->chan[i].raw > 1500) {
max_values[i] = global_data_rc_channels->chan[i].raw;
} else {
max_values[i] = 0;
min_values[i] = 0;
}
}
global_data_unlock(&global_data_rc_channels->access_conf);
return 0;
} else
return -1;
}
void write_data(void)
{
// global_data_lock(&global_data_rc_channels->access_conf);
// uint8_t i;
// for(i=0; i < NR_CHANNELS; i++){
// //Write the data to global_data_rc_channels (if not 0)
// if(mid_values[i]!=0 && min_values[i]!=0 && max_values[i]!=0){
// global_data_rc_channels->chan[i].scaling_factor =
// 10000/((max_values[i] - min_values[i])/2);
//
// global_data_rc_channels->chan[i].mid = mid_values[i];
// }
//
// printf("Channel %i\t Function %s \t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
// i,
// global_data_rc_channels->function_name[global_data_rc_channels->function[i]],
// min_values[i], max_values[i],
// global_data_rc_channels->chan[i].scaling_factor,
// global_data_rc_channels->chan[i].mid);
// }
// global_data_unlock(&global_data_rc_channels->access_conf);
//Write to the Parameter storage
global_data_parameter_storage->pm.param_values[PARAM_RC1_MIN] = min_values[0];
global_data_parameter_storage->pm.param_values[PARAM_RC2_MIN] = min_values[1];
global_data_parameter_storage->pm.param_values[PARAM_RC3_MIN] = min_values[2];
global_data_parameter_storage->pm.param_values[PARAM_RC4_MIN] = min_values[3];
global_data_parameter_storage->pm.param_values[PARAM_RC5_MIN] = min_values[4];
global_data_parameter_storage->pm.param_values[PARAM_RC6_MIN] = min_values[5];
global_data_parameter_storage->pm.param_values[PARAM_RC7_MIN] = min_values[6];
global_data_parameter_storage->pm.param_values[PARAM_RC8_MIN] = min_values[7];
global_data_parameter_storage->pm.param_values[PARAM_RC1_MAX] = max_values[0];
global_data_parameter_storage->pm.param_values[PARAM_RC2_MAX] = max_values[1];
global_data_parameter_storage->pm.param_values[PARAM_RC3_MAX] = max_values[2];
global_data_parameter_storage->pm.param_values[PARAM_RC4_MAX] = max_values[3];
global_data_parameter_storage->pm.param_values[PARAM_RC5_MAX] = max_values[4];
global_data_parameter_storage->pm.param_values[PARAM_RC6_MAX] = max_values[5];
global_data_parameter_storage->pm.param_values[PARAM_RC7_MAX] = max_values[6];
global_data_parameter_storage->pm.param_values[PARAM_RC8_MAX] = max_values[7];
global_data_parameter_storage->pm.param_values[PARAM_RC1_TRIM] = mid_values[0];
global_data_parameter_storage->pm.param_values[PARAM_RC2_TRIM] = mid_values[1];
global_data_parameter_storage->pm.param_values[PARAM_RC3_TRIM] = mid_values[2];
global_data_parameter_storage->pm.param_values[PARAM_RC4_TRIM] = mid_values[3];
global_data_parameter_storage->pm.param_values[PARAM_RC5_TRIM] = mid_values[4];
global_data_parameter_storage->pm.param_values[PARAM_RC6_TRIM] = mid_values[5];
global_data_parameter_storage->pm.param_values[PARAM_RC7_TRIM] = mid_values[6];
global_data_parameter_storage->pm.param_values[PARAM_RC8_TRIM] = mid_values[7];
usleep(3e6);
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
printf("Channel %i:\t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
i,
min_values[i], max_values[i],
global_data_rc_channels->chan[i].scaling_factor,
global_data_rc_channels->chan[i].mid);
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
int range_cal(int argc, char *argv[])
{
printf("The range calibration routine assumes you already did the channel\n");
printf("assignment\n");
printf("This routine chooses the minimum, maximum and middle\n");
printf("value for each channel separatly. The ROLL, PITCH and YAW function\n");
printf("get their middle value from the RC direct, for the rest it is\n");
printf("calculated out of the min and max values.\n");
press_enter();
printf("Hold both sticks in lower left corner and continue\n ");
press_enter();
usleep(500000);
while (get_value());
printf("Hold both sticks in upper right corner and continue\n");
press_enter();
usleep(500000);
while (get_value());
printf("Set the trim to 0 and leave the sticks in the neutral position\n");
press_enter();
//Loop until successfull
while (set_mid());
//write the values to global_data_rc_channels
write_data();
return 0;
}

View File

@ -1,264 +0,0 @@
/****************************************************************************
* servo_cal.c
*
* Copyright (C) 2012 Nils Wenzler. All rights reserved.
* Authors: Nils Wenzler <wenzlern@ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <stdlib.h>
#include <arch/board/drv_pwm_servo.h>
#include <fcntl.h>
#include "calibration.h"
/****************************************************************************
* Defines
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
//Store the values here before writing them to global_data_rc_channels
uint16_t max_values_servo[PWM_SERVO_MAX_CHANNELS];
uint16_t min_values_servo[PWM_SERVO_MAX_CHANNELS];
uint16_t mid_values_servo[PWM_SERVO_MAX_CHANNELS];
// Servo loop thread
pthread_t servo_calib_thread;
/****************************************************************************
* Private Functions
****************************************************************************/
/**This sets the middle values
*/
uint8_t set_mid_s(void)
{
if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
uint8_t i;
for (i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
if (i == global_data_rc_channels->function[ROLL] ||
i == global_data_rc_channels->function[YAW] ||
i == global_data_rc_channels->function[PITCH]) {
mid_values_servo[i] = global_data_rc_channels->chan[i].raw;
} else {
mid_values_servo[i] = (max_values_servo[i] + min_values_servo[i]) / 2;
}
}
global_data_unlock(&global_data_rc_channels->access_conf);
return 0;
} else
return -1;
}
/**This gets all current values and writes them to min or max
*/
uint8_t get_value_s(void)
{
if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
uint8_t i;
for (i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
//see if the value is bigger or smaller than 1500 (roughly neutral)
//and write to the appropriate array
if (global_data_rc_channels->chan[i].raw != 0 &&
global_data_rc_channels->chan[i].raw < 1500) {
min_values_servo[i] = global_data_rc_channels->chan[i].raw;
} else if (global_data_rc_channels->chan[i].raw != 0 &&
global_data_rc_channels->chan[i].raw > 1500) {
max_values_servo[i] = global_data_rc_channels->chan[i].raw;
} else {
max_values_servo[i] = 0;
min_values_servo[i] = 0;
}
}
global_data_unlock(&global_data_rc_channels->access_conf);
return 0;
} else
return -1;
}
void write_data_s(void)
{
// global_data_lock(&global_data_rc_channels->access_conf);
// uint8_t i;
// for(i=0; i < NR_CHANNELS; i++){
// //Write the data to global_data_rc_channels (if not 0)
// if(mid_values_servo[i]!=0 && min_values_servo[i]!=0 && max_values_servo[i]!=0){
// global_data_rc_channels->chan[i].scaling_factor =
// 10000/((max_values_servo[i] - min_values_servo[i])/2);
//
// global_data_rc_channels->chan[i].mid = mid_values_servo[i];
// }
//
// printf("Channel %i\t Function %s \t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
// i,
// global_data_rc_channels->function_name[global_data_rc_channels->function[i]],
// min_values_servo[i], max_values_servo[i],
// global_data_rc_channels->chan[i].scaling_factor,
// global_data_rc_channels->chan[i].mid);
// }
// global_data_unlock(&global_data_rc_channels->access_conf);
//Write to the Parameter storage
global_data_lock(&global_data_parameter_storage->access_conf);
global_data_parameter_storage->pm.param_values[PARAM_SERVO1_MIN] = min_values_servo[0];
global_data_parameter_storage->pm.param_values[PARAM_SERVO2_MIN] = min_values_servo[1];
global_data_parameter_storage->pm.param_values[PARAM_SERVO3_MIN] = min_values_servo[2];
global_data_parameter_storage->pm.param_values[PARAM_SERVO4_MIN] = min_values_servo[3];
global_data_parameter_storage->pm.param_values[PARAM_SERVO1_MAX] = max_values_servo[0];
global_data_parameter_storage->pm.param_values[PARAM_SERVO2_MAX] = max_values_servo[1];
global_data_parameter_storage->pm.param_values[PARAM_SERVO3_MAX] = max_values_servo[2];
global_data_parameter_storage->pm.param_values[PARAM_SERVO4_MAX] = max_values_servo[3];
global_data_parameter_storage->pm.param_values[PARAM_SERVO1_TRIM] = mid_values_servo[0];
global_data_parameter_storage->pm.param_values[PARAM_SERVO2_TRIM] = mid_values_servo[1];
global_data_parameter_storage->pm.param_values[PARAM_SERVO3_TRIM] = mid_values_servo[2];
global_data_parameter_storage->pm.param_values[PARAM_SERVO4_TRIM] = mid_values_servo[3];
global_data_unlock(&global_data_parameter_storage->access_conf);
usleep(3e6);
uint8_t i;
for (i = 0; i < NR_CHANNELS; i++) {
printf("Channel %i:\t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
i,
min_values_servo[i], max_values_servo[i],
global_data_rc_channels->chan[i].scaling_factor,
global_data_rc_channels->chan[i].mid);
}
}
static void *servo_loop(void *arg)
{
// Set thread name
prctl(1, "calibration servo", getpid());
// initialize servos
int fd;
servo_position_t data[PWM_SERVO_MAX_CHANNELS];
fd = open("/dev/pwm_servo", O_RDWR);
if (fd < 0) {
printf("failed opening /dev/pwm_servo\n");
}
ioctl(fd, PWM_SERVO_ARM, 0);
while (1) {
int i;
for (i = 0; i < 4; i++) {
data[i] = global_data_rc_channels->chan[global_data_rc_channels->function[THROTTLE]].raw;
}
int result = write(fd, &data, sizeof(data));
if (result != sizeof(data)) {
printf("failed bulk-reading channel values\n");
}
// 5Hz loop
usleep(200000);
}
return NULL;
}
/****************************************************************************
* Public Functions
****************************************************************************/
int servo_cal(int argc, char *argv[])
{
// pthread_attr_t servo_loop_attr;
// pthread_attr_init(&servo_loop_attr);
// pthread_attr_setstacksize(&servo_loop_attr, 1024);
pthread_create(&servo_calib_thread, NULL, servo_loop, NULL);
pthread_join(servo_calib_thread, NULL);
printf("The servo calibration routine assumes you already did the channel\n");
printf("assignment with 'calibration channels'\n");
printf("This routine chooses the minimum, maximum and middle\n");
printf("value for each channel separately. The ROLL, PITCH and YAW function\n");
printf("get their middle value from the RC direct, for the rest it is\n");
printf("calculated out of the min and max values.\n");
press_enter();
printf("Hold both sticks in lower left corner and continue\n ");
press_enter();
usleep(500000);
while (get_value_s());
printf("Hold both sticks in upper right corner and continue\n");
press_enter();
usleep(500000);
while (get_value_s());
printf("Set the trim to 0 and leave the sticks in the neutral position\n");
press_enter();
//Loop until successfull
while (set_mid_s());
//write the values to global_data_rc_channels
write_data_s();
return 0;
}

View File

@ -1,160 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file delay_test.c
*
* Simple but effective delay test using leds and a scope to measure
* communication delays end-to-end accurately.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
#include <fcntl.h>
#include <errno.h>
#include <poll.h>
#include <string.h>
#include <systemlib/err.h>
#include <drivers/drv_led.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_tone_alarm.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_command.h>
__EXPORT int delay_test_main(int argc, char *argv[]);
static int led_on(int leds, int led);
static int led_off(int leds, int led);
int delay_test_main(int argc, char *argv[])
{
bool vicon_msg = false;
bool command_msg = false;
if (argc > 1 && !strcmp(argv[1], "--help")) {
warnx("usage: delay_test [vicon] [command]\n");
exit(1);
}
if (argc > 1 && !strcmp(argv[1], "vicon")) {
vicon_msg = true;
}
if (argc > 1 && !strcmp(argv[1], "command")) {
command_msg = true;
}
int buzzer = open("/dev/tone_alarm", O_WRONLY);
int leds = open(LED_DEVICE_PATH, 0);
/* prepare use of amber led */
led_off(leds, LED_AMBER);
int topic;
/* subscribe to topic */
if (vicon_msg) {
topic = orb_subscribe(ORB_ID(vehicle_vicon_position));
} else if (command_msg) {
topic = orb_subscribe(ORB_ID(vehicle_command));
} else {
errx(1, "No topic selected for delay test, use --help for a list of topics.");
}
const int testcount = 20;
warnx("running %d iterations..\n", testcount);
struct pollfd fds[1];
fds[0].fd = topic;
fds[0].events = POLLIN;
/* display and sound error */
for (int i = 0; i < testcount; i++)
{
/* wait for topic */
int ret = poll(&fds[0], 1, 2000);
/* this would be bad... */
if (ret < 0) {
warnx("poll error %d", errno);
usleep(1000000);
continue;
}
/* do we have a topic update? */
if (fds[0].revents & POLLIN) {
/* copy object to disable poll ready state */
if (vicon_msg) {
struct vehicle_vicon_position_s vicon_position;
orb_copy(ORB_ID(vehicle_vicon_position), topic, &vicon_position);
} else if (command_msg) {
struct vehicle_command_s vehicle_command;
orb_copy(ORB_ID(vehicle_command), topic, &vehicle_command);
}
led_on(leds, LED_AMBER);
ioctl(buzzer, TONE_SET_ALARM, 4);
/* keep led on for 50 ms to make it barely visible */
usleep(50000);
led_off(leds, LED_AMBER);
}
}
/* stop alarm */
ioctl(buzzer, TONE_SET_ALARM, 0);
/* switch on leds */
led_on(leds, LED_BLUE);
led_on(leds, LED_AMBER);
exit(0);
}
static int led_off(int leds, int led)
{
return ioctl(leds, LED_OFF, led);
}
static int led_on(int leds, int led)
{
return ioctl(leds, LED_ON, led);
}

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build the eeprom tool.
#
APPNAME = eeprom
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build the i2c test tool.
#
APPNAME = i2c
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Reboot command.
#
APPNAME = preflight_check
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build the pwm tool.
#
APPNAME = pwm
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk

View File

@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# realtime system performance display
#
APPNAME = top
PRIORITY = SCHED_PRIORITY_DEFAULT - 10
STACKSIZE = 3000
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

71
makefiles/README.txt Normal file
View File

@ -0,0 +1,71 @@
PX4 Build System
================
The files in this directory implement the PX4 runtime firmware build system
and configuration for the standard PX4 boards and software, in conjunction
with Makefile in the parent directory.
../Makefile
Top-level makefile for the PX4 build system. This makefile supports
building NuttX archives, as well as supervising the building of all
of the defined PX4 firmware configurations.
Try 'make help' in the parent directory for documentation.
firmware.mk
Manages the build for one specific firmware configuration.
See the comments at the top of this file for detailed documentation.
Builds modules, builtin command lists and the ROMFS (if configured).
This is the makefile directly used by external build systems; it can
be configured to compile modules both inside and outside the PX4
source tree. When used in this mode, at least BOARD, MODULES and
CONFIG_FILE must be set.
module.mk
Called by firmware.mk to build individual modules.
See the comments at the top of this file for detailed documentation.
Not normally used other than by firmware.mk.
nuttx.mk
Called by ../Makefile to build or download the NuttX archives.
upload.mk
Called by ../Makefile to upload files to a target board. Can be used
by external build systems as well.
setup.mk
Provides common path and tool definitions. Implements host system-specific
compatibility hacks.
board_<boardname>.mk
Board-specific configuration for <boardname>. Typically sets CONFIG_ARCH
and then includes the toolchain definition for the board.
config_<boardname>_<configname>.mk
Parameters for a specific configuration on a specific board.
The board name is derived from the filename. Sets MODULES to select
source modules to be included in the configuration, may also set
ROMFS_ROOT to build a ROMFS and BUILTIN_COMMANDS to include non-module
commands (e.g. from NuttX)
toolchain_<toolchainname>.mk
Provides macros used to compile and link source files.
Accepts EXTRADEFINES to add additional pre-processor symbol definitions,
EXTRACFLAGS, EXTRACXXFLAGS, EXTRAAFLAGS and EXTRALDFLAGS to pass
additional flags to the C compiler, C++ compiler, assembler and linker
respectively.
Defines the COMPILE, COMPILEXX, ASSEMBLE, PRELINK, ARCHIVE and LINK
macros that are used elsewhere in the build system.

10
makefiles/board_px4fmu.mk Normal file
View File

@ -0,0 +1,10 @@
#
# Board-specific definitions for the PX4FMU
#
#
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM4F
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk

10
makefiles/board_px4io.mk Normal file
View File

@ -0,0 +1,10 @@
#
# Board-specific definitions for the PX4IO
#
#
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM3
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk

View File

@ -0,0 +1,127 @@
#
# Makefile for the px4fmu_default configuration
#
#
# Use the configuration's ROMFS.
#
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
#
# Board support modules
#
MODULES += drivers/device
MODULES += drivers/stm32
MODULES += drivers/stm32/adc
MODULES += drivers/stm32/tone_alarm
MODULES += drivers/led
MODULES += drivers/px4io
MODULES += drivers/px4fmu
MODULES += drivers/boards/px4fmu
MODULES += drivers/ardrone_interface
MODULES += drivers/l3gd20
MODULES += drivers/bma180
MODULES += drivers/mpu6000
MODULES += drivers/hmc5883
MODULES += drivers/ms5611
MODULES += drivers/mb12xx
MODULES += drivers/gps
MODULES += drivers/hil
MODULES += drivers/hott_telemetry
MODULES += drivers/blinkm
MODULES += drivers/mkblctrl
MODULES += drivers/md25
MODULES += drivers/ets_airspeed
MODULES += modules/sensors
#
# System commands
#
MODULES += systemcmds/eeprom
MODULES += systemcmds/bl_update
MODULES += systemcmds/boardinfo
MODULES += systemcmds/i2c
MODULES += systemcmds/mixer
MODULES += systemcmds/param
MODULES += systemcmds/perf
MODULES += systemcmds/preflight_check
MODULES += systemcmds/pwm
MODULES += systemcmds/reboot
MODULES += systemcmds/top
MODULES += systemcmds/tests
#
# General system control
#
MODULES += modules/commander
MODULES += modules/mavlink
MODULES += modules/mavlink_onboard
#
# Estimation modules (EKF / other filters)
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/position_estimator_mc
MODULES += modules/position_estimator
MODULES += modules/att_pos_estimator_ekf
#
# Vehicle Control
#
MODULES += modules/fixedwing_backside
MODULES += modules/fixedwing_att_control
MODULES += modules/fixedwing_pos_control
MODULES += modules/multirotor_att_control
MODULES += modules/multirotor_pos_control
#
# Logging
#
MODULES += modules/sdlog
#
# Libraries
#
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/mathlib
MODULES += modules/mathlib/CMSIS
MODULES += modules/controllib
MODULES += modules/uORB
#
# Demo apps
#
#MODULES += examples/math_demo
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/hello_sky
#MODULES += examples/px4_simple_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/daemon
#MODULES += examples/px4_daemon_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/debug_values
#MODULES += examples/px4_mavlink_debug
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
MODULES += examples/fixedwing_control
#
# Transitional support - add commands from the NuttX export archive.
#
# In general, these should move to modules over time.
#
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
# to make the table a bit more readable.
#
define _B
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
endef
# command priority stack entrypoint
BUILTIN_COMMANDS := \
$(call _B, sercon, , 2048, sercon_main ) \
$(call _B, serdis, , 2048, serdis_main )

View File

@ -0,0 +1,10 @@
#
# Makefile for the px4io_default configuration
#
#
# Board support modules
#
MODULES += drivers/stm32
MODULES += drivers/boards/px4io
MODULES += modules/px4iofirmware

450
makefiles/firmware.mk Normal file
View File

@ -0,0 +1,450 @@
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#
# Generic Makefile for PX4 firmware images.
#
# Requires:
#
# BOARD
# Must be set to a board name known to the PX4 distribution (as
# we need a corresponding NuttX export archive to link with).
#
# Optional:
#
# MODULES
# Contains a list of module paths or path fragments used
# to find modules. The names listed here are searched in
# the following directories:
# <absolute path>
# $(MODULE_SEARCH_DIRS)
# WORK_DIR
# MODULE_SRC
# PX4_MODULE_SRC
#
# Application directories are expected to contain a module.mk
# file which provides build configuration for the module. See
# makefiles/module.mk for more details.
#
# BUILTIN_COMMANDS
# Contains a list of built-in commands not explicitly provided
# by modules / libraries. Each entry in this list is formatted
# as <command>.<priority>.<stacksize>.<entrypoint>
#
# PX4_BASE:
# Points to a PX4 distribution. Normally determined based on the
# path to this file.
#
# CONFIG:
# Used when searching for the configuration file, and available
# to module Makefiles to select optional features.
# If not set, CONFIG_FILE must be set and CONFIG will be derived
# automatically from it.
#
# CONFIG_FILE:
# If set, overrides the configuration file search logic. Sets
# CONFIG to the name of the configuration file, strips any
# leading config_ prefix and any suffix. e.g. config_board_foo.mk
# results in CONFIG being set to 'board_foo'.
#
# WORK_DIR:
# Sets the directory in which the firmware will be built. Defaults
# to the directory 'build' under the directory containing the
# parent Makefile.
#
# ROMFS_ROOT:
# If set to the path to a directory, a ROMFS image will be generated
# containing the files under the directory and linked into the final
# image.
#
# MODULE_SEARCH_DIRS:
# Extra directories to search first for MODULES before looking in the
# usual places.
#
################################################################################
# Paths and configuration
################################################################################
#
# Work out where this file is, so we can find other makefiles in the
# same directory.
#
# If PX4_BASE wasn't set previously, work out what it should be
# and set it here now.
#
MK_DIR ?= $(dir $(lastword $(MAKEFILE_LIST)))
ifeq ($(PX4_BASE),)
export PX4_BASE := $(abspath $(MK_DIR)/..)
endif
$(info % PX4_BASE = $(PX4_BASE))
ifneq ($(words $(PX4_BASE)),1)
$(error Cannot build when the PX4_BASE path contains one or more space characters.)
endif
#
# Set a default target so that included makefiles or errors here don't
# cause confusion.
#
# XXX We could do something cute here with $(DEFAULT_GOAL) if it's not one
# of the maintenance targets and set CONFIG based on it.
#
all: firmware
#
# Get path and tool config
#
include $(MK_DIR)/setup.mk
#
# Locate the configuration file
#
ifneq ($(CONFIG_FILE),)
CONFIG := $(subst config_,,$(basename $(notdir $(CONFIG_FILE))))
else
CONFIG_FILE := $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk)
endif
ifeq ($(CONFIG),)
$(error Missing configuration name or file (specify with CONFIG=<config>))
endif
export CONFIG
include $(CONFIG_FILE)
$(info % CONFIG = $(CONFIG))
#
# Sanity-check the BOARD variable and then get the board config.
# If BOARD was not set by the configuration, extract it automatically.
#
# The board config in turn will fetch the toolchain configuration.
#
ifeq ($(BOARD),)
BOARD := $(firstword $(subst _, ,$(CONFIG)))
endif
BOARD_FILE := $(wildcard $(PX4_MK_DIR)/board_$(BOARD).mk)
ifeq ($(BOARD_FILE),)
$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
endif
export BOARD
include $(BOARD_FILE)
$(info % BOARD = $(BOARD))
#
# If WORK_DIR is not set, create a 'build' directory next to the
# parent Makefile.
#
PARENT_MAKEFILE := $(lastword $(filter-out $(lastword $(MAKEFILE_LIST)),$(MAKEFILE_LIST)))
ifeq ($(WORK_DIR),)
export WORK_DIR := $(dir $(PARENT_MAKEFILE))build/
endif
$(info % WORK_DIR = $(WORK_DIR))
#
# Things that, if they change, might affect everything
#
GLOBAL_DEPS += $(MAKEFILE_LIST)
#
# Extra things we should clean
#
EXTRA_CLEANS =
################################################################################
# Modules
################################################################################
#
# We don't actually know what a module is called; all we have is a path fragment
# that we can search for, and where we expect to find a module.mk file.
#
# As such, we replicate the successfully-found path inside WORK_DIR for the
# module's build products in order to keep modules separated from each other.
#
# XXX If this becomes unwieldy or breaks for other reasons, we will need to
# move to allocating directory names and keeping tabs on makefiles via
# the directory name. That will involve arithmetic (it'd probably be time
# for GMSL).
# where to look for modules
MODULE_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC)
# sort and unique the modules list
MODULES := $(sort $(MODULES))
# locate the first instance of a module by full path or by looking on the
# module search path
define MODULE_SEARCH
$(firstword $(abspath $(wildcard $(1)/module.mk)) \
$(abspath $(foreach search_dir,$(MODULE_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/module.mk))) \
MISSING_$1)
endef
# make a list of module makefiles and check that we found them all
MODULE_MKFILES := $(foreach module,$(MODULES),$(call MODULE_SEARCH,$(module)))
MISSING_MODULES := $(subst MISSING_,,$(filter MISSING_%,$(MODULE_MKFILES)))
ifneq ($(MISSING_MODULES),)
$(error Can't find module(s): $(MISSING_MODULES))
endif
# Make a list of the object files we expect to build from modules
# Note that this path will typically contain a double-slash at the WORK_DIR boundary; this must be
# preserved as it is used below to get the absolute path for the module.mk file correct.
#
MODULE_OBJS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)module.pre.o)
# rules to build module objects
.PHONY: $(MODULE_OBJS)
$(MODULE_OBJS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
$(MODULE_OBJS): mkfile = $(patsubst %module.pre.o,%module.mk,$(relpath))
$(MODULE_OBJS): workdir = $(@D)
$(MODULE_OBJS): $(GLOBAL_DEPS) $(NUTTX_CONFIG_HEADER)
$(Q) $(MKDIR) -p $(workdir)
$(Q) $(MAKE) -r -f $(PX4_MK_DIR)module.mk \
-C $(workdir) \
MODULE_WORK_DIR=$(workdir) \
MODULE_OBJ=$@ \
MODULE_MK=$(mkfile) \
MODULE_NAME=$(lastword $(subst /, ,$(workdir))) \
module
# make a list of phony clean targets for modules
MODULE_CLEANS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)/clean)
# rules to clean modules
.PHONY: $(MODULE_CLEANS)
$(MODULE_CLEANS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
$(MODULE_CLEANS): mkfile = $(patsubst %clean,%module.mk,$(relpath))
$(MODULE_CLEANS):
@$(ECHO) %% cleaning using $(mkfile)
$(Q) $(MAKE) -r -f $(PX4_MK_DIR)module.mk \
MODULE_WORK_DIR=$(dir $@) \
MODULE_MK=$(mkfile) \
clean
################################################################################
# NuttX libraries and paths
################################################################################
include $(PX4_MK_DIR)/nuttx.mk
################################################################################
# ROMFS generation
################################################################################
ifneq ($(ROMFS_ROOT),)
ifeq ($(wildcard $(ROMFS_ROOT)),)
$(error ROMFS_ROOT specifies a directory that does not exist)
endif
#
# Note that there is no support for more than one root directory or constructing
# a root from several templates. That would be a nice feature.
#
# Add dependencies on anything in the ROMFS root
ROMFS_FILES += $(wildcard \
$(ROMFS_ROOT)/* \
$(ROMFS_ROOT)/*/* \
$(ROMFS_ROOT)/*/*/* \
$(ROMFS_ROOT)/*/*/*/* \
$(ROMFS_ROOT)/*/*/*/*/* \
$(ROMFS_ROOT)/*/*/*/*/*/*)
ifeq ($(ROMFS_FILES),)
$(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files)
endif
ROMFS_DEPS += $(ROMFS_FILES)
ROMFS_IMG = romfs.img
ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
LINK_DEPS += $(ROMFS_OBJ)
# Turn the ROMFS image into an object file
$(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
$(call BIN_TO_OBJ,$<,$@,romfs_img)
# Generate the ROMFS image from the root
$(ROMFS_IMG): $(ROMFS_DEPS) $(GLOBAL_DEPS)
@$(ECHO) "ROMFS: $@"
$(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
endif
################################################################################
# Builtin command list generation
################################################################################
#
# Builtin commands can be generated by the configuration, in which case they
# must refer to commands that already exist, or indirectly generated by modules
# when they are built.
#
# The configuration supplies builtin command information in the BUILTIN_COMMANDS
# variable. Applications make empty files in $(WORK_DIR)/builtin_commands whose
# filename contains the same information.
#
# In each case, the command information consists of four fields separated with a
# period. These fields are the command's name, its thread priority, its stack size
# and the name of the function to call when starting the thread.
#
BUILTIN_CSRC = $(WORK_DIR)builtin_commands.c
# command definitions from modules (may be empty at Makefile parsing time...)
MODULE_COMMANDS = $(subst COMMAND.,,$(notdir $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)))
# We must have at least one pre-defined builtin command in order to generate
# any of this.
#
ifneq ($(BUILTIN_COMMANDS),)
# (BUILTIN_PROTO,<cmdspec>,<outputfile>)
define BUILTIN_PROTO
$(ECHO) 'extern int $(word 4,$1)(int argc, char *argv[]);' >> $2;
endef
# (BUILTIN_DEF,<cmdspec>,<outputfile>)
define BUILTIN_DEF
$(ECHO) ' {"$(word 1,$1)", $(word 2,$1), $(word 3,$1), $(word 4,$1)},' >> $2;
endef
# Don't generate until modules have updated their command files
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES)
@$(ECHO) "CMDS: $@"
$(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
$(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
$(Q) $(ECHO) '#include <nuttx/binfmt/builtin.h>' >> $@
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
$(Q) $(ECHO) 'const struct builtin_s g_builtins[] = {' >> $@
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
$(Q) $(ECHO) ' {NULL, 0, 0, NULL}' >> $@
$(Q) $(ECHO) '};' >> $@
$(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS) $(MODULE_COMMANDS));' >> $@
SRCS += $(BUILTIN_CSRC)
EXTRA_CLEANS += $(BUILTIN_CSRC)
endif
################################################################################
# Default SRCS generation
################################################################################
#
# If there are no SRCS, the build will fail; in that case, generate an empty
# source file.
#
ifeq ($(SRCS),)
EMPTY_SRC = $(WORK_DIR)empty.c
$(EMPTY_SRC):
$(Q) $(ECHO) '/* this is an empty file */' > $@
SRCS += $(EMPTY_SRC)
endif
################################################################################
# Build rules
################################################################################
#
# What we're going to build.
#
PRODUCT_BUNDLE = $(WORK_DIR)firmware.px4
PRODUCT_BIN = $(WORK_DIR)firmware.bin
PRODUCT_ELF = $(WORK_DIR)firmware.elf
.PHONY: firmware
firmware: $(PRODUCT_BUNDLE)
#
# Object files we will generate from sources
#
OBJS := $(foreach src,$(SRCS),$(WORK_DIR)$(src).o)
#
# SRCS -> OBJS rules
#
$(OBJS): $(GLOBAL_DEPS)
$(filter %.c.o,$(OBJS)): $(WORK_DIR)%.c.o: %.c $(GLOBAL_DEPS)
$(call COMPILE,$<,$@)
$(filter %.cpp.o,$(OBJS)): $(WORK_DIR)%.cpp.o: %.cpp $(GLOBAL_DEPS)
$(call COMPILEXX,$<,$@)
$(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
$(call ASSEMBLE,$<,$@)
#
# Built product rules
#
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
@$(ECHO) %% Generating $@
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
--git_identity $(PX4_BASE) \
--image $< > $@
$(PRODUCT_BIN): $(PRODUCT_ELF)
$(call SYM_TO_BIN,$<,$@)
$(PRODUCT_ELF): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
$(call LINK,$@,$(OBJS) $(MODULE_OBJS))
#
# Utility rules
#
.PHONY: upload
upload: $(PRODUCT_BUNDLE) $(PRODUCT_BIN)
$(Q) $(MAKE) -f $(PX4_MK_DIR)/upload.mk \
METHOD=serial \
CONFIG=$(CONFIG) \
BOARD=$(BOARD) \
BUNDLE=$(PRODUCT_BUNDLE) \
BIN=$(PRODUCT_BIN)
.PHONY: clean
clean: $(MODULE_CLEANS)
@$(ECHO) %% cleaning
$(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_ELF)
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
$(Q) $(RMDIR) $(NUTTX_EXPORT_DIR)
#
# DEP_INCLUDES is defined by the toolchain include in terms of $(OBJS)
#
-include $(DEP_INCLUDES)

241
makefiles/module.mk Normal file
View File

@ -0,0 +1,241 @@
#
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#
# Framework makefile for PX4 modules
#
# This makefile is invoked by firmware.mk to build each of the modules
# that will subsequently be linked into the firmware image.
#
# Applications are built as prelinked objects with a limited set of exported
# symbols, as the global namespace is shared between all modules. Normally an
# module will just export one or more <command>_main functions.
#
# IMPORTANT NOTE:
#
# This makefile assumes it is being invoked in the module's output directory.
#
#
# Variables that can be set by the module's module.mk:
#
#
# SRCS (required)
#
# Lists the .c, cpp and .S files that should be compiled/assembled to
# produce the module.
#
# MODULE_COMMAND (optional)
# MODULE_ENTRYPOINT (optional if MODULE_COMMAND is set)
# MODULE_STACKSIZE (optional if MODULE_COMMAND is set)
# MODULE_PRIORITY (optional if MODULE_COMMAND is set)
#
# Defines a single builtin command exported by the module.
# MODULE_COMMAND must be unique for any configuration, but need not be the
# same as the module directory name.
#
# If MODULE_ENTRYPOINT is set, it names the function (which must be exported)
# that will be the entrypoint for the builtin command. It defaults to
# $(MODULE_COMMAND)_main.
#
# If MODULE_STACKSIZE is set, it is the size in bytes of the stack to be
# allocated for the builtin command. If it is not set, it defaults
# to CONFIG_PTHREAD_STACK_DEFAULT.
#
# If MODULE_PRIORITY is set, it is the thread priority for the builtin
# command. If it is not set, it defaults to SCHED_PRIORITY_DEFAULT.
#
# MODULE_COMMANDS (optional if MODULE_COMMAND is not set)
#
# Defines builtin commands exported by the module. Each word in
# the list should be formatted as:
# <command>.<priority>.<stacksize>.<entrypoint>
#
# INCLUDE_DIRS (optional, must be appended)
#
# The list of directories searched for include files. If non-standard
# includes (e.g. those from another module) are required, paths to search
# can be added here.
#
# DEFAULT_VISIBILITY (optional)
#
# If not set, global symbols defined in a module will not be visible
# outside the module. Symbols that should be globally visible must be
# marked __EXPORT.
# If set, global symbols defined in a module will be globally visible.
#
#
# Variables visible to the module's module.mk:
#
# CONFIG
# BOARD
# MODULE_WORK_DIR
# MODULE_OBJ
# MODULE_MK
# Anything set in setup.mk, board_$(BOARD).mk and the toolchain file.
# Anything exported from config_$(CONFIG).mk
#
################################################################################
# No user-serviceable parts below.
################################################################################
ifeq ($(MODULE_MK),)
$(error No module makefile specified)
endif
$(info %% MODULE_MK = $(MODULE_MK))
#
# Get the board/toolchain config
#
include $(PX4_MK_DIR)/board_$(BOARD).mk
#
# Get the module's config
#
include $(MODULE_MK)
MODULE_SRC := $(dir $(MODULE_MK))
$(info % MODULE_NAME = $(MODULE_NAME))
$(info % MODULE_SRC = $(MODULE_SRC))
$(info % MODULE_OBJ = $(MODULE_OBJ))
$(info % MODULE_WORK_DIR = $(MODULE_WORK_DIR))
#
# Things that, if they change, might affect everything
#
GLOBAL_DEPS += $(MAKEFILE_LIST)
################################################################################
# Builtin command definitions
################################################################################
ifneq ($(MODULE_COMMAND),)
MODULE_ENTRYPOINT ?= $(MODULE_COMMAND)_main
MODULE_STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
MODULE_PRIORITY ?= SCHED_PRIORITY_DEFAULT
MODULE_COMMANDS += $(MODULE_COMMAND).$(MODULE_PRIORITY).$(MODULE_STACKSIZE).$(MODULE_ENTRYPOINT)
endif
ifneq ($(MODULE_COMMANDS),)
MODULE_COMMAND_FILES := $(addprefix $(WORK_DIR)/builtin_commands/COMMAND.,$(MODULE_COMMANDS))
# Create the command files
# Ensure that there is only one entry for each command
#
.PHONY: $(MODULE_COMMAND_FILES)
$(MODULE_COMMAND_FILES): command = $(word 2,$(subst ., ,$(notdir $(@))))
$(MODULE_COMMAND_FILES): exclude = $(dir $@)COMMAND.$(command).*
$(MODULE_COMMAND_FILES): $(GLOBAL_DEPS)
@$(REMOVE) -f $(exclude)
@$(MKDIR) -p $(dir $@)
@$(ECHO) "CMD: $(command)"
$(Q) $(TOUCH) $@
endif
################################################################################
# Adjust compilation flags to implement EXPORT
################################################################################
ifeq ($(DEFAULT_VISIBILITY),)
DEFAULT_VISIBILITY = hidden
else
DEFAULT_VISIBILITY = default
endif
CFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
################################################################################
# Build rules
################################################################################
#
# What we're going to build
#
module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES)
##
## Locate sources (allows relative source paths in module.mk)
##
#define SRC_SEARCH
# $(abspath $(firstword $(wildcard $1) $(wildcard $(MODULE_SRC)/$1) MISSING_$1))
#endef
#
#ABS_SRCS ?= $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src)))
#MISSING_SRCS := $(subst MISSING_,,$(filter MISSING_%,$(ABS_SRCS)))
#ifneq ($(MISSING_SRCS),)
#$(error $(MODULE_MK): missing in SRCS: $(MISSING_SRCS))
#endif
#ifeq ($(ABS_SRCS),)
#$(error $(MODULE_MK): nothing to compile in SRCS)
#endif
#
##
## Object files we will generate from sources
##
#OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o)
OBJS = $(addsuffix .o,$(SRCS))
$(info SRCS $(SRCS))
$(info OBJS $(OBJS))
#
# SRCS -> OBJS rules
#
$(OBJS): $(GLOBAL_DEPS)
vpath %.c $(MODULE_SRC)
$(filter %.c.o,$(OBJS)): %.c.o: %.c $(GLOBAL_DEPS)
$(call COMPILE,$<,$@)
vpath %.cpp $(MODULE_SRC)
$(filter %.cpp.o,$(OBJS)): %.cpp.o: %.cpp $(GLOBAL_DEPS)
$(call COMPILEXX,$<,$@)
vpath %.S $(MODULE_SRC)
$(filter %.S.o,$(OBJS)): %.S.o: %.S $(GLOBAL_DEPS)
$(call ASSEMBLE,$<,$@)
#
# Built product rules
#
$(MODULE_OBJ): $(OBJS) $(GLOBAL_DEPS)
$(call PRELINK,$@,$(OBJS))
#
# Utility rules
#
clean:
$(Q) $(REMOVE) $(MODULE_PRELINK) $(OBJS)

View File

@ -1,4 +1,3 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
@ -29,30 +28,51 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build the px4io application.
# Rules and definitions related to handling the NuttX export archives when
# building firmware.
#
#
# Note that we pull a couple of specific files from the systemlib, since
# we can't support it all.
# Check that the NuttX archive for the selected board is available.
#
CSRCS = adc.c \
controls.c \
dsm.c \
i2c.c \
px4io.c \
registers.c \
safety.c \
sbus.c \
../systemlib/hx_stream.c \
../systemlib/perf_counter.c \
../systemlib/up_cxxinitialize.c
NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).export)
ifeq ($(NUTTX_ARCHIVE),)
$(error The NuttX export archive for $(BOARD) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
endif
CXXSRCS = mixer.cpp
#
# The NuttX config header should always be present in the NuttX archive, and
# if it changes, everything should be rebuilt. So, use it as the trigger to
# unpack the NuttX archive.
#
NUTTX_EXPORT_DIR = $(WORK_DIR)nuttx-export/
NUTTX_CONFIG_HEADER = $(NUTTX_EXPORT_DIR)include/nuttx/config.h
$(info % NUTTX_EXPORT_DIR = $(NUTTX_EXPORT_DIR))
$(info % NUTTX_CONFIG_HEADER = $(NUTTX_CONFIG_HEADER))
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
include $(APPDIR)/mk/app.mk
GLOBAL_DEPS += $(NUTTX_CONFIG_HEADER)
#
# Use the linker script from the NuttX export
#
LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
#
# Add directories from the NuttX export to the relevant search paths
#
INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \
$(NUTTX_EXPORT_DIR)arch/chip \
$(NUTTX_EXPORT_DIR)arch/common
LIB_DIRS += $(NUTTX_EXPORT_DIR)libs
LIBS += -lapps -lnuttx
LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \
$(NUTTX_EXPORT_DIR)libs/libnuttx.a
$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
@$(ECHO) %% Unpacking $(NUTTX_ARCHIVE)
$(Q) $(UNZIP_CMD) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
$(Q) $(TOUCH) $@

91
makefiles/setup.mk Normal file
View File

@ -0,0 +1,91 @@
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#
# Path and tool setup
#
#
# Some useful paths.
#
# Note that in general we always keep directory paths with the separator
# at the end, and join paths without explicit separators. This reduces
# the number of duplicate slashes we have lying around in paths,
# and is consistent with joining the results of $(dir) and $(notdir).
#
export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/
export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/
export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
export NUTTX_SRC = $(abspath $(PX4_BASE)/nuttx)/
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/apps)/
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/
export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/
export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/
export BUILD_DIR = $(abspath $(PX4_BASE)/Build)/
export ARCHIVE_DIR = $(abspath $(PX4_BASE)/Archives)/
#
# Default include paths
#
export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
$(PX4_MODULE_SRC)/modules/ \
$(PX4_INCLUDE_DIR)
#
# Tools
#
export MKFW = $(PX4_BASE)/Tools/px_mkfw.py
export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
export COPY = cp
export REMOVE = rm -f
export RMDIR = rm -rf
export GENROMFS = genromfs
export TOUCH = touch
export MKDIR = mkdir
export ECHO = echo
export UNZIP_CMD = unzip
export PYTHON = python
export OPENOCD = openocd
#
# Host-specific paths, hacks and fixups
#
export SYSTYPE := $(shell uname -s)
ifeq ($(SYSTYPE),Darwin)
# Eclipse may not have the toolchain on its path.
export PATH := $(PATH):/usr/local/bin
endif
#
# Makefile debugging.
#
export Q := $(if $(V),,@)

View File

@ -0,0 +1,285 @@
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#
# Definitions for a generic GNU ARM-EABI toolchain
#
#$(info TOOLCHAIN gnu-arm-eabi)
# Toolchain commands. Normally only used inside this file.
#
CROSSDEV = arm-none-eabi-
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
MAXOPTIMIZATION = -O3
# Base CPU flags for each of the supported architectures.
#
ARCHCPUFLAGS_CORTEXM4F = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
ARCHCPUFLAGS_CORTEXM4 = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfloat-abi=soft
ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \
-mthumb \
-march=armv7-m \
-mfloat-abi=soft
# Pick the right set of flags for the architecture.
#
ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH))
ifeq ($(ARCHCPUFLAGS),)
$(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3)
endif
# optimisation flags
#
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-g \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
# enable precise stack overflow tracking
# note - requires corresponding support in NuttX
INSTRUMENTATIONDEFINES = -finstrument-functions \
-ffixed-r10
# Language-specific flags
#
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
# Generic warnings
#
ARCHWARNINGS = -Wall \
-Wextra \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
-Wframe-larger-than=1024 \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
# C-specific warnings
#
ARCHCWARNINGS = $(ARCHWARNINGS) \
-Wbad-function-cast \
-Wstrict-prototypes \
-Wold-style-declaration \
-Wmissing-parameter-type \
-Wmissing-prototypes \
-Wnested-externs \
-Wunsuffixed-float-constants
# C++-specific warnings
#
ARCHWARNINGSXX = $(ARCHWARNINGS)
# pull in *just* libm from the toolchain ... this is grody
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
EXTRA_LIBS += $(LIBM)
# Flags we pass to the C compiler
#
CFLAGS = $(ARCHCFLAGS) \
$(ARCHCWARNINGS) \
$(ARCHOPTIMIZATION) \
$(ARCHCPUFLAGS) \
$(ARCHINCLUDES) \
$(INSTRUMENTATIONDEFINES) \
$(ARCHDEFINES) \
$(EXTRADEFINES) \
$(EXTRACFLAGS) \
-fno-common \
$(addprefix -I,$(INCLUDE_DIRS))
# Flags we pass to the C++ compiler
#
CXXFLAGS = $(ARCHCXXFLAGS) \
$(ARCHWARNINGSXX) \
$(ARCHOPTIMIZATION) \
$(ARCHCPUFLAGS) \
$(ARCHXXINCLUDES) \
$(INSTRUMENTATIONDEFINES) \
$(ARCHDEFINES) \
-DCONFIG_WCHAR_BUILTIN \
$(EXTRADEFINES) \
$(EXTRACXXFLAGS) \
$(addprefix -I,$(INCLUDE_DIRS))
# Flags we pass to the assembler
#
AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
$(EXTRADEFINES) \
$(EXTRAAFLAGS)
# Flags we pass to the linker
#
LDFLAGS += --warn-common \
--gc-sections \
$(EXTRALDFLAGS) \
$(addprefix -T,$(LDSCRIPT)) \
$(addprefix -L,$(LIB_DIRS))
# Compiler support library
#
LIBGCC := $(shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name)
# Files that the final link depends on
#
LINK_DEPS += $(LDSCRIPT)
# Files to include to get automated dependencies
#
DEP_INCLUDES = $(subst .o,.d,$(OBJS))
# Compile C source $1 to object $2
# as a side-effect, generate a dependency file
#
define COMPILE
@$(ECHO) "CC: $1"
@$(MKDIR) -p $(dir $2)
$(Q) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
endef
# Compile C++ source $1 to $2
# as a side-effect, generate a dependency file
#
define COMPILEXX
@$(ECHO) "CXX: $1"
@$(MKDIR) -p $(dir $2)
$(Q) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
endef
# Assemble $1 into $2
#
define ASSEMBLE
@$(ECHO) "AS: $1"
@$(MKDIR) -p $(dir $2)
$(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2
endef
# Produce partially-linked $1 from files in $2
#
define PRELINK
@$(ECHO) "PRELINK: $1"
@$(MKDIR) -p $(dir $1)
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
# Update the archive $1 with the files in $2
#
define ARCHIVE
@$(ECHO) "AR: $2"
@$(MKDIR) -p $(dir $1)
$(Q) $(AR) $1 $2
endef
# Link the objects in $2 into the binary $1
#
define LINK
@$(ECHO) "LINK: $1"
@$(MKDIR) -p $(dir $1)
$(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
endef
# Convert $1 from a linked object to a raw binary in $2
#
define SYM_TO_BIN
@$(ECHO) "BIN: $2"
@$(MKDIR) -p $(dir $2)
$(Q) $(OBJCOPY) -O binary $1 $2
endef
# Take the raw binary $1 and make it into an object file $2.
# The symbol $3 points to the beginning of the file, and $3_len
# gives its length.
#
# - compile an empty file to generate a suitable object file
# - relink the object and insert the binary file
# - edit symbol names to suit
#
# NOTE: exercise caution using this with absolute pathnames; it looks
# like the MinGW tools insert an extra _ in the binary symbol name; e.g.
# the path:
#
# /d/px4/firmware/Build/px4fmu_default.build/romfs.img
#
# is assigned symbols like:
#
# _binary_d__px4_firmware_Build_px4fmu_default_build_romfs_img_size
#
# when we would expect
#
# _binary__d_px4_firmware_Build_px4fmu_default_build_romfs_img_size
#
define BIN_SYM_PREFIX
_binary_$(subst /,_,$(subst .,_,$1))
endef
define BIN_TO_OBJ
@$(ECHO) "OBJ: $2"
@$(MKDIR) -p $(dir $2)
$(Q) $(ECHO) > $2.c
$(call COMPILE,$2.c,$2.c.o)
$(Q) $(LD) -r -o $2 $2.c.o -b binary $1
$(Q) $(OBJCOPY) $2 \
--redefine-sym $(call BIN_SYM_PREFIX,$1)_start=$3 \
--redefine-sym $(call BIN_SYM_PREFIX,$1)_size=$3_len \
--strip-symbol $(call BIN_SYM_PREFIX,$1)_end
$(Q) $(REMOVE) $2.c $2.c.o
endef

44
makefiles/upload.mk Normal file
View File

@ -0,0 +1,44 @@
#
# Rules and tools for uploading firmware to various PX4 boards.
#
UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
SYSTYPE := $(shell uname -s)
#
# Serial port defaults.
#
# XXX The uploader should be smarter than this.
#
ifeq ($(SYSTYPE),Darwin)
SERIAL_PORTS ?= "/dev/tty.usbmodemPX1,/dev/tty.usbmodemPX2,/dev/tty.usbmodemPX3,/dev/tty.usbmodemPX4,/dev/tty.usbmodem1,/dev/tty.usbmodem2,/dev/tty.usbmodem3,/dev/tty.usbmodem4"
endif
ifeq ($(SYSTYPE),Linux)
SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
endif
ifeq ($(SERIAL_PORTS),)
SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
endif
.PHONY: all upload-$(METHOD)-$(BOARD)
all: upload-$(METHOD)-$(BOARD)
upload-serial-px4fmu: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
#
# JTAG firmware uploading with OpenOCD
#
JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg
upload-jtag-px4fmu: all
@$(ECHO) Attempting to flash PX4FMU board via JTAG
$(Q) $(OPENOCD) -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
upload-jtag-px4io: all
@$(ECHO) Attempting to flash PX4IO board via JTAG
$(Q) $(OPENOCD) -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown

View File

@ -1512,7 +1512,6 @@ static inline void stm32_ep0out_receive(FAR struct stm32_ep_s *privep, int bcnt)
DEBUGASSERT(privep && privep->ep.priv);
priv = (FAR struct stm32_usbdev_s *)privep->ep.priv;
DEBUGASSERT(priv->ep0state == EP0STATE_SETUP_OUT);
ullvdbg("EP0: bcnt=%d\n", bcnt);
usbtrace(TRACE_READ(EP0), bcnt);

View File

@ -308,6 +308,10 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
@ -321,6 +325,8 @@
#define PX4_SPIDEV_ACCEL 2
#define PX4_SPIDEV_MPU 3
#define PX4_SPIDEV_ACCEL_MAG 2 // external for anti vibration test
/*
* Tone alarm output
*/

View File

@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* nsh_romfsetc.h
*
* This file is a stub for 'make export' purposes; the actual ROMFS
* must be supplied by the library client.
*/
extern unsigned char romfs_img[];
extern unsigned int romfs_img_len;

View File

@ -41,98 +41,6 @@ CONFIGURED_APPS += examples/nsh
CONFIGURED_APPS += nshlib
CONFIGURED_APPS += system/readline
# System library - utility functions
CONFIGURED_APPS += systemlib
CONFIGURED_APPS += systemlib/mixer
# Math library
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += mathlib
CONFIGURED_APPS += mathlib/CMSIS
CONFIGURED_APPS += examples/math_demo
endif
# Control library
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += controllib
CONFIGURED_APPS += examples/control_demo
CONFIGURED_APPS += examples/kalman_demo
endif
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
CONFIGURED_APPS += systemcmds/perf
CONFIGURED_APPS += systemcmds/top
CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/pwm
CONFIGURED_APPS += systemcmds/bl_update
CONFIGURED_APPS += systemcmds/preflight_check
CONFIGURED_APPS += systemcmds/delay_test
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/hello_sky
# CONFIGURED_APPS += examples/px4_simple_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/deamon
# CONFIGURED_APPS += examples/px4_deamon_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/debug_values
# CONFIGURED_APPS += examples/px4_mavlink_debug
# Shared object broker; required by many parts of the system.
CONFIGURED_APPS += uORB
CONFIGURED_APPS += mavlink
CONFIGURED_APPS += mavlink_onboard
CONFIGURED_APPS += commander
CONFIGURED_APPS += sdlog
CONFIGURED_APPS += sensors
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += ardrone_interface
CONFIGURED_APPS += multirotor_att_control
CONFIGURED_APPS += multirotor_pos_control
CONFIGURED_APPS += position_estimator_mc
CONFIGURED_APPS += fixedwing_att_control
CONFIGURED_APPS += fixedwing_pos_control
CONFIGURED_APPS += position_estimator
CONFIGURED_APPS += attitude_estimator_ekf
CONFIGURED_APPS += hott_telemetry
endif
# Hacking tools
#CONFIGURED_APPS += system/i2c
CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
CONFIGURED_APPS += drivers/boards/px4fmu
CONFIGURED_APPS += drivers/device
CONFIGURED_APPS += drivers/ms5611
CONFIGURED_APPS += drivers/hmc5883
CONFIGURED_APPS += drivers/mpu6000
CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/mkblctrl
CONFIGURED_APPS += drivers/hil
CONFIGURED_APPS += drivers/gps
CONFIGURED_APPS += drivers/mb12xx
# Testing stuff
CONFIGURED_APPS += px4/sensors_bringup
CONFIGURED_APPS += px4/tests
ifeq ($(CONFIG_CAN),y)
#CONFIGURED_APPS += examples/can
endif

View File

@ -85,7 +85,7 @@ CONFIG_ARCH_FPU=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=y
@ -647,10 +647,14 @@ CONFIG_DISABLE_POLL=n
# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
# 5.1234567
# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
# CONFIG_LIBC_STRERR - allow printing of error text
# CONFIG_LIBC_STRERR_SHORT - allow printing of short error text
#
CONFIG_NOPRINTF_FIELDWIDTH=n
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_HAVE_LONG_LONG=y
CONFIG_LIBC_STRERROR=n
CONFIG_LIBC_STRERROR_SHORT=n
#
# Allow for architecture optimized implementations

View File

@ -100,12 +100,19 @@
* Some of the USART pins are not available; override the GPIO
* definitions with an invalid pin configuration.
*/
#undef GPIO_USART2_CTS
#define GPIO_USART2_CTS 0xffffffff
#undef GPIO_USART2_RTS
#define GPIO_USART2_RTS 0xffffffff
#undef GPIO_USART2_CK
#define GPIO_USART2_CK 0xffffffff
#undef GPIO_USART3_TX
#define GPIO_USART3_TX 0xffffffff
#undef GPIO_USART3_CK
#define GPIO_USART3_CK 0xffffffff
#undef GPIO_USART3_CTS
#define GPIO_USART3_CTS 0xffffffff
#undef GPIO_USART3_RTS
#define GPIO_USART3_RTS 0xffffffff
/*
@ -156,6 +163,10 @@ extern "C" {
************************************************************************************/
EXTERN void stm32_boardinitialize(void);
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_BOARD_BOARD_H */

View File

@ -30,11 +30,3 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
CONFIGURED_APPS += drivers/boards/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += px4io
# Mixer library from systemlib
CONFIGURED_APPS += systemlib/mixer

View File

@ -43,6 +43,7 @@
/****************************************************************************
* Included Files
****************************************************************************/
#include <math.h>
/****************************************************************************
* Pre-processor Definitions
@ -104,6 +105,13 @@ static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes)
* Private Functions
****************************************************************************/
static void lib_dtoa_string(FAR struct lib_outstream_s *obj, const char *str)
{
while (*str) {
obj->put(obj, *str++);
}
}
/****************************************************************************
* Name: lib_dtoa
*
@ -137,9 +145,23 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
int nchars; /* Number of characters to print */
int dsgn; /* Unused sign indicator */
int i;
bool done_decimal_point = false;
/* special handling for NaN and Infinity */
if (isnan(value)) {
lib_dtoa_string(obj, "NaN");
return;
}
if (isinf(value)) {
if (value < 0.0d) {
obj->put(obj, '-');
}
lib_dtoa_string(obj, "Infinity");
return;
}
/* Non-zero... positive or negative */
if (value < 0)
{
value = -value;
@ -178,6 +200,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
if (prec > 0 || IS_ALTFORM(flags))
{
obj->put(obj, '.');
done_decimal_point = true;
/* Always print at least one digit to the right of the decimal point. */
@ -203,6 +226,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
/* Print the decimal point */
obj->put(obj, '.');
done_decimal_point = true;
/* Print any leading zeros to the right of the decimal point */
@ -249,6 +273,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
/* Print the decimal point */
obj->put(obj, '.');
done_decimal_point = true;
/* Always print at least one digit to the right of the decimal
* point.
@ -285,8 +310,9 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec,
}
/* Finally, print any trailing zeroes */
zeroes(obj, prec);
if (done_decimal_point) {
zeroes(obj, prec);
}
/* Is this memory supposed to be freed or not? */

View File

@ -1215,7 +1215,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
fmt = FMT_RJUST;
width = 0;
#ifdef CONFIG_LIBC_FLOATINGPOINT
trunc = 0;
trunc = 6;
#endif
#endif
@ -1245,6 +1245,11 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
{
#ifndef CONFIG_NOPRINTF_FIELDWIDTH
fmt = FMT_RJUST0;
#ifdef CONFIG_LIBC_FLOATINGPOINT
if (IS_HASDOT(flags)) {
trunc = 0;
}
#endif
#endif
}
#if 0

3
platforms/empty.c Normal file
View File

@ -0,0 +1,3 @@
/*
* This is an empty C source file, used when building default firmware configurations.
*/

View File

@ -482,10 +482,10 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : 10;
/* Failsafe logic - should never be necessary */
motor_pwm[0] = (motor_pwm[0] <= 512) ? motor_pwm[0] : 512;
motor_pwm[1] = (motor_pwm[1] <= 512) ? motor_pwm[1] : 512;
motor_pwm[2] = (motor_pwm[2] <= 512) ? motor_pwm[2] : 512;
motor_pwm[3] = (motor_pwm[3] <= 512) ? motor_pwm[3] : 512;
motor_pwm[0] = (motor_pwm[0] <= 511) ? motor_pwm[0] : 511;
motor_pwm[1] = (motor_pwm[1] <= 511) ? motor_pwm[1] : 511;
motor_pwm[2] = (motor_pwm[2] <= 511) ? motor_pwm[2] : 511;
motor_pwm[3] = (motor_pwm[3] <= 511) ? motor_pwm[3] : 511;
/* send motors via UART */
ardrone_write_motor_commands(ardrone_write, motor_pwm[0], motor_pwm[1], motor_pwm[2], motor_pwm[3]);

Some files were not shown because too many files have changed in this diff Show More