Skip to content

Commit

Permalink
CA: add thust vectoring actuator effectiveness
Browse files Browse the repository at this point in the history
  • Loading branch information
bresch committed Jan 27, 2025
1 parent 07e7c64 commit a16dfa9
Show file tree
Hide file tree
Showing 8 changed files with 185 additions and 0 deletions.
4 changes: 4 additions & 0 deletions src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,6 +270,10 @@ ControlAllocator::update_effectiveness_source()
tmp = new ActuatorEffectivenessHelicopterCoaxial(this);
break;

case EffectivenessSource::THRUST_VECTORING:
tmp = new ActuatorEffectivenessThrustVectoring(this);
break;

default:
PX4_ERR("Unknown airframe");
break;
Expand Down
2 changes: 2 additions & 0 deletions src/modules/control_allocator/ControlAllocator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <ActuatorEffectiveness.hpp>
#include <ActuatorEffectivenessMultirotor.hpp>
#include <ActuatorEffectivenessStandardVTOL.hpp>
#include <ActuatorEffectivenessThrustVectoring.hpp>
#include <ActuatorEffectivenessTiltrotorVTOL.hpp>
#include <ActuatorEffectivenessTailsitterVTOL.hpp>
#include <ActuatorEffectivenessRoverAckermann.hpp>
Expand Down Expand Up @@ -158,6 +159,7 @@ class ControlAllocator : public ModuleBase<ControlAllocator>, public ModuleParam
HELICOPTER_TAIL_ESC = 10,
HELICOPTER_TAIL_SERVO = 11,
HELICOPTER_COAXIAL = 12,
THRUST_VECTORING = 14,
};

enum class FailureMode {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,3 +186,11 @@ void ActuatorEffectivenessControlSurfaces::applySpoilers(float spoilers_control,
actuator_sp(i + first_actuator_idx) += _spoilers_setpoint_with_slewrate.getState() * _params[i].scale_spoiler;
}
}

