delete lib/mixer and mixer_module static mixing

This commit is contained in:
Daniel Agar
2022-08-24 16:50:02 -04:00
parent 0019ffbea6
commit a7bbcd5b04
79 changed files with 219 additions and 6835 deletions
@@ -51,6 +51,5 @@ px4_add_module(
mathlib
ActuatorEffectiveness
ControlAllocation
mixer
px4_work_queue
)
@@ -57,19 +57,12 @@ public:
private:
explicit MavlinkStreamHILActuatorControls(Mavlink *mavlink) : MavlinkStream(mavlink)
{
int32_t sys_ctrl_alloc = 0;
param_get(param_find("SYS_CTRL_ALLOC"), &sys_ctrl_alloc);
_use_dynamic_mixing = sys_ctrl_alloc >= 1;
if (_use_dynamic_mixing) {
_act_sub = uORB::Subscription{ORB_ID(actuator_outputs_sim)};
}
_act_sub = uORB::Subscription{ORB_ID(actuator_outputs_sim)};
}
uORB::Subscription _act_sub{ORB_ID(actuator_outputs)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
bool _use_dynamic_mixing{false};
bool send() override
{
@@ -79,90 +72,8 @@ private:
mavlink_hil_actuator_controls_t msg{};
msg.time_usec = act.timestamp;
if (_use_dynamic_mixing) {
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) {
msg.controls[i] = act.output[i];
}
} else {
static constexpr float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2;
unsigned system_type = _mavlink->get_system_type();
/* scale outputs depending on system type */
if (system_type == MAV_TYPE_QUADROTOR ||
system_type == MAV_TYPE_HEXAROTOR ||
system_type == MAV_TYPE_OCTOROTOR ||
system_type == MAV_TYPE_VTOL_TAILSITTER_DUOROTOR ||
system_type == MAV_TYPE_VTOL_TAILSITTER_QUADROTOR ||
system_type == MAV_TYPE_VTOL_FIXEDROTOR) {
/* multirotors: set number of rotor outputs depending on type */
unsigned n;
switch (system_type) {
case MAV_TYPE_QUADROTOR:
n = 4;
break;
case MAV_TYPE_HEXAROTOR:
n = 6;
break;
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
n = 2;
break;
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
n = 4;
break;
case MAV_TYPE_VTOL_FIXEDROTOR:
n = 8;
break;
default:
n = 8;
break;
}
for (unsigned i = 0; i < 16; i++) {
if (act.output[i] > PWM_DEFAULT_MIN / 2) {
if (i < n) {
/* scale PWM out 900..2100 us to 0..1 for rotors */
msg.controls[i] = (act.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
} else {
/* scale PWM out 900..2100 us to -1..1 for other channels */
msg.controls[i] = (act.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
}
} else {
/* send 0 when disarmed and for disabled channels */
msg.controls[i] = 0.0f;
}
}
} else {
/* fixed wing: scale throttle to 0..1 and other channels to -1..1 */
for (unsigned i = 0; i < 16; i++) {
if (act.output[i] > PWM_DEFAULT_MIN / 2) {
if (i != 3) {
/* scale PWM out 900..2100 us to -1..1 for normal channels */
msg.controls[i] = (act.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
} else {
/* scale PWM out 900..2100 us to 0..1 for throttle */
msg.controls[i] = (act.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
}
} else {
/* set 0 for disabled channels */
msg.controls[i] = 0.0f;
}
}
}
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) {
msg.controls[i] = act.output[i];
}
// mode (MAV_MODE_FLAG)
@@ -33,7 +33,6 @@
#pragma once
#include <lib/mixer/MixerBase/Mixer.hpp> // Airmode
#include <matrix/matrix/math.hpp>
#include <perf/perf_counter.h>
#include <px4_platform_common/px4_config.h>
@@ -117,7 +117,7 @@ MulticopterAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt,
_man_yaw_sp = yaw;
} else if (math::constrain(_manual_control_setpoint.z, 0.0f, 1.0f) > 0.05f
|| _param_mc_airmode.get() == (int32_t)Mixer::Airmode::roll_pitch_yaw) {
|| _param_mc_airmode.get() == 2) {
const float yaw_rate = math::radians(_param_mpc_man_y_max.get());
attitude_setpoint.yaw_sp_move_rate = _manual_control_setpoint.r * yaw_rate;
@@ -45,6 +45,5 @@ px4_add_module(
MODULE_CONFIG
${module_config}
DEPENDS
mixer
mixer_module
)
@@ -139,7 +139,7 @@ PWMSim::ioctl(device::file_t *filp, int cmd, unsigned long arg)
struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
for (unsigned i = 0; i < pwm->channel_count; i++) {
if (i < OutputModuleInterface::MAX_ACTUATORS && !_mixing_output.useDynamicMixing()) {
if (i < OutputModuleInterface::MAX_ACTUATORS && false) {
_mixing_output.minValue(i) = pwm->values[i];
}
}
@@ -151,7 +151,7 @@ PWMSim::ioctl(device::file_t *filp, int cmd, unsigned long arg)
struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
for (unsigned i = 0; i < pwm->channel_count; i++) {
if (i < OutputModuleInterface::MAX_ACTUATORS && !_mixing_output.useDynamicMixing()) {
if (i < OutputModuleInterface::MAX_ACTUATORS && false) {
_mixing_output.maxValue(i) = pwm->values[i];
}
}
@@ -84,8 +84,6 @@ private:
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
void mixerChanged() override {}
void Run() override;
bool updateClock(const uint64_t tv_sec, const uint64_t tv_nsec);
@@ -91,10 +91,6 @@ static constexpr vehicle_odometry_s vehicle_odometry_empty {
SimulatorMavlink::SimulatorMavlink() :
ModuleParams(nullptr)
{
int32_t sys_ctrl_alloc = 0;
param_get(param_find("SYS_CTRL_ALLOC"), &sys_ctrl_alloc);
_use_dynamic_mixing = sys_ctrl_alloc >= 1;
for (int i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; ++i) {
char param_name[17];
snprintf(param_name, sizeof(param_name), "%s_%s%d", "PWM_MAIN", "FUNC", i + 1);
@@ -123,91 +119,9 @@ void SimulatorMavlink::actuator_controls_from_outputs(mavlink_hil_actuator_contr
bool armed = (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
int _system_type = _param_mav_type.get();
if (_use_dynamic_mixing) {
if (armed) {
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) {
msg->controls[i] = _actuator_outputs.output[i];
}
}
} else {
/* 'pos_thrust_motors_count' indicates number of motor channels which are configured with 0..1 range (positive thrust)
all other motors are configured for -1..1 range */
unsigned pos_thrust_motors_count;
bool is_fixed_wing;
switch (_system_type) {
case MAV_TYPE_AIRSHIP:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_COAXIAL:
pos_thrust_motors_count = 2;
is_fixed_wing = false;
break;
case MAV_TYPE_TRICOPTER:
pos_thrust_motors_count = 3;
is_fixed_wing = false;
break;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
pos_thrust_motors_count = 4;
is_fixed_wing = false;
break;
case MAV_TYPE_VTOL_FIXEDROTOR:
pos_thrust_motors_count = 5;
is_fixed_wing = false;
break;
case MAV_TYPE_HEXAROTOR:
pos_thrust_motors_count = 6;
is_fixed_wing = false;
break;
case MAV_TYPE_OCTOROTOR:
pos_thrust_motors_count = 8;
is_fixed_wing = false;
break;
case MAV_TYPE_SUBMARINE:
pos_thrust_motors_count = 0;
is_fixed_wing = false;
break;
case MAV_TYPE_FIXED_WING:
pos_thrust_motors_count = 0;
is_fixed_wing = true;
break;
default:
pos_thrust_motors_count = 0;
is_fixed_wing = false;
break;
}
if (armed) {
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) {
if (!armed) {
/* send 0 when disarmed and for disabled channels */
msg->controls[i] = 0.0f;
} else if ((is_fixed_wing && i == 4) ||
(!is_fixed_wing && i < pos_thrust_motors_count)) { //multirotor, rotor channel
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to 0..1 for rotors */
msg->controls[i] = (_actuator_outputs.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
msg->controls[i] = math::constrain(msg->controls[i], 0.f, 1.f);
} else {
const float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2;
const float pwm_delta = (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2;
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to -1..1 for other channels */
msg->controls[i] = (_actuator_outputs.output[i] - pwm_center) / pwm_delta;
msg->controls[i] = math::constrain(msg->controls[i], -1.f, 1.f);
}
msg->controls[i] = _actuator_outputs.output[i];
}
}
@@ -1065,12 +979,7 @@ void SimulatorMavlink::send()
// Subscribe to topics.
// Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS.
if (_use_dynamic_mixing) {
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs_sim), 0);
} else {
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0);
}
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs_sim), 0);
// Before starting, we ought to send a heartbeat to initiate the SITL
// simulator to start sending sensor data which will set the time and
@@ -296,7 +296,6 @@ private:
float _last_magx{0.0f};
float _last_magy{0.0f};
float _last_magz{0.0f};
bool _use_dynamic_mixing{false};
float _last_baro_pressure{0.0f};
float _last_baro_temperature{0.0f};