forked from Archive/PX4-Autopilot
Merge pull request #33 from mcharleb/cmake-mc-2
Hack to get posix build partially working
This commit is contained in:
commit
d9a620ce69
|
@ -110,6 +110,7 @@ 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})
|
||||
|
||||
|
|
2
Makefile
2
Makefile
|
@ -11,7 +11,7 @@ px4fmu-v2_simple-upload: px4fmu-v2_simple
|
|||
|
||||
posix-sitl_simple:
|
||||
mkdir -p $d/build_$@ && cd $d/build_$@ && \
|
||||
cmake .. \
|
||||
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-posix-clang-native.cmake \
|
||||
-DOS=posix -DBOARD=sitl -DLABEL=simple && \
|
||||
make -s && ctest -V && cpack -G ZIP
|
||||
|
||||
|
|
|
@ -31,7 +31,6 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# Defined functions in this file
|
||||
|
|
|
@ -0,0 +1,84 @@
|
|||
/* builtin command list - automatically generated, do not edit */
|
||||
#include <string>
|
||||
#include <map>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_posix.h>
|
||||
#include <px4_log.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
extern void px4_show_devices(void);
|
||||
|
||||
extern "C" {
|
||||
${builtin_apps_decl_string}
|
||||
static int shutdown_main(int argc, char *argv[]);
|
||||
static int list_tasks_main(int argc, char *argv[]);
|
||||
static int list_files_main(int argc, char *argv[]);
|
||||
static int list_devices_main(int argc, char *argv[]);
|
||||
static int list_topics_main(int argc, char *argv[]);
|
||||
static int sleep_main(int argc, char *argv[]);
|
||||
}
|
||||
|
||||
|
||||
void init_app_map(map<string,px4_main_t> &apps)
|
||||
{
|
||||
${builtin_apps_string}
|
||||
apps["shutdown"] = shutdown_main;
|
||||
apps["list_tasks"] = list_tasks_main;
|
||||
apps["list_files"] = list_files_main;
|
||||
apps["list_devices"] = list_devices_main;
|
||||
apps["list_topics"] = list_topics_main;
|
||||
apps["sleep"] = sleep_main;
|
||||
}
|
||||
|
||||
void list_builtins(map<string,px4_main_t> &apps)
|
||||
{
|
||||
printf("Builtin Commands:\\n");
|
||||
for (map<string,px4_main_t>::iterator it=apps.begin(); it!=apps.end(); ++it)
|
||||
printf("\\t%s\\n", (it->first).c_str());
|
||||
}
|
||||
|
||||
static int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
printf("Shutting down\\n");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static int list_tasks_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_tasks();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_devices_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_devices();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_topics_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_topics();
|
||||
return 0;
|
||||
}
|
||||
static int list_files_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_files();
|
||||
return 0;
|
||||
}
|
||||
static int sleep_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc != 2) {
|
||||
PX4_WARN( "Usage: sleep <seconds>" );
|
||||
return 1;
|
||||
}
|
||||
|
||||
unsigned long usecs = ( (unsigned long) atol( argv[1] ) ) * 1000 * 1000;
|
||||
PX4_WARN("Sleeping for %s, %ld",argv[1],usecs);
|
||||
usleep( usecs );
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,56 @@
|
|||
function(px4_set_config_modules out_module_list)
|
||||
set(config_module_list
|
||||
drivers/led
|
||||
drivers/device
|
||||
drivers/boards/sitl
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/gpssim
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
platforms/posix/drivers/accelsim
|
||||
platforms/posix/drivers/airspeedsim
|
||||
platforms/posix/drivers/barosim
|
||||
platforms/posix/drivers/gyrosim
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
modules/uORB
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/mavlink
|
||||
modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/simulator
|
||||
modules/commander
|
||||
modules/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
)
|
||||
message(STATUS "modules: ${config_module_list}")
|
||||
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
|
||||
endfunction()
|
||||
|
|
@ -1,43 +0,0 @@
|
|||
list(APPEND module_directories
|
||||
./src/platforms/posix/px4_layer
|
||||
./src/platforms/posix/work_queue
|
||||
./src/platforms/posix/drivers/adcsim
|
||||
./src/platforms/posix/drivers/gpssim
|
||||
./src/platforms/posix/drivers/tonealrmsim
|
||||
./src/platforms/posix/drivers/accelsim
|
||||
./src/platforms/posix/drivers/airspeedsim
|
||||
./src/platforms/posix/drivers/barosim
|
||||
./src/platforms/posix/drivers/gyrosim
|
||||
./src/systemcmds/param
|
||||
./src/systemcmds/mixer
|
||||
./src/systemcmds/topic_listener
|
||||
./src/systemcmds/ver
|
||||
./src/systemcmds/esc_calib
|
||||
./src/systemcmds/reboot
|
||||
./src/modules/sensors
|
||||
./src/modules/mavlink
|
||||
./src/modules/attitude_estimator_ekf
|
||||
./src/modules/attitude_estimator_q
|
||||
./src/modules/ekf_att_pos_estimator
|
||||
./src/modules/position_estimator_inav
|
||||
./src/modules/navigator
|
||||
./src/modules/mc_pos_control
|
||||
./src/modules/mc_att_control
|
||||
./src/modules/mc_pos_control_multiplatform
|
||||
./src/modules/mc_att_control_multiplatform
|
||||
./src/modules/land_detector
|
||||
./src/modules/fw_att_control
|
||||
./src/modules/fw_pos_control_l1
|
||||
./src/modules/dataman
|
||||
./src/modules/sdlog2
|
||||
./src/modules/simulator
|
||||
./src/modules/commander
|
||||
./src/modules/controllib
|
||||
./src/lib/mathlib
|
||||
./src/lib/ecl
|
||||
./src/lib/external_lgpl
|
||||
./src/lib/geo
|
||||
./src/lib/geo_lookup
|
||||
./src/lib/launchdetection
|
||||
)
|
||||
|
|
@ -0,0 +1,262 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# Defined functions in this file
|
||||
#
|
||||
# OS Specific Functions
|
||||
#
|
||||
# * px4_posix_add_firmware
|
||||
# * px4_posix_generate_builtin_commands
|
||||
# * px4_posix_add_export
|
||||
# * px4_posix_generate_romfs
|
||||
#
|
||||
# Required OS Inteface Functions
|
||||
#
|
||||
# * px4_os_add_flags
|
||||
# * px4_os_prebuild_targets
|
||||
#
|
||||
|
||||
include(px4_base)
|
||||
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/posix)
|
||||
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/posix/configs)
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# px4_posix_generate_builtin_commands
|
||||
#
|
||||
# This function generates the builtin_commands.c src for posix
|
||||
#
|
||||
# Usage:
|
||||
# px4_posix_generate_builtin_commands(
|
||||
# MODULE_LIST <in-list>
|
||||
# OUT <file>)
|
||||
#
|
||||
# Input:
|
||||
# MODULE_LIST : list of modules
|
||||
#
|
||||
# Output:
|
||||
# OUT : generated builtin_commands.c src
|
||||
#
|
||||
# Example:
|
||||
# px4_posix_generate_builtin_commands(
|
||||
# OUT <generated-src> MODULE_LIST px4_simple_app)
|
||||
#
|
||||
function(px4_posix_generate_builtin_commands)
|
||||
px4_parse_function_args(
|
||||
NAME px4_posix_generate_builtin_commands
|
||||
ONE_VALUE OUT
|
||||
MULTI_VALUE MODULE_LIST
|
||||
REQUIRED MODULE_LIST OUT
|
||||
ARGN ${ARGN})
|
||||
set(builtin_apps_string)
|
||||
set(builtin_apps_decl_string)
|
||||
set(command_count 0)
|
||||
foreach(module ${MODULE_LIST})
|
||||
# default
|
||||
set(MAIN_DEFAULT MAIN-NOTFOUND)
|
||||
set(STACK_DEFAULT 1024)
|
||||
set(PRIORITY_DEFAULT SCHED_PRIORITY_DEFAULT)
|
||||
foreach(property MAIN STACK PRIORITY)
|
||||
get_target_property(${property} ${module} ${property})
|
||||
if(NOT ${property})
|
||||
set(${property} ${${property}_DEFAULT})
|
||||
endif()
|
||||
endforeach()
|
||||
if (MAIN)
|
||||
set(builtin_apps_string
|
||||
"${builtin_apps_string}\tapps[\"${MAIN}\"] = ${MAIN}_main;\n")
|
||||
set(builtin_apps_decl_string
|
||||
"${builtin_apps_decl_string}extern int ${MAIN}_main(int argc, char *argv[]);\n")
|
||||
math(EXPR command_count "${command_count}+1")
|
||||
endif()
|
||||
endforeach()
|
||||
configure_file(${CMAKE_SOURCE_DIR}/cmake/posix/builtin_commands.cpp_in
|
||||
${OUT})
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# px4_os_add_flags
|
||||
#
|
||||
# Set ths posix build flags.
|
||||
#
|
||||
# Usage:
|
||||
# px4_os_add_flags(
|
||||
# C_FLAGS <inout-variable>
|
||||
# CXX_FLAGS <inout-variable>
|
||||
# EXE_LINKER_FLAGS <inout-variable>
|
||||
# INCLUDE_DIRS <inout-variable>
|
||||
# LINK_DIRS <inout-variable>
|
||||
# DEFINITIONS <inout-variable>)
|
||||
#
|
||||
# Input:
|
||||
# BOARD : flags depend on board/posix config
|
||||
#
|
||||
# Input/Output: (appends to existing variable)
|
||||
# C_FLAGS : c compile flags variable
|
||||
# CXX_FLAGS : c++ compile flags variable
|
||||
# EXE_LINKER_FLAGS : executable linker flags variable
|
||||
# INCLUDE_DIRS : include directories
|
||||
# LINK_DIRS : link directories
|
||||
# DEFINITIONS : definitions
|
||||
#
|
||||
# Example:
|
||||
# px4_os_add_flags(
|
||||
# C_FLAGS CMAKE_C_FLAGS
|
||||
# CXX_FLAGS CMAKE_CXX_FLAGS
|
||||
# EXE_LINKER_FLAG CMAKE_EXE_LINKER_FLAGS
|
||||
# INCLUDES <list>)
|
||||
#
|
||||
function(px4_os_add_flags)
|
||||
|
||||
set(inout_vars
|
||||
C_FLAGS CXX_FLAGS EXE_LINKER_FLAGS INCLUDE_DIRS LINK_DIRS DEFINITIONS)
|
||||
|
||||
px4_parse_function_args(
|
||||
NAME px4_add_flags
|
||||
ONE_VALUE ${inout_vars} BOARD
|
||||
REQUIRED ${inout_vars} BOARD
|
||||
ARGN ${ARGN})
|
||||
|
||||
px4_add_common_flags(
|
||||
BOARD ${BOARD}
|
||||
C_FLAGS ${C_FLAGS}
|
||||
CXX_FLAGS ${CXX_FLAGS}
|
||||
EXE_LINKER_FLAGS ${EXE_LINKER_FLAGS}
|
||||
INCLUDE_DIRS ${INCLUDE_DIRS}
|
||||
LINK_DIRS ${LINK_DIRS}
|
||||
DEFINITIONS ${DEFINITIONS})
|
||||
|
||||
set(PX4_BASE )
|
||||
set(added_include_dirs
|
||||
src/modules/systemlib
|
||||
src/lib/eigen
|
||||
src/platforms/posix/include
|
||||
mavlink/include/mavlink
|
||||
)
|
||||
|
||||
set(added_definitions
|
||||
-D__PX4_POSIX
|
||||
-D__PX4_LINUX
|
||||
-DCLOCK_MONOTONIC=1
|
||||
-Dnoreturn_function=__attribute__\(\(noreturn\)\)
|
||||
-include ${PX4_INCLUDE_DIR}visibility.h
|
||||
)
|
||||
|
||||
set(added_exe_linker_flags
|
||||
-lpthread
|
||||
)
|
||||
|
||||
|
||||
# Add the toolchain specific flags
|
||||
set(added_cflags ${POSIX_CMAKE_C_FLAGS})
|
||||
set(added_cxx_flags ${POSIX_CMAKE_CXX_FLAGS})
|
||||
|
||||
# output
|
||||
foreach(var ${inout_vars})
|
||||
string(TOLOWER ${var} lower_var)
|
||||
set(${${var}} ${${${var}}} ${added_${lower_var}} PARENT_SCOPE)
|
||||
#message(STATUS "posix: set(${${var}} ${${${var}}} ${added_${lower_var}} PARENT_SCOPE)")
|
||||
endforeach()
|
||||
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# px4_os_prebuild_targets
|
||||
#
|
||||
# This function generates os dependent targets
|
||||
#
|
||||
# Usage:
|
||||
# px4_os_prebuild_targets(
|
||||
# OUT <out-list_of_targets>
|
||||
# BOARD <in-string>
|
||||
# )
|
||||
#
|
||||
# Input:
|
||||
# BOARD : board
|
||||
# THREADS : number of threads for building
|
||||
#
|
||||
# Output:
|
||||
# OUT : the target list
|
||||
#
|
||||
# Example:
|
||||
# px4_os_prebuild_targets(OUT target_list BOARD px4fmu-v2)
|
||||
#
|
||||
function(px4_os_prebuild_targets)
|
||||
px4_parse_function_args(
|
||||
NAME px4_os_prebuild_targets
|
||||
ONE_VALUE OUT BOARD THREADS
|
||||
REQUIRED OUT BOARD
|
||||
ARGN ${ARGN})
|
||||
add_custom_target(${OUT})
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
# px4_posix_add_modules
|
||||
#
|
||||
# This function adds target modules
|
||||
#
|
||||
# Usage:
|
||||
# px4_os_prebuild_targets(
|
||||
# OUT_MODULES <module-subdir-list>
|
||||
# BOARD <in-string>
|
||||
# )
|
||||
#
|
||||
# Input:
|
||||
# BOARD : board
|
||||
#
|
||||
# Output:
|
||||
# OUT_MODULES : the updated module list
|
||||
#
|
||||
# Example:
|
||||
# px4_posix_add_modules(module_list "hil")
|
||||
#
|
||||
function(px4_posix_add_modules OUT_MODULES BOARD)
|
||||
include(config-posix-${BOARD})
|
||||
set(config_modules)
|
||||
px4_set_config_modules(config_modules)
|
||||
set(${OUT_MODULES} ${${OUT_MODULES}} ${config_modules} PARENT_SCOPE)
|
||||
endfunction()
|
||||
|
||||
|
||||
macro(px4_target_firmware)
|
||||
set(installed_targets)
|
||||
add_executable(main ./src/platforms/posix/main.cpp)
|
||||
target_link_libraries(main ${module_list} ${EXE_LINK_LIBS} ${module_list} ${EXE_LINK_LIBS})
|
||||
list(APPEND installed_targets main)
|
||||
endmacro()
|
||||
|
|
@ -1,111 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#=============================================================================
|
||||
# FILE: posix/px4_target_impl.cmake
|
||||
#
|
||||
# Each PX4 target OS must implement the cmake/${OS}/px4_target_impl.cmake
|
||||
# rules for their target that implement the following macros:
|
||||
#
|
||||
# px4_target_set_flags
|
||||
# px4_target_validate_config
|
||||
# px4_target_firmware
|
||||
# px4_target_rules
|
||||
# px4_target_testing
|
||||
#
|
||||
# The macros are called from the top level CMakeLists.txt
|
||||
#
|
||||
set(POSIX_APPS_HEADER ${CMAKE_BINARY_DIR}/apps.h)
|
||||
|
||||
add_git_submodule(eigen src/lib/eigen)
|
||||
|
||||
macro(px4_target_set_flags)
|
||||
include_directories(
|
||||
src/platforms/posix/include
|
||||
)
|
||||
add_definitions(
|
||||
-D__PX4_POSIX
|
||||
-D__PX4_LINUX
|
||||
"-Dnoreturn_function=__attribute__\(\(noreturn\)\)"
|
||||
-DCLOCK_MONOTONIC=1
|
||||
)
|
||||
list(APPEND EXE_LINK_LIBS
|
||||
pthread
|
||||
)
|
||||
endmacro()
|
||||
|
||||
macro(px4_target_validate_config)
|
||||
if(NOT EXISTS ${CMAKE_SOURCE_DIR}/cmake/${OS}/${TARGET_NAME}.cmake)
|
||||
message(FATAL_ERROR "not implemented yet: ${TARGET_NAME}")
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
macro(px4_target_set_modules)
|
||||
# Include the target config file
|
||||
include(${TARGET_NAME})
|
||||
endmacro()
|
||||
|
||||
macro(px4_target_firmware)
|
||||
set(installed_targets)
|
||||
add_executable(main ./src/platforms/posix/main.cpp)
|
||||
target_link_libraries(main ${module_list} ${EXE_LINK_LIBS} ${module_list} ${EXE_LINK_LIBS})
|
||||
list(APPEND installed_targets main)
|
||||
endmacro()
|
||||
|
||||
macro(px4_target_rules)
|
||||
#=============================================================================
|
||||
# apps
|
||||
#
|
||||
add_custom_command(OUTPUT ${POSIX_APPS_HEADER}
|
||||
COMMAND PYTHONPATH=${PYTHONPATH} ${PYTHON_EXECUTABLE}
|
||||
${CMAKE_SOURCE_DIR}/Tools/posix_apps.py > ${POSIX_APPS_HEADER}
|
||||
COMMENT "Generating posix apps"
|
||||
VERBATIM
|
||||
)
|
||||
|
||||
add_custom_target(posix_apps ALL DEPENDS ${POSIX_APPS_HEADER})
|
||||
endmacro()
|
||||
|
||||
macro(px4_target_testing)
|
||||
if (${BOARD} STREQUAL "sitl")
|
||||
|
||||
add_test(test_px4_simple_app ${PYTHON_EXECUTABLE} ${CMAKE_SOURCE_DIR}/cmake/test_compare.py
|
||||
--command ${CMAKE_BINARY_DIR}/main
|
||||
--stdout ${CMAKE_BINARY_DIR}/test/px4_simple_app_output.txt
|
||||
--stdin ${CMAKE_SOURCE_DIR}/cmake/test/px4_simple_app_input.txt
|
||||
--check ${CMAKE_SOURCE_DIR}/cmake/test/px4_simple_app_correct.txt
|
||||
--start 4 --stop -1
|
||||
)
|
||||
|
||||
endif()
|
||||
endmacro()
|
|
@ -4,6 +4,6 @@ add_subdirectory(./platforms)
|
|||
add_subdirectory(./systemcmds)
|
||||
add_subdirectory(./examples)
|
||||
add_subdirectory(./modules)
|
||||
add_subdirectory(./firmware)
|
||||
add_subdirectory(./firmware/${OS})
|
||||
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
|
|
@ -1,3 +1,26 @@
|
|||
#TODO
|
||||
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}")
|
||||
|
||||
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 builtin_commands.cpp
|
||||
MODULE_LIST ${module_list})
|
||||
|
||||
add_executable(mainapp builtin_commands.cpp)
|
||||
target_link_libraries(mainapp
|
||||
-Wl,--start-group
|
||||
${module_list}
|
||||
pthread m
|
||||
-Wl,--end-group
|
||||
)
|
||||
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
|
|
@ -0,0 +1,2 @@
|
|||
#define PX4_GIT_VERSION_STR "1234567890123456789012345678901234567890"
|
||||
#define PX4_GIT_VERSION_BINARY 0x1234567890123456
|
|
@ -30,6 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
set(SIMULATOR_SRCS simulator.cpp)
|
||||
if (NOT ${OS} STREQUAL "qurt")
|
||||
list(APPEND SIMULATOR_SRCS
|
||||
simulator_mavlink.cpp)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__simulator
|
||||
MAIN simulator
|
||||
|
@ -40,8 +46,9 @@ px4_add_module(
|
|||
-Wno-packed
|
||||
|
||||
SRCS
|
||||
simulator.cpp
|
||||
${SIMULATOR_SRCS}
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
|
|
@ -589,7 +589,7 @@ measairspeedsim_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
int ret;
|
||||
int ret = 0;
|
||||
|
||||
/*
|
||||
* Start/load the driver.
|
||||
|
|
|
@ -16,7 +16,7 @@ set(directories
|
|||
./motor_test
|
||||
./esc_calib
|
||||
./perf
|
||||
./topic_listener
|
||||
# ./topic_listener
|
||||
./dumpfile
|
||||
./pwm
|
||||
)
|
||||
|
|
|
@ -30,15 +30,15 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
#px4_add_module(
|
||||
#MODULE systemcmds__topic_listener
|
||||
#MAIN listener
|
||||
#STACK 1800
|
||||
#COMPILE_FLAGS
|
||||
#-Os
|
||||
#SRCS
|
||||
#topic_listener.cpp
|
||||
#DEPENDS
|
||||
#platforms__common
|
||||
#)
|
||||
px4_add_module(
|
||||
MODULE systemcmds__topic_listener
|
||||
MAIN listener
|
||||
STACK 1800
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
topic_listener.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
|
Loading…
Reference in New Issue