void ActuatorEffectivenessControlSurfaces::applyScale(float scale, int first_actuator_idx,
ActuatorVector &actuator_sp) const
{
for (int i = 0; i < _count; ++i) {
actuator_sp(i + first_actuator_idx) *= scale;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ class ActuatorEffectivenessControlSurfaces : public ModuleParams, public Actuato

void applyFlaps(float flaps_control, int first_actuator_idx, float dt, ActuatorVector &actuator_sp);
void applySpoilers(float spoilers_control, int first_actuator_idx, float dt, ActuatorVector &actuator_sp);
void applyScale(float scale, int first_actuator_idx, ActuatorVector &actuator_sp) const;

private:
void updateParams() override;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/

#include "ActuatorEffectivenessThrustVectoring.hpp"

using namespace matrix;

ActuatorEffectivenessThrustVectoring::ActuatorEffectivenessThrustVectoring(ModuleParams *parent)
: ModuleParams(parent),
_rotors(this, ActuatorEffectivenessRotors::AxisConfiguration::FixedUpwards),
_control_surfaces(this)
{
}

bool
ActuatorEffectivenessThrustVectoring::getEffectivenessMatrix(Configuration &configuration,
EffectivenessUpdateReason external_update)
{
if (external_update == EffectivenessUpdateReason::NO_EXTERNAL_UPDATE) {
return false;
}

// Motors
_rotors.enablePropellerTorque(false);
const bool rotors_added_successfully = _rotors.addActuators(configuration);

// Control Surfaces
_first_control_surface_idx = configuration.num_actuators_matrix[0];
const bool surfaces_added_successfully = _control_surfaces.addActuators(configuration);

return (rotors_added_successfully && surfaces_added_successfully);
}

void ActuatorEffectivenessThrustVectoring::updateSetpoint(const matrix::Vector<float, NUM_AXES> &control_sp,
int matrix_index, ActuatorVector &actuator_sp, const matrix::Vector<float, NUM_ACTUATORS> &actuator_min,
const matrix::Vector<float, NUM_ACTUATORS> &actuator_max)
{
esc_status_s esc_status;
hrt_abstime now = hrt_absolute_time();
float rpm = 0.f;

if (_esc_status_sub.copy(&esc_status) && (now < esc_status.timestamp + 1_s)) {

for (size_t esc = 0; esc < math::min(esc_status.esc_count, (uint8_t)MAX_NUM_ESCS); esc++) {
const esc_report_s &esc_report = esc_status.esc[esc];

const bool esc_connected = (esc_status.esc_online_flags & (1 << esc)) || (esc_report.esc_rpm != 0);

if (esc_connected && (now < esc_report.timestamp + 1_s)) {
rpm = esc_report.esc_rpm;
break;
}
}
}

constexpr float propeller_coefficient = 1.f / (20000.f * 20000.f); // scale down the thrust
float thrust = rpm * rpm * propeller_coefficient;

// Use thrust setpoint if there is no ESC telemetry available
if (thrust < FLT_EPSILON) {
vehicle_thrust_setpoint_s vehicle_thrust_setpoint;

if (_vehicle_thrust_setpoint_sub.copy(&vehicle_thrust_setpoint)) {
thrust = vehicle_thrust_setpoint.xyz[2];
}
}

const float scale = 1.f / fmaxf(thrust, 0.2f);
_control_surfaces.applyScale(scale, _first_control_surface_idx, actuator_sp);
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/****************************************************************************
*
* Copyright (c) 2023 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.
*
****************************************************************************/

#pragma once

#include "ActuatorEffectiveness.hpp"
#include "ActuatorEffectivenessRotors.hpp"
#include "ActuatorEffectivenessControlSurfaces.hpp"

#include <uORB/topics/esc_status.h>
#include <uORB/topics/vehicle_thrust_setpoint.h>

class ActuatorEffectivenessThrustVectoring : public ModuleParams, public ActuatorEffectiveness
{
public:
ActuatorEffectivenessThrustVectoring(ModuleParams *parent);
virtual ~ActuatorEffectivenessThrustVectoring() = default;

bool getEffectivenessMatrix(Configuration &configuration, EffectivenessUpdateReason external_update) override;

const char *name() const override { return "Thrust Vectoring"; }

void updateSetpoint(const matrix::Vector<float, NUM_AXES> &control_sp, int matrix_index,
ActuatorVector &actuator_sp, const matrix::Vector<float, NUM_ACTUATORS> &actuator_min,
const matrix::Vector<float, NUM_ACTUATORS> &actuator_max) override;

private:
static constexpr int MAX_NUM_ESCS = sizeof(esc_status_s::esc) / sizeof(esc_status_s::esc[0]);

ActuatorEffectivenessRotors _rotors;
ActuatorEffectivenessControlSurfaces _control_surfaces;

uORB::Subscription _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint)};
uORB::Subscription _esc_status_sub {ORB_ID(esc_status)};

int _first_control_surface_idx{0};
};
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ px4_add_library(VehicleActuatorEffectiveness
ActuatorEffectivenessMCTilt.hpp
ActuatorEffectivenessMultirotor.cpp
ActuatorEffectivenessMultirotor.hpp
ActuatorEffectivenessThrustVectoring.cpp
ActuatorEffectivenessThrustVectoring.hpp
ActuatorEffectivenessTilts.cpp
ActuatorEffectivenessTilts.hpp
ActuatorEffectivenessRotors.cpp
Expand Down
1 change: 1 addition & 0 deletions src/modules/control_allocator/module.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ parameters:
11: Helicopter (tail Servo)
12: Helicopter (Coaxial)
13: Rover (Mecanum)
14: Thrust Vectoring
default: 0

CA_METHOD:
Expand Down

0 comments on commit a16dfa9

Please sign in to comment.