param gen reorganize and fix DISABLE_PARAMS_MODULE_SCOPING

This commit is contained in:
Daniel Agar 2017-06-05 15:24:10 -04:00
parent 9b5de23553
commit f26cd01d16
51 changed files with 184 additions and 259 deletions

View File

@ -99,7 +99,7 @@
#
#=============================================================================
if ("${CMAKE_VERSION}" VERSION_LESS 3.1.0)
if (${CMAKE_VERSION} VERSION_LESS 3.1.0)
message("Not a valid CMake version")
message("On Ubuntu >= 16.04, install or upgrade via:")
message(" sudo apt-get install cmake")
@ -158,7 +158,7 @@ if (NOT CMAKE_BUILD_TYPE)
if (${OS} STREQUAL "nuttx")
set(PX4_BUILD_TYPE "MinSizeRel")
elseif (${OS} STREQUAL "qurt")
set(PX4_BUILD_TYPE "MinSizeRel")
set(PX4_BUILD_TYPE "Debug")
elseif (${OS} STREQUAL "bebop")
set(PX4_BUILD_TYPE "MinSizeRel")
else()
@ -371,7 +371,7 @@ link_directories(${link_dirs})
add_definitions(${definitions})
#=============================================================================
# message, parameter, and airframe generation
# message, and airframe generation
#
include(common/px4_metadata)
@ -384,13 +384,7 @@ px4_generate_messages(TARGET msg_gen
DEPENDS git_genmsg git_gencpp prebuild_targets
)
px4_generate_parameters_xml(OUT parameters.xml
BOARD ${BOARD}
MODULES ${config_module_list}
OVERRIDES ${PARAM_DEFAULT_OVERRIDES})
px4_generate_airframes_xml(OUT airframes.xml BOARD ${BOARD})
add_custom_target(xml_gen DEPENDS parameters.xml airframes.xml)
px4_generate_airframes_xml(BOARD ${BOARD})
#=============================================================================
# DriverFramework

View File

@ -307,9 +307,8 @@ format:
# --------------------------------------------------------------------
.PHONY: unittest run_tests_posix tests tests_coverage
unittest: posix_sitl_default
$(call cmake-build,unittest,$(SRC_DIR)/unittests)
@(cd build_unittest && ctest -j2 --output-on-failure)
unittest:
echo "UNIT TEST DISABLED"
run_tests_posix:
$(MAKE) --no-print-directory posix_sitl_default test_results

View File

