Browse Source

Cleanup of module building.

sbg
James Goppert 10 years ago
parent
commit
bf18c84652
  1. 28
      CMakeLists.txt
  2. 21
      Makefile
  3. 32
      cmake/common/px4_base.cmake
  4. 23
      cmake/configs/config_nuttx_px4fmu-v2_simple.cmake
  5. 7
      cmake/configs/config_posix_sitl_simple.cmake
  6. 1
      cmake/configs/config_qurt_hil_simple.cmake
  7. 2
      cmake/nuttx/px4_impl_nuttx.cmake
  8. 2
      cmake/posix/px4_impl_posix.cmake
  9. 31
      cmake/px4_git_hash.cmake
  10. 2
      cmake/qurt/px4_impl_qurt.cmake
  11. 0
      cmake/scripts/bin_to_object.py
  12. 2
      cmake/scripts/convert_modules_to_cmake.py
  13. 0
      cmake/scripts/test_compare.py
  14. 0
      cmake/templates/build_git_version.h.in
  15. 0
      cmake/templates/cmake_lists.jinja
  16. 0
      cmake/toolchains/Toolchain-arm-none-eabi.cmake
  17. 2
      cmake/toolchains/Toolchain-hexagon.cmake
  18. 0
      cmake/toolchains/Toolchain-native.cmake
  19. 0
      cmake/toolchains/Toolchain-posix-clang-native.cmake
  20. 4
      nuttx-configs/sim/nsh/defconfig
  21. 9
      src/CMakeLists.txt
  22. 55
      src/drivers/CMakeLists.txt
  23. 14
      src/drivers/device/CMakeLists.txt
  24. 16
      src/examples/CMakeLists.txt
  25. 33
      src/firmware/nuttx/CMakeLists.txt
  26. 17
      src/firmware/posix/CMakeLists.txt
  27. 15
      src/lib/CMakeLists.txt
  28. 4
      src/lib/mathlib/math/filter/LowPassFilter2p.cpp
  29. 40
      src/modules/CMakeLists.txt
  30. 2
      src/modules/systemlib/mcu_version.c
  31. 4
      src/modules/systemlib/printload.c
  32. 26
      src/platforms/CMakeLists.txt
  33. 5
      src/platforms/common/CMakeLists.txt
  34. 4
      src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c
  35. 15
      src/platforms/px4_subscriber.h
  36. 26
      src/systemcmds/CMakeLists.txt

28
CMakeLists.txt

