Skip to content

Commit

Permalink
Merge branch 'main' into dev/sbgecom_driver
Browse files Browse the repository at this point in the history
  • Loading branch information
tolesam authored Jan 15, 2025
2 parents 7627a34 + 974446c commit 53f750e
Show file tree
Hide file tree
Showing 61 changed files with 345 additions and 74 deletions.
9 changes: 2 additions & 7 deletions .github/workflows/dev_container.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ on:
jobs:
build:
name: Build and Push Container
runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false]
runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
steps:
- uses: actions/checkout@v4
with:
Expand Down Expand Up @@ -52,12 +52,7 @@ jobs:
ghcr.io/PX4/px4-dev
${{ (github.event_name != 'pull_request') && 'px4io/px4-dev' || '' }}
tags: |
type=semver,pattern={{version}}
type=semver,pattern={{major}}.{{minor}}
type=semver,pattern={{major}}
type=ref,event=branch,value=${{ steps.px4-tag.outputs.tag }},priority=700
type=ref,event=branch,suffix=-{{date 'YYYY-MM-DD'}},priority=600
type=ref,event=branch,suffix=,priority=500
type=raw,enable=true,value=${{ steps.px4-tag.outputs.tag }},priority=1000
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v3
Expand Down
1 change: 1 addition & 0 deletions ROMFS/px4fmu_common/init.d/rc.heli_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ param set-default MAV_TYPE 4

param set-default COM_PREARM_MODE 2
param set-default COM_SPOOLUP_TIME 10
param set-default COM_DISARM_PRFLT 60

# No need for minimum collective pitch (or airmode) to keep torque authority
param set-default MPC_MANTHR_MIN 0
6 changes: 5 additions & 1 deletion boards/micoair/h743-aio/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,15 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
Expand Down
6 changes: 5 additions & 1 deletion boards/micoair/h743-v2/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,15 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_GOERTEK_SPL06=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
Expand Down
6 changes: 5 additions & 1 deletion boards/micoair/h743/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,15 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
Expand Down
8 changes: 4 additions & 4 deletions msg/PwmInput.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
uint64 timestamp # Time since system start (microseconds)
uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5)
uint32 pulse_width # Pulse width, timer counts
uint32 period # Period, timer counts
uint64 timestamp # Time since system start (microseconds)
uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5)
uint32 pulse_width # Pulse width, timer counts (microseconds)
uint32 period # Period, timer counts (microseconds)
1 change: 1 addition & 0 deletions msg/Rpm.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
uint64 timestamp # time since system start (microseconds)

# rpm values of 0.0 mean within a timeout there is no movement measured
float32 rpm_estimate # filtered revolutions per minute
float32 rpm_raw
1 change: 1 addition & 0 deletions src/lib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ add_subdirectory(cdrstream EXCLUDE_FROM_ALL)
add_subdirectory(circuit_breaker EXCLUDE_FROM_ALL)
add_subdirectory(collision_prevention EXCLUDE_FROM_ALL)
add_subdirectory(component_information EXCLUDE_FROM_ALL)
add_subdirectory(control_allocation EXCLUDE_FROM_ALL)
add_subdirectory(controllib EXCLUDE_FROM_ALL)
add_subdirectory(conversion EXCLUDE_FROM_ALL)
add_subdirectory(crc EXCLUDE_FROM_ALL)
Expand Down
35 changes: 35 additions & 0 deletions src/lib/control_allocation/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
############################################################################
#
# Copyright (c) 2025 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.
#
############################################################################

add_subdirectory(control_allocation)
add_subdirectory(actuator_effectiveness)
Original file line number Diff line number Diff line change
Expand Up @@ -34,42 +34,12 @@
px4_add_library(ActuatorEffectiveness
ActuatorEffectiveness.cpp
ActuatorEffectiveness.hpp
ActuatorEffectivenessUUV.cpp
ActuatorEffectivenessUUV.hpp
ActuatorEffectivenessControlSurfaces.cpp
ActuatorEffectivenessControlSurfaces.hpp
ActuatorEffectivenessCustom.cpp
ActuatorEffectivenessCustom.hpp
ActuatorEffectivenessFixedWing.cpp
ActuatorEffectivenessFixedWing.hpp
ActuatorEffectivenessHelicopter.cpp
ActuatorEffectivenessHelicopter.hpp
ActuatorEffectivenessHelicopterCoaxial.cpp
ActuatorEffectivenessHelicopterCoaxial.hpp
ActuatorEffectivenessMCTilt.cpp
ActuatorEffectivenessMCTilt.hpp
ActuatorEffectivenessMultirotor.cpp
ActuatorEffectivenessMultirotor.hpp
ActuatorEffectivenessTilts.cpp
ActuatorEffectivenessTilts.hpp
ActuatorEffectivenessRotors.cpp
ActuatorEffectivenessRotors.hpp
ActuatorEffectivenessStandardVTOL.cpp
ActuatorEffectivenessStandardVTOL.hpp
ActuatorEffectivenessTiltrotorVTOL.cpp
ActuatorEffectivenessTiltrotorVTOL.hpp
ActuatorEffectivenessTailsitterVTOL.cpp
ActuatorEffectivenessTailsitterVTOL.hpp
ActuatorEffectivenessRoverAckermann.hpp
ActuatorEffectivenessRoverAckermann.cpp
)

