Skip to content

Commit

Permalink
Added experimental LTO kconfig option
Browse files Browse the repository at this point in the history
  • Loading branch information
PetervdPerk-NXP authored and dagar committed May 2, 2022
1 parent 8da02e2 commit 108c98a
Show file tree
Hide file tree
Showing 6 changed files with 26 additions and 11 deletions.
10 changes: 9 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@
#
#=============================================================================

cmake_minimum_required(VERSION 3.2 FATAL_ERROR)
cmake_minimum_required(VERSION 3.9 FATAL_ERROR)

set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}" CACHE FILEPATH "PX4 source directory" FORCE)
set(PX4_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}" CACHE FILEPATH "PX4 binary directory" FORCE)
Expand Down Expand Up @@ -234,6 +234,14 @@ message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
#
project(px4 CXX C ASM)

# Check if LTO option and check if toolchain supports it
if(LTO)
include(CheckIPOSupported)
check_ipo_supported()
message(AUTHOR_WARNING "LTO enabled: LTO is highly experimental and should not be used in production")
set(CMAKE_INTERPROCEDURAL_OPTIMIZATION TRUE)
endif()

set(package-contact "[email protected]")

set(CMAKE_CXX_STANDARD 14)
Expand Down
7 changes: 7 additions & 0 deletions Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,13 @@ menu "Toolchain"
string "Architecture"
default ""

config BOARD_LTO
bool "(EXPERIMENTAL) Link Time Optimization (LTO)"
default n
help
Enables LTO flag in linker
Note: Highly EXPERIMENTAL, furthermore make sure you're using a modern compiler GCC 9 or later

config BOARD_FULL_OPTIMIZATION
bool "Full optmization (O3)"
default n
Expand Down
2 changes: 1 addition & 1 deletion src/modules/mc_pos_control/MulticopterPositionControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class MulticopterPositionControl : public ModuleBase<MulticopterPositionControl>
private:
void Run() override;

Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */
TakeoffHandling _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */

orb_advert_t _mavlink_log_pub{nullptr};

Expand Down
8 changes: 4 additions & 4 deletions src/modules/mc_pos_control/Takeoff/Takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>

void Takeoff::generateInitialRampValue(float velocity_p_gain)
void TakeoffHandling::generateInitialRampValue(float velocity_p_gain)
{
velocity_p_gain = math::max(velocity_p_gain, 0.01f);
_takeoff_ramp_vz_init = -CONSTANTS_ONE_G / velocity_p_gain;
}

void Takeoff::updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff,
const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
void TakeoffHandling::updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff,
const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
{
_spoolup_time_hysteresis.set_state_and_update(armed, now_us);

Expand Down Expand Up @@ -109,7 +109,7 @@ void Takeoff::updateTakeoffState(const bool armed, const bool landed, const bool
}
}

float Takeoff::updateRamp(const float dt, const float takeoff_desired_vz)
float TakeoffHandling::updateRamp(const float dt, const float takeoff_desired_vz)
{
float upwards_velocity_limit = takeoff_desired_vz;

Expand Down
6 changes: 3 additions & 3 deletions src/modules/mc_pos_control/Takeoff/Takeoff.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,11 @@ enum class TakeoffState {
flight = takeoff_status_s::TAKEOFF_STATE_FLIGHT
};

class Takeoff
class TakeoffHandling
{
public:
Takeoff() = default;
~Takeoff() = default;
TakeoffHandling() = default;
~TakeoffHandling() = default;

// initialize parameters
void setSpoolupTime(const float seconds) { _spoolup_time_hysteresis.set_hysteresis_time_from(false, seconds * 1_s); }
Expand Down
4 changes: 2 additions & 2 deletions src/modules/mc_pos_control/Takeoff/TakeoffTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,13 @@

TEST(TakeoffTest, Initialization)
{
Takeoff takeoff;
TakeoffHandling takeoff;
EXPECT_EQ(takeoff.getTakeoffState(), TakeoffState::disarmed);
}

TEST(TakeoffTest, RegularTakeoffRamp)
{
Takeoff takeoff;
TakeoffHandling takeoff;
takeoff.setSpoolupTime(1.f);
takeoff.setTakeoffRampTime(2.0);
takeoff.generateInitialRampValue(CONSTANTS_ONE_G / 0.5f);
Expand Down

0 comments on commit 108c98a

Please sign in to comment.