Add CMake file for raspberry pi without shield

This commit is contained in:
zhangfan 2017-02-24 18:38:43 +08:00 committed by Beat Küng
parent c89351c453
commit 8a691d9bfb
3 changed files with 334 additions and 0 deletions

View File

@ -0,0 +1,116 @@
# 使px4firmware
include(posix/px4_impl_posix)
# This definition allows to differentiate if this just the usual POSIX build
# or if it is for the RPi.
add_definitions(
-D__PX4_POSIX_RPI
-D__DF_LINUX # For DriverFramework
-D__DF_RPI # For raspberry pi
-D__DF_RPI_SINGLE # For raspberry pi alone
)
#
set(config_module_list
#
# Board support modules
#
drivers/device
modules/sensors
platforms/posix/drivers/df_mpu9250_wrapper
platforms/posix/drivers/df_ms5611_wrapper
platforms/posix/drivers/df_trone_wrapper
#
# System commands
#
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/esc_calib
systemcmds/reboot
systemcmds/topic_listener
systemcmds/perf
#
# Estimation modules
#
modules/attitude_estimator_q
modules/position_estimator_inav
modules/local_position_estimator
modules/ekf2
#
# Vehicle Control
#
modules/mc_att_control
modules/mc_pos_control
modules/fw_att_control
modules/fw_pos_control_l1
modules/vtol_att_control
#
# Library modules
#
modules/sdlog2
modules/logger
modules/commander
modules/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/dataman
modules/land_detector
modules/navigator
modules/mavlink
#
# PX4 drivers
#
drivers/gps
drivers/rpi_rc_in
drivers/rpi_pca9685_pwm_out
#
# Libraries
#
lib/controllib
lib/mathlib
lib/mathlib/math/filter
lib/geo
lib/ecl
lib/geo_lookup
lib/launchdetection
lib/external_lgpl
lib/conversion
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
lib/DriverFramework/framework
#
# POSIX
#
platforms/common
platforms/posix/px4_layer
platforms/posix/work_queue
)
#
# DriverFramework driver
#
set(config_df_driver_list
mpu9250
ms5611
trone
#isl29501
)
#
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-bcm2835-linx-gnueabihf-raspbian.cmake)
#set(CMAKE_PROGRAM_PATH
# "${RPI_TOOLCHAIN_DIR}/arm-bcm2835-linux-gnueabihf/bin"
# ${CMAKE_PROGRAM_PATH}
#)*/

View File

@ -0,0 +1,119 @@
# This file is shared between posix_rpi_native.cmake
# and posix_rpi_cross.cmake.
include(posix/px4_impl_posix)
# This definition allows to differentiate if this just the usual POSIX build
# or if it is for the RPi.
add_definitions(
-D__PX4_POSIX_RPI
-D__DF_LINUX # For DriverFramework
-D__DF_RPI # For raspberry pi
)
set(config_module_list
#
# Board support modules
#
drivers/device
modules/sensors
platforms/posix/drivers/df_mpu9250_wrapper
#platforms/posix/drivers/df_lsm9ds1_wrapper
platforms/posix/drivers/df_ms5611_wrapper
#platforms/posix/drivers/df_hmc5883_wrapper
platforms/posix/drivers/df_trone_wrapper
#platforms/posix/drivers/df_isl29501_wrapper
#
# System commands
#
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/esc_calib
systemcmds/reboot
systemcmds/topic_listener
systemcmds/perf
#
# Estimation modules
#
modules/attitude_estimator_q
modules/position_estimator_inav
modules/local_position_estimator
modules/ekf2
#
# Vehicle Control
#
modules/mc_att_control
modules/mc_pos_control
modules/fw_att_control
modules/fw_pos_control_l1
modules/vtol_att_control
#
# Library modules
#
modules/sdlog2
modules/logger
modules/commander
modules/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/dataman
modules/land_detector
modules/navigator
modules/mavlink
#
# PX4 drivers
#
drivers/gps
drivers/rpi_rc_in
drivers/rpi_pca9685_pwm_out
#drivers/navio_sysfs_rc_in
#drivers/navio_sysfs_pwm_out
#drivers/navio_gpio
#drivers/navio_rgbled
#
# Libraries
#
lib/controllib
lib/mathlib
lib/mathlib/math/filter
lib/geo
lib/ecl
lib/geo_lookup
lib/launchdetection
lib/external_lgpl
lib/conversion
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
lib/DriverFramework/framework
#
# POSIX
#
platforms/common
platforms/posix/px4_layer
platforms/posix/work_queue
)
#
# DriverFramework driver
#
set(config_df_driver_list
mpu9250
#lsm9ds1
ms5611
#hmc5883
trone
#isl29501
)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)

