Skip to content

Commit

Permalink
AP_HAL_QURT: Bunch of changes to link everything properly and call th…
Browse files Browse the repository at this point in the history
…e run method
  • Loading branch information
katzfey committed May 21, 2024
1 parent ec9d4c1 commit 2bc85ba
Show file tree
Hide file tree
Showing 5 changed files with 64 additions and 17 deletions.
24 changes: 14 additions & 10 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -1666,8 +1666,7 @@ def configure_env(self, cfg, env):
super(QURT, self).configure_env(cfg, env)

env.BOARD_CLASS = "QURT"
env.HEAXGON_APP = "libardupilot.so"
env.HEXAGON_LINKFLAGS = f"-march=hexagon -mcpu=hexagonv66 -fpic -shared -call_shared -mG0lib -G0 {cfg.env.TOOLCHAIN_DIR}/target/hexagon/lib/v66/G0/pic/initS.o -L{cfg.env.TOOLCHAIN_DIR}/target/hexagon/lib/v66/G0/pic -Bsymbolic {cfg.env.TOOLCHAIN_DIR}/target/hexagon/lib/v66/G0/pic/libgcc.a --wrap=malloc --wrap=calloc --wrap=free --wrap=realloc --wrap=memalign --wrap=__stack_chk_fail -lc -soname={env.HEXAGON_APP} --start-group --whole-archive OBJECT_LIST --end-group --start-group -lgcc --end-group {cfg.env.TOOLCHAIN_DIR}/target/hexagon/lib/v66/G0/pic/finiS.o"
env.HEXAGON_APP = "libardupilot.so"
env.INCLUDES += [cfg.env.HEXAGON_SDK_DIR + "/rtos/qurt/computev66/include/qurt"]
env.INCLUDES += [cfg.env.HEXAGON_SDK_DIR + "/rtos/qurt/computev66/include/posix"]
env.CXXFLAGS += ["-fPIC", "-MD"]
Expand All @@ -1679,6 +1678,18 @@ def configure_env(self, cfg, env):
AP_SIM_ENABLED = 0,
)

# The linking has to be done very precisely for QURT. Below is an example of a
# linker run_str that works correctly. This needs to be modified in the waflib/Tools/cxx.py
# file in the waf submodule

# class cxxprogram(link_task):
# "Links object files into c++ programs"
# # run_str = '${LINK_CXX} ${LINKFLAGS} ${CXXLNK_SRC_F}${SRC} ${CXXLNK_TGT_F}${TGT[0].relpath()} ${RPATH_ST:RPATH} ${FRAMEWORKPATH_ST:FRAMEWORKPATH} ${FRAMEWORK_ST:FRAMEWORK} ${ARCH_ST:ARCH} ${STLIB_MARKER} ${STLIBPATH_ST:STLIBPATH} ${STLIB_ST:STLIB} ${SHLIB_MARKER} ${LIBPATH_ST:LIBPATH} ${LIB_ST:LIB} ${LDFLAGS}'
# run_str = '${LINK_CXX} ${CXXLNK_TGT_F} ${TGT[0].relpath()} ${LINKFLAGS} ${STLIBPATH_ST:STLIBPATH} --start-group --whole-archive ${CXXLNK_SRC_F}${SRC} ${STLIB_ST:STLIB} --end-group --start-group -lgcc --end-group /opt/hexagon-sdk/4.1.0.4-lite/tools/HEXAGON_Tools/8.4.05/Tools/target/hexagon/lib/v66/G0/pic/finiS.o'
# vars = ['LINKDEPS']
# ext_out = ['.bin']
# inst_to = '${BINDIR}'

env.LINKFLAGS = [
"-march=hexagon",
"-mcpu=hexagonv66",
Expand All @@ -1696,14 +1707,7 @@ def configure_env(self, cfg, env):
"--wrap=memalign",
"--wrap=__stack_chk_fail",
"-lc",
f"-soname={cfg.env.HEXAGON_APP}",
"--start-group",
"--whole-archive",
"--end-group",
"--start-group",
"-lgcc",
"--end-group",
cfg.env.TOOLCHAIN_DIR + "/target/hexagon/lib/v66/G0/pic/finiS.o"
"-lc++"
]

if not cfg.env.DEBUG:
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL/board/qurt.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#pragma once

#include <AP_HAL_QURT/AP_HAL_QURT_Main.h>

#define HAL_BOARD_NAME "QURT"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_MEM_CLASS HAL_MEM_CLASS_1000
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_QURT/AP_HAL_QURT_Main.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,6 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once

#define AP_MAIN qurt_arducopter_main

13 changes: 7 additions & 6 deletions libraries/AP_HAL_QURT/HAL_QURT_Class.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,12 +86,13 @@ void HAL_QURT::run(int argc, char* const argv[], Callbacks* callbacks) const
schedulerInstance.hal_initialized();
serial0Driver.begin(115200);
rcinDriver.init();
callbacks->setup();
scheduler->set_system_initialized();

for (;;) {
callbacks->loop();
}
// Runs okay up to here. Next line causes a crash!
// callbacks->setup();
// scheduler->set_system_initialized();
//
// for (;;) {
// callbacks->loop();
// }
}

const AP_HAL::HAL& AP_HAL::get_HAL() {
Expand Down
39 changes: 38 additions & 1 deletion libraries/AP_HAL_QURT/replace.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,9 +133,15 @@ int ArduPilot_main(int argc, const char *argv[])

}

extern "C" int qurt_arducopter_main(int argc, char* const argv[]);

int px4muorb_orb_initialize(fc_func_ptrs *func_ptrs, int32_t clock_offset_us)
{
return 0;
HAP_PRINTF("About to call qurt_arducopter_main %p", &qurt_arducopter_main);

qurt_arducopter_main(0, NULL);

return 0;
}

int px4muorb_topic_advertised(const char *name)
Expand All @@ -162,3 +168,34 @@ float px4muorb_get_cpu_load(void)
{
return 0.0f;
}

extern "C" void free(void *ptr) {
return;
}

// malloc
extern "C" void *malloc(size_t size) {
return NULL;
}

// posix_memalign
extern "C" int posix_memalign(void **memptr, size_t alignment, size_t size) {
return 0;
}

// calloc
extern "C" void *calloc(size_t nmemb, size_t size) {
return NULL;
}


// realloc
extern "C" void *realloc(void *ptr, size_t size) {
return NULL;
}

// nanosleep
#include <time.h>
extern "C" int nanosleep(const struct timespec *req, struct timespec *_Nullable rem) {
return 0;
}

0 comments on commit 2bc85ba

Please sign in to comment.