mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Improvements to cmake.
This commit is contained in:
parent
5e92e1f982
commit
5489b84f8e
1
.gitignore
vendored
1
.gitignore
vendored
@ -6,3 +6,4 @@ serialsent.raw
|
||||
CMakeFiles
|
||||
CMakeCache.txt
|
||||
cmake_install.cmake
|
||||
build
|
||||
|
1
ArduCopter/.gitignore
vendored
Normal file
1
ArduCopter/.gitignore
vendored
Normal file
@ -0,0 +1 @@
|
||||
arducopter.cpp
|
@ -126,8 +126,6 @@ set(${FIRMWARE_NAME}_LIBS
|
||||
c
|
||||
m
|
||||
)
|
||||
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)
|
||||
|
||||
|
||||
#${CONSOLE_PORT}
|
||||
set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port
|
||||
|
1
ArduPlane/.gitignore
vendored
Normal file
1
ArduPlane/.gitignore
vendored
Normal file
@ -0,0 +1 @@
|
||||
ArduPlane.cpp
|
@ -126,8 +126,6 @@ set(${FIRMWARE_NAME}_LIBS
|
||||
c
|
||||
m
|
||||
)
|
||||
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)
|
||||
|
||||
|
||||
#${CONSOLE_PORT}
|
||||
set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port
|
||||
|
1
apo/.gitignore
vendored
Normal file
1
apo/.gitignore
vendored
Normal file
@ -0,0 +1 @@
|
||||
apo.cpp
|
@ -1,32 +1,52 @@
|
||||
#=============================================================================#
|
||||
# Author: Sebastian Rohde #
|
||||
# Date: 30.08.2011 #
|
||||
#=============================================================================#
|
||||
cmake_minimum_required(VERSION 2.6)
|
||||
|
||||
set(CMAKE_SOURCE_DIR "${CMAKE_SOURCE_DIR}/../")
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake)
|
||||
|
||||
#====================================================================#
|
||||
# Settings #
|
||||
#====================================================================#
|
||||
set(FIRMWARE_NAME apo)
|
||||
string(REGEX REPLACE ".*/" "" PROJECT_NAME ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
project(${PROJECT_NAME} C CXX)
|
||||
set(FIRMWARE_NAME ${PROJECT_NAME})
|
||||
|
||||
set(${FIRMWARE_NAME}_BOARD ${BOARD}) # Arduino Target board
|
||||
set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
|
||||
|
||||
set(${FIRMWARE_NAME}_SKETCHES
|
||||
apo.pde
|
||||
) # Firmware sketches
|
||||
find_package(Arduino 22 REQUIRED)
|
||||
|
||||
set(${FIRMWARE_NAME}_SRCS
|
||||
) # Firmware sources
|
||||
if (NOT DEFINED BOARD)
|
||||
message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
|
||||
set(BOARD "mega")
|
||||
endif()
|
||||
message(STATUS "Board configured as: ${BOARD}")
|
||||
|
||||
set(${FIRMWARE_NAME}_HDRS
|
||||
ControllerPlane.h
|
||||
ControllerQuad.h
|
||||
PlaneEasystar.h
|
||||
QuadArducopter.h
|
||||
QuadMikrokopter.h
|
||||
) # Firmware sources
|
||||
# need to configure based on host operating system
|
||||
set(${PROJECT_NAME}_PORT COM2)
|
||||
set(${PROJECT_NAME}_SERIAL putty -serial COM2 -sercfg 57600,8,n,1,X )
|
||||
|
||||
set(${FIRMWARE_NAME}_LIBS
|
||||
include_directories(
|
||||
${ARDUINO_LIBRARIES_PATH}/Wire
|
||||
${CMAKE_SOURCE_DIR}/libraries/APO
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
${CMAKE_SOURCE_DIR}/libraries/ModeFilter
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Compass
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_RangeFinder
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_GPS
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_IMU
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_ADC
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_DCM
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_RC
|
||||
${CMAKE_SOURCE_DIR}/libraries/GCS_MAVLink
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_BMP085
|
||||
)
|
||||
|
||||
add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
|
||||
file(WRITE ${PROJECT_NAME}.cpp "// Do not edit")
|
||||
set(${PROJECT_NAME}_BOARD ${BOARD})
|
||||
file(GLOB ${PROJECT_NAME}_SKETCHES *.pde)
|
||||
file(GLOB ${PROJECT_NAME}_SRCS *.cpp)
|
||||
file(GLOB ${PROJECT_NAME}_HDRS *.h)
|
||||
set(${PROJECT_NAME}_LIBS
|
||||
c
|
||||
m
|
||||
APO
|
||||
FastSerial
|
||||
@ -43,32 +63,9 @@ set(${FIRMWARE_NAME}_LIBS
|
||||
ModeFilter
|
||||
)
|
||||
|
||||
|
||||
#${CONSOLE_PORT}
|
||||
set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port
|
||||
set(${FIRMWARE_NAME}_SERIAL putty -serial COM2 -sercfg 57600,8,n,1,X ) # Serial terminal cmd
|
||||
|
||||
include_directories(
|
||||
${CMAKE_SOURCE_DIR}/libraries/APO
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
${CMAKE_SOURCE_DIR}/libraries/ModeFilter
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Compass
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_RangeFinder
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_GPS
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_IMU
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_ADC
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_DCM
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_RC
|
||||
${CMAKE_SOURCE_DIR}/libraries/GCS_MAVLink
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_BMP085
|
||||
)
|
||||
#====================================================================#
|
||||
# Target generation #
|
||||
#====================================================================#
|
||||
generate_arduino_firmware(${FIRMWARE_NAME})
|
||||
generate_arduino_firmware(${PROJECT_NAME})
|
||||
|
||||
install(FILES
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${FIRMWARE_NAME}.hex
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.hex
|
||||
DESTINATION bin
|
||||
)
|
||||
|
@ -1,4 +1,5 @@
|
||||
// Libraries
|
||||
#include <WProgram.h>
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_RC.h>
|
||||
|
7
cmake/modules/ApmMakeLib.cmake
Normal file
7
cmake/modules/ApmMakeLib.cmake
Normal file
@ -0,0 +1,7 @@
|
||||
string(REGEX REPLACE ".*/" "" LIB_NAME ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
#message(STATUS "building lib: ${LIB_NAME}")
|
||||
file(GLOB ${LIB_NAME}_SRCS *.cpp)
|
||||
file(GLOB ${LIB_NAME}_HDRS *.h)
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
set_target_properties(${LIB_NAME} PROPERTIES LINKER_LANGUAGE CXX)
|
74
cmake/modules/ApmMakeSketch.cmake
Normal file
74
cmake/modules/ApmMakeSketch.cmake
Normal file
@ -0,0 +1,74 @@
|
||||
cmake_minimum_required(VERSION 2.6)
|
||||
|
||||
set(CMAKE_SOURCE_DIR "${CMAKE_SOURCE_DIR}/../")
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake)
|
||||
|
||||
string(REGEX REPLACE ".*/" "" PROJECT_NAME ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
project(${PROJECT_NAME} C CXX)
|
||||
|
||||
set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
|
||||
|
||||
find_package(Arduino 22 REQUIRED)
|
||||
|
||||
if (NOT DEFINED BOARD)
|
||||
message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
|
||||
set(BOARD "mega")
|
||||
endif()
|
||||
message(STATUS "Board configured as: ${BOARD}")
|
||||
|
||||
# need to configure based on host operating system
|
||||
set(${PROJECT_NAME}_PORT COM2)
|
||||
set(${PROJECT_NAME}_SERIAL putty -serial COM2 -sercfg 57600,8,n,1,X )
|
||||
|
||||
include_directories(
|
||||
${ARDUINO_LIBRARIES_PATH}/Wire
|
||||
${CMAKE_SOURCE_DIR}/libraries/APO
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
${CMAKE_SOURCE_DIR}/libraries/ModeFilter
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Compass
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_RangeFinder
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_GPS
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_IMU
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_ADC
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_DCM
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_RC
|
||||
${CMAKE_SOURCE_DIR}/libraries/GCS_MAVLink
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_BMP085
|
||||
)
|
||||
|
||||
add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
|
||||
|
||||
set(${PROJECT_NAME}_BOARD ${BOARD})
|
||||
file(GLOB ${PROJECT_NAME}_SKETCHES *.pde)
|
||||
file(GLOB ${PROJECT_NAME}_SRCS *.cpp)
|
||||
file(GLOB ${PROJECT_NAME}_HDRS *.h)
|
||||
set(${PROJECT_NAME}_LIBS
|
||||
c
|
||||
m
|
||||
APO
|
||||
FastSerial
|
||||
AP_Common
|
||||
GCS_MAVLink
|
||||
AP_GPS
|
||||
APM_RC
|
||||
AP_DCM
|
||||
AP_ADC
|
||||
AP_Compass
|
||||
AP_IMU
|
||||
AP_RangeFinder
|
||||
APM_BMP085
|
||||
ModeFilter
|
||||
)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
generate_arduino_firmware(${PROJECT_NAME})
|
||||
|
||||
install(FILES
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.hex
|
||||
DESTINATION bin
|
||||
)
|
@ -1,22 +1 @@
|
||||
set(LIB_NAME APM_BMP085)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
APM_BMP085.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
APM_BMP085.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME APM_PI)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
APM_PI.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
APM_PI.h
|
||||
#AP_OpticalFlow_ADNS3080.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/APM_PerfMon/CMakeLists.txt
Normal file
1
libraries/APM_PerfMon/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,22 +1 @@
|
||||
set(LIB_NAME APM_RC)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
APM_RC.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
APM_RC.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,39 +1 @@
|
||||
set(LIB_NAME APO)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_Autopilot.cpp
|
||||
AP_CommLink.cpp
|
||||
AP_Controller.cpp
|
||||
AP_Guide.cpp
|
||||
AP_HardwareAbstractionLayer.cpp
|
||||
AP_MavlinkCommand.cpp
|
||||
AP_Navigator.cpp
|
||||
AP_RcChannel.cpp
|
||||
APO.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_Autopilot.h
|
||||
AP_CommLink.h
|
||||
AP_Controller.h
|
||||
AP_Guide.h
|
||||
AP_HardwareAbstractionLayer.h
|
||||
AP_MavlinkCommand.h
|
||||
AP_Navigator.h
|
||||
AP_RcChannel.h
|
||||
AP_Var_keys.h
|
||||
APO.h
|
||||
constants.h
|
||||
template.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
# ${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
${CMAKE_SOURCE_DIR}/libraries/ModeFilter
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,26 +1 @@
|
||||
set(LIB_NAME AP_ADC)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_ADC_HIL.cpp
|
||||
AP_ADC_ADS7844.cpp
|
||||
AP_ADC.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_ADC_HIL.h
|
||||
AP_ADC_ADS7844.h
|
||||
AP_ADC.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,33 +1 @@
|
||||
set(LIB_NAME AP_Common)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_Common.cpp
|
||||
AP_Loop.cpp
|
||||
AP_MetaClass.cpp
|
||||
AP_Var.cpp
|
||||
AP_Var_menufuncs.cpp
|
||||
c++.cpp
|
||||
menu.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_Common.h
|
||||
AP_Loop.h
|
||||
AP_MetaClass.h
|
||||
AP_Var.h
|
||||
AP_Test.h
|
||||
c++.h
|
||||
AP_Vector.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,27 +1 @@
|
||||
set(LIB_NAME AP_Compass)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_Compass_HIL.cpp
|
||||
AP_Compass_HMC5843.cpp
|
||||
Compass.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
Compass.h
|
||||
AP_Compass_HIL.h
|
||||
AP_Compass_HMC5843.h
|
||||
AP_Compass.h
|
||||
)
|
||||
|
||||
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${ARDUINO_LIBRARIES_PATH}/Wire
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,25 +1 @@
|
||||
set(LIB_NAME AP_DCM)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_DCM.cpp
|
||||
AP_DCM_HIL.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_DCM.h
|
||||
AP_DCM_HIL.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_DCM
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/AP_EEPROMB/CMakeLists.txt
Normal file
1
libraries/AP_EEPROMB/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,44 +1 @@
|
||||
set(LIB_NAME AP_GPS)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_GPS_406.cpp
|
||||
AP_GPS_Auto.cpp
|
||||
AP_GPS_HIL.cpp
|
||||
AP_GPS_IMU.cpp
|
||||
AP_GPS_MTK.cpp
|
||||
AP_GPS_MTK16.cpp
|
||||
AP_GPS_NMEA.cpp
|
||||
AP_GPS_SIRF.cpp
|
||||
AP_GPS_UBLOX.cpp
|
||||
GPS.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_GPS_406.h
|
||||
AP_GPS_Auto.h
|
||||
AP_GPS_HIL.h
|
||||
AP_GPS_IMU.h
|
||||
AP_GPS_MTK.h
|
||||
AP_GPS_MTK_Common.h
|
||||
AP_GPS_MTK16.h
|
||||
AP_GPS_NMEA.h
|
||||
AP_GPS_None.h
|
||||
AP_GPS_Shim.h
|
||||
AP_GPS_SIRF.h
|
||||
AP_GPS_UBLOX.h
|
||||
AP_GPS.h
|
||||
GPS.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,25 +1 @@
|
||||
set(LIB_NAME AP_IMU)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_IMU_Oilpan.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_IMU.h
|
||||
AP_IMU_Shim.h
|
||||
AP_IMU_Oilpan.h
|
||||
IMU.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME AP_Math)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_Math.h
|
||||
matrix3.h
|
||||
vector2.h
|
||||
vector3.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
# ${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/AP_Navigation/CMakeLists.txt
Normal file
1
libraries/AP_Navigation/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME AP_OpticalFlow)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_OpticalFlow.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_OpticalFlow.h
|
||||
#AP_OpticalFlow_ADNS3080.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME AP_PID)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_PID.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_PID.h
|
||||
#AP_OpticalFlow_ADNS3080.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/AP_RC/CMakeLists.txt
Normal file
1
libraries/AP_RC/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/AP_RC_Channel/CMakeLists.txt
Normal file
1
libraries/AP_RC_Channel/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,27 +1 @@
|
||||
set(LIB_NAME AP_RangeFinder)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
AP_RangeFinder_MaxsonarXL.cpp
|
||||
AP_RangeFinder_SharpGP2Y.cpp
|
||||
RangeFinder.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
AP_RangeFinder.h
|
||||
AP_RangeFinder_MaxsonarXL.h
|
||||
AP_RangeFinder_SharpGP2Y.h
|
||||
RangeFinder.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,24 +1,34 @@
|
||||
add_subdirectory(DataFlash)
|
||||
add_subdirectory(AP_Math)
|
||||
add_subdirectory(PID)
|
||||
add_subdirectory(AP_Common)
|
||||
add_subdirectory(RC_Channel)
|
||||
add_subdirectory(AP_OpticalFlow)
|
||||
add_subdirectory(ModeFilter)
|
||||
add_subdirectory(memcheck)
|
||||
add_subdirectory(APM_PI)
|
||||
add_subdirectory(AP_GPS)
|
||||
add_subdirectory(AP_DCM)
|
||||
add_subdirectory(AP_Compass)
|
||||
add_subdirectory(AP_ADC)
|
||||
add_subdirectory(AP_Common)
|
||||
add_subdirectory(AP_Compass)
|
||||
add_subdirectory(AP_DCM)
|
||||
add_subdirectory(AP_EEPROMB)
|
||||
add_subdirectory(AP_GPS)
|
||||
add_subdirectory(AP_IMU)
|
||||
add_subdirectory(AP_RangeFinder)
|
||||
|
||||
add_subdirectory(APM_RC)
|
||||
add_subdirectory(AP_Math)
|
||||
add_subdirectory(APM_BMP085)
|
||||
|
||||
#add_subdirectory(APO)
|
||||
add_subdirectory(APM_PerfMon)
|
||||
add_subdirectory(APM_PI)
|
||||
add_subdirectory(APM_RC)
|
||||
add_subdirectory(AP_Navigation)
|
||||
add_subdirectory(APO)
|
||||
add_subdirectory(AP_OpticalFlow)
|
||||
add_subdirectory(AP_PID)
|
||||
add_subdirectory(AP_RangeFinder)
|
||||
add_subdirectory(AP_RC)
|
||||
add_subdirectory(AP_RC_Channel)
|
||||
add_subdirectory(DataFlash)
|
||||
add_subdirectory(FastSerial)
|
||||
add_subdirectory(GCS_MAVLink)
|
||||
add_subdirectory(GCS_SIMPLE)
|
||||
add_subdirectory(GPS_IMU)
|
||||
add_subdirectory(GPS_MTK)
|
||||
add_subdirectory(GPS_NMEA)
|
||||
add_subdirectory(GPS_UBLOX)
|
||||
add_subdirectory(memcheck)
|
||||
add_subdirectory(ModeFilter)
|
||||
add_subdirectory(PID)
|
||||
add_subdirectory(RC_Channel)
|
||||
add_subdirectory(Waypoints)
|
||||
add_subdirectory(Trig_LUT)
|
||||
|
||||
#add_subdirectory(playgroundlib)
|
||||
|
@ -1,21 +1 @@
|
||||
set(LIB_NAME DataFlash)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
DataFlash.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
DataFlash.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
# ${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,28 +1 @@
|
||||
set(LIB_NAME FastSerial)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
BetterStream.cpp
|
||||
FastSerial.cpp
|
||||
vprintf.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
BetterStream.h
|
||||
FastSerial.h
|
||||
ftoa_engine.h
|
||||
ntz.h
|
||||
xtoa_fast.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,19 +1 @@
|
||||
set(LIB_NAME GCS_MAVLink)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
GCS_MAVLink.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
GCS_MAVLink.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
#${CMAKE_SOURCE_DIR}/libraries/
|
||||
${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/GCS_SIMPLE/CMakeLists.txt
Normal file
1
libraries/GCS_SIMPLE/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/GPS_IMU/CMakeLists.txt
Normal file
1
libraries/GPS_IMU/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/GPS_MTK/CMakeLists.txt
Normal file
1
libraries/GPS_MTK/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/GPS_NMEA/CMakeLists.txt
Normal file
1
libraries/GPS_NMEA/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/GPS_UBLOX/CMakeLists.txt
Normal file
1
libraries/GPS_UBLOX/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME ModeFilter)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
ModeFilter.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
ModeFilter.h
|
||||
#AP_OpticalFlow_ADNS3080.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,21 +1 @@
|
||||
set(LIB_NAME PID)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
PID.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
PID.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME RC_Channel)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
RC_Channel.cpp
|
||||
RC_Channel_aux.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
RC_Channel.h
|
||||
RC_Channel_aux.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
${CMAKE_SOURCE_DIR}/libraries/APM_RC
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
1
libraries/Trig_LUT/CMakeLists.txt
Normal file
1
libraries/Trig_LUT/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
1
libraries/Waypoints/CMakeLists.txt
Normal file
1
libraries/Waypoints/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
include(ApmMakeLib)
|
@ -1,24 +1 @@
|
||||
set(LIB_NAME memcheck)
|
||||
|
||||
set(${LIB_NAME}_SRCS
|
||||
memcheck.cpp
|
||||
#AP_OpticalFlow_ADNS3080.cpp
|
||||
) # Firmware sources
|
||||
|
||||
set(${LIB_NAME}_HDRS
|
||||
memcheck.h
|
||||
#AP_OpticalFlow_ADNS3080.h
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
-
|
||||
#${CMAKE_SOURCE_DIR}/libraries/AP_Math
|
||||
${CMAKE_SOURCE_DIR}/libraries/AP_Common
|
||||
#${CMAKE_SOURCE_DIR}/libraries/FastSerial
|
||||
#
|
||||
)
|
||||
|
||||
set(${LIB_NAME}_BOARD ${BOARD})
|
||||
|
||||
generate_arduino_library(${LIB_NAME})
|
||||
include(ApmMakeLib)
|
||||
|
Loading…
Reference in New Issue
Block a user