mirror of https://github.com/ArduPilot/ardupilot
build: removed makefile build system
This commit is contained in:
parent
7c5d82ed15
commit
088442880e
|
@ -1 +0,0 @@
|
||||||
include ../mk/apm.mk
|
|
|
@ -1,54 +0,0 @@
|
||||||
LIBRARIES = AP_Common
|
|
||||||
LIBRARIES += AP_Param
|
|
||||||
LIBRARIES += StorageManager
|
|
||||||
LIBRARIES += AP_GPS
|
|
||||||
LIBRARIES += AP_Baro
|
|
||||||
LIBRARIES += AP_Compass
|
|
||||||
LIBRARIES += AP_Math
|
|
||||||
LIBRARIES += AP_InertialSensor
|
|
||||||
LIBRARIES += AP_AccelCal
|
|
||||||
LIBRARIES += AP_AHRS
|
|
||||||
LIBRARIES += AP_NavEKF2
|
|
||||||
LIBRARIES += AP_NavEKF3
|
|
||||||
LIBRARIES += AP_Mission
|
|
||||||
LIBRARIES += AP_Rally
|
|
||||||
LIBRARIES += AP_Terrain
|
|
||||||
LIBRARIES += RC_Channel
|
|
||||||
LIBRARIES += AP_RangeFinder
|
|
||||||
LIBRARIES += Filter
|
|
||||||
LIBRARIES += Butter
|
|
||||||
LIBRARIES += AP_Buffer
|
|
||||||
LIBRARIES += ModeFilter
|
|
||||||
LIBRARIES += AverageFilter
|
|
||||||
LIBRARIES += AP_Mount
|
|
||||||
LIBRARIES += AP_Camera
|
|
||||||
LIBRARIES += GCS_MAVLink
|
|
||||||
LIBRARIES += AP_SerialManager
|
|
||||||
LIBRARIES += AP_Vehicle
|
|
||||||
LIBRARIES += DataFlash
|
|
||||||
LIBRARIES += AP_RCMapper
|
|
||||||
LIBRARIES += AP_Scheduler
|
|
||||||
LIBRARIES += AP_Navigation
|
|
||||||
LIBRARIES += APM_Control
|
|
||||||
LIBRARIES += AP_L1_Control
|
|
||||||
LIBRARIES += AP_BoardConfig
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
|
||||||
LIBRARIES += AP_Notify
|
|
||||||
LIBRARIES += AP_BattMonitor
|
|
||||||
LIBRARIES += AP_OpticalFlow
|
|
||||||
LIBRARIES += AP_Declination
|
|
||||||
LIBRARIES += AP_RPM
|
|
||||||
LIBRARIES += AP_Arming
|
|
||||||
LIBRARIES += AP_Stats
|
|
||||||
LIBRARIES += AP_Beacon
|
|
||||||
LIBRARIES += AP_WheelEncoder
|
|
||||||
LIBRARIES += AP_AdvancedFailsafe
|
|
||||||
LIBRARIES += AR_AttitudeControl
|
|
||||||
LIBRARIES += AC_PID
|
|
||||||
LIBRARIES += AC_Fence
|
|
||||||
LIBRARIES += AP_SmartRTL
|
|
||||||
LIBRARIES += AC_AttitudeControl
|
|
||||||
LIBRARIES += AP_Devo_Telem
|
|
||||||
LIBRARIES += AP_Follow
|
|
||||||
LIBRARIES += AP_OSD
|
|
||||||
LIBRARIES += AP_WindVane
|
|
|
@ -1 +0,0 @@
|
||||||
include ../mk/apm.mk
|
|
|
@ -1,34 +0,0 @@
|
||||||
LIBRARIES += AP_Common
|
|
||||||
LIBRARIES += AP_Param
|
|
||||||
LIBRARIES += StorageManager
|
|
||||||
LIBRARIES += AP_GPS
|
|
||||||
LIBRARIES += AP_Baro
|
|
||||||
LIBRARIES += AP_Compass
|
|
||||||
LIBRARIES += AP_Math
|
|
||||||
LIBRARIES += AP_AccelCal
|
|
||||||
LIBRARIES += AP_InertialSensor
|
|
||||||
LIBRARIES += AP_AHRS
|
|
||||||
LIBRARIES += Filter
|
|
||||||
LIBRARIES += AP_Buffer
|
|
||||||
LIBRARIES += GCS_MAVLink
|
|
||||||
LIBRARIES += AP_SerialManager
|
|
||||||
LIBRARIES += AP_Declination
|
|
||||||
LIBRARIES += DataFlash
|
|
||||||
LIBRARIES += AC_PID
|
|
||||||
LIBRARIES += AP_Scheduler
|
|
||||||
LIBRARIES += AP_NavEKF2
|
|
||||||
LIBRARIES += AP_NavEKF3
|
|
||||||
LIBRARIES += AP_Vehicle
|
|
||||||
LIBRARIES += AP_Mission
|
|
||||||
LIBRARIES += AP_Terrain
|
|
||||||
LIBRARIES += AP_Rally
|
|
||||||
LIBRARIES += AP_Notify
|
|
||||||
LIBRARIES += AP_BattMonitor
|
|
||||||
LIBRARIES += RC_Channel
|
|
||||||
LIBRARIES += AP_BoardConfig
|
|
||||||
LIBRARIES += AP_OpticalFlow
|
|
||||||
LIBRARIES += AP_RangeFinder
|
|
||||||
LIBRARIES += AP_Mount
|
|
||||||
LIBRARIES += AP_RPM
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
|
||||||
LIBRARIES += AP_Beacon
|
|
|
@ -1,2 +0,0 @@
|
||||||
include ../mk/apm.mk
|
|
||||||
|
|
|
@ -1,64 +0,0 @@
|
||||||
LIBRARIES += AP_Common
|
|
||||||
LIBRARIES += AP_AdvancedFailsafe
|
|
||||||
LIBRARIES += AP_Param
|
|
||||||
LIBRARIES += StorageManager
|
|
||||||
LIBRARIES += GCS
|
|
||||||
LIBRARIES += GCS_MAVLink
|
|
||||||
LIBRARIES += AP_SerialManager
|
|
||||||
LIBRARIES += AP_GPS
|
|
||||||
LIBRARIES += DataFlash
|
|
||||||
LIBRARIES += AP_Baro
|
|
||||||
LIBRARIES += AP_Compass
|
|
||||||
LIBRARIES += AP_Math
|
|
||||||
LIBRARIES += AP_InertialSensor
|
|
||||||
LIBRARIES += AP_AccelCal
|
|
||||||
LIBRARIES += AP_AHRS
|
|
||||||
LIBRARIES += AP_NavEKF2
|
|
||||||
LIBRARIES += AP_NavEKF3
|
|
||||||
LIBRARIES += AP_Mission
|
|
||||||
LIBRARIES += AP_Rally
|
|
||||||
LIBRARIES += AC_PID
|
|
||||||
LIBRARIES += AC_PI_2D
|
|
||||||
LIBRARIES += AC_HELI_PID
|
|
||||||
LIBRARIES += AC_P
|
|
||||||
LIBRARIES += AC_AttitudeControl
|
|
||||||
LIBRARIES += AC_AttitudeControl_Heli
|
|
||||||
LIBRARIES += AC_PosControl
|
|
||||||
LIBRARIES += RC_Channel
|
|
||||||
LIBRARIES += AP_Motors
|
|
||||||
LIBRARIES += AP_RangeFinder
|
|
||||||
LIBRARIES += AP_OpticalFlow
|
|
||||||
LIBRARIES += Filter
|
|
||||||
LIBRARIES += AP_Buffer
|
|
||||||
LIBRARIES += AP_Camera
|
|
||||||
LIBRARIES += AP_Mount
|
|
||||||
LIBRARIES += AP_Vehicle
|
|
||||||
LIBRARIES += AP_InertialNav
|
|
||||||
LIBRARIES += AC_WPNav
|
|
||||||
LIBRARIES += AC_Loiter
|
|
||||||
LIBRARIES += AC_Circle
|
|
||||||
LIBRARIES += AP_Declination
|
|
||||||
LIBRARIES += AC_Fence
|
|
||||||
LIBRARIES += AP_Scheduler
|
|
||||||
LIBRARIES += AP_RCMapper
|
|
||||||
LIBRARIES += AP_Notify
|
|
||||||
LIBRARIES += AP_BattMonitor
|
|
||||||
LIBRARIES += AP_BoardConfig
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
|
||||||
LIBRARIES += AP_Parachute
|
|
||||||
LIBRARIES += AP_Terrain
|
|
||||||
LIBRARIES += AP_RPM
|
|
||||||
LIBRARIES += AC_PrecLand
|
|
||||||
LIBRARIES += AP_IRLock
|
|
||||||
LIBRARIES += AC_InputManager
|
|
||||||
LIBRARIES += AP_ADSB
|
|
||||||
LIBRARIES += AP_Avoidance
|
|
||||||
LIBRARIES += AP_Stats
|
|
||||||
LIBRARIES += AP_Beacon
|
|
||||||
LIBRARIES += AP_Arming
|
|
||||||
LIBRARIES += AP_SmartRTL
|
|
||||||
LIBRARIES += AP_Winch
|
|
||||||
LIBRARIES += AP_WheelEncoder
|
|
||||||
LIBRARIES += AP_Follow
|
|
||||||
LIBRARIES += AP_Devo_Telem
|
|
||||||
LIBRARIES += AP_OSD
|
|
|
@ -1,2 +0,0 @@
|
||||||
include ../mk/apm.mk
|
|
||||||
|
|
|
@ -1,60 +0,0 @@
|
||||||
LIBRARIES += AP_Common
|
|
||||||
LIBRARIES += AP_Param
|
|
||||||
LIBRARIES += StorageManager
|
|
||||||
LIBRARIES += AP_GPS
|
|
||||||
LIBRARIES += AP_Baro
|
|
||||||
LIBRARIES += AP_Compass
|
|
||||||
LIBRARIES += AP_Math
|
|
||||||
LIBRARIES += AP_InertialSensor
|
|
||||||
LIBRARIES += AP_AccelCal
|
|
||||||
LIBRARIES += AP_AHRS
|
|
||||||
LIBRARIES += RC_Channel
|
|
||||||
LIBRARIES += AP_RangeFinder
|
|
||||||
LIBRARIES += Filter
|
|
||||||
LIBRARIES += AP_Buffer
|
|
||||||
LIBRARIES += AP_Camera
|
|
||||||
LIBRARIES += AP_Terrain
|
|
||||||
LIBRARIES += AP_AdvancedFailsafe
|
|
||||||
LIBRARIES += APM_Control
|
|
||||||
LIBRARIES += AP_AutoTune
|
|
||||||
LIBRARIES += GCS
|
|
||||||
LIBRARIES += GCS_MAVLink
|
|
||||||
LIBRARIES += AP_SerialManager
|
|
||||||
LIBRARIES += AP_Mount
|
|
||||||
LIBRARIES += AP_Declination
|
|
||||||
LIBRARIES += DataFlash
|
|
||||||
LIBRARIES += AP_Scheduler
|
|
||||||
LIBRARIES += AP_Navigation
|
|
||||||
LIBRARIES += AP_L1_Control
|
|
||||||
LIBRARIES += AP_RCMapper
|
|
||||||
LIBRARIES += AP_Vehicle
|
|
||||||
LIBRARIES += AP_SpdHgtControl
|
|
||||||
LIBRARIES += AP_TECS
|
|
||||||
LIBRARIES += AP_NavEKF2
|
|
||||||
LIBRARIES += AP_NavEKF3
|
|
||||||
LIBRARIES += AP_Mission
|
|
||||||
LIBRARIES += AP_Notify
|
|
||||||
LIBRARIES += AP_BattMonitor
|
|
||||||
LIBRARIES += AP_Arming
|
|
||||||
LIBRARIES += AP_BoardConfig
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
|
||||||
LIBRARIES += AP_Rally
|
|
||||||
LIBRARIES += AP_OpticalFlow
|
|
||||||
LIBRARIES += AP_RPM
|
|
||||||
LIBRARIES += AP_Parachute
|
|
||||||
LIBRARIES += AP_ADSB
|
|
||||||
LIBRARIES += AP_Avoidance
|
|
||||||
LIBRARIES += AP_Motors
|
|
||||||
LIBRARIES += AC_AttitudeControl
|
|
||||||
LIBRARIES += AC_PID
|
|
||||||
LIBRARIES += AP_InertialNav
|
|
||||||
LIBRARIES += AC_WPNav
|
|
||||||
LIBRARIES += AC_Fence
|
|
||||||
LIBRARIES += AP_Tuning
|
|
||||||
LIBRARIES += AP_Stats
|
|
||||||
LIBRARIES += AP_Landing
|
|
||||||
LIBRARIES += AP_Beacon
|
|
||||||
LIBRARIES += PID
|
|
||||||
LIBRARIES += AP_Soaring
|
|
||||||
LIBRARIES += AP_Devo_Telem
|
|
||||||
LIBRARIES += AP_OSD
|
|
|
@ -1,2 +0,0 @@
|
||||||
include ../mk/apm.mk
|
|
||||||
|
|
|
@ -1,50 +0,0 @@
|
||||||
LIBRARIES += AP_Common
|
|
||||||
LIBRARIES += AP_Param
|
|
||||||
LIBRARIES += StorageManager
|
|
||||||
LIBRARIES += GCS
|
|
||||||
LIBRARIES += GCS_MAVLink
|
|
||||||
LIBRARIES += AP_SerialManager
|
|
||||||
LIBRARIES += AP_GPS
|
|
||||||
LIBRARIES += DataFlash
|
|
||||||
LIBRARIES += AP_Baro
|
|
||||||
LIBRARIES += AP_Compass
|
|
||||||
LIBRARIES += AP_Math
|
|
||||||
LIBRARIES += AP_InertialSensor
|
|
||||||
LIBRARIES += AP_AccelCal
|
|
||||||
LIBRARIES += AP_AHRS
|
|
||||||
LIBRARIES += AP_NavEKF2
|
|
||||||
LIBRARIES += AP_NavEKF3
|
|
||||||
LIBRARIES += AP_Mission
|
|
||||||
LIBRARIES += AP_Rally
|
|
||||||
LIBRARIES += AC_PID
|
|
||||||
LIBRARIES += AC_PI_2D
|
|
||||||
LIBRARIES += AC_P
|
|
||||||
LIBRARIES += AC_AttitudeControl
|
|
||||||
LIBRARIES += AC_PosControl_Sub
|
|
||||||
LIBRARIES += RC_Channel
|
|
||||||
LIBRARIES += AP_Motors
|
|
||||||
LIBRARIES += AP_RangeFinder
|
|
||||||
LIBRARIES += AP_OpticalFlow
|
|
||||||
LIBRARIES += Filter
|
|
||||||
LIBRARIES += AP_Camera
|
|
||||||
LIBRARIES += AP_Mount
|
|
||||||
LIBRARIES += AP_Vehicle
|
|
||||||
LIBRARIES += AP_InertialNav
|
|
||||||
LIBRARIES += AC_WPNav
|
|
||||||
LIBRARIES += AC_Loiter
|
|
||||||
LIBRARIES += AC_Circle
|
|
||||||
LIBRARIES += AP_Declination
|
|
||||||
LIBRARIES += AC_Fence
|
|
||||||
LIBRARIES += AP_Scheduler
|
|
||||||
LIBRARIES += AP_RCMapper
|
|
||||||
LIBRARIES += AP_Notify
|
|
||||||
LIBRARIES += AP_BattMonitor
|
|
||||||
LIBRARIES += AP_BoardConfig
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
|
||||||
LIBRARIES += AP_Terrain
|
|
||||||
LIBRARIES += AP_RPM
|
|
||||||
LIBRARIES += AP_JSButton
|
|
||||||
LIBRARIES += AP_LeakDetector
|
|
||||||
LIBRARIES += AP_Beacon
|
|
||||||
LIBRARIES += AP_TemperatureSensor
|
|
||||||
LIBRARIES += AP_Arming
|
|
99
Makefile
99
Makefile
|
@ -1,30 +1,89 @@
|
||||||
# top level makefile to build SITL for primary vehicle targets.
|
ROOT = $(dir $(lastword $(MAKEFILE_LIST)))
|
||||||
# Useful for static analysis tools
|
|
||||||
|
|
||||||
all: sitl
|
WAF_BINARY = $(realpath $(ROOT)/modules/waf/waf-light)
|
||||||
|
WAF = $(WAF_BINARY) $(WAF_FLAGS)
|
||||||
|
|
||||||
sitl: TARGET=sitl
|
EXPLICIT_COMMANDS = check check-all clean list_boards
|
||||||
sitl: plane copter rover sub antennatracker
|
|
||||||
|
|
||||||
linux: TARGET=linux
|
VEHICLES = copter plane rover
|
||||||
linux: plane copter rover sub antennatracker
|
|
||||||
|
|
||||||
clean: TARGET=clean
|
all: $(WAF_BINARY)
|
||||||
clean: plane copter rover sub antennatracker
|
@$(WAF) build
|
||||||
|
|
||||||
.PHONY: plane copter rover sub antennatracker
|
$(WAF_BINARY):
|
||||||
|
@git submodule init && git submodule update
|
||||||
|
|
||||||
plane:
|
waf-%: $(WAF_BINARY)
|
||||||
$(MAKE) -C ArduPlane $(TARGET)
|
@$(WAF) $*
|
||||||
|
|
||||||
copter:
|
%-configure: $(WAF_BINARY)
|
||||||
$(MAKE) -C ArduCopter $(TARGET)
|
@$(WAF) configure --board $*
|
||||||
|
|
||||||
rover:
|
$(EXPLICIT_COMMANDS): $(WAF_BINARY)
|
||||||
$(MAKE) -C APMrover2 $(TARGET)
|
@$(WAF) $@
|
||||||
|
|
||||||
sub:
|
$(VEHICLES): $(WAF_BINARY)
|
||||||
$(MAKE) -C ArduSub $(TARGET)
|
@echo Build for vehicle $@
|
||||||
|
@$(WAF) $@
|
||||||
|
|
||||||
antennatracker:
|
.DEFAULT: %-configure
|
||||||
$(MAKE) -C AntennaTracker $(TARGET)
|
@$(WAF) configure --board $@ build
|
||||||
|
|
||||||
|
help:
|
||||||
|
@echo "Ardupilot Building"
|
||||||
|
@echo "=================="
|
||||||
|
@echo "This is a make wrapper for Ardupilot's Waf build system. This wrapper is"
|
||||||
|
@echo "intended to provide convenience for basic and common build tasks. If you need"
|
||||||
|
@echo "more than what this wrapper provides, it's a good idea to use waf directly."
|
||||||
|
@echo "The waf executable is at '$(WAF_BINARY)'."
|
||||||
|
@echo ""
|
||||||
|
@echo "WARNING: Ardupilot's Waf build system is still a work in progress, it's still"
|
||||||
|
@echo "missing features from the current official build system."
|
||||||
|
@echo ""
|
||||||
|
@echo "Note: The examples in this help consider this wrapper being named as Makefile"
|
||||||
|
@echo "or makefile. In a Linux environment, alias make='make -f THIS_MAKEFILE'"
|
||||||
|
@echo "should make them work."
|
||||||
|
@echo ""
|
||||||
|
@echo "Boards"
|
||||||
|
@echo "------"
|
||||||
|
@echo "In order to trigger the build for a board/platform, the name of the board is"
|
||||||
|
@echo "used as the target. Example: make linux"
|
||||||
|
@echo "If no target is passed, then the build will be triggered for the last board"
|
||||||
|
@echo "used. You can suffix the board/platform with '-configure' in order to just "
|
||||||
|
@echo "configure without triggering a build command."
|
||||||
|
@echo ""
|
||||||
|
@echo "Vehicles"
|
||||||
|
@echo "--------"
|
||||||
|
@echo "It's possible to build for a specific vehicle by defining the target as one of:"
|
||||||
|
@echo " $(VEHICLES)"
|
||||||
|
@echo ""
|
||||||
|
@echo "Not that if it's your first time building or you want to change the target "
|
||||||
|
@echo "board/platform, you'll need to configure the build before (e.g"
|
||||||
|
@echo "make linux-configure)"
|
||||||
|
@echo ""
|
||||||
|
@echo "Check"
|
||||||
|
@echo "-----"
|
||||||
|
@echo "Check targets are used for running tests. There are two targets available:"
|
||||||
|
@echo " check: for running tests that are still failing or that are new or"
|
||||||
|
@echo " have been modified"
|
||||||
|
@echo " check-all: to run all tests"
|
||||||
|
@echo ""
|
||||||
|
@echo "Waf commands"
|
||||||
|
@echo "------------"
|
||||||
|
@echo "Waf commands can be explicitly called with targets prefixed by 'waf-'. Example:"
|
||||||
|
@echo " make waf-clean"
|
||||||
|
@echo " make waf-build"
|
||||||
|
@echo ""
|
||||||
|
@echo "Common commands"
|
||||||
|
@echo "---------------"
|
||||||
|
@echo "Some Waf commands can be executed without the need of prefixing the target name"
|
||||||
|
@echo "with 'waf-'. They are: $(EXPLICIT_COMMANDS)"
|
||||||
|
@echo ""
|
||||||
|
@echo "Waf flags"
|
||||||
|
@echo "---------"
|
||||||
|
@echo "The variable WAF_FLAGS can be used to set any waf command line options that"
|
||||||
|
@echo "come to be necessary. Ex: make linux WAF_FLAGS='-c no'"
|
||||||
|
@echo ""
|
||||||
|
|
||||||
|
# Don't run in parallel, let waf take care of that.
|
||||||
|
.NOTPARALLEL:
|
||||||
|
|
89
Makefile.waf
89
Makefile.waf
|
@ -1,89 +0,0 @@
|
||||||
ROOT = $(dir $(lastword $(MAKEFILE_LIST)))
|
|
||||||
|
|
||||||
WAF_BINARY = $(realpath $(ROOT)/modules/waf/waf-light)
|
|
||||||
WAF = $(WAF_BINARY) $(WAF_FLAGS)
|
|
||||||
|
|
||||||
EXPLICIT_COMMANDS = check check-all clean list_boards
|
|
||||||
|
|
||||||
VEHICLES = copter plane rover
|
|
||||||
|
|
||||||
all: $(WAF_BINARY)
|
|
||||||
@$(WAF) build
|
|
||||||
|
|
||||||
$(WAF_BINARY):
|
|
||||||
@git submodule init && git submodule update
|
|
||||||
|
|
||||||
waf-%: $(WAF_BINARY)
|
|
||||||
@$(WAF) $*
|
|
||||||
|
|
||||||
%-configure: $(WAF_BINARY)
|
|
||||||
@$(WAF) configure --board $*
|
|
||||||
|
|
||||||
$(EXPLICIT_COMMANDS): $(WAF_BINARY)
|
|
||||||
@$(WAF) $@
|
|
||||||
|
|
||||||
$(VEHICLES): $(WAF_BINARY)
|
|
||||||
@echo Build for vehicle $@
|
|
||||||
@$(WAF) $@
|
|
||||||
|
|
||||||
.DEFAULT: %-configure
|
|
||||||
@$(WAF) configure --board $@ build
|
|
||||||
|
|
||||||
help:
|
|
||||||
@echo "Ardupilot Building"
|
|
||||||
@echo "=================="
|
|
||||||
@echo "This is a make wrapper for Ardupilot's Waf build system. This wrapper is"
|
|
||||||
@echo "intended to provide convenience for basic and common build tasks. If you need"
|
|
||||||
@echo "more than what this wrapper provides, it's a good idea to use waf directly."
|
|
||||||
@echo "The waf executable is at '$(WAF_BINARY)'."
|
|
||||||
@echo ""
|
|
||||||
@echo "WARNING: Ardupilot's Waf build system is still a work in progress, it's still"
|
|
||||||
@echo "missing features from the current official build system."
|
|
||||||
@echo ""
|
|
||||||
@echo "Note: The examples in this help consider this wrapper being named as Makefile"
|
|
||||||
@echo "or makefile. In a Linux environment, alias make='make -f THIS_MAKEFILE'"
|
|
||||||
@echo "should make them work."
|
|
||||||
@echo ""
|
|
||||||
@echo "Boards"
|
|
||||||
@echo "------"
|
|
||||||
@echo "In order to trigger the build for a board/platform, the name of the board is"
|
|
||||||
@echo "used as the target. Example: make linux"
|
|
||||||
@echo "If no target is passed, then the build will be triggered for the last board"
|
|
||||||
@echo "used. You can suffix the board/platform with '-configure' in order to just "
|
|
||||||
@echo "configure without triggering a build command."
|
|
||||||
@echo ""
|
|
||||||
@echo "Vehicles"
|
|
||||||
@echo "--------"
|
|
||||||
@echo "It's possible to build for a specific vehicle by defining the target as one of:"
|
|
||||||
@echo " $(VEHICLES)"
|
|
||||||
@echo ""
|
|
||||||
@echo "Not that if it's your first time building or you want to change the target "
|
|
||||||
@echo "board/platform, you'll need to configure the build before (e.g"
|
|
||||||
@echo "make linux-configure)"
|
|
||||||
@echo ""
|
|
||||||
@echo "Check"
|
|
||||||
@echo "-----"
|
|
||||||
@echo "Check targets are used for running tests. There are two targets available:"
|
|
||||||
@echo " check: for running tests that are still failing or that are new or"
|
|
||||||
@echo " have been modified"
|
|
||||||
@echo " check-all: to run all tests"
|
|
||||||
@echo ""
|
|
||||||
@echo "Waf commands"
|
|
||||||
@echo "------------"
|
|
||||||
@echo "Waf commands can be explicitly called with targets prefixed by 'waf-'. Example:"
|
|
||||||
@echo " make waf-clean"
|
|
||||||
@echo " make waf-build"
|
|
||||||
@echo ""
|
|
||||||
@echo "Common commands"
|
|
||||||
@echo "---------------"
|
|
||||||
@echo "Some Waf commands can be executed without the need of prefixing the target name"
|
|
||||||
@echo "with 'waf-'. They are: $(EXPLICIT_COMMANDS)"
|
|
||||||
@echo ""
|
|
||||||
@echo "Waf flags"
|
|
||||||
@echo "---------"
|
|
||||||
@echo "The variable WAF_FLAGS can be used to set any waf command line options that"
|
|
||||||
@echo "come to be necessary. Ex: make linux WAF_FLAGS='-c no'"
|
|
||||||
@echo ""
|
|
||||||
|
|
||||||
# Don't run in parallel, let waf take care of that.
|
|
||||||
.NOTPARALLEL:
|
|
|
@ -1 +0,0 @@
|
||||||
!*.d
|
|
|
@ -1,2 +0,0 @@
|
||||||
bootloaders for PX4 build are now in Tools/bootloaders/
|
|
||||||
|
|
|
@ -1,48 +0,0 @@
|
||||||
#!nsh
|
|
||||||
|
|
||||||
# APM startup script for NuttX on PX4
|
|
||||||
|
|
||||||
# To disable APM startup add a /fs/microsd/APM/nostart file
|
|
||||||
|
|
||||||
# check for an old file called APM, caused by
|
|
||||||
# a bug in an earlier firmware release
|
|
||||||
if [ -f /fs/microsd/APM ]
|
|
||||||
then
|
|
||||||
echo "APM file found - renaming"
|
|
||||||
mv /fs/microsd/APM /fs/microsd/APM.old
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ -f /fs/microsd/APM/nostart ]
|
|
||||||
then
|
|
||||||
echo "APM/nostart found - skipping APM startup"
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
set sketch NONE
|
|
||||||
if rm /fs/microsd/APM/boot.log
|
|
||||||
then
|
|
||||||
echo "removed old boot.log"
|
|
||||||
fi
|
|
||||||
set logfile /fs/microsd/APM/BOOT.LOG
|
|
||||||
|
|
||||||
if mkdir /fs/microsd/APM > /dev/null
|
|
||||||
then
|
|
||||||
echo "Created APM directory"
|
|
||||||
fi
|
|
||||||
|
|
||||||
if uorb start
|
|
||||||
then
|
|
||||||
echo "uorb started OK"
|
|
||||||
else
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo Starting ArduPilot
|
|
||||||
if ArduPilot start
|
|
||||||
then
|
|
||||||
echo ArduPilot started OK
|
|
||||||
else
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo "rc.APM finished"
|
|
|
@ -1,5 +0,0 @@
|
||||||
# AEROFC-V1 custom definitions
|
|
||||||
|
|
||||||
set NSH_ERROR_UART1 /dev/ttyS4
|
|
||||||
set NSH_ERROR_UART2 none
|
|
||||||
set USB none
|
|
|
@ -1,19 +0,0 @@
|
||||||
echo "Error in startup"
|
|
||||||
|
|
||||||
if [ $HAVE_RGBLED == 1 ]
|
|
||||||
then
|
|
||||||
rgbled rgb 16 0 0
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $NSH_ERROR_UART1 != none ]
|
|
||||||
then
|
|
||||||
nshterm $NSH_ERROR_UART1 &
|
|
||||||
sleep 1
|
|
||||||
fi
|
|
||||||
if [ $NSH_ERROR_UART2 != none ]
|
|
||||||
then
|
|
||||||
nshterm $NSH_ERROR_UART2 &
|
|
||||||
sleep 1
|
|
||||||
fi
|
|
||||||
|
|
||||||
exit
|
|
|
@ -1,77 +0,0 @@
|
||||||
#!nsh
|
|
||||||
#
|
|
||||||
# PX4FMU startup script.
|
|
||||||
#
|
|
||||||
# This script is responsible for:
|
|
||||||
#
|
|
||||||
# - mounting the microSD card (if present)
|
|
||||||
# - running the user startup script from the microSD card (if present)
|
|
||||||
# - detecting the configuration of the system and picking a suitable
|
|
||||||
# startup script to continue with
|
|
||||||
#
|
|
||||||
# Note: DO NOT add configuration-specific commands to this script;
|
|
||||||
# add them to the per-configuration scripts instead.
|
|
||||||
#
|
|
||||||
|
|
||||||
set USB autoconnect
|
|
||||||
set NSH_ERROR_UART1 /dev/ttyACM0
|
|
||||||
set NSH_ERROR_UART2 /dev/ttyS0
|
|
||||||
|
|
||||||
#
|
|
||||||
# Try to mount the microSD card.
|
|
||||||
#
|
|
||||||
echo "[init] looking for microSD..."
|
|
||||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
|
||||||
then
|
|
||||||
echo "[init] card mounted at /fs/microsd"
|
|
||||||
fi
|
|
||||||
|
|
||||||
# Look for an additional init script that allows changing the default
|
|
||||||
# behavior. Settings may be overriden in the following order:
|
|
||||||
#
|
|
||||||
# board-specific file
|
|
||||||
# etc/rc on microSD card
|
|
||||||
# etc/rc.txt on microSD card
|
|
||||||
if [ -f /etc/init.d/rc.board ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /etc/init.d/rc.board"
|
|
||||||
sh /etc/init.d/rc.board
|
|
||||||
fi
|
|
||||||
if [ -f /fs/microsd/etc/rc ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /fs/microsd/etc/rc"
|
|
||||||
sh /fs/microsd/etc/rc
|
|
||||||
fi
|
|
||||||
# Also consider rc.txt files
|
|
||||||
if [ -f /fs/microsd/etc/rc.txt ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
|
||||||
sh /fs/microsd/etc/rc.txt
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# Check for USB host
|
|
||||||
#
|
|
||||||
if [ $USB != autoconnect ]
|
|
||||||
then
|
|
||||||
echo "[init] not connecting USB"
|
|
||||||
else
|
|
||||||
if sercon
|
|
||||||
then
|
|
||||||
echo "[init] USB interface connected"
|
|
||||||
else
|
|
||||||
echo "[init] No USB connected"
|
|
||||||
fi
|
|
||||||
fi
|
|
||||||
|
|
||||||
# if this is an APM build then there will be a rc.APM script
|
|
||||||
# from an EXTERNAL_SCRIPTS build option
|
|
||||||
if [ -f /etc/init.d/rc.APM -a ! -f /fs/microsd/APM/nostart ]
|
|
||||||
then
|
|
||||||
echo Running rc.APM
|
|
||||||
# if APM startup is successful then nsh will exit
|
|
||||||
sh /etc/init.d/rc.APM
|
|
||||||
else
|
|
||||||
echo "Opening USB nsh"
|
|
||||||
nshterm /dev/ttyACM0 &
|
|
||||||
fi
|
|
|
@ -1,14 +0,0 @@
|
||||||
#!nsh
|
|
||||||
set USB autoconnect
|
|
||||||
set NSH_ERROR_UART1 /dev/ttyACM0
|
|
||||||
set NSH_ERROR_UART2 /dev/ttyS0
|
|
||||||
|
|
||||||
if sercon
|
|
||||||
then
|
|
||||||
echo "[init] USB interface connected"
|
|
||||||
else
|
|
||||||
echo "[init] No USB connected"
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo Running rc.APM
|
|
||||||
sh /etc/init.d/rc.APM
|
|
|
@ -1 +0,0 @@
|
||||||
MFT240L8O4aO5dcO4aO5dcO4aO5dcL16dcdcdcdc
|
|
|
@ -1,7 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the px4fmu-v1_APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/PX4/px4_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/px4fmu-v1
|
|
||||||
MODULES += drivers/px4io
|
|
|
@ -1,9 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the px4fmu-v2_APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/PX4/px4_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/px4fmu-v2
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
MODULES += drivers/px4io
|
|
||||||
|
|
|
@ -1,9 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the px4fmu-v2_APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/PX4/px4_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/px4fmu-v2
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
MODULES += drivers/px4io
|
|
||||||
MODULES += drivers/oreoled
|
|
|
@ -1,7 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the px4fmu-v4_APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/PX4/px4_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/px4fmu-v4
|
|
||||||
MODULES += drivers/pwm_input
|
|
|
@ -1,9 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the px4fmu-v2_APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/PX4/px4_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/px4fmu-v4pro
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
MODULES += drivers/px4io
|
|
||||||
|
|
|
@ -1,74 +0,0 @@
|
||||||
#
|
|
||||||
# common makefile elements for all PX4 boards
|
|
||||||
#
|
|
||||||
|
|
||||||
#
|
|
||||||
# Use the configuration's ROMFS.
|
|
||||||
#
|
|
||||||
ROMFS_ROOT = $(SKETCHBOOK)/mk/PX4/ROMFS
|
|
||||||
MODULES += $(APM_MODULE_DIR)
|
|
||||||
|
|
||||||
#
|
|
||||||
# Board support modules
|
|
||||||
#
|
|
||||||
MODULES += drivers/device
|
|
||||||
MODULES += drivers/stm32
|
|
||||||
MODULES += drivers/stm32/adc
|
|
||||||
MODULES += drivers/stm32/tone_alarm
|
|
||||||
MODULES += drivers/led
|
|
||||||
MODULES += drivers/px4fmu
|
|
||||||
#MODULES += drivers/gps
|
|
||||||
#MODULES += drivers/hil
|
|
||||||
#MODULES += drivers/hott_telemetry
|
|
||||||
#MODULES += drivers/blinkm
|
|
||||||
#MODULES += modules/sensors
|
|
||||||
|
|
||||||
#
|
|
||||||
# System commands
|
|
||||||
#
|
|
||||||
MODULES += systemcmds/bl_update
|
|
||||||
MODULES += systemcmds/mixer
|
|
||||||
MODULES += systemcmds/perf
|
|
||||||
MODULES += systemcmds/reboot
|
|
||||||
MODULES += systemcmds/top
|
|
||||||
#MODULES += systemcmds/tests
|
|
||||||
MODULES += systemcmds/nshterm
|
|
||||||
MODULES += systemcmds/mtd
|
|
||||||
MODULES += systemcmds/ver
|
|
||||||
|
|
||||||
ifneq ($(wildcard $(PX4_ROOT)/src/systemcmds/usb_connected),)
|
|
||||||
MODULES += systemcmds/usb_connected
|
|
||||||
endif
|
|
||||||
|
|
||||||
#
|
|
||||||
# Library modules
|
|
||||||
#
|
|
||||||
MODULES += modules/systemlib
|
|
||||||
MODULES += modules/systemlib/mixer
|
|
||||||
MODULES += modules/uORB
|
|
||||||
|
|
||||||
# Note: auth disabled to keep us under 1MB flash because of STM32 bug
|
|
||||||
#ifneq ($(wildcard $(PX4_ROOT)/src/systemcmds/auth),)
|
|
||||||
#MODULES += systemcmds/auth
|
|
||||||
#endif
|
|
||||||
#ifneq ($(wildcard $(PX4_ROOT)/src/modules/libtomfastmath),)
|
|
||||||
#MODULES += modules/libtomfastmath
|
|
||||||
#MODULES += modules/libtomcrypt
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#
|
|
||||||
# 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 )
|
|
|
@ -1,71 +0,0 @@
|
||||||
#!nsh
|
|
||||||
|
|
||||||
# APM startup script for NuttX on VRBRAIN
|
|
||||||
|
|
||||||
# To disable APM startup add a /fs/microsd/APM/nostart file
|
|
||||||
|
|
||||||
# check for an old file called APM, caused by
|
|
||||||
# a bug in an earlier firmware release
|
|
||||||
if [ -f /fs/microsd/APM ]
|
|
||||||
then
|
|
||||||
echo "APM file found - renaming"
|
|
||||||
mv /fs/microsd/APM /fs/microsd/APM.old
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ -f /fs/microsd/APM/nostart ]
|
|
||||||
then
|
|
||||||
echo "APM/nostart found - skipping APM startup"
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
# mount binfs so we can find the built-in apps
|
|
||||||
if [ -f /bin/reboot ]
|
|
||||||
then
|
|
||||||
echo "binfs already mounted"
|
|
||||||
else
|
|
||||||
echo "Mounting binfs"
|
|
||||||
if mount -t binfs /dev/null /bin
|
|
||||||
then
|
|
||||||
echo "binfs mounted OK"
|
|
||||||
else
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
fi
|
|
||||||
|
|
||||||
set sketch NONE
|
|
||||||
if rm /fs/microsd/APM/boot.log
|
|
||||||
then
|
|
||||||
echo "removed old boot.log"
|
|
||||||
fi
|
|
||||||
set logfile /fs/microsd/APM/BOOT.LOG
|
|
||||||
|
|
||||||
if [ ! -f /bin/ArduPilot ]
|
|
||||||
then
|
|
||||||
echo "/bin/ardupilot not found"
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
if mkdir /fs/microsd/APM > /dev/null
|
|
||||||
then
|
|
||||||
echo "Created APM directory"
|
|
||||||
fi
|
|
||||||
|
|
||||||
if uorb start
|
|
||||||
then
|
|
||||||
echo "uorb started OK"
|
|
||||||
else
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo Starting ArduPilot
|
|
||||||
if ArduPilot start
|
|
||||||
then
|
|
||||||
echo ArduPilot started OK
|
|
||||||
else
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
|
|
||||||
echo "Exiting from nsh shell"
|
|
||||||
exit
|
|
||||||
|
|
||||||
echo "rc.APM finished"
|
|
|
@ -1,21 +0,0 @@
|
||||||
echo "Error in startup"
|
|
||||||
|
|
||||||
tone_alarm MNCC
|
|
||||||
|
|
||||||
if [ $HAVE_RGBLED == 1 ]
|
|
||||||
then
|
|
||||||
rgbled rgb 16 0 0
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $NSH_ERROR_UART1 != none ]
|
|
||||||
then
|
|
||||||
nshterm $NSH_ERROR_UART1 &
|
|
||||||
sleep 1
|
|
||||||
fi
|
|
||||||
if [ $NSH_ERROR_UART2 != none ]
|
|
||||||
then
|
|
||||||
nshterm $NSH_ERROR_UART2 &
|
|
||||||
sleep 1
|
|
||||||
fi
|
|
||||||
|
|
||||||
exit
|
|
|
@ -1,98 +0,0 @@
|
||||||
#!nsh
|
|
||||||
#
|
|
||||||
# VRBRAIN startup script.
|
|
||||||
#
|
|
||||||
# This script is responsible for:
|
|
||||||
#
|
|
||||||
# - mounting the microSD card (if present)
|
|
||||||
# - running the user startup script from the microSD card (if present)
|
|
||||||
# - detecting the configuration of the system and picking a suitable
|
|
||||||
# startup script to continue with
|
|
||||||
#
|
|
||||||
# Note: DO NOT add configuration-specific commands to this script;
|
|
||||||
# add them to the per-configuration scripts instead.
|
|
||||||
#
|
|
||||||
|
|
||||||
set USB autoconnect
|
|
||||||
set NSH_ERROR_UART1 /dev/ttyACM0
|
|
||||||
set NSH_ERROR_UART2 /dev/ttyS0
|
|
||||||
|
|
||||||
#
|
|
||||||
# Try to mount the microSD card.
|
|
||||||
#
|
|
||||||
echo "[init] looking for microSD..."
|
|
||||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
|
||||||
then
|
|
||||||
echo "[init] card mounted at /fs/microsd"
|
|
||||||
set HAVE_MICROSD 1
|
|
||||||
# Start playing the startup tune
|
|
||||||
if [ -f /etc/tones/startup ]
|
|
||||||
then
|
|
||||||
tone_alarm /etc/tones/startup
|
|
||||||
else
|
|
||||||
tone_alarm 1
|
|
||||||
fi
|
|
||||||
else
|
|
||||||
set HAVE_MICROSD 0
|
|
||||||
tone_alarm MNBGG
|
|
||||||
fi
|
|
||||||
|
|
||||||
# Look for an additional init script that allows changing the default
|
|
||||||
# behavior. Settings may be overriden in the following order:
|
|
||||||
#
|
|
||||||
# board-specific file
|
|
||||||
# etc/rc on microSD card
|
|
||||||
# etc/rc.txt on microSD card
|
|
||||||
if [ -f /etc/init.d/rc.board ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /etc/init.d/rc.board"
|
|
||||||
sh /etc/init.d/rc.board
|
|
||||||
fi
|
|
||||||
if [ -f /fs/microsd/etc/rc ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /fs/microsd/etc/rc"
|
|
||||||
sh /fs/microsd/etc/rc
|
|
||||||
fi
|
|
||||||
# Also consider rc.txt files
|
|
||||||
if [ -f /fs/microsd/etc/rc.txt ]
|
|
||||||
then
|
|
||||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
|
||||||
sh /fs/microsd/etc/rc.txt
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# Check for USB host
|
|
||||||
#
|
|
||||||
if [ $USB != autoconnect ]
|
|
||||||
then
|
|
||||||
echo "[init] not connecting USB"
|
|
||||||
else
|
|
||||||
if sercon
|
|
||||||
then
|
|
||||||
echo "[init] USB interface connected"
|
|
||||||
else
|
|
||||||
echo "[init] No USB connected"
|
|
||||||
fi
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $HAVE_MICROSD == 0 ]
|
|
||||||
then
|
|
||||||
if usb_connected
|
|
||||||
then
|
|
||||||
echo "Opening USB nsh"
|
|
||||||
else
|
|
||||||
echo "booting with no microSD"
|
|
||||||
set HAVE_MICROSD 1
|
|
||||||
fi
|
|
||||||
fi
|
|
||||||
|
|
||||||
# if this is an APM build then there will be a rc.APM script
|
|
||||||
# from an EXTERNAL_SCRIPTS build option
|
|
||||||
if [ -f /etc/init.d/rc.APM -a $HAVE_MICROSD == 1 -a ! -f /fs/microsd/APM/nostart ]
|
|
||||||
then
|
|
||||||
echo Running rc.APM
|
|
||||||
# if APM startup is successful then nsh will exit
|
|
||||||
sh /etc/init.d/rc.APM
|
|
||||||
else
|
|
||||||
nshterm /dev/ttyACM0 &
|
|
||||||
fi
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRBRAIN 5.1 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrbrain-v51
|
|
||||||
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRBRAIN 5.2E APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrbrain-v52E
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRBRAIN 5.2 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrbrain-v52
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRBRAIN 5.4 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrbrain-v54
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRCORE 1.0 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrcore-v10
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRUBRAIN 5.1 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrubrain-v51
|
|
||||||
MODULES += drivers/pwm_input
|
|
||||||
|
|
|
@ -1,8 +0,0 @@
|
||||||
#
|
|
||||||
# Makefile for the VRUBRAIN 5.2 APM configuration
|
|
||||||
#
|
|
||||||
include $(SKETCHBOOK)/mk/VRBRAIN/vrbrain_common.mk
|
|
||||||
|
|
||||||
MODULES += drivers/boards/vrubrain-v52
|
|
||||||
|
|
||||||
|
|
|
@ -1,74 +0,0 @@
|
||||||
#
|
|
||||||
# common makefile elements for all PX4 boards
|
|
||||||
#
|
|
||||||
|
|
||||||
#
|
|
||||||
# Use the configuration's ROMFS.
|
|
||||||
#
|
|
||||||
ROMFS_ROOT = $(SKETCHBOOK)/mk/VRBRAIN/ROMFS
|
|
||||||
MODULES += $(APM_MODULE_DIR)
|
|
||||||
|
|
||||||
#
|
|
||||||
# Board support modules
|
|
||||||
#
|
|
||||||
MODULES += drivers/device
|
|
||||||
MODULES += drivers/stm32
|
|
||||||
MODULES += drivers/stm32/adc
|
|
||||||
MODULES += drivers/stm32/tone_alarm
|
|
||||||
MODULES += drivers/led
|
|
||||||
MODULES += drivers/px4fmu
|
|
||||||
#MODULES += drivers/gps
|
|
||||||
#MODULES += drivers/hil
|
|
||||||
#MODULES += drivers/hott_telemetry
|
|
||||||
#MODULES += drivers/blinkm
|
|
||||||
#MODULES += modules/sensors
|
|
||||||
|
|
||||||
#
|
|
||||||
# System commands
|
|
||||||
#
|
|
||||||
MODULES += systemcmds/bl_update
|
|
||||||
MODULES += systemcmds/mixer
|
|
||||||
MODULES += systemcmds/perf
|
|
||||||
MODULES += systemcmds/reboot
|
|
||||||
MODULES += systemcmds/top
|
|
||||||
#MODULES += systemcmds/tests
|
|
||||||
MODULES += systemcmds/nshterm
|
|
||||||
MODULES += systemcmds/mtd
|
|
||||||
MODULES += systemcmds/ver
|
|
||||||
|
|
||||||
ifneq ($(wildcard $(PX4_ROOT)/src/systemcmds/usb_connected),)
|
|
||||||
MODULES += systemcmds/usb_connected
|
|
||||||
endif
|
|
||||||
|
|
||||||
#
|
|
||||||
# Library modules
|
|
||||||
#
|
|
||||||
MODULES += modules/systemlib
|
|
||||||
MODULES += modules/systemlib/mixer
|
|
||||||
MODULES += modules/uORB
|
|
||||||
|
|
||||||
# Note: auth disabled to keep us under 1MB flash because of STM32 bug
|
|
||||||
#ifneq ($(wildcard $(PX4_ROOT)/src/systemcmds/auth),)
|
|
||||||
#MODULES += systemcmds/auth
|
|
||||||
#endif
|
|
||||||
#ifneq ($(wildcard $(PX4_ROOT)/src/modules/libtomfastmath),)
|
|
||||||
#MODULES += modules/libtomfastmath
|
|
||||||
#MODULES += modules/libtomcrypt
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#
|
|
||||||
# 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 )
|
|
27
mk/make.inc
27
mk/make.inc
|
@ -1,27 +0,0 @@
|
||||||
# libraries linked into every program
|
|
||||||
LIBRARIES += AP_Module
|
|
||||||
LIBRARIES += AP_Button
|
|
||||||
LIBRARIES += AP_ICEngine
|
|
||||||
LIBRARIES += AP_FlashStorage
|
|
||||||
LIBRARIES += SRV_Channel
|
|
||||||
LIBRARIES += AP_UAVCAN
|
|
||||||
LIBRARIES += AP_ADC
|
|
||||||
LIBRARIES += AP_Airspeed
|
|
||||||
LIBRARIES += AP_Relay
|
|
||||||
LIBRARIES += AP_ServoRelayEvents
|
|
||||||
LIBRARIES += AP_Volz_Protocol
|
|
||||||
LIBRARIES += AP_SBusOut
|
|
||||||
LIBRARIES += AP_TempCalibration
|
|
||||||
LIBRARIES += AP_Radio
|
|
||||||
LIBRARIES += AP_Param_Helper
|
|
||||||
LIBRARIES += AP_VisualOdom
|
|
||||||
LIBRARIES += AP_RSSI
|
|
||||||
LIBRARIES += AP_Proximity
|
|
||||||
LIBRARIES += AP_Gripper
|
|
||||||
LIBRARIES += AP_RTC
|
|
||||||
LIBRARIES += AP_ROMFS
|
|
||||||
LIBRARIES += AC_Sprayer
|
|
||||||
LIBRARIES += AC_Avoidance
|
|
||||||
LIBRARIES += AP_LandingGear
|
|
||||||
LIBRARIES += AC_AutoTune
|
|
||||||
LIBRARIES += AP_RobotisServo
|
|
Loading…
Reference in New Issue