@ -14,13 +14,19 @@ class SourceScanner(object):
Scans provided path and passes all found contents to the parser using
parser.Parse method.
"""
extensions1 = tuple([".c"])
extensions1 = tuple([".h"])
extensions2 = tuple([".c"])
for srcdir in srcdirs:
for filename in os.listdir(srcdir):
if filename.endswith(extensions1):
path = os.path.join(srcdir, filename)
if not self.ScanFile(path, parser):
return False
for filename in os.listdir(srcdir):
if filename.endswith(extensions2):
path = os.path.join(srcdir, filename)
if not self.ScanFile(path, parser):
return False
return True
def ScanFile(self, path, parser):

View File

@ -9,13 +9,12 @@ import argparse
from jinja2 import Environment, FileSystemLoader
import os
def generate(xml_file, dest='.', modules=None):
def generate(xml_file, dest='.'):
"""
Generate px4 param source from xml.
@param xml_file: input parameter xml file
@param dest: Destination directory for generated files
@param modules: The list of px4 modules to search for params.
None means to scan everything.
"""
# pylint: disable=broad-except
@ -26,9 +25,6 @@ def generate(xml_file, dest='.', modules=None):
for group in root:
if group.tag == "group" and "no_code_generation" not in group.attrib:
for param in group:
scope_ = param.find('scope').text
if (modules is not None) and (not scope_ in modules):
continue
params.append(param)
params = sorted(params, key=lambda name: name.attrib["name"])
@ -55,9 +51,8 @@ def generate(xml_file, dest='.', modules=None):
if __name__ == "__main__":
arg_parser = argparse.ArgumentParser()
arg_parser.add_argument("--xml", help="parameter xml file")
arg_parser.add_argument("--modules", help="px4 module list", default=None)
arg_parser.add_argument("--dest", help="destination path", default=os.path.curdir)
args = arg_parser.parse_args()
generate(xml_file=args.xml, modules=args.modules, dest=args.dest)
generate(xml_file=args.xml, dest=args.dest)
# vim: set et fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :

View File

@ -1,2 +0,0 @@
#!/bin/sh
python px_process_params.py --xml

View File

@ -118,13 +118,14 @@ def main():
metavar="SUMMARY",
default="Automagically updated parameter documentation from code.",
help="DokuWiki page edit summary")
parser.add_argument('-v', '--verbose', action='store_true', help="verbose output")
parser.add_argument('-v', '--verbose',
action='store_true',
help="verbose output")
parser.add_argument("-o", "--overrides",
default="{}",
metavar="OVERRIDES",
help="a dict of overrides in the form of a json string")
args = parser.parse_args()
# Check for valid command
@ -138,7 +139,8 @@ def main():
parser = srcparser.SourceParser()
# Scan directories, and parse the files
if (args.verbose): print("Scanning source path " + str(args.src_path))
if (args.verbose):
print("Scanning source path " + str(args.src_path))
if not scanner.ScanDir(args.src_path, parser):
sys.exit(1)
@ -162,7 +164,8 @@ def main():
# Output to XML file
if args.xml:
if args.verbose: print("Creating XML file " + args.xml)
if args.verbose:
print("Creating XML file " + args.xml)
cur_dir = os.path.dirname(os.path.realpath(__file__))
out = xmlout.XMLOutput(param_groups, args.board,
os.path.join(cur_dir, args.inject_xml))

View File

@ -1,2 +0,0 @@
# Remember to set the XMLRPCUSER and XMLRPCPASS environment variables
python px_process_params.py --wiki-update

View File

@ -212,7 +212,7 @@ function(px4_add_module)
# default stack max to stack main
if(NOT STACK_MAIN AND STACK)
set(STACK_MAIN ${STACK})
message(AUTHOR_WARNING "STACK deprecated, USE STACK_MAIN instead!!!!!!!!!!!!")
message(AUTHOR_WARNING "STACK deprecated, USE STACK_MAIN instead!")
endif()
foreach(property MAIN STACK_MAIN PRIORITY)
@ -245,7 +245,7 @@ function(px4_add_module)
endif()
if(INCLUDES)
target_include_directories(${MODULE} ${INCLUDES})
target_include_directories(${MODULE} PRIVATE ${INCLUDES})
endif()
if(DEPENDS)

View File

@ -38,8 +38,6 @@
# utility functions
#
# * px4_generate_messages
# * px4_generate_parameters_xml
# * px4_generate_parameters_source
# * px4_generate_airframes_xml
#
@ -167,116 +165,6 @@ function(px4_generate_messages)
endif()
endfunction()
#=============================================================================
#
# px4_generate_parameters_xml
#
# Generates a parameters.xml file.
#
# Usage:
# px4_generate_parameters_xml(OUT <param-xml_file>)
#
# Input:
# BOARD : the board
# MODULES : a list of px4 modules used to limit scope of the paramaters
# OVERRIDES : A json dict with param names as keys and param default
# overrides as values
#
# Output:
# OUT : the generated xml file
#
# Example:
# px4_generate_parameters_xml(OUT parameters.xml)
#
function(px4_generate_parameters_xml)
px4_parse_function_args(
NAME px4_generate_parameters_xml
ONE_VALUE OUT BOARD OVERRIDES
MULTI_VALUE MODULES
REQUIRED MODULES OUT BOARD
ARGN ${ARGN})
set(path ${PX4_SOURCE_DIR}/src)
file(GLOB_RECURSE param_src_files
${PX4_SOURCE_DIR}/src/*params.c
)
if (NOT OVERRIDES)
set(OVERRIDES "{}")
endif()
# get full path for each module
set(module_list)
if(DISABLE_PARAMS_MODULE_SCOPING)
set(module_list ${path})
else()
foreach(module ${MODULES})
list(APPEND module_list ${PX4_SOURCE_DIR}/src/${module})
endforeach()
endif()
add_custom_command(OUTPUT ${OUT}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
-s ${module_list} ${EXTERNAL_MODULES_LOCATION}
--board CONFIG_ARCH_${BOARD} --xml --inject-xml
--overrides ${OVERRIDES}
DEPENDS ${param_src_files} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
${PX4_SOURCE_DIR}/Tools/px_generate_params.py
)
set(${OUT} ${${OUT}} PARENT_SCOPE)
endfunction()
#=============================================================================
#
# px4_generate_parameters_source
#
# Generates a source file with all parameters.
#
# Usage:
# px4_generate_parameters_source(OUT <list-source-files> XML <param-xml-file> MODULES px4 module list)
#
# Input:
# XML : the parameters.xml file
# MODULES : a list of px4 modules used to limit scope of the paramaters
# DEPS : target dependencies
#
# Output:
# OUT : the generated source files
#
# Example:
# px4_generate_parameters_source(OUT param_files XML parameters.xml MODULES lib/controllib modules/ekf2)
#
function(px4_generate_parameters_source)
px4_parse_function_args(
NAME px4_generate_parameters_source
ONE_VALUE OUT XML DEPS
MULTI_VALUE MODULES
REQUIRED MODULES OUT XML
ARGN ${ARGN})
set(generated_files
${CMAKE_CURRENT_BINARY_DIR}/px4_parameters.h
${CMAKE_CURRENT_BINARY_DIR}/px4_parameters.c)
set_source_files_properties(${generated_files} PROPERTIES GENERATED TRUE)
if(DISABLE_PARAMS_MODULE_SCOPING)
add_custom_command(OUTPUT ${generated_files}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_generate_params.py
--xml ${XML} --dest ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS ${XML} ${DEPS}
)
else()
px4_join(OUT module_list LIST ${MODULES} GLUE ",")
add_custom_command(OUTPUT ${generated_files}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_generate_params.py
--xml ${XML} --modules ${module_list} --dest ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS ${XML} ${DEPS}
)
endif()
set(${OUT} ${generated_files} PARENT_SCOPE)
endfunction()
#=============================================================================
#
# px4_generate_airframes_xml
@ -299,14 +187,15 @@ endfunction()
function(px4_generate_airframes_xml)
px4_parse_function_args(
NAME px4_generate_airframes_xml
ONE_VALUE OUT BOARD
REQUIRED OUT BOARD
ONE_VALUE BOARD
REQUIRED BOARD
ARGN ${ARGN})
set(process_airframes ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py)
add_custom_command(OUTPUT ${OUT}
COMMAND ${PYTHON_EXECUTABLE} ${process_airframes}
add_custom_command(OUTPUT ${PX4_SOURCE_DIR}/airframes.xml
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
-a ${PX4_SOURCE_DIR}/ROMFS/${config_romfs_root}/init.d
--board CONFIG_ARCH_BOARD_${BOARD} --xml
DEPENDS ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
)
set(${OUT} ${${OUT}} PARENT_SCOPE)
add_custom_target(airframes_xml DEPENDS ${PX4_SOURCE_DIR}/airframes.xml)
endfunction()

View File

@ -103,7 +103,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -83,7 +83,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -125,7 +125,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -75,7 +75,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -64,7 +64,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/uORB
lib/version

View File

@ -127,7 +127,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -29,7 +29,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -55,7 +55,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/uORB
lib/version

View File

@ -64,7 +64,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
lib/version

View File

@ -98,7 +98,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -129,7 +129,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -123,7 +123,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -134,7 +134,7 @@ set(config_module_list
# Library modules
#
modules/dataman
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -133,7 +133,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -135,7 +135,7 @@ set(config_module_list
# Library modules
#
modules/dataman
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -133,7 +133,7 @@ set(config_module_list
# Library modules
#
modules/dataman
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -111,7 +111,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -55,7 +55,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
lib/version

View File

@ -79,7 +79,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -62,7 +62,7 @@ set(config_module_list
modules/sdlog2
modules/logger
modules/commander
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -28,7 +28,7 @@ set(config_module_list
modules/mavlink
modules/param
modules/systemlib/param
modules/systemlib
modules/uORB
modules/sensors

View File

@ -56,7 +56,7 @@ set(config_module_list
modules/sdlog2
modules/logger
modules/commander
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -61,7 +61,7 @@ set(config_module_list
modules/sdlog2
modules/logger
modules/commander
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -52,7 +52,7 @@ set(config_module_list
modules/mc_pos_control
modules/mc_att_control
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -44,7 +44,7 @@ set(config_module_list
modules/mc_pos_control
modules/mc_att_control
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -99,7 +99,7 @@ set(config_module_list
# Library modules
#
modules/dataman
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -12,7 +12,7 @@ set(config_module_list
systemcmds/ver
systemcmds/perf
modules/uORB
modules/param
modules/systemlib/param
modules/systemlib
modules/ekf2
modules/ekf2_replay

View File

@ -31,7 +31,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/uORB

View File

@ -52,7 +52,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -31,7 +31,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/uORB

View File

@ -31,7 +31,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -57,7 +57,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -62,7 +62,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -58,7 +58,7 @@ set(config_module_list
#
# Library modules
#
modules/param
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB

View File

@ -81,17 +81,19 @@ function(px4_nuttx_add_firmware)
ARGN ${ARGN})
set(extra_args)
set(dependencies)
if (PARAM_XML)
list(APPEND extra_args
--parameter_xml ${PARAM_XML}
)
list(APPEND dependencies parameters_xml)
endif()
if (AIRFRAMES_XML)
list(APPEND extra_args
--airframe_xml ${AIRFRAMES_XML}
)
list(APPEND dependencies airframes_xml)
endif()
add_custom_command(OUTPUT ${OUT} ${EXE}.bin
@ -101,7 +103,7 @@ function(px4_nuttx_add_firmware)
--git_identity ${PX4_SOURCE_DIR}
${extra_args}
--image ${EXE}.bin > ${OUT}
DEPENDS ${EXE}
DEPENDS ${EXE} ${dependencies}
)
add_custom_target(build_firmware_${BOARD} ALL DEPENDS ${OUT})
endfunction()

View File

@ -95,10 +95,8 @@ function(px4_qurt_generate_builtin_commands)
math(EXPR command_count "${command_count}+1")
endif()
endforeach()
configure_file(${PX4_SOURCE_DIR}/src/platforms/apps.cpp.in
${OUT}.cpp)
configure_file(${PX4_SOURCE_DIR}/src/platforms/apps.h.in
${OUT}.h)
configure_file(${PX4_SOURCE_DIR}/src/platforms/apps.cpp.in ${OUT}.cpp)
configure_file(${PX4_SOURCE_DIR}/src/platforms/apps.h.in ${OUT}.h)
endfunction()
#=============================================================================
@ -181,8 +179,8 @@ function(px4_os_add_flags)
)
# Add the toolchain specific flags
set(added_cflags -O0)
set(added_cxx_flags -O0)
set(added_cflags)
set(added_cxx_flags)
# Clear -rdynamic flag which fails for hexagon
set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")

View File

@ -34,10 +34,10 @@ if ("${QURT_ENABLE_STUBS}" STREQUAL "1")
-Wl,--end-group
)
else()
message("module_libraries = ${module_libraries}")
message("target_libraries = ${target_libraries}")
message("df_driver_libs = ${df_driver_libs}")
message("module_external_libraries = ${module_external_libraries}")
#message("module_libraries = ${module_libraries}")
#message("target_libraries = ${target_libraries}")
#message("df_driver_libs = ${df_driver_libs}")
#message("module_external_libraries = ${module_external_libraries}")
# Generate the DSP lib and stubs but not the apps side executable
# The Apps side executable is generated via the posix_eagle_xxxx target
QURT_LIB(LIB_NAME px4

View File

@ -1,49 +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.
#
############################################################################
include_directories(${CMAKE_CURRENT_BINARY_DIR})
px4_generate_parameters_source(OUT param_files
XML ${PX4_BINARY_DIR}/parameters.xml
MODULES ${config_module_list}
DEPS xml_gen
)
px4_add_module(
MODULE modules__param
COMPILE_FLAGS
SRCS ${param_files}
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -31,9 +31,6 @@
#
############################################################################
# for generated files
include_directories(${PX4_BINARY_DIR}/src/modules/param)
set(SRCS
perf_counter.c
conversions.c
@ -55,19 +52,16 @@ if(${OS} STREQUAL "nuttx")
list(APPEND SRCS
err.c
printload.c
param/param.c
flashparams/flashparams.c
flashparams/flashfs.c
up_cxxinitialize.c
)
elseif ("${CONFIG_SHMEM}" STREQUAL "1")
list(APPEND SRCS
param/param_shmem.c
print_load_posix.c
)
else()
list(APPEND SRCS
param/param.c
print_load_posix.c
)
endif()
@ -85,6 +79,5 @@ px4_add_module(
SRCS ${SRCS}
DEPENDS
platforms__common
modules__param
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -341,8 +341,6 @@ int flash_param_save(void)
return param_export_internal(false);
}
int flash_param_load(void)
{
param_reset_all();

View File

@ -0,0 +1,101 @@
############################################################################
#
# Copyright (c) 2017 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.
#
############################################################################
set(SRCS)
if ("${CONFIG_SHMEM}" STREQUAL "1")
message(STATUS "parameters shared memory enabled")
list(APPEND SRCS
param_shmem.c
)
else()
list(APPEND SRCS
param.c
)
endif()
if (NOT PARAM_DEFAULT_OVERRIDES)
set(PARAM_DEFAULT_OVERRIDES "{}")
endif()
# get full path for each module
set(module_list)
if (DISABLE_PARAMS_MODULE_SCOPING)
# search all directories with .c files (potentially containing parameters)
file(GLOB_RECURSE new_list ${PX4_SOURCE_DIR}/src/*.c)
foreach(file_path ${new_list})
get_filename_component(dir_path ${file_path} PATH)
list(APPEND module_list "${dir_path}")
endforeach()
list(REMOVE_DUPLICATES module_list)
else()
foreach(module ${config_module_list})
list(APPEND module_list ${PX4_SOURCE_DIR}/src/${module})
endforeach()
endif()
set(parameters_xml ${PX4_BINARY_DIR}/parameters.xml)
file(GLOB_RECURSE param_src_files ${PX4_SOURCE_DIR}/src/*params.c)
add_custom_command(OUTPUT ${parameters_xml}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
-s ${module_list} ${EXTERNAL_MODULES_LOCATION}
--board CONFIG_ARCH_${BOARD} --xml --inject-xml
--overrides ${PARAM_DEFAULT_OVERRIDES}
DEPENDS ${param_src_files} ${PX4_SOURCE_DIR}/Tools/px_process_params.py
WORKING_DIRECTORY ${PX4_BINARY_DIR}
)
add_custom_target(parameters_xml DEPENDS ${parameters_xml})
# generate px4_parameters.c and px4_parameters.h
add_custom_command(OUTPUT px4_parameters.c px4_parameters.h
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_generate_params.py
--xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR}
DEPENDS
${parameters_xml}
${PX4_SOURCE_DIR}/Tools/px_generate_params.py
${PX4_SOURCE_DIR}/Tools/templates/px4_parameters.c.jinja
${PX4_SOURCE_DIR}/Tools/templates/px4_parameters.h.jinja
)
set_source_files_properties(px4_parameters.c PROPERTIES GENERATED TRUE)
px4_add_module(
MODULE modules__systemlib__param
COMPILE_FLAGS
INCLUDES
${CMAKE_CURRENT_BINARY_DIR}
SRCS
${SRCS}
px4_parameters.c
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -64,7 +64,7 @@
#include "systemlib/uthash/utarray.h"
#include "systemlib/bson/tinybson.h"
//#define PARAM_NO_ORB ///< if defined, avoid uorb depenency. This disables publication of parameter_update on param change
//#define PARAM_NO_ORB ///< if defined, avoid uorb dependency. This disables publication of parameter_update on param change
//#define PARAM_NO_AUTOSAVE ///< if defined, do not autosave (avoids LP work queue dependency)
#if !defined(PARAM_NO_ORB)