target_compile_options(ActuatorEffectiveness PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
target_include_directories(ActuatorEffectiveness PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(ActuatorEffectiveness
PRIVATE
mathlib
PID
)

px4_add_functional_gtest(SRC ActuatorEffectivenessHelicopterTest.cpp LINKLIBS ActuatorEffectiveness)
px4_add_functional_gtest(SRC ActuatorEffectivenessRotorsTest.cpp LINKLIBS ActuatorEffectiveness)
Original file line number Diff line number Diff line change
Expand Up @@ -44,4 +44,4 @@ target_include_directories(ControlAllocation PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(ControlAllocation PRIVATE mathlib)

px4_add_unit_gtest(SRC ControlAllocationPseudoInverseTest.cpp LINKLIBS ControlAllocation)
px4_add_functional_gtest(SRC ControlAllocationSequentialDesaturationTest.cpp LINKLIBS ControlAllocation ActuatorEffectiveness)
# px4_add_functional_gtest(SRC ControlAllocationSequentialDesaturationTest.cpp LINKLIBS ControlAllocation ActuatorEffectiveness)
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@

#include <matrix/matrix/math.hpp>

#include "ActuatorEffectiveness/ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

class ControlAllocation
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

#include <gtest/gtest.h>
#include <ControlAllocationSequentialDesaturation.hpp>
#include <../ActuatorEffectiveness/ActuatorEffectivenessRotors.hpp>
#include <actuator_effectiveness/ActuatorEffectivenessRotors.hpp>

using namespace matrix;

Expand Down
3 changes: 2 additions & 1 deletion src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2268,7 +2268,8 @@ void Commander::handleAutoDisarm()
_auto_disarm_landed.set_state_and_update(_vehicle_land_detected.landed, hrt_absolute_time());

} else if (_param_com_disarm_prflt.get() > 0 && !_have_taken_off_since_arming) {
_auto_disarm_landed.set_hysteresis_time_from(false, _param_com_disarm_prflt.get() * 1_s);
_auto_disarm_landed.set_hysteresis_time_from(false,
(_param_com_spoolup_time.get() + _param_com_disarm_prflt.get()) * 1_s);
_auto_disarm_landed.set_state_and_update(true, hrt_absolute_time());
}

Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,6 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
param_t _param_rc_map_fltmode{PARAM_INVALID};

DEFINE_PARAMETERS(

(ParamFloat<px4::params::COM_DISARM_LAND>) _param_com_disarm_land,
(ParamFloat<px4::params::COM_DISARM_PRFLT>) _param_com_disarm_prflt,
(ParamBool<px4::params::COM_DISARM_MAN>) _param_com_disarm_man,
Expand All @@ -347,6 +346,7 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
(ParamFloat<px4::params::COM_OBC_LOSS_T>) _param_com_obc_loss_t,
(ParamInt<px4::params::COM_PREARM_MODE>) _param_com_prearm_mode,
(ParamInt<px4::params::COM_RC_OVERRIDE>) _param_com_rc_override,
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time,
(ParamInt<px4::params::COM_FLIGHT_UUID>) _param_com_flight_uuid,
(ParamInt<px4::params::COM_TAKEOFF_ACT>) _param_com_takeoff_act,
(ParamFloat<px4::params::COM_CPU_MAX>) _param_com_cpu_max
Expand Down
4 changes: 2 additions & 2 deletions src/modules/control_allocator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@
############################################################################

include_directories(${CMAKE_CURRENT_SOURCE_DIR})
add_subdirectory(ActuatorEffectiveness)
add_subdirectory(ControlAllocation)
add_subdirectory(VehicleActuatorEffectiveness)

px4_add_module(
MODULE modules__control_allocator
Expand All @@ -50,6 +49,7 @@ px4_add_module(
DEPENDS
mathlib
ActuatorEffectiveness
VehicleActuatorEffectiveness
ControlAllocation
px4_work_queue
SlewRate
Expand Down
2 changes: 1 addition & 1 deletion src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -314,7 +314,7 @@ ControlAllocator::Run()
#endif

// Check if parameters have changed
if (_parameter_update_sub.updated() && !_armed) {
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s param_update;
_parameter_update_sub.copy(&param_update);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

#include <px4_platform_common/module_params.h>
#include <lib/slew_rate/SlewRate.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessControlSurfaces.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessControlSurfaces.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,12 @@ void ActuatorEffectivenessHelicopter::updateSetpoint(const matrix::Vector<float,
{
_saturation_flags = {};

const float spoolup_progress = throttleSpoolupProgress();
_rpm_control.setSpoolupProgress(spoolup_progress);

// throttle/collective pitch curve
const float throttle = math::interpolateN(-control_sp(ControlAxis::THRUST_Z),
_geometry.throttle_curve) * throttleSpoolupProgress();
const float throttle = (math::interpolateN(-control_sp(ControlAxis::THRUST_Z),
_geometry.throttle_curve) + _rpm_control.getActuatorCorrection()) * spoolup_progress;
const float collective_pitch = math::interpolateN(-control_sp(ControlAxis::THRUST_Z), _geometry.pitch_curve);

// actuator mapping
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,16 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

#include <px4_platform_common/module_params.h>

#include <uORB/Subscription.hpp>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/manual_control_switches.h>

#include "RpmControl.hpp"

class ActuatorEffectivenessHelicopter : public ModuleParams, public ActuatorEffectiveness
{
public:
Expand Down Expand Up @@ -131,4 +133,6 @@ class ActuatorEffectivenessHelicopter : public ModuleParams, public ActuatorEffe
bool _main_motor_engaged{true};

const ActuatorType _tail_actuator_type;

RpmControl _rpm_control{this};
};
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

#include <px4_platform_common/module_params.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessTilts.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"

class ActuatorEffectivenessMultirotor : public ModuleParams, public ActuatorEffectiveness
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

#include <px4_platform_common/module_params.h>
#include <uORB/Subscription.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"

class ActuatorEffectivenessRoverAckermann : public ActuatorEffectiveness
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessControlSurfaces.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "control_allocation/actuator_effectiveness/ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessControlSurfaces.hpp"

Expand Down
Loading

0 comments on commit 53f750e

Please sign in to comment.