@ -57,7 +57,7 @@ @@ -57,7 +57,7 @@
# ---------------------------------------------------------------------------
#
# * Use px4_parse_function_args to parse functions and check for required
# arguments.
# arguments. Unless there is only one argument in the function and it is clear.
#
# * Never use macros. They allow overwriting global variables and this
# makes variable declarations hard to locate.
@ -112,22 +112,21 @@ set(package-contact "px4users@googlegroups.com") @@ -112,22 +112,21 @@ set(package-contact "px4users@googlegroups.com")
# set module path
message("OS = ${OS}")
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/${OS})
# prefer board implementation module over os implmementation module
set(board_impl_module px4_impl_${OS}_${BOARD})
set(os_impl_module px4_impl_${OS})
if (EXISTS ${board_impl_module})
set(impl_module ${board_impl_module})
set(config_module "configs/config_${OS}_${BOARD}_${LABEL}")
set(config_path "${CMAKE_SOURCE_DIR}/cmake/${config_module}.cmake")
if (EXISTS ${config_path})
include(${config_module})
else()
set(impl_module ${os_impl_module})
message(FATAL_ERROR "build config not found: ${config_path}")
endif()
include(${impl_module})
# require px4 module interface
set(px4_required_functions
px4_os_prebuild_targets
px4_os_add_flags
px4_set_config_modules
)
foreach(cmd ${px4_required_functions})
if(NOT COMMAND ${cmd})
@ -232,15 +231,20 @@ px4_generate_messages(TARGET msg_gen @@ -232,15 +231,20 @@ px4_generate_messages(TARGET msg_gen
#=============================================================================
# subdirectories
#
add_subdirectory(src)
px4_set_config_modules(config_modules)
set(module_libraries)
foreach(module ${config_modules})
add_subdirectory(src/${module})
px4_mangle_name(${module} mangled_name)
list(APPEND module_libraries ${mangled_name})
message(STATUS "adding module: ${module}")
endforeach()
# set the overall objective of the build
add_custom_target(ALL firmware_${OS})
add_subdirectory(src/firmware/${OS})
#=============================================================================
# generate git version
#
include(px4_git_hash)
px4_create_git_hash_header(HEADER ${CMAKE_BINARY_DIR}/build_git_version.h)
#=============================================================================

21
Makefile

@ -1,30 +1,33 @@ @@ -1,30 +1,33 @@
d=$(PWD)
px4fmu-v2_simple:
nuttx_px4fmu-v2_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-arm-none-eabi.cmake \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-arm-none-eabi.cmake \
-DOS=nuttx -DBOARD=px4fmu-v2 -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
px4fmu-v2_simple: nuttx_px4fmu-v2_simple
nuttx-sim-simple:
nuttx_sim_simple:
echo "nuttx-sim-simple is a work in progress"
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-native.cmake \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-native.cmake \
-DOS=nuttx -DBOARD=sim -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
px4fmu-v2_simple-upload: px4fmu-v2_simple
nuttx_px4fmu-v2_simple_upload: nuttx_px4fmu-v2_simple
cd $d/build_$< && make upload
px4fmu-v2_simple_upload: px4fmu-v2_simple_upload
posix-sitl_simple:
posix_sitl_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-posix-clang-native.cmake \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-posix-clang-native.cmake \
-DOS=posix -DBOARD=sitl -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
qurt-hil_simple:
qurt_hil_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DQURT_ENABLE_STUBS=1 -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-hexagon.cmake \
cmake .. -DQURT_ENABLE_STUBS=1 -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-hexagon.cmake \
-DOS=qurt -DBOARD=hil -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP

32
cmake/px4_base.cmake → cmake/common/px4_base.cmake

@ -640,4 +640,36 @@ function(px4_mangle_name dirname newname) @@ -640,4 +640,36 @@ function(px4_mangle_name dirname newname)
set(${newname} ${tmp} PARENT_SCOPE)
endfunction()
#=============================================================================
#
# px4_create_git_hash_header
#
# Create a header file containing the git hash of the current tree
#
# Usage:
# px4_create_git_hash_header(HEADER ${CMAKE_BUILD_DIR}/git_hash.h)
#
# Input:
# HEADER : path of the header file to generate
#
# Example:
# px4_create_git_hash_header(HEADER ${CMAKE_BUILD_DIR}/git_hash.h)
#
function(px4_create_git_hash_header)
px4_parse_function_args(
NAME px4_create_git_hash_header
ONE_VALUE HEADER
REQUIRED HEADER
ARGN ${ARGN})
execute_process(
COMMAND git log -n 1 --pretty=format:"%H"
OUTPUT_VARIABLE git_desc
OUTPUT_STRIP_TRAILING_WHITESPACE
)
message(STATUS "GIT_DESC = ${git_desc}")
set(git_desc_short)
string(SUBSTRING ${git_desc} 1 16 git_desc_short)
configure_file(${CMAKE_SOURCE_DIR}/cmake/templates/build_git_version.h.in ${HEADER} @ONLY)
endfunction()
# vim: set noet fenc=utf-8 ff=unix nowrap:

23
cmake/configs/config_nuttx_px4fmu-v2_simple.cmake

@ -0,0 +1,23 @@ @@ -0,0 +1,23 @@
include(nuttx/px4_impl_nuttx)
function(px4_set_config_modules out_module_list)
set(config_module_list
platforms/nuttx
platforms/nuttx/px4_layer
platforms/common
drivers/led
drivers/device
modules/systemlib
modules/uORB
examples/px4_simple_app
drivers/boards/px4fmu-v2
drivers/stm32
lib/mathlib/math/filter
lib/conversion
)
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
endfunction()

7
cmake/posix/configs/config-posix-sitl.cmake → cmake/configs/config_posix_sitl_simple.cmake

@ -1,4 +1,7 @@ @@ -1,4 +1,7 @@
include(posix/px4_impl_posix)
function(px4_set_config_modules out_module_list)
set(config_module_list
drivers/led
drivers/device
@ -39,7 +42,6 @@ function(px4_set_config_modules out_module_list) @@ -39,7 +42,6 @@ function(px4_set_config_modules out_module_list)
modules/fw_pos_control_l1
modules/dataman
modules/sdlog2
modules/simulator
modules/commander
modules/controllib
lib/mathlib
@ -51,7 +53,8 @@ function(px4_set_config_modules out_module_list) @@ -51,7 +53,8 @@ function(px4_set_config_modules out_module_list)
lib/geo_lookup
lib/launchdetection
)
message(STATUS "modules: ${config_module_list}")
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
endfunction()

1
cmake/qurt/configs/config-qurt-hil.cmake → cmake/configs/config_qurt_hil_simple.cmake

@ -80,7 +80,6 @@ function(px4_set_config_modules out_module_list) @@ -80,7 +80,6 @@ function(px4_set_config_modules out_module_list)
#
modules/muorb/adsp
)
message(STATUS "modules: ${config_module_list}")
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
endfunction()

2
cmake/nuttx/px4_impl_nuttx.cmake

@ -49,7 +49,7 @@ @@ -49,7 +49,7 @@
# * px4_os_prebuild_targets
#
include(px4_base)
include(common/px4_base)
#=============================================================================
#

2
cmake/posix/px4_impl_posix.cmake

@ -48,7 +48,7 @@ @@ -48,7 +48,7 @@
# * px4_os_prebuild_targets
#
include(px4_base)
include(common/px4_base)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/posix)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/posix/configs)