View File

@ -0,0 +1,99 @@
# defines:
#
# NM
# OBJCOPY
# LD
# CXX_COMPILER
# C_COMPILER
# CMAKE_SYSTEM_NAME
# CMAKE_SYSTEM_VERSION
# LINKER_FLAGS
# CMAKE_EXE_LINKER_FLAGS
# CMAKE_FIND_ROOT_PATH
# CMAKE_FIND_ROOT_PATH_MODE_PROGRAM
# CMAKE_FIND_ROOT_PATH_MODE_LIBRARY
# CMAKE_FIND_ROOT_PATH_MODE_INCLUDE
include(CMakeForceCompiler)
if ("$ENV{RPI_TOOLCHAIN_DIR}" STREQUAL "")
message(FATAL_ERROR "RPI_TOOLCHAIN_DIR not set")
else()
set(RPI_TOOLCHAIN_DIR $ENV{RPI_TOOLCHAIN_DIR})
endif()
if ("$ENV{CROSS_COMPILE_PREFIX}" STREQUAL "")
message(FATAL_ERROR "CROSS_COMPILE_PREFIX not set")
else()
set(CROSS_COMPILE_PREFIX $ENV{CROSS_COMPILE_PREFIX})
endif()
# this one is important
set(CMAKE_SYSTEM_NAME Generic)
#this one not so much
set(CMAKE_SYSTEM_VERSION 1)
# specify the cross compiler
find_program(C_COMPILER ${CROSS_COMPILE_PREFIX}-gcc
PATHS ${RPI_TOOLCHAIN_DIR}/bin
NO_DEFAULT_PATH
)
if(NOT C_COMPILER)
message(FATAL_ERROR "could not find ${CROSS_COMPILE_PREFIX}-gcc compiler")
endif()
cmake_force_c_compiler(${C_COMPILER} GNU)
find_program(CXX_COMPILER ${CROSS_COMPILE_PREFIX}-g++
PATHS ${RPI_TOOLCHAIN_DIR}/bin
NO_DEFAULT_PATH
)
if(NOT CXX_COMPILER)
message(FATAL_ERROR "could not find ${CROSS_COMPILE_PREFIX}-g++ compiler")
endif()
cmake_force_cxx_compiler(${CXX_COMPILER} GNU)
# compiler tools
foreach(tool objcopy nm ld)
string(TOUPPER ${tool} TOOL)
find_program(${TOOL} ${CROSS_COMPILE_PREFIX}-${tool}
PATHS ${RPI_TOOLCHAIN_DIR}/bin
NO_DEFAULT_PATH
)
if(NOT ${TOOL})
message(FATAL_ERROR "could not find ${CROSS_COMPILE_PREFIX}-${tool}")
endif()
endforeach()
# os tools
foreach(tool echo grep rm mkdir nm cp touch make unzip)
string(TOUPPER ${tool} TOOL)
find_program(${TOOL} ${tool})
if(NOT ${TOOL})
message(FATAL_ERROR "could not find ${TOOL}")
endif()
endforeach()
add_definitions(
-D __DF_RPI
)
set(LINKER_FLAGS "-Wl,-gc-sections")
set(CMAKE_EXE_LINKER_FLAGS ${LINKER_FLAGS})
set(CMAKE_C_FLAGS ${C_FLAGS})
set(CMAKE_CXX_LINKER_FLAGS ${C_FLAGS})
# where is the target environment
set(CMAKE_FIND_ROOT_PATH get_file_component(${C_COMPILER} PATH))
# search for programs in the build host directories
set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
# for libraries and headers in the target directories
set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)