forked from Archive/PX4-Autopilot
Use DriverFramework as a PX4 module (#4415)
* Use DriverFramework as a PX4 module Targets wanting to use DriverFramework must add lib/DriverFramework/framework to their config file. Signed-off-by: Mark Charlebois <charlebm@gmail.com> * Removed spurious code No need to add if check before for loop Signed-off-by: Mark Charlebois <charlebm@gmail.com> * Added DriverFramework to NuttX configs Added lib/DriverFramework/firmware to nuttx configs Signed-off-by: Mark Charlebois <charlebm@gmail.com> * Updated src/lib/DriverFramework * Removed DF_TARGET and __DF_${OS} defines These are now handled inside DriverFramework Signed-off-by: Mark Charlebois <charlebm@gmail.com> * Updated DriverFramework Signed-off-by: Mark Charlebois <charlebm@gmail.com> * Restored __DF_${OS} The include files in DriverFramwork need to know the target OS. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
23a9af9088
commit
8cb8987bcd
|
@ -150,16 +150,6 @@ list(GET config_args 1 BOARD)
|
|||
list(GET config_args 2 LABEL)
|
||||
set(target_name "${OS}-${BOARD}-${LABEL}")
|
||||
|
||||
if("${OS}" STREQUAL "posix")
|
||||
if (APPLE)
|
||||
set(DF_TARGET darwin)
|
||||
else()
|
||||
set(DF_TARGET linux)
|
||||
endif()
|
||||
else()
|
||||
set(DF_TARGET ${OS})
|
||||
endif()
|
||||
|
||||
message(STATUS "${target_name}")
|
||||
|
||||
# switch to ros CMake file if building ros
|
||||
|
@ -333,12 +323,11 @@ execute_process(COMMAND cmake -E make_directory ${ep_base}/Install/include)
|
|||
#=============================================================================
|
||||
# DriverFramework Drivers
|
||||
#
|
||||
#message("ADDING DRIVERS")
|
||||
set(df_driver_libs)
|
||||
foreach(driver ${config_df_driver_list})
|
||||
add_subdirectory(src/lib/DriverFramework/drivers/${driver})
|
||||
list(APPEND df_driver_libs df_${driver})
|
||||
message("adding driver: ${driver}")
|
||||
message("Adding DF driver: ${driver}")
|
||||
endforeach()
|
||||
|
||||
#=============================================================================
|
||||
|
@ -361,8 +350,6 @@ endforeach()
|
|||
|
||||
add_subdirectory(src/firmware/${OS})
|
||||
|
||||
add_subdirectory(src/lib/DriverFramework/framework/src)
|
||||
|
||||
#add_dependencies(df_driver_framework nuttx_export_${CONFIG}.stamp)
|
||||
if (NOT "${OS}" STREQUAL "nuttx")
|
||||
endif()
|
||||
|
|
|
@ -130,6 +130,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -43,6 +43,7 @@ set(config_module_list
|
|||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -115,6 +115,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -124,6 +124,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -123,6 +123,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -125,6 +125,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -55,6 +55,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
|
|
@ -33,6 +33,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
|
|
@ -56,6 +56,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
|
|
@ -35,6 +35,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
|
|
@ -9,6 +9,8 @@ set(config_module_list
|
|||
|
||||
modules/uORB
|
||||
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
|
||||
|
|
|
@ -29,6 +29,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
|
|
|
@ -44,4 +44,5 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
)
|
||||
|
|
|
@ -53,4 +53,5 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
)
|
||||
|
|
|
@ -62,6 +62,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
examples/px4_simple_app
|
||||
)
|
||||
|
||||
|
|
|
@ -62,6 +62,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
examples/px4_simple_app
|
||||
)
|
||||
|
||||
|
|
|
@ -61,6 +61,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
examples/px4_simple_app
|
||||
)
|
||||
|
||||
|
|
|
@ -25,6 +25,7 @@ set(config_module_list
|
|||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/DriverFramework/framework
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
|
|
|
@ -74,6 +74,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -59,6 +59,7 @@ set(config_module_list
|
|||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/controllib
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -77,6 +77,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -87,6 +87,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -33,6 +33,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -83,6 +83,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -31,6 +31,7 @@ set(config_module_list
|
|||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -67,6 +67,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
|
|
|
@ -500,8 +500,6 @@ function(px4_os_add_flags)
|
|||
#message(STATUS "nuttx: set(${${var}} ${${${var}}} ${added_${lower_var}} PARENT_SCOPE)")
|
||||
endforeach()
|
||||
|
||||
set(DF_TARGET "nuttx" PARENT_SCOPE)
|
||||
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
|
|
|
@ -177,8 +177,6 @@ function(px4_os_add_flags)
|
|||
set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")
|
||||
set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "")
|
||||
|
||||
set(DF_TARGET "qurt" PARENT_SCOPE)
|
||||
|
||||
# output
|
||||
foreach(var ${inout_vars})
|
||||
string(TOLOWER ${var} lower_var)
|
||||
|
|
|
@ -13,7 +13,7 @@ add_executable(firmware_nuttx
|
|||
set(nuttx_export_dir ${CMAKE_BINARY_DIR}/${BOARD}/NuttX/nuttx-export)
|
||||
|
||||
set(link_libs
|
||||
romfs apps nuttx m gcc df_driver_framework
|
||||
romfs apps nuttx m gcc
|
||||
)
|
||||
|
||||
if(NOT ${BOARD} STREQUAL "sim")
|
||||
|
@ -29,6 +29,7 @@ endif()
|
|||
target_link_libraries(firmware_nuttx
|
||||
-Wl,--start-group
|
||||
${module_libraries}
|
||||
${df_driver_libs}
|
||||
${config_extra_libs}
|
||||
${link_libs}
|
||||
-Wl,--end-group)
|
||||
|
|
|
@ -17,17 +17,16 @@ if ("${BOARD}" STREQUAL "eagle")
|
|||
IDL_NAME px4muorb
|
||||
APPS_DEST "/home/linaro"
|
||||
SOURCES
|
||||
px4muorb_stub.c
|
||||
${CMAKE_SOURCE_DIR}/src/platforms/posix/main.cpp
|
||||
apps.h
|
||||
px4muorb_stub.c
|
||||
${CMAKE_SOURCE_DIR}/src/platforms/posix/main.cpp
|
||||
apps.h
|
||||
LINK_LIBS
|
||||
-Wl,--start-group
|
||||
${module_libraries}
|
||||
df_driver_framework
|
||||
${df_driver_libs}
|
||||
${FASTRPC_ARM_LIBS}
|
||||
pthread m rt
|
||||
-Wl,--end-group
|
||||
-Wl,--start-group
|
||||
${module_libraries}
|
||||
${df_driver_libs}
|
||||
${FASTRPC_ARM_LIBS}
|
||||
pthread m rt
|
||||
-Wl,--end-group
|
||||
)
|
||||
|
||||
px4_add_adb_push(OUT upload
|
||||
|
@ -47,7 +46,6 @@ else()
|
|||
target_link_libraries(mainapp
|
||||
-Wl,--start-group
|
||||
${module_libraries}
|
||||
df_driver_framework
|
||||
${df_driver_libs}
|
||||
pthread m rt
|
||||
-Wl,--end-group
|
||||
|
@ -55,7 +53,6 @@ else()
|
|||
else()
|
||||
target_link_libraries(mainapp
|
||||
${module_libraries}
|
||||
df_driver_framework
|
||||
${df_driver_libs}
|
||||
pthread m
|
||||
)
|
||||
|
|
|
@ -27,7 +27,6 @@ if ("${QURT_ENABLE_STUBS}" STREQUAL "1")
|
|||
-Wl,--start-group
|
||||
${module_libraries}
|
||||
${target_libraries}
|
||||
df_driver_framework
|
||||
${df_driver_libs}
|
||||
-Wl,--end-group
|
||||
)
|
||||
|
@ -44,7 +43,6 @@ else()
|
|||
LINK_LIBS
|
||||
${module_libraries}
|
||||
${target_libraries}
|
||||
df_driver_framework
|
||||
${df_driver_libs}
|
||||
m
|
||||
)
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit 360197265628a79429a0c828c7ded81157a6b1cf
|
||||
Subproject commit 0b57c455e4eb789f5132c46af958517eada55cb5
|
Loading…
Reference in New Issue