Skip to content

Commit

Permalink
Try adding CMake
Browse files Browse the repository at this point in the history
* Mavlink generates headers at build time
* Ardupilot waf using different tooling and they end up in a different
  path
* Perhaps add a custom target that copies them to the new path that
  occurs at build time

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Sep 14, 2024
1 parent fc2f518 commit bd69024
Show file tree
Hide file tree
Showing 9 changed files with 231 additions and 14 deletions.
9 changes: 9 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# cmake -B build -DCONFIG_HAL_BOARD=3
# cmake --build build
cmake_minimum_required(VERSION 3.23)
project(ardupilot)

add_subdirectory(modules/mavlink)
add_subdirectory(libraries)


49 changes: 49 additions & 0 deletions libraries/AP_Common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
get_filename_component(_library_path ${CMAKE_CURRENT_SOURCE_DIR} DIRECTORY)
file(RELATIVE_PATH _lib_name ${_library_path} ${CMAKE_CURRENT_SOURCE_DIR})
add_library(${_lib_name})
add_library(${PROJECT_NAME}::${_lib_name} ALIAS ${_lib_name})

# ls -1 *.h
list(APPEND _headers
AP_Common.h
AP_ExpandingArray.h
AP_FWVersionDefine.h
AP_FWVersion.h
AP_Test.h
Bitmask.h
ExpandingString.h
float16.h
Location.h
MultiHeap.h
NMEA.h
sorting.h
time.h
TSIndex.h
)
# ls -1 *.cpp
list(APPEND _sources
AP_Common.cpp
AP_ExpandingArray.cpp
AP_FWVersion.cpp
c++.cpp
ExpandingString.cpp
float16.cpp
Location.cpp
MultiHeap.cpp
NMEA.cpp
sorting.cpp
time.cpp
)
target_sources(AP_Common PUBLIC
${_headers}
PRIVATE
${_sources}
)

target_link_libraries(${_lib_name} PUBLIC ${PROJECT_NAME}::AP_HAL ${PROJECT_NAME}::GCS_MAVLink)

target_compile_options(${_lib_name}
PUBLIC
"-fsingle-precision-constant"
)

6 changes: 5 additions & 1 deletion libraries/AP_HAL/AP_HAL_Boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@

/* DEFINITIONS FOR BOARDS */

#define CONFIG_HAL_BOARD HAL_BOARD_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL/board/sitl.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
Expand All @@ -143,9 +144,12 @@
#elif CONFIG_HAL_BOARD == HAL_BOARD_QURT
#include <AP_HAL/board/qurt.h>
#else
#error "Unknown CONFIG_HAL_BOARD type"
#define XSTR(x) STR(x)
#define STR(x) #x
#error "Unknown CONFIG_HAL_BOARD type of " XSTR(CONFIG_HAL_BOARD)
#endif

#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_LINUX_NONE
#ifndef CONFIG_HAL_BOARD_SUBTYPE
#error "No CONFIG_HAL_BOARD_SUBTYPE set"
#endif
Expand Down
71 changes: 71 additions & 0 deletions libraries/AP_HAL/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
get_filename_component(_library_path ${CMAKE_CURRENT_SOURCE_DIR} DIRECTORY)
file(RELATIVE_PATH _lib_name ${_library_path} ${CMAKE_CURRENT_SOURCE_DIR})
add_library(${_lib_name})
add_library(${PROJECT_NAME}::${_lib_name} ALIAS ${_lib_name})

# ls -1 *.h
list(APPEND _headers
AnalogIn.h
AP_HAL_Boards.h
AP_HAL.h
AP_HAL_Macros.h
AP_HAL_Main.h
AP_HAL_Namespace.h
CANIface.h
Device.h
DSP.h
Flash.h
GPIO.h
HAL.h
I2CDevice.h
LogStructure.h
OpticalFlow.h
RCInput.h
RCOutput.h
Scheduler.h
Semaphores.h
SIMState.h
SPIDevice.h
Storage.h
system.h
UARTDriver.h
Util.h
WSPIDevice.h
)
# ls -1 *.cpp
list(APPEND _sources
CANIface.cpp
Device.cpp
DSP.cpp
GPIO.cpp
HAL.cpp
RCOutput.cpp
Scheduler.cpp
Semaphores.cpp
SIMState.cpp
Storage.cpp
system.cpp
UARTDriver.cpp
Util.cpp
)
target_sources(${_lib_name}
PUBLIC
FILE_SET
HEADERS
BASE_DIRS ".."
FILES
${_headers}
PRIVATE
${_sources}
)

