diff --git a/CMakeLists.txt b/CMakeLists.txt index 51927e1755..b6faa2448b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -274,7 +274,7 @@ px4_generate_messages(TARGET msg_gen px4_generate_parameters_xml(OUT parameters.xml BOARD ${BOARD}) px4_generate_airframes_xml(OUT airframes.xml BOARD ${BOARD}) add_custom_target(xml_gen - DEPENDS parameters.xml airframes.xml) + DEPENDS git_eigen parameters.xml airframes.xml) #============================================================================= # external projects diff --git a/cmake/common/px4_base.cmake b/cmake/common/px4_base.cmake index 51ff486868..257254ba43 100644 --- a/cmake/common/px4_base.cmake +++ b/cmake/common/px4_base.cmake @@ -731,7 +731,9 @@ function(px4_generate_parameters_xml) REQUIRED OUT BOARD ARGN ${ARGN}) set(path ${CMAKE_SOURCE_DIR}/src) - file(GLOB_RECURSE param_src_files ${path}/*.h* ${path}/*.c*) + file(GLOB_RECURSE param_src_files + ${CMAKE_SOURCE_DIR}/src/*params.c + ) add_custom_command(OUTPUT ${OUT} COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_SOURCE_DIR}/Tools/px_process_params.py -s ${path} --board CONFIG_ARCH_${BOARD} --xml diff --git a/cmake/qurt/px4_impl_qurt.cmake b/cmake/qurt/px4_impl_qurt.cmake index 6c8a6340b1..49bd83f53b 100644 --- a/cmake/qurt/px4_impl_qurt.cmake +++ b/cmake/qurt/px4_impl_qurt.cmake @@ -229,7 +229,7 @@ function(px4_os_prebuild_targets) COMMAND patch -p1 -i ${CMAKE_SOURCE_DIR}/cmake/qurt/qurt_eigen.patch DEPENDS git_eigen) add_custom_target(${OUT} DEPENDS git_dspal git_eigen_patched) - add_custom_target(ALL DEPENDS git_eigen) + add_custom_target(ALL DEPENDS git_eigen_patched) endfunction() diff --git a/cmake/qurt/qurt_funcs.cmake b/cmake/qurt/qurt_funcs.cmake index 7ecd0cc818..4690799b2b 100644 --- a/cmake/qurt/qurt_funcs.cmake +++ b/cmake/qurt/qurt_funcs.cmake @@ -46,5 +46,3 @@ # The macros are called from the top level CMakeLists.txt # px4_add_git_submodule(TARGET git_dspal PATH "src/lib/dspal") -px4_add_git_submodule(TARGET git_eigen32 PATH "src/lib/eigen-3.2") - diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index c8a0e7d870..a863328f03 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -56,6 +56,7 @@ px4_add_module( mavlink_rate_limiter.cpp mavlink_receiver.cpp mavlink_ftp.cpp + mavlink_params.c DEPENDS platforms__common ) diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 0c2d56173a..1073d09c20 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -46,75 +46,6 @@ #include "mavlink_bridge_header.h" #include -/** - * MAVLink system ID - * @group MAVLink - * @min 1 - * @max 250 - */ -PARAM_DEFINE_INT32(MAV_SYS_ID, 1); - -/** - * MAVLink component ID - * @group MAVLink - * @min 1 - * @max 250 - */ -PARAM_DEFINE_INT32(MAV_COMP_ID, 1); - -/** - * MAVLink Radio ID - * - * When non-zero the MAVLink app will attempt to configure the - * radio to this ID and re-set the parameter to 0. If the value - * is negative it will reset the complete radio config to - * factory defaults. - * - * @group MAVLink - * @min -1 - * @max 240 - */ -PARAM_DEFINE_INT32(MAV_RADIO_ID, 0); - -/** - * MAVLink airframe type - * - * @min 1 - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_TYPE, 1); - -/** - * Use/Accept HIL GPS message even if not in HIL mode - * - * If set to 1 incoming HIL GPS messages are parsed. - * - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); - -/** - * Forward external setpoint messages - * - * If set to 1 incoming external setpoint messages will be directly forwarded - * to the controllers if in offboard control mode - * - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); - -/** - * Test parameter - * - * This parameter is not actively used by the system. Its purpose is to allow - * testing the parameter interface on the communication level. - * - * @group MAVLink - * @min -1000 - * @max 1000 - */ -PARAM_DEFINE_INT32(MAV_TEST_PAR, 1); - mavlink_system_t mavlink_system = { 100, 50 diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c new file mode 100644 index 0000000000..4edaa7b582 --- /dev/null +++ b/src/modules/mavlink/mavlink_params.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 + +/** + * MAVLink system ID + * @group MAVLink + * @min 1 + * @max 250 + */ +PARAM_DEFINE_INT32(MAV_SYS_ID, 1); + +/** + * MAVLink component ID + * @group MAVLink + * @min 1 + * @max 250 + */ +PARAM_DEFINE_INT32(MAV_COMP_ID, 1); + +/** + * MAVLink Radio ID + * + * When non-zero the MAVLink app will attempt to configure the + * radio to this ID and re-set the parameter to 0. If the value + * is negative it will reset the complete radio config to + * factory defaults. + * + * @group MAVLink + * @min -1 + * @max 240 + */ +PARAM_DEFINE_INT32(MAV_RADIO_ID, 0); + +/** + * MAVLink airframe type + * + * @min 1 + * @group MAVLink + */ +PARAM_DEFINE_INT32(MAV_TYPE, 1); + +/** + * Use/Accept HIL GPS message even if not in HIL mode + * + * If set to 1 incoming HIL GPS messages are parsed. + * + * @group MAVLink + */ +PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); + +/** + * Forward external setpoint messages + * + * If set to 1 incoming external setpoint messages will be directly forwarded + * to the controllers if in offboard control mode + * + * @group MAVLink + */ +PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); + +/** + * Test parameter + * + * This parameter is not actively used by the system. Its purpose is to allow + * testing the parameter interface on the communication level. + * + * @group MAVLink + * @min -1000 + * @max 1000 + */ +PARAM_DEFINE_INT32(MAV_TEST_PAR, 1); + diff --git a/src/modules/muorb/adsp/px4muorb.cpp b/src/modules/muorb/adsp/px4muorb.cpp index 53318f8e49..df951eb967 100644 --- a/src/modules/muorb/adsp/px4muorb.cpp +++ b/src/modules/muorb/adsp/px4muorb.cpp @@ -31,38 +31,30 @@ * ****************************************************************************/ #include "px4muorb.hpp" -//#include "qurt.h" #include "uORBFastRpcChannel.hpp" #include "uORBManager.hpp" #include #include #include -#include -#include +#include #include "px4_log.h" #include "uORB/topics/sensor_combined.h" #include "uORB.h" -#define _ENABLE_MUORB 1 - -extern "C" { -int dspal_main(int argc, const char *argv[]); -void HAP_power_request(int a, int b, int c); -}; - +__BEGIN_DECLS +extern int dspal_main(int argc, char *argv[]); +__END_DECLS int px4muorb_orb_initialize() { - int rc = 0; - PX4_WARN("Before calling dspal_entry() method..."); HAP_power_request(100, 100, 1000); // register the fastrpc muorb with uORBManager. uORB::Manager::get_instance()->set_uorb_communicator(uORB::FastRpcChannel::GetInstance()); - const char *argv[2] = { "dspal", "start" }; + const char *argv[] = { "dspal", "start" }; int argc = 2; - dspal_main(argc, argv); - PX4_WARN("After calling dspal_entry"); + int rc; + rc = dspal_main(argc, (char **)argv); return rc; } @@ -102,7 +94,6 @@ int px4muorb_remove_subscriber(const char *name) } return rc; - } int px4muorb_send_topic_data(const char *name, const uint8_t *data, int data_len_in_bytes) diff --git a/src/modules/sdlog2/CMakeLists.txt b/src/modules/sdlog2/CMakeLists.txt index b438f30fd5..1e33df2a86 100644 --- a/src/modules/sdlog2/CMakeLists.txt +++ b/src/modules/sdlog2/CMakeLists.txt @@ -44,6 +44,7 @@ px4_add_module( SRCS sdlog2.c logbuffer.c + params.c DEPENDS platforms__common ) diff --git a/src/modules/sdlog2/params.c b/src/modules/sdlog2/params.c new file mode 100644 index 0000000000..77575e2ad3 --- /dev/null +++ b/src/modules/sdlog2/params.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 + +/** + * Logging rate. + * + * A value of -1 indicates the commandline argument + * should be obeyed. A value of 0 sets the minimum rate, + * any other value is interpreted as rate in Hertz. This + * parameter is only read out before logging starts (which + * commonly is before arming). + * + * @min -1 + * @max 1 + * @group SD Logging + */ +PARAM_DEFINE_INT32(SDLOG_RATE, -1); + +/** + * Enable extended logging mode. + * + * A value of -1 indicates the commandline argument + * should be obeyed. A value of 0 disables extended + * logging mode, a value of 1 enables it. This + * parameter is only read out before logging starts + * (which commonly is before arming). + * + * @min -1 + * @max 1 + * @group SD Logging + */ +PARAM_DEFINE_INT32(SDLOG_EXT, -1); + +/** + * Use timestamps only if GPS 3D fix is available + * + * A value of 1 constrains the log folder creation + * to only use the time stamp if a 3D GPS lock is + * present. + * + * @min 0 + * @max 1 + * @group SD Logging + */ +PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1); diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index efb33c3da7..94719380f1 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -124,49 +124,6 @@ #define PX4_EPOCH_SECS 1234567890L -/** - * Logging rate. - * - * A value of -1 indicates the commandline argument - * should be obeyed. A value of 0 sets the minimum rate, - * any other value is interpreted as rate in Hertz. This - * parameter is only read out before logging starts (which - * commonly is before arming). - * - * @min -1 - * @max 1 - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_RATE, -1); - -/** - * Enable extended logging mode. - * - * A value of -1 indicates the commandline argument - * should be obeyed. A value of 0 disables extended - * logging mode, a value of 1 enables it. This - * parameter is only read out before logging starts - * (which commonly is before arming). - * - * @min -1 - * @max 1 - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_EXT, -1); - -/** - * Use timestamps only if GPS 3D fix is available - * - * A value of 1 constrains the log folder creation - * to only use the time stamp if a 3D GPS lock is - * present. - * - * @min 0 - * @max 1 - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1); - #define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \ log_msgs_written++; \ } else { \ diff --git a/src/platforms/qurt/px4_layer/CMakeLists.txt b/src/platforms/qurt/px4_layer/CMakeLists.txt index c9720b7e8e..dcd217c05c 100644 --- a/src/platforms/qurt/px4_layer/CMakeLists.txt +++ b/src/platforms/qurt/px4_layer/CMakeLists.txt @@ -38,6 +38,7 @@ set(QURT_LAYER_SRCS drv_hrt.c qurt_stubs.c main.cpp + params.c ) if ("${QURT_ENABLE_STUBS}" STREQUAL "1") list(APPEND QURT_LAYER_SRCS diff --git a/src/platforms/qurt/px4_layer/main.cpp b/src/platforms/qurt/px4_layer/main.cpp index ba2374dcfd..15907ded78 100644 --- a/src/platforms/qurt/px4_layer/main.cpp +++ b/src/platforms/qurt/px4_layer/main.cpp @@ -1,6 +1,5 @@ /**************************************************************************** - * - * Copyright (C) 2015 Mark Charlebois. All rights reserved. + * Copyright (C) 2015 Mark Charlebois. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -42,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -100,15 +100,6 @@ static void process_commands(map &apps, const char *cmds) bool found_first_char = false; char arg[256]; - // This is added because it is a parameter used by commander, yet created by mavlink. Since mavlink is not - // running on QURT, we need to manually define it so it is available to commander. "2" is for quadrotor. - - // Following is hack to prevent duplicate parameter definition error in param parser - /** - * @board QuRT_App - */ - PARAM_DEFINE_INT32(MAV_TYPE,2); - // Eat leading whitespace eat_whitespace(b, i); @@ -152,7 +143,7 @@ extern void init_once(void); }; __BEGIN_DECLS -extern int dspal_main(int argc, char *argv[]); +int dspal_main(int argc, char *argv[]); __END_DECLS @@ -164,13 +155,13 @@ int dspal_entry( int argc, char* argv[] ) px4::init_once(); px4::init(argc, (char **)argv, "mainapp"); process_commands(apps, get_commands()); - usleep( 1000000 ); // give time for all commands to execute before starting external function + sleep(1); // give time for all commands to execute before starting external function if(qurt_external_hook) { qurt_external_hook(); } - for( ;; ){ - usleep( 1000000 ); + for(;;){ + sleep(1); } return 0; } diff --git a/src/platforms/qurt/px4_layer/params.c b/src/platforms/qurt/px4_layer/params.c new file mode 100644 index 0000000000..3ad35a6a12 --- /dev/null +++ b/src/platforms/qurt/px4_layer/params.c @@ -0,0 +1,43 @@ +/**************************************************************************** + * Copyright (C) 2015 Mark Charlebois. 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 + +// This is added because it is a parameter used by commander, yet created by mavlink. Since mavlink is not +// running on QURT, we need to manually define it so it is available to commander. "2" is for quadrotor. + +// Following is hack to prevent duplicate parameter definition error in param parser +/** + * @board QuRT_App + */ +PARAM_DEFINE_INT32(MAV_TYPE,2); + diff --git a/src/platforms/qurt/px4_layer/qurt_stubs.c b/src/platforms/qurt/px4_layer/qurt_stubs.c index 9764710fa0..1ec8f2e71f 100644 --- a/src/platforms/qurt/px4_layer/qurt_stubs.c +++ b/src/platforms/qurt/px4_layer/qurt_stubs.c @@ -31,107 +31,90 @@ * ****************************************************************************/ #include "px4_log.h" -//extern "C" { -void block_indefinite( void ); -void _Read_uleb( void ); -void _Parse_fde_instr( void ); -void _Parse_csd( void ); -void _Valbytes( void ); -void _Get_eh_data( void ); -void _Parse_lsda( void ); -void __cxa_guard_release( void ); -void _Read_enc_ptr( void ); -void _Read_sleb( void ); -void __cxa_guard_acquire( void ); -void __cxa_pure_virtual( void ); +#include + +void block_indefinite(void); +void _Read_uleb(void); +void _Parse_fde_instr(void); +void _Parse_csd(void); +void _Valbytes(void); +void _Get_eh_data(void); +void _Parse_lsda(void); +void __cxa_guard_release(void); +void _Read_enc_ptr(void); +void _Read_sleb(void); +void __cxa_guard_acquire(void); +void __cxa_pure_virtual(void); void block_indefinite( void ) { - for(;;) - { - volatile int x = 0; - ++x; - } + sem_t forever; + sem_init(&forever, 0, 0); + sem_wait(&forever); } void _Read_uleb( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Parse_fde_instr( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Parse_csd( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } -#if 0 -void _Locksyslock( int x ) -{ - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); -} - -void _Unlocksyslock( int x ) -{ - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); -} -#endif - void _Valbytes( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Get_eh_data( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Parse_lsda( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void __cxa_guard_release( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Read_enc_ptr( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void _Read_sleb( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void __cxa_guard_acquire( void ) { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } void __cxa_pure_virtual() { - PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); - block_indefinite(); + PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ ); + block_indefinite(); } - -//} diff --git a/src/platforms/qurt/stubs/stubs_qurt.c b/src/platforms/qurt/stubs/stubs_qurt.c index 0fb8ac71bf..f114791c4d 100644 --- a/src/platforms/qurt/stubs/stubs_qurt.c +++ b/src/platforms/qurt/stubs/stubs_qurt.c @@ -1,4 +1,6 @@ +#include #include +#include void HAP_debug(const char *msg, int level, const char *filename, int line) {