31
cmake/px4_git_hash.cmake

@ -1,31 +0,0 @@ @@ -1,31 +0,0 @@
#=============================================================================
#
# px4_create_git_hash_header
#
# Create a header file containing the git hash of the current tree
#
# Usage:
# px4_create_git_hash_header(HEADER ${CMAKE_BUILD_DIR}/git_hash.h)
#
# Input:
# HEADER : path of the header file to generate
#
# Example:
# px4_create_git_hash_header(HEADER ${CMAKE_BUILD_DIR}/git_hash.h)
#
function(px4_create_git_hash_header)
px4_parse_function_args(
NAME px4_create_git_hash_header
ONE_VALUE HEADER
REQUIRED HEADER
ARGN ${ARGN})
execute_process(
COMMAND git log -n 1 --pretty=format:"%H"
OUTPUT_VARIABLE git_desc
OUTPUT_STRIP_TRAILING_WHITESPACE
)
message(STATUS "GIT_DESC = ${git_desc}")
set(git_desc_short)
string(SUBSTRING ${git_desc} 1 16 git_desc_short)
configure_file(${CMAKE_SOURCE_DIR}/cmake/build_git_version.h.in ${HEADER} @ONLY)
endfunction()

2
cmake/qurt/px4_impl_qurt.cmake

@ -49,7 +49,7 @@ @@ -49,7 +49,7 @@
# * px4_os_prebuild_targets
#
include(px4_base)
include(common/px4_base)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/qurt)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/qurt/configs)
include(qurt_funcs)

0
cmake/bin_to_object.py → cmake/scripts/bin_to_object.py

2
cmake/convert_modules_to_cmake.py → cmake/scripts/convert_modules_to_cmake.py