# option(CONFIG_HAL_BOARD "Which board type" "CONFIG_HAL_LINUX")
target_compile_definitions(${_lib_name}
PUBLIC
# CONFIG_HAL_BOARD=3
CONFIG_HAL_BOARD=HAL_BOARD_SITL
CONFIG_HAL_BOARD_SUBTYPE=HAL_BOARD_SUBTYPE_LINUX_NONE
__AP_LINE__=__LINE__
HAL_LOGGING_ENABLED=0
ENABLE_HEAP=1
)
6 changes: 3 additions & 3 deletions libraries/AP_HAL/DSP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
#include <AP_Math/AP_Math.h>
#include "AP_HAL.h"
#include "DSP.h"
#ifndef HAL_NO_UARTDRIVER
#include <GCS_MAVLink/GCS.h>
#endif
// #ifndef HAL_NO_UARTDRIVER
// #include <GCS_MAVLink/GCS.h>
// #endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <assert.h>
#endif
Expand Down
18 changes: 9 additions & 9 deletions libraries/AP_HAL/GPIO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <AP_HAL/AP_HAL.h>

#include <GCS_MAVLink/GCS.h>
// #include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand All @@ -24,10 +24,10 @@ bool AP_HAL::PWMSource::set_pin(int16_t new_pin, const char *subsystem)

if (interrupt_attached) {
if (!hal.gpio->detach_interrupt(_pin)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"%s: Failed to detach interrupt from %d",
subsystem,
_pin);
// GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
// "%s: Failed to detach interrupt from %d",
// subsystem,
// _pin);
}
interrupt_attached = false;
}
Expand All @@ -51,10 +51,10 @@ bool AP_HAL::PWMSource::set_pin(int16_t new_pin, const char *subsystem)
uint32_t),
AP_HAL::GPIO::INTERRUPT_BOTH)) {
// failed to attach interrupt
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"%s: Failed to attach interrupt to %d",
subsystem,
_pin);
// GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
// "%s: Failed to attach interrupt to %d",
// subsystem,
// _pin);
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Mission/AP_Mission.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "AP_Mission_config.h"

#include <GCS_MAVLink/GCS_MAVLink.h>
// #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
Expand Down
3 changes: 3 additions & 0 deletions libraries/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
add_subdirectory(AP_HAL)
add_subdirectory(AP_Common)
add_subdirectory(GCS_MAVLink)
81 changes: 81 additions & 0 deletions libraries/GCS_MAVLink/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@

get_filename_component(_library_path ${CMAKE_CURRENT_SOURCE_DIR} DIRECTORY)
unset(_lib_name)
file(RELATIVE_PATH _lib_name ${_library_path} ${CMAKE_CURRENT_SOURCE_DIR})
add_library(${_lib_name})
add_library(${PROJECT_NAME}::${_lib_name} ALIAS ${_lib_name})

# ls -1 *.h
list(APPEND _headers
ap_message.h
GCS_config.h
GCS_Dummy.h
GCS.h
GCS_MAVLink.h
MAVLink_routing.h
MissionItemProtocol_Fence.h
MissionItemProtocol.h
MissionItemProtocol_Rally.h
MissionItemProtocol_Waypoints.h
)
# ls -1 *.cpp
list(APPEND _sources
GCS_Common.cpp
GCS.cpp
GCS_DeviceOp.cpp
GCS_Dummy.cpp
GCS_Fence.cpp
GCS_FTP.cpp
GCS_MAVLink.cpp
GCS_Param.cpp
GCS_Rally.cpp
GCS_serial_control.cpp
GCS_ServoRelay.cpp
GCS_Signing.cpp
MAVLink_routing.cpp
MissionItemProtocol.cpp
MissionItemProtocol_Fence.cpp
MissionItemProtocol_Rally.cpp
MissionItemProtocol_Waypoints.cpp
)
target_sources(${_lib_name}
PUBLIC
FILE_SET
HEADERS
BASE_DIRS ".."
FILES
${_headers}
PRIVATE
${_sources}
)

option(CONFIG_HAL_BOARD "Which board type" 3)

set(_mavlink_bindir ${PROJECT_BINARY_DIR}/modules/mavlink)
set(_mavlink_incdir ${_mavlink_bindir}/ardu_include)
target_include_directories(${_lib_name}
PUBLIC
${_mavlink_incdir}
# $<BUILD_INTERFACE:>
)
include(CMakePrintHelpers)

cmake_print_properties(TARGETS ${_lib_name} PROPERTIES
INCLUDE_DIRECTORIES)

# target_link_libraries(${_lib_name} PUBLIC common.xml-v2.0) # This doesn't work

add_dependencies(${_lib_name} _mavlink_intermediate)

add_custom_target(_mavlink_intermediate DEPENDS common.xml-v2.0 all-xml-v1.0) # Unclear how to get all.xml

add_custom_command(
TARGET _mavlink_intermediate
POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy_directory
${_mavlink_bindir}/include
${_mavlink_incdir}/include/mavlink # The weird include path in ArduPilot source code.
)

# have build/modules/mavlink/ include/v2.0/common/version.h
# need build/modules/mavlink/ include/mavlink/v2.0/common/version.h

0 comments on commit bd69024

Please sign in to comment.