forked from Archive/PX4-Autopilot
cmake: changes required for qurt build
Fixed CMakeLists.txt to be consistent with module.mk Converted PX4_TICKS_PER_SEC to define for QURT to get around relocation error Added stubs for QURT so building a full executable can be tested. This will enable CI testing without the full Hexagon SDK. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
5a59d7d74f
commit
9c376119d0
2
Makefile
2
Makefile
|
@ -24,7 +24,7 @@ posix-sitl_simple:
|
|||
|
||||
qurt-hil_simple:
|
||||
mkdir -p $d/build_$@ && cd $d/build_$@ && \
|
||||
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-hexagon.cmake \
|
||||
cmake .. -DQURT_ENABLE_STUBS=1 -DCMAKE_TOOLCHAIN_FILE=../cmake/Toolchain-hexagon.cmake \
|
||||
-DOS=qurt -DBOARD=hil -DLABEL=simple && \
|
||||
make -s && ctest -V && cpack -G ZIP
|
||||
|
||||
|
|
|
@ -6,7 +6,6 @@ function(px4_set_config_modules out_module_list)
|
|||
drivers/led
|
||||
drivers/rgbled
|
||||
modules/sensors
|
||||
modules/uORB
|
||||
|
||||
# drivers/blinkm
|
||||
# drivers/ms5611
|
||||
|
@ -60,6 +59,7 @@ function(px4_set_config_modules out_module_list)
|
|||
#
|
||||
# QuRT port
|
||||
#
|
||||
platforms/common
|
||||
platforms/qurt/px4_layer
|
||||
platforms/posix/work_queue
|
||||
# platforms/posix/drivers/accelsim
|
||||
|
|
|
@ -104,8 +104,7 @@ function(px4_qurt_generate_builtin_commands)
|
|||
math(EXPR command_count "${command_count}+1")
|
||||
endif()
|
||||
endforeach()
|
||||
configure_file(${CMAKE_SOURCE_DIR}/cmake/qurt/apps.h_in
|
||||
${OUT})
|
||||
configure_file(${CMAKE_SOURCE_DIR}/cmake/qurt/apps.h_in ${OUT})
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
|
|
|
@ -7,9 +7,6 @@ message(STATUS "module list: ${module_dir_list}")
|
|||
|
||||
include_directories(${CMAKE_CURRENT_BINARY_DIR})
|
||||
|
||||
#add_custom_command(OUTPUT apps.h
|
||||
# COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_SOURCE_DIR}/Tools/posix_apps.py > apps.h)
|
||||
|
||||
foreach(directory ${module_dir_list})
|
||||
message(STATUS "directory: ${directory}")
|
||||
px4_mangle_name(${directory} mangled_name)
|
||||
|
|
|
@ -15,8 +15,9 @@ foreach(directory ${module_dir_list})
|
|||
list(APPEND module_list
|
||||
${mangled_name})
|
||||
endforeach()
|
||||
|
||||
px4_qurt_generate_builtin_commands(
|
||||
OUT apps.h
|
||||
OUT ${CMAKE_BINARY_DIR}/apps.h
|
||||
MODULE_LIST ${module_list})
|
||||
|
||||
# FIXME @jgoppert - how to work around issues like this?
|
||||
|
@ -25,9 +26,22 @@ px4_qurt_generate_builtin_commands(
|
|||
set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")
|
||||
set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "")
|
||||
|
||||
add_library(mainapp
|
||||
${CMAKE_SOURCE_DIR}/src/platforms/qurt/px4_layer/main.cpp
|
||||
apps.h)
|
||||
# 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("${QURT_ENABLE_STUBS}" STREQUAL "1")
|
||||
add_library(mainapp
|
||||
${CMAKE_SOURCE_DIR}/src/platforms/qurt/dspal/dspal_stub.c
|
||||
${CMAKE_BINARY_DIR}/apps.h)
|
||||
endif()
|
||||
|
||||
set(main_link_flags
|
||||
"-T${CMAKE_SOURCE_DIR}/cmake/posix/ld.script"
|
||||
)
|
||||
px4_join(OUT main_link_flags LIST ${main_link_flags} GLUE " ")
|
||||
set_target_properties(mainapp PROPERTIES LINK_FLAGS ${main_link_flags})
|
||||
|
||||
target_link_libraries(mainapp
|
||||
-Wl,--whole-archive
|
||||
|
|
|
@ -63,6 +63,11 @@ elseif(${OS} STREQUAL "posix-arm")
|
|||
uORBManager_posix.cpp
|
||||
uORBTest_UnitTest.cpp
|
||||
)
|
||||
elseif(${OS} STREQUAL "qurt")
|
||||
list(APPEND SRCS
|
||||
uORBDevices_posix.cpp
|
||||
uORBManager_posix.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
|
|
|
@ -144,9 +144,13 @@ typedef param_t px4_param_t;
|
|||
/* FIXME - Used to satisfy build */
|
||||
#define getreg32(a) (*(volatile uint32_t *)(a))
|
||||
|
||||
#ifdef __PX4_QURT
|
||||
#define PX4_TICKS_PER_SEC 1000L
|
||||
#else
|
||||
__BEGIN_DECLS
|
||||
extern long PX4_TICKS_PER_SEC;
|
||||
__END_DECLS
|
||||
#endif
|
||||
|
||||
#define USEC_PER_TICK (1000000UL/PX4_TICKS_PER_SEC)
|
||||
#define USEC2TICK(x) (((x)+(USEC_PER_TICK/2))/USEC_PER_TICK)
|
||||
|
|
|
@ -33,20 +33,16 @@
|
|||
#include <stdio.h>
|
||||
#include <dlfcn.h>
|
||||
|
||||
#define STACK_SIZE 0x8000
|
||||
static char __attribute__ ((aligned (16))) stack1[STACK_SIZE];
|
||||
//#define STACK_SIZE 0x8000
|
||||
//static char __attribute__ ((aligned (16))) stack1[STACK_SIZE];
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
static void do_dlopen()
|
||||
{
|
||||
int ret = 0;
|
||||
char *builtin[]={"libgcc.so", "libc.so", "libstdc++.so"};
|
||||
#if 0
|
||||
void *handle;
|
||||
char *error;
|
||||
void (*entry_function)() = NULL;
|
||||
|
||||
printf("In DSPAL main\n");
|
||||
dlinit(3, builtin);
|
||||
#if 0
|
||||
handle = dlopen ("libdspal_client.so", RTLD_LAZY);
|
||||
if (!handle) {
|
||||
printf("Error opening libdspal_client.so\n");
|
||||
|
@ -59,6 +55,18 @@ int main(int argc, char* argv[])
|
|||
}
|
||||
dlclose(handle);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
int ret = 0;
|
||||
char *builtin[]={"libgcc.so", "libc.so", "libstdc++.so"};
|
||||
|
||||
printf("In DSPAL main\n");
|
||||
dlinit(3, builtin);
|
||||
|
||||
do_dlopen();
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
|
|
@ -30,17 +30,31 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
set(QURT_LAYER_SRCS
|
||||
px4_qurt_impl.cpp
|
||||
px4_qurt_tasks.cpp
|
||||
lib_crc32.c
|
||||
drv_hrt.c
|
||||
qurt_stubs.c
|
||||
main.cpp
|
||||
)
|
||||
if ("${QURT_ENABLE_STUBS}" STREQUAL "1")
|
||||
list(APPEND QURT_LAYER_SRCS
|
||||
../stubs/stubs_posix.c
|
||||
../stubs/stubs_qurt.c
|
||||
)
|
||||
endif()
|
||||
|
||||
set(CONFIG_SRC commands_${BOARD}.c)
|
||||
|
||||
px4_add_module(
|
||||
MODULE platforms__qurt__px4_layer
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
px4_qurt_impl.cpp
|
||||
px4_qurt_tasks.cpp
|
||||
lib_crc32.c
|
||||
drv_hrt.c
|
||||
qurt_stubs.c
|
||||
main.cpp
|
||||
${QURT_LAYER_SRCS}
|
||||
${CONFIG_SRC}
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
* @author Mark Charlebois <charlebm@gmail.com>
|
||||
*/
|
||||
|
||||
const char *get_commands(void);
|
||||
const char *get_commands()
|
||||
{
|
||||
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
#include <string>
|
||||
#include <map>
|
||||
#include <stdio.h>
|
||||
#include <apps.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
|
@ -100,18 +101,17 @@ static void process_commands(map<string,px4_main_t> &apps, const char *cmds)
|
|||
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.
|
||||
// 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
|
||||
*/
|
||||
// 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);
|
||||
|
||||
|
||||
for(;;) {
|
||||
// End of command line
|
||||
if (b[i] == '\n' || b[i] == '\0') {
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
__BEGIN_DECLS
|
||||
extern uint64_t get_ticks_per_us();
|
||||
|
||||
long PX4_TICKS_PER_SEC = 1000;
|
||||
//long PX4_TICKS_PER_SEC = 1000L;
|
||||
|
||||
unsigned int sleep(unsigned int sec)
|
||||
{
|
||||
|
|
|
@ -32,6 +32,18 @@
|
|||
****************************************************************************/
|
||||
#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 );
|
||||
|
||||
void block_indefinite( void )
|
||||
{
|
||||
|
@ -71,7 +83,8 @@ void _Unlocksyslock( int x )
|
|||
{
|
||||
PX4_WARN( "Error: Calling unresolved symbol stub[%s]", __FUNCTION__ );
|
||||
block_indefinite();
|
||||
#endif}
|
||||
}
|
||||
#endif
|
||||
|
||||
void _Valbytes( void )
|
||||
{
|
||||
|
|
|
@ -0,0 +1,99 @@
|
|||
#include <semaphore.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <signal.h>
|
||||
#include <time.h>
|
||||
|
||||
int sem_init(sem_t *sem, int pshared, unsigned int value)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int sem_wait(sem_t *sem)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int sem_destroy(sem_t *sem)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int sem_post(sem_t *sem)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int sem_getvalue(sem_t *sem, int *sval)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int usleep(useconds_t usec)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
pthread_t pthread_self(void)
|
||||
{
|
||||
pthread_t x = 0;
|
||||
return x;
|
||||
}
|
||||
|
||||
|
||||
int pthread_kill(pthread_t thread, int sig)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
void pthread_exit(void *retval)
|
||||
{
|
||||
}
|
||||
|
||||
int pthread_join(pthread_t thread, void **retval)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_cancel(pthread_t thread)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
int pthread_attr_init(pthread_attr_t *attr)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_attr_setstacksize(pthread_attr_t *attr, size_t stacksize)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_attr_getstacksize(const pthread_attr_t *attr, size_t *stacksize)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_attr_setschedparam(pthread_attr_t *attr, const struct sched_param *param)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_create(pthread_t *thread, const pthread_attr_t *attr, void *(*start_routine) (void *), void *arg)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
int pthread_attr_getschedparam(const pthread_attr_t *attr, struct sched_param *param)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pthread_attr_destroy(pthread_attr_t *attr)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
int clock_gettime(clockid_t clk_id, struct timespec *tp)
|
||||
{
|
||||
return 1;
|
||||
}
|
|
@ -0,0 +1,14 @@
|
|||
#include <qurt_log.h>
|
||||
|
||||
void HAP_debug(const char *msg, int level, const char *filename, int line)
|
||||
{
|
||||
}
|
||||
|
||||
void HAP_power_request(int a, int b, int c)
|
||||
{
|
||||
}
|
||||
|
||||
int dlinit(int a, char **b)
|
||||
{
|
||||
return 1;
|
||||
}
|
Loading…
Reference in New Issue