@ -19,7 +19,7 @@ parser.add_argument('--backup', help='create backup of existing files if overwri @@ -19,7 +19,7 @@ parser.add_argument('--backup', help='create backup of existing files if overwri
parser.set_defaults(overwrite=False, backup=False)
args = parser.parse_args()
cmake_template = jinja2.Template(open('cmake/cmake_lists.jinja', 'r').read())
cmake_template = jinja2.Template(open('cmake/scripts/cmake_lists.jinja', 'r').read())
module_files = []
for root, dirnames, filenames in os.walk(args.path):

0
cmake/test_compare.py → cmake/scripts/test_compare.py

0
cmake/build_git_version.h.in → cmake/templates/build_git_version.h.in

0
cmake/cmake_lists.jinja → cmake/templates/cmake_lists.jinja

0
cmake/Toolchain-arm-none-eabi.cmake → cmake/toolchains/Toolchain-arm-none-eabi.cmake

2
cmake/Toolchain-hexagon.cmake → cmake/toolchains/Toolchain-hexagon.cmake

@ -32,7 +32,7 @@ @@ -32,7 +32,7 @@
include(CMakeForceCompiler)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
include(px4_base)
include(common/px4_base)
if(NOT HEXAGON_TOOLS_ROOT)
set(HEXAGON_TOOLS_ROOT /opt/6.4.05)

0
cmake/Toolchain-native.cmake → cmake/toolchains/Toolchain-native.cmake

0
cmake/Toolchain-posix-clang-native.cmake → cmake/toolchains/Toolchain-posix-clang-native.cmake

4
nuttx-configs/sim/nsh/defconfig

@ -118,7 +118,7 @@ CONFIG_NSH_MMCSDMINOR=0 @@ -118,7 +118,7 @@ CONFIG_NSH_MMCSDMINOR=0
#
CONFIG_MSEC_PER_TICK=10
CONFIG_RR_INTERVAL=0
# CONFIG_SCHED_INSTRUMENTATION is not set
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_TASK_NAME_SIZE=32
CONFIG_SCHED_HAVE_PARENT=y
# CONFIG_SCHED_CHILD_STATUS is not set
@ -182,7 +182,7 @@ CONFIG_PTHREAD_STACK_DEFAULT=8192 @@ -182,7 +182,7 @@ CONFIG_PTHREAD_STACK_DEFAULT=8192
#
# Device Drivers
#
CONFIG_DISABLE_POLL=y
#CONFIG_DISABLE_POLL is not set
CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set

9
src/CMakeLists.txt

@ -1,9 +0,0 @@ @@ -1,9 +0,0 @@
add_subdirectory(./lib)
add_subdirectory(./drivers)
add_subdirectory(./platforms)
add_subdirectory(./systemcmds)
add_subdirectory(./examples)
add_subdirectory(./modules)
add_subdirectory(./firmware/${OS})
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

55
src/drivers/CMakeLists.txt

@ -1,55 +0,0 @@ @@ -1,55 +0,0 @@
set(directories
./roboclaw
./device
./px4io
./boards/px4fmu-v2
./boards/px4-stm32f4discovery
./boards/px4io-v2
./boards/px4io-v1
./boards/px4fmu-v1
./boards/aerocore
./boards/sitl
./mpu6000
./gimbal
./camera_trigger
./pwm_input
./pwm_out_sim
./pca9685
./mkblctrl
./sf0x
./hott/hott_telemetry
./hott/hott_sensors
./hott
./ms5611
./led
./irlock
./bma180
./l3gd20
./blinkm
./md25
./lsm303d
./pca8574
./mb12xx
./trone
./airspeed
./rgbled
./frsky_telemetry
./meas_airspeed
./px4flow
./mpu9250
./gps
./ets_airspeed
./ll40ls
./ardrone_interface
./hmc5883
./px4fmu
./stm32/tone_alarm
./stm32/adc
./stm32
./oreoled
./batt_smbus
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()

14
src/drivers/device/CMakeLists.txt

@ -35,13 +35,17 @@ set(SRCS) @@ -35,13 +35,17 @@ set(SRCS)
if(${OS} STREQUAL "nuttx")
list(APPEND SRCS
device_nuttx.cpp
cdev.cpp
i2c_nuttx.cpp
pio.cpp
spi.cpp
ringbuffer.cpp
)
if (NOT ${BOARD} STREQUAL "sim")
list(APPEND SRCS
device_nuttx.cpp
cdev.cpp
i2c_nuttx.cpp
pio.cpp
spi.cpp
)
endif()
else()
list(APPEND SRCS
device_posix.cpp

16
src/examples/CMakeLists.txt

@ -1,16 +0,0 @@ @@ -1,16 +0,0 @@
set(directories
./px4_simple_app
./fixedwing_control
./rover_steering_control
./px4_mavlink_debug
./px4_daemon_app
./flow_position_estimator
./matlab_csv_serial
./subscriber
./hwtest
./publisher
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()

33
src/firmware/nuttx/CMakeLists.txt

@ -1,30 +1,29 @@ @@ -1,30 +1,29 @@
# a list of modules that will be linked to main
set(module_list)
set(module_list
platforms__nuttx
platforms__nuttx__px4_layer
platforms__common
drivers__led
drivers__device
modules__systemlib
modules__uORB
)
if (${LABEL} STREQUAL "simple")
list(APPEND module_list
drivers__led
drivers__device
platforms__common
modules__systemlib
modules__uORB
examples__px4_simple_app
lib__mathlib__math__filter
lib__conversion
)
endif()
if (${LABEL} STREQUAL "simple")
list(APPEND module_list ${module_list_simple})
if(${BOARD} STREQUAL "px4fmu-v2")
list(APPEND module_list
drivers__boards__px4fmu-v2
drivers__stm32
lib__mathlib__math__filter
lib__conversion
)
endif()
list(APPEND module_list
platforms__nuttx
platforms__nuttx__px4_layer
drivers__boards__px4fmu-v2
drivers__stm32
)
px4_nuttx_generate_builtin_commands(
OUT builtin_commands.c
MODULE_LIST ${module_list})

17
src/firmware/posix/CMakeLists.txt

@ -1,21 +1,8 @@ @@ -1,21 +1,8 @@
include(px4_base)
set(module_dir_list)
set(module_list)
px4_posix_add_modules(module_dir_list ${BOARD})
message(STATUS "module list: ${module_dir_list}")
include_directories(${CMAKE_CURRENT_BINARY_DIR})
foreach(directory ${module_dir_list})
message(STATUS "directory: ${directory}")
px4_mangle_name(${directory} mangled_name)
list(APPEND module_list
${mangled_name})
endforeach()
px4_posix_generate_builtin_commands(
OUT apps.h
MODULE_LIST ${module_list})
MODULE_LIST ${module_libraries})
add_executable(mainapp
${CMAKE_SOURCE_DIR}/src/platforms/posix/main.cpp
@ -30,7 +17,7 @@ set_target_properties(mainapp PROPERTIES LINK_FLAGS ${main_link_flags}) @@ -30,7 +17,7 @@ set_target_properties(mainapp PROPERTIES LINK_FLAGS ${main_link_flags})
target_link_libraries(mainapp
-Wl,--start-group
${module_list}
${module_libraries}
pthread m
-Wl,--end-group
)

15
src/lib/CMakeLists.txt

@ -1,15 +0,0 @@ @@ -1,15 +0,0 @@
set(directories
./external_lgpl
./geo
./launchdetection
./mathlib/math/filter
./mathlib
./rc
./geo_lookup
./ecl
./conversion
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()

4
src/lib/mathlib/math/filter/LowPassFilter2p.cpp

@ -41,6 +41,10 @@ @@ -41,6 +41,10 @@
#include "LowPassFilter2p.hpp"
#include "math.h"
#ifndef M_PI_F
#define M_PI_F 3.14159f
#endif
namespace math
{

40
src/modules/CMakeLists.txt

@ -1,40 +0,0 @@ @@ -1,40 +0,0 @@
set(directories
./navigator
./segway
./fw_pos_control_l1
./uavcan
./position_estimator_inav
./px4iofirmware
./gpio_led
./dataman
./fixedwing_backside
./uORB
./land_detector
./muorb/krait
./muorb/adsp
./simulator
./ekf_att_pos_estimator
./mc_pos_control
./attitude_estimator_ekf
./sensors
./vtol_att_control
./fw_att_control
./unit_test
./mc_att_control_multiplatform
./commander/commander_tests
./commander
./mavlink/mavlink_tests
./mavlink
./mc_att_control
./bottle_drop
./systemlib/mixer
./systemlib
./mc_pos_control_multiplatform
./sdlog2
./controllib
./attitude_estimator_q
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()

2
src/modules/systemlib/mcu_version.c

@ -62,7 +62,7 @@ @@ -62,7 +62,7 @@
/** Copy the 96bit MCU Unique ID into the provided pointer */
void mcu_unique_id(uint32_t *uid_96_bit)
{
#ifdef __PX4_NUTTX
#ifdef CONFIG_ARCH_CHIP_STM32
uid_96_bit[0] = getreg32(UNIQUE_ID);
uid_96_bit[1] = getreg32(UNIQUE_ID + 4);
uid_96_bit[2] = getreg32(UNIQUE_ID + 8);

4
src/modules/systemlib/printload.c

@ -261,7 +261,11 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state) @@ -261,7 +261,11 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state)
stack_size - stack_free,
stack_size,
system_load.tasks[i].tcb->sched_priority,
#if CONFIG_ARCH_BOARD_SIM
0);
#else
system_load.tasks[i].tcb->base_priority);
#endif
#if CONFIG_RR_INTERVAL > 0
/* print scheduling info with RR time slice */

26
src/platforms/CMakeLists.txt

@ -1,26 +0,0 @@ @@ -1,26 +0,0 @@
set(directories
./posix/tests/hrt_test
./posix/tests/wqueue
./posix/tests/hello
./posix/tests/muorb
./posix/tests/vcdev_test
./posix/work_queue
./posix/px4_layer
./posix/drivers/adcsim
./posix/drivers/gpssim
./posix/drivers/tonealrmsim
./posix/drivers/accelsim
./posix/drivers/airspeedsim
./posix/drivers/barosim
./posix/drivers/gyrosim
./qurt/tests/hello
./qurt/tests/muorb
./qurt/px4_layer
./common
./nuttx/px4_layer
./nuttx
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()

5
src/platforms/common/CMakeLists.txt

@ -33,10 +33,11 @@ @@ -33,10 +33,11 @@
set(depends
msg_gen
prebuild_targets
git_mavlink
)
if(${OS} STREQUAL "posix")
list(APPEND depends git_eigen git_mavlink)
if(${OS} STREQUAL "posix" OR ${BOARD} STREQUAL "sim")
list(APPEND depends git_eigen)
endif()
px4_add_module(

4
src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c

@ -50,7 +50,9 @@ @@ -50,7 +50,9 @@
#include <sys/stat.h>
#include <sys/types.h>
#ifndef CONFIG_ARCH_BOARD_SIM
#include <stm32_pwr.h>
#endif
#include <systemlib/systemlib.h>
@ -61,7 +63,9 @@ void @@ -61,7 +63,9 @@ void
px4_systemreset(bool to_bootloader)
{
if (to_bootloader) {
#ifndef CONFIG_ARCH_BOARD_SIM
stm32_pwr_enablebkp();
#endif
/* XXX wow, this is evil - write a magic number into backup register zero */
*(uint32_t *)0x40002850 = 0xb007b007;

15
src/platforms/px4_subscriber.h

@ -38,8 +38,10 @@ @@ -38,8 +38,10 @@
*/
#pragma once
#ifndef CONFIG_ARCH_BOARD_SIM
#include <functional>
#include <type_traits>
#endif
#if defined(__PX4_ROS)
/* includes when building for ros */
@ -219,10 +221,12 @@ public: @@ -219,10 +221,12 @@ public:
protected:
uORB::SubscriptionBase * _uorb_sub; /**< Handle to the subscription */
#ifndef CONFIG_ARCH_BOARD_SIM
typename std::remove_reference<decltype(((T*)nullptr)->data())>::type getUORBData()
{
return (typename std::remove_reference<decltype(((T*)nullptr)->data())>::type)*_uorb_sub;
}
#endif
/**
* Get void pointer to last message value
@ -242,8 +246,13 @@ public: @@ -242,8 +246,13 @@ public:
* @param cbf Callback, executed on receiving a new message
* @param interval Minimal interval between calls to callback
*/
SubscriberUORBCallback(unsigned interval,
std::function<void(const T &)> cbf) :
SubscriberUORBCallback(unsigned interval
#ifndef CONFIG_ARCH_BOARD_SIM
,std::function<void(const T &)> cbf)
#else
)
#endif
:
SubscriberUORB<T>(interval),
_cbf(cbf)
{}
@ -277,7 +286,9 @@ public: @@ -277,7 +286,9 @@ public:
};
protected:
#ifndef CONFIG_ARCH_BOARD_SIM
std::function<void(const T &)> _cbf; /**< Callback that the user provided on the subscription */
#endif
};
#endif

26
src/systemcmds/CMakeLists.txt

@ -1,26 +0,0 @@ @@ -1,26 +0,0 @@
set(directories
./mtd
./ver
./mixer
./tests
./nshterm
./config
./top
./bl_update
./reboot
./i2c
./param
./reflect
./usb_connected
./motor_test
./esc_calib
./perf
./topic_listener
./dumpfile
./pwm
)
foreach(directory ${directories})
add_subdirectory(${directory} EXCLUDE_FROM_ALL)
endforeach()
Loading…
Cancel
Save