mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 22:32:11 +08:00
control_allocator: add module.yaml, add CA_MC_R_COUNT param & update defaults
This commit is contained in:
@@ -19,7 +19,6 @@ param set-default VM_INERTIA_YY 0.03
|
||||
param set-default VM_INERTIA_ZZ 0.05
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_METHOD 1
|
||||
param set-default CA_ACT0_MIN 0.0
|
||||
param set-default CA_ACT1_MIN 0.0
|
||||
param set-default CA_ACT2_MIN 0.0
|
||||
|
||||
@@ -37,7 +37,6 @@ param set-default VM_INERTIA_YY 0.06
|
||||
param set-default VM_INERTIA_ZZ 0.10
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_METHOD 1
|
||||
param set-default CA_ACT0_MIN 0.0
|
||||
param set-default CA_ACT1_MIN 0.0
|
||||
param set-default CA_ACT2_MIN 0.0
|
||||
|
||||
@@ -25,7 +25,6 @@ param set-default VM_INERTIA_YY 0.03
|
||||
param set-default VM_INERTIA_ZZ 0.05
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_METHOD 1
|
||||
param set-default CA_ACT0_MIN 0.0
|
||||
param set-default CA_ACT1_MIN 0.0
|
||||
param set-default CA_ACT2_MIN 0.0
|
||||
|
||||
@@ -21,7 +21,6 @@ param set-default VM_INERTIA_YY 0.03
|
||||
param set-default VM_INERTIA_ZZ 0.05
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_METHOD 1
|
||||
param set-default CA_ACT0_MIN 0.0
|
||||
param set-default CA_ACT1_MIN 0.0
|
||||
param set-default CA_ACT2_MIN 0.0
|
||||
|
||||
+5
-3
@@ -127,6 +127,8 @@ ActuatorEffectivenessMultirotor::getEffectivenessMatrix(matrix::Matrix<float, NU
|
||||
geometry.rotors[7].thrust_coef = _param_ca_mc_r7_ct.get();
|
||||
geometry.rotors[7].moment_ratio = _param_ca_mc_r7_km.get();
|
||||
|
||||
geometry.num_rotors = _param_ca_mc_r_count.get();
|
||||
|
||||
_num_actuators = computeEffectivenessMatrix(geometry, matrix);
|
||||
return true;
|
||||
}
|
||||
@@ -142,7 +144,7 @@ ActuatorEffectivenessMultirotor::computeEffectivenessMatrix(const MultirotorGeom
|
||||
|
||||
effectiveness.setZero();
|
||||
|
||||
for (size_t i = 0; i < NUM_ROTORS_MAX; i++) {
|
||||
for (int i = 0; i < math::min(NUM_ROTORS_MAX, geometry.num_rotors); i++) {
|
||||
|
||||
// Get rotor axis
|
||||
matrix::Vector3f axis(
|
||||
@@ -188,9 +190,9 @@ ActuatorEffectivenessMultirotor::computeEffectivenessMatrix(const MultirotorGeom
|
||||
effectiveness(j, i) = moment(j);
|
||||
effectiveness(j + 3, i) = thrust(j);
|
||||
}
|
||||
|
||||
num_actuators = i + 1;
|
||||
}
|
||||
|
||||
num_actuators = geometry.num_rotors;
|
||||
|
||||
return num_actuators;
|
||||
}
|
||||
|
||||
+8
-5
@@ -57,7 +57,7 @@ public:
|
||||
|
||||
static constexpr int NUM_ROTORS_MAX = 8;
|
||||
|
||||
typedef struct {
|
||||
struct RotorGeometry {
|
||||
float position_x;
|
||||
float position_y;
|
||||
float position_z;
|
||||
@@ -66,11 +66,12 @@ public:
|
||||
float axis_z;
|
||||
float thrust_coef;
|
||||
float moment_ratio;
|
||||
} RotorGeometry;
|
||||
};
|
||||
|
||||
typedef struct {
|
||||
struct MultirotorGeometry {
|
||||
RotorGeometry rotors[NUM_ROTORS_MAX];
|
||||
} MultirotorGeometry;
|
||||
int num_rotors{0};
|
||||
};
|
||||
|
||||
static int computeEffectivenessMatrix(const MultirotorGeometry &geometry,
|
||||
matrix::Matrix<float, NUM_AXES, NUM_ACTUATORS> &effectiveness);
|
||||
@@ -153,6 +154,8 @@ private:
|
||||
(ParamFloat<px4::params::CA_MC_R7_AY>) _param_ca_mc_r7_ay,
|
||||
(ParamFloat<px4::params::CA_MC_R7_AZ>) _param_ca_mc_r7_az,
|
||||
(ParamFloat<px4::params::CA_MC_R7_CT>) _param_ca_mc_r7_ct,
|
||||
(ParamFloat<px4::params::CA_MC_R7_KM>) _param_ca_mc_r7_km
|
||||
(ParamFloat<px4::params::CA_MC_R7_KM>) _param_ca_mc_r7_km,
|
||||
|
||||
(ParamInt<px4::params::CA_MC_R_COUNT>) _param_ca_mc_r_count
|
||||
)
|
||||
};
|
||||
|
||||
-560
File diff suppressed because it is too large
Load Diff
@@ -43,6 +43,8 @@ px4_add_module(
|
||||
SRCS
|
||||
ControlAllocator.cpp
|
||||
ControlAllocator.hpp
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
mathlib
|
||||
ActuatorEffectiveness
|
||||
|
||||
@@ -40,30 +40,16 @@
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* Airframe ID
|
||||
*
|
||||
* This is used to retrieve pre-computed control effectiveness matrix
|
||||
*
|
||||
* @min 0
|
||||
* @max 2
|
||||
* @value 0 Multirotor
|
||||
* @value 1 Standard VTOL (WIP)
|
||||
* @value 2 Tiltrotor VTOL (WIP)
|
||||
* @group Control Allocation
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CA_AIRFRAME, 0);
|
||||
|
||||
/**
|
||||
* Control allocation method
|
||||
*
|
||||
* @value 0 Pseudo-inverse with output clipping (default)
|
||||
* @value 0 Pseudo-inverse with output clipping
|
||||
* @value 1 Pseudo-inverse with sequential desaturation technique
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Control Allocation
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CA_METHOD, 0);
|
||||
PARAM_DEFINE_INT32(CA_METHOD, 1);
|
||||
|
||||
/**
|
||||
* Battery power level scaler
|
||||
|
||||
@@ -0,0 +1,135 @@
|
||||
__max_num_mc_motors: &max_num_mc_motors 8
|
||||
|
||||
module_name: Control Allocation
|
||||
|
||||
parameters:
|
||||
- group: Control Allocation
|
||||
definitions:
|
||||
CA_AIRFRAME:
|
||||
description:
|
||||
short: Airframe selection
|
||||
long: |
|
||||
Defines which mixer implementation to use.
|
||||
Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators.
|
||||
type: enum
|
||||
values:
|
||||
0: Multirotor
|
||||
1: Standard VTOL (WIP)
|
||||
2: Tiltrotor VTOL (WIP)
|
||||
default: 0
|
||||
|
||||
# MC rotors
|
||||
CA_MC_R_COUNT:
|
||||
description:
|
||||
short: Total number of rotors
|
||||
type: enum
|
||||
values:
|
||||
0: 0 Motors
|
||||
1: 1 Motor
|
||||
2: 2 Motors
|
||||
3: 3 Motors
|
||||
4: 4 Motors
|
||||
5: 5 Motors
|
||||
6: 6 Motors
|
||||
7: 7 Motors
|
||||
8: 8 Motors
|
||||
default: 0
|
||||
CA_MC_R${i}_PX:
|
||||
description:
|
||||
short: Position of rotor ${i} along X body axis
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
unit: m
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: 0.0
|
||||
CA_MC_R${i}_PY:
|
||||
description:
|
||||
short: Position of rotor ${i} along Y body axis
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
unit: m
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: 0.0
|
||||
CA_MC_R${i}_PZ:
|
||||
description:
|
||||
short: Position of rotor ${i} along Z body axis
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
unit: m
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: 0.0
|
||||
|
||||
CA_MC_R${i}_AX:
|
||||
description:
|
||||
short: Axis of rotor ${i} thrust vector, X body axis component
|
||||
long: Only the direction is considered (the vector is normalized).
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: 0.0
|
||||
CA_MC_R${i}_AY:
|
||||
description:
|
||||
short: Axis of rotor ${i} thrust vector, Y body axis component
|
||||
long: Only the direction is considered (the vector is normalized).
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: 0.0
|
||||
CA_MC_R${i}_AZ:
|
||||
description:
|
||||
short: Axis of rotor ${i} thrust vector, Z body axis component
|
||||
long: Only the direction is considered (the vector is normalized).
|
||||
type: float
|
||||
decimal: 2
|
||||
increment: 0.1
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -100
|
||||
max: 100
|
||||
default: -1.0
|
||||
|
||||
CA_MC_R${i}_CT:
|
||||
description:
|
||||
short: Thrust coefficient of rotor ${i}
|
||||
long: |
|
||||
The thrust coefficient if defined as Thrust = CT * u^2,
|
||||
where u (with value between actuator minimum and maximum)
|
||||
is the output signal sent to the motor controller.
|
||||
type: float
|
||||
decimal: 1
|
||||
increment: 1
|
||||
num_instances: *max_num_mc_motors
|
||||
min: 0
|
||||
max: 100
|
||||
default: 6.5
|
||||
|
||||
CA_MC_R${i}_KM:
|
||||
description:
|
||||
short: Moment coefficient of rotor ${i}
|
||||
long: |
|
||||
The moment coefficient if defined as Torque = KM * Thrust.
|
||||
|
||||
Use a positive value for a rotor with CCW rotation.
|
||||
Use a negative value for a rotor with CW rotation.
|
||||
type: float
|
||||
decimal: 3
|
||||
increment: 0.01
|
||||
num_instances: *max_num_mc_motors
|
||||
min: -1
|
||||
max: 1
|
||||
default: 0.05
|
||||
|
||||
Reference in New Issue
Block a user