diff --git a/cmake/common/px4_base.cmake b/cmake/common/px4_base.cmake index fa34b1584d..dadaf9ec74 100644 --- a/cmake/common/px4_base.cmake +++ b/cmake/common/px4_base.cmake @@ -266,6 +266,10 @@ function(px4_add_module) add_library(${MODULE} STATIC EXCLUDE_FROM_ALL ${SRCS}) + if(${OS} STREQUAL "qurt" ) + set_property(TARGET ${MODULE} PROPERTY POSITION_INDEPENDENT_CODE TRUE) + endif() + if(MAIN) set_target_properties(${MODULE} PROPERTIES COMPILE_DEFINITIONS PX4_MAIN=${MAIN}_app_main) diff --git a/cmake/configs/qurt_eagle_default.cmake b/cmake/configs/qurt_eagle_default.cmake index e39a96fe3e..b2a88be322 100644 --- a/cmake/configs/qurt_eagle_default.cmake +++ b/cmake/configs/qurt_eagle_default.cmake @@ -11,17 +11,18 @@ include(qurt/px4_impl_qurt) #include_directories(${HEXAGON_DRIVERS_ROOT}/inc) # For Actual flight we need to link against the driver dynamic libraries -set(target_libraries - -L${HEXAGON_DRIVERS_ROOT}/libs +#set(target_libraries +# -L${HEXAGON_DRIVERS_ROOT}/libs # The plan is to replace these with our drivers # mpu9x50 # uart_esc # csr_gps # rc_receiver - ) +# ) -set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake) +set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake) +include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake) set(config_module_list # diff --git a/cmake/qurt/px4_impl_qurt.cmake b/cmake/qurt/px4_impl_qurt.cmake index 5c40dfebd7..0f7441c158 100644 --- a/cmake/qurt/px4_impl_qurt.cmake +++ b/cmake/qurt/px4_impl_qurt.cmake @@ -172,16 +172,13 @@ function(px4_os_add_flags) set(added_definitions -D__PX4_QURT -D__PX4_POSIX - -D__DF_QURT -include ${PX4_INCLUDE_DIR}visibility.h ) # Add the toolchain specific flags - set(added_cflags ${QURT_CMAKE_C_FLAGS}) - set(added_cxx_flags ${QURT_CMAKE_CXX_FLAGS}) + set(added_cflags -O0) + set(added_cxx_flags -O0) - # FIXME @jgoppert - how to work around issues like this? - # Without changing global variables? # Clear -rdynamic flag which fails for hexagon set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "") set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "") diff --git a/src/firmware/qurt/CMakeLists.txt b/src/firmware/qurt/CMakeLists.txt index bb55e8dc22..c16ed4f2b9 100644 --- a/src/firmware/qurt/CMakeLists.txt +++ b/src/firmware/qurt/CMakeLists.txt @@ -1,32 +1,29 @@ include_directories(${CMAKE_CURRENT_BINARY_DIR}) +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-missing-prototypes") + px4_qurt_generate_builtin_commands( OUT ${CMAKE_BINARY_DIR}/apps.h MODULE_LIST ${module_libraries}) -# Clear -rdynamic flag which fails for hexagon -# this change is scoped in this directory and below -set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "") -set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "") - # Enable build without HexagonSDK to check link dependencies if ("${QURT_ENABLE_STUBS}" STREQUAL "1") add_executable(mainapp ${CMAKE_SOURCE_DIR}/src/platforms/qurt/dspal/dspal_stub.c ${CMAKE_BINARY_DIR}/apps.h) else() - add_library(mainapp + QURT_BUNDLE(APP_NAME + mainapp + DSP_SOURCES ${CMAKE_SOURCE_DIR}/src/platforms/qurt/dspal/dspal_stub.c - ${CMAKE_BINARY_DIR}/apps.h) + ${CMAKE_BINARY_DIR}/apps.h + DSP_LINK_LIBS + ${module_libraries} + ${target_libraries} + df_driver_framework + m + ) + endif() -target_link_libraries(mainapp - -Wl,--whole-archive - ${module_libraries} - ${target_libraries} - df_driver_framework - m - -Wl,--no-whole-archive - -Wl,${TOOLSLIB}/pic/libstdc++.a) - # vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index f9b0b1cbca..326ae229af 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -74,12 +74,17 @@ static uint64_t IMUusec = 0; static constexpr float rc = 10.0f; // RC time constant of 1st order LPF in seconds static constexpr uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000; ///< units: microseconds static constexpr float POS_RESET_THRESHOLD = 5.0f; ///< Seconds before we signal a total GPS failure + +// These are unused +#if 0 static constexpr unsigned MAG_SWITCH_HYSTERESIS = 10; ///< Ignore the first few mag failures (which amounts to a few milliseconds) static constexpr unsigned GYRO_SWITCH_HYSTERESIS = 5; ///< Ignore the first few gyro failures (which amounts to a few milliseconds) static constexpr unsigned ACCEL_SWITCH_HYSTERESIS = 5; ///< Ignore the first few accel failures (which amounts to a few milliseconds) +#endif + static constexpr float EPH_LARGE_VALUE = 1000.0f; static constexpr float EPV_LARGE_VALUE = 1000.0f; diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 067fa909ae..5461f0ec97 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -291,12 +291,6 @@ private: namespace mc_att_control { -/* oddly, ERROR is not defined for c++ */ -#ifdef ERROR -# undef ERROR -#endif -static const int ERROR = -1; - MulticopterAttitudeControl *g_control; } @@ -1025,4 +1019,4 @@ int mc_att_control_main(int argc, char *argv[]) warnx("unrecognized command"); return 1; -} \ No newline at end of file +} diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index dad5173cd5..bfc368367b 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -333,12 +333,6 @@ private: namespace pos_control { -/* oddly, ERROR is not defined for c++ */ -#ifdef ERROR -# undef ERROR -#endif -static const int ERROR = -1; - MulticopterPositionControl *g_control; } diff --git a/src/modules/muorb/adsp/uORBFastRpcChannel.cpp b/src/modules/muorb/adsp/uORBFastRpcChannel.cpp index 82a3301322..cd8648f08a 100644 --- a/src/modules/muorb/adsp/uORBFastRpcChannel.cpp +++ b/src/modules/muorb/adsp/uORBFastRpcChannel.cpp @@ -38,7 +38,6 @@ // static intialization. uORB::FastRpcChannel uORB::FastRpcChannel::_Instance; -static hrt_abstime _check_time; static unsigned long _dropped_pkts; static unsigned long _get_min = 0xFFFFFF; static unsigned long _get_max = 0; @@ -136,7 +135,6 @@ int16_t uORB::FastRpcChannel::send_message(const char *messageName, int32_t leng int16_t rc = 0; hrt_abstime t1, t2; static hrt_abstime check_time = 0; - int32_t initial_queue_size = 0; if (_RemoteSubscribers.find(messageName) == _RemoteSubscribers.end()) { //there is no-remote subscriber. So do not queue the message. @@ -280,7 +278,7 @@ int16_t uORB::FastRpcChannel::get_data static hrt_abstime check_time = 0; hrt_abstime t1 = hrt_absolute_time(); _DataAvailableSemaphore.wait(); - hrt_abstime t2 = hrt_absolute_time(); + // hrt_abstime t2 = hrt_absolute_time(); _QueueMutex.lock(); if (DataQSize() != 0 || ControlQSize() != 0) { @@ -395,7 +393,7 @@ int16_t uORB::FastRpcChannel::get_bulk_data static hrt_abstime check_time = 0; hrt_abstime t1 = hrt_absolute_time(); _DataAvailableSemaphore.wait(); - hrt_abstime t2 = hrt_absolute_time(); + //hrt_abstime t2 = hrt_absolute_time(); _QueueMutex.lock(); diff --git a/src/platforms/qurt/px4_layer/main.cpp b/src/platforms/qurt/px4_layer/main.cpp index d8caf4659b..e9c7ff9cdf 100644 --- a/src/platforms/qurt/px4_layer/main.cpp +++ b/src/platforms/qurt/px4_layer/main.cpp @@ -102,7 +102,6 @@ static void process_commands(map &apps, const char *cmds) vector appargs; int i = 0; const char *b = cmds; - bool found_first_char = false; char arg[256]; // Eat leading whitespace diff --git a/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp b/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp index b73e296b0c..aa89d25606 100644 --- a/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp +++ b/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp @@ -363,7 +363,6 @@ static void timer_cb(void *data) int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *ts) { - void *result; work_s _hpwork = {}; // Create a timer to unblock