mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 09:16:01 +03:00
Merge pull request #2978 from iNavFlight/dzikuvx-mixer-rework
Mixer refactoring - make FC unaware of anything besides mixer rules
This commit is contained in:
commit
9dfd2d08e6
31 changed files with 164 additions and 787 deletions
|
@ -79,7 +79,6 @@ Re-apply any new defaults as desired.
|
|||
| `help` | |
|
||||
| `led` | configure leds |
|
||||
| `map` | mapping of rc channel order |
|
||||
| `mixer` | mixer name or list |
|
||||
| `motor` | get/set motor output value |
|
||||
| `play_sound` | index, or none for next |
|
||||
| `profile` | index (0 to 2) |
|
||||
|
@ -414,6 +413,9 @@ Re-apply any new defaults as desired.
|
|||
| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
|
||||
| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
|
||||
| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
|
||||
| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
|
||||
| mixer_preset | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. |
|
||||
|
||||
This Markdown table is made by MarkdwonTableMaker addon for google spreadsheet.
|
||||
Original Spreadsheet used to make this table can be found here https://docs.google.com/spreadsheets/d/1ubjYdMGmZ2aAMUNYkdfe3hhIF7wRfIjcuPOi_ysmp00/edit?usp=sharing
|
||||
|
|
106
docs/Mixer.md
106
docs/Mixer.md
|
@ -1,83 +1,31 @@
|
|||
# Mixer
|
||||
# Mixer and platform type
|
||||
|
||||
INAV supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft.
|
||||
|
||||
## Configuration
|
||||
|
||||
To use a built-in mixing configuration, you can use the Chrome configuration GUI. It includes images of the various mixer types to assist in making the proper connections. See the Configuration section of the documentation for more information on the GUI.
|
||||
INAV Configurator provides graphical user interface for mixer configuration. All supported vehicle types are configurable with _mixer presets_ using Configurator. `mmix` and `smix` manual configuration in CLI should be used only for backup/restore purposes.
|
||||
|
||||
You can also use the Command Line Interface (CLI) to set the mixer type:
|
||||
User interface is described in [this video](https://www.youtube.com/watch?v=0cLFu-5syi0)
|
||||
|
||||
1. Use `mixer list` to see a list of supported mixes
|
||||
2. Select a mixer. For example, to select TRI, use `mixer TRI`
|
||||
3. You must use `save` to preserve your changes
|
||||
## Platform type
|
||||
|
||||
## Supported Mixer Types
|
||||
INAV can be used on a variety of vehicle types configured via Configurator or `platform_type` CLI property. Certain settings applies only when specific platform type is selected. For example, _flaps_ can be configured only if **AIRPLANE** platform type is used. The same goes for flight modes, output mappings, stabilization algorithms, etc.
|
||||
|
||||
| Name | Description | Motors | Servos |
|
||||
| ---------------- | ------------------------- | -------------- | ---------------- |
|
||||
| TRI | Tricopter | M1-M3 | S1 |
|
||||
| QUADP | Quadcopter-Plus | M1-M4 | None |
|
||||
| QUADX | Quadcopter-X | M1-M4 | None |
|
||||
| BI | Bicopter (left/right) | M1-M2 | S1, S2 |
|
||||
| GIMBAL | Gimbal control | N/A | S1, S2 |
|
||||
| Y6 | Y6-copter | M1-M6 | None |
|
||||
| HEX6 | Hexacopter-Plus | M1-M6 | None |
|
||||
| FLYING_WING | Fixed wing; elevons | M1 | S1, S2 |
|
||||
| Y4 | Y4-copter | M1-M4 | None |
|
||||
| HEX6X | Hexacopter-X | M1-M6 | None |
|
||||
| OCTOX8 | Octocopter-X (over/under) | M1-M8 | None |
|
||||
| OCTOFLATP | Octocopter-FlatPlus | M1-M8 | None |
|
||||
| OCTOFLATX | Octocopter-FlatX | M1-M8 | None |
|
||||
| AIRPLANE | Fixed wing; Ax2, R, E | M1 | S1, S2, S3, S4 |
|
||||
| HELI_120_CCPM | | | |
|
||||
| HELI_90_DEG | | | |
|
||||
| VTAIL4 | Quadcopter with V-Tail | M1-M4 | N/A |
|
||||
| HEX6H | Hexacopter-H | M1-M6 | None |
|
||||
| PPM_TO_SERVO | | | |
|
||||
| DUALCOPTER | Dualcopter | M1-M2 | S1, S2 |
|
||||
| SINGLECOPTER | Conventional helicopter | M1 | S1 |
|
||||
| ATAIL4 | Quadcopter with A-Tail | M1-M4 | N/A |
|
||||
| CUSTOM | User-defined | | |
|
||||
| CUSTOM AIRPLANE | User-defined airplane | | |
|
||||
| CUSTOM TRICOPTER | User-defined tricopter | | |
|
||||
Currently, following platform types are supported:
|
||||
|
||||
## Servo configuration
|
||||
* MULTIROTOR
|
||||
* AIRPLANE
|
||||
* TRICOPTER
|
||||
|
||||
The cli `servo` command defines the settings for the servo outputs.
|
||||
The cli mixer `smix` command controllers how the mixer maps internal FC data (RC input, PID stabilization output, channel forwarding, etc) to servo outputs.
|
||||
|
||||
## Servo filtering
|
||||
|
||||
A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example.
|
||||
|
||||
### Configuration
|
||||
|
||||
Currently, it can only be configured via the CLI:
|
||||
|
||||
Use `set servo_lpf_hz=20` to enable filtering. This will set servo low pass filter to 20Hz.
|
||||
|
||||
### Tuning
|
||||
|
||||
One method for tuning the filter cutoff is as follows:
|
||||
|
||||
1. Ensure your vehicle can move at least somewhat freely in the troublesome axis. For example, if you are having yaw oscillations on a tricopter, ensure that the copter is supported in a way that allows it to rotate left and right to at least some degree. Suspension near the CG is ideal. Alternatively, you can just fly the vehicle and trigger the problematic condition you are trying to eliminate, although tuning will be more tedious.
|
||||
|
||||
2. Tap the vehicle at its end in the axis under evaluation. Directly commanding the servo in question to move may also be used. In the tricopter example, tap the end of the tail boom from the side, or command a yaw using your transmitter.
|
||||
|
||||
3. If your vehicle oscillates for several seconds or even continues oscillating indefinitely, then the filter cutoff frequency should be reduced. Reduce the value of `servo_lowpass_freq` by half its current value and repeat the previous step.
|
||||
|
||||
4. If the oscillations are dampened within roughly a second or are no longer present, then you are done. Be sure to run `save`.
|
||||
|
||||
## Custom Motor Mixing
|
||||
## Motor Mixing
|
||||
|
||||
Custom motor mixing allows for completely customized motor configurations. Each motor must be defined with a custom mixing table for that motor. The mix must reflect how close each motor is with reference to the CG (Center of Gravity) of the flight controller. A motor closer to the CG of the flight controller will need to travel less distance than a motor further away.
|
||||
|
||||
Steps to configure custom mixer in the CLI:
|
||||
|
||||
1. Use `mixer custom` to enable the custom mixing.
|
||||
2. Use `mmix reset` to erase any existing custom mixing.
|
||||
3. Issue a `mmix` statement for each motor.
|
||||
1. Use `mmix reset` to erase any existing custom mixing.
|
||||
1. Issue a `mmix` statement for each motor.
|
||||
|
||||
The mmix statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
|
||||
|
||||
|
@ -91,7 +39,7 @@ The mmix statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
|
|||
|
||||
Note: the `mmix` command may show a motor mix that is not active, custom motor mixes are only active for models that use custom mixers.
|
||||
|
||||
## Custom Servo Mixing
|
||||
## Servo Mixing
|
||||
|
||||
Custom servo mixing rules can be applied to each servo. Rules are applied in the CLI using `smix`. Rules link flight controller stabilization and receiver signals to physical PWM output pins on the FC board. Currently, pin id's 0 and 1 can only be used for motor outputs. Other pins may or may not work depending on the board you are using.
|
||||
|
||||
|
@ -176,6 +124,34 @@ i.e. when mixing rudder servo slot (`5`) using Stabilised YAW input source (`2`)
|
|||
|
||||
`smix reverse` is a per-profile setting. So ensure you configure it for your profiles as required.
|
||||
|
||||
## Servo configuration
|
||||
|
||||
The cli `servo` command defines the settings for the servo outputs.
|
||||
The cli mixer `smix` command controllers how the mixer maps internal FC data (RC input, PID stabilization output, channel forwarding, etc) to servo outputs.
|
||||
|
||||
## Servo filtering
|
||||
|
||||
A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example.
|
||||
|
||||
### Configuration
|
||||
|
||||
Currently, it can only be configured via the CLI:
|
||||
|
||||
Use `set servo_lpf_hz=20` to enable filtering. This will set servo low pass filter to 20Hz.
|
||||
|
||||
### Tuning
|
||||
|
||||
One method for tuning the filter cutoff is as follows:
|
||||
|
||||
1. Ensure your vehicle can move at least somewhat freely in the troublesome axis. For example, if you are having yaw oscillations on a tricopter, ensure that the copter is supported in a way that allows it to rotate left and right to at least some degree. Suspension near the CG is ideal. Alternatively, you can just fly the vehicle and trigger the problematic condition you are trying to eliminate, although tuning will be more tedious.
|
||||
|
||||
2. Tap the vehicle at its end in the axis under evaluation. Directly commanding the servo in question to move may also be used. In the tricopter example, tap the end of the tail boom from the side, or command a yaw using your transmitter.
|
||||
|
||||
3. If your vehicle oscillates for several seconds or even continues oscillating indefinitely, then the filter cutoff frequency should be reduced. Reduce the value of `servo_lowpass_freq` by half its current value and repeat the previous step.
|
||||
|
||||
4. If the oscillations are dampened within roughly a second or are no longer present, then you are done. Be sure to run `save`.
|
||||
|
||||
|
||||
### Example 1: A KK2.0 wired motor setup
|
||||
Here's an example of an X configuration quad, but the motors are still wired using the KK board motor numbering scheme.
|
||||
|
||||
|
|
|
@ -476,7 +476,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
return getMotorCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
|
||||
return mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI;
|
||||
return mixerConfig()->platformType == PLATFORM_TRICOPTER;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
|
@ -1176,10 +1176,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
|
||||
blackboxCurrent->rssi = getRSSI();
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
//Tail servo for tricopters
|
||||
blackboxCurrent->servo[5] = servo[5];
|
||||
#endif
|
||||
|
||||
#ifdef NAV_BLACKBOX
|
||||
blackboxCurrent->navState = navCurrentState;
|
||||
|
|
|
@ -28,10 +28,7 @@
|
|||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
#include "flight/servos.h"
|
||||
#endif
|
||||
|
||||
#include "io/osd.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
|
|
@ -177,9 +177,8 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
}
|
||||
|
||||
// Handle outputs - may override the PWM/PPM inputs
|
||||
if (init->flyingPlatformType == PLATFORM_MULTIROTOR) {
|
||||
if (init->flyingPlatformType == PLATFORM_MULTIROTOR || init->flyingPlatformType == PLATFORM_TRICOPTER) {
|
||||
// Multicopter
|
||||
#ifdef USE_SERVOS
|
||||
if (init->useServoOutputs && (timerHardwarePtr->usageFlags & TIM_USE_MC_SERVO)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
|
@ -187,13 +186,10 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
#ifdef USE_SERVOS
|
||||
else if (init->flyingPlatformType == PLATFORM_AIRPLANE || init->flyingPlatformType == PLATFORM_HELICOPTER) {
|
||||
} else {
|
||||
// Fixed wing or HELI (one/two motors and a lot of servos
|
||||
if (timerHardwarePtr->usageFlags & TIM_USE_FW_SERVO) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
|
@ -202,37 +198,10 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// If timer not mapped - skip
|
||||
if (type == MAP_TO_NONE)
|
||||
continue;
|
||||
/*
|
||||
#ifdef USE_SERVOS
|
||||
if (init->useServos && !init->airplane) {
|
||||
#if defined(SPRACINGF3MINI)
|
||||
// remap PWM6+7 as servos
|
||||
if ((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SINGULARITY)
|
||||
// remap PWM6+7 as servos
|
||||
if (timerIndex == PWM6 || timerIndex == PWM7)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(SPRACINGF3MINI)
|
||||
if (((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15)
|
||||
|| ((timerIndex == PWM8 || timerIndex == PWM9 || timerIndex == PWM10 || timerIndex == PWM11) && timerHardwarePtr->tim == TIM2)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_SERVOS
|
||||
*/
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#if defined(USE_RX_PPM)
|
||||
|
@ -284,7 +253,6 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
continue;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (pwmServoConfig(timerHardwarePtr, pwmIOConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse, init->enablePWMOutput)) {
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_SERVO | PWM_PF_OUTPUT_PROTOCOL_PWM;
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].index = pwmIOConfiguration.servoCount;
|
||||
|
@ -298,7 +266,6 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
} else {
|
||||
continue;
|
||||
}
|
||||
|
|
|
@ -18,14 +18,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#if defined(USE_QUAD_MIXER_ONLY)
|
||||
#define MAX_PWM_MOTORS 4
|
||||
#define MAX_PWM_SERVOS 1
|
||||
#define MAX_MOTORS 4
|
||||
#define MAX_SERVOS 1
|
||||
|
||||
#elif defined(TARGET_MOTOR_COUNT)
|
||||
#if defined(TARGET_MOTOR_COUNT)
|
||||
#define MAX_PWM_MOTORS TARGET_MOTOR_COUNT
|
||||
#define MAX_PWM_SERVOS 8
|
||||
#define MAX_MOTORS TARGET_MOTOR_COUNT
|
||||
|
@ -49,12 +44,6 @@ typedef struct rangefinderIOConfig_s {
|
|||
ioTag_t echoTag;
|
||||
} rangefinderIOConfig_t;
|
||||
|
||||
typedef enum {
|
||||
PLATFORM_MULTIROTOR = 0,
|
||||
PLATFORM_AIRPLANE = 1,
|
||||
PLATFORM_HELICOPTER = 2
|
||||
} flyingPlatformType_e;
|
||||
|
||||
typedef struct drv_pwm_config_s {
|
||||
int flyingPlatformType;
|
||||
|
||||
|
@ -74,12 +63,10 @@ typedef struct drv_pwm_config_s {
|
|||
#ifdef USE_RANGEFINDER
|
||||
bool useTriggerRangefinder;
|
||||
#endif
|
||||
#ifdef USE_SERVOS
|
||||
bool useServoOutputs;
|
||||
bool useChannelForwarding; // configure additional channels as servos
|
||||
uint16_t servoPwmRate;
|
||||
uint16_t servoCenterPulse;
|
||||
#endif
|
||||
uint8_t pwmProtocolType;
|
||||
uint16_t motorPwmRate;
|
||||
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
|
||||
|
|
|
@ -50,10 +50,7 @@ typedef struct {
|
|||
static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
|
||||
|
||||
static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
|
||||
#endif
|
||||
|
||||
#ifdef BEEPER_PWM
|
||||
static pwmOutputPort_t beeperPwmPort;
|
||||
|
@ -290,7 +287,6 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
|
|||
return false;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput)
|
||||
{
|
||||
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, PWM_TIMER_MHZ, 1000000 / servoPwmRate, servoCenterPulse, enableOutput);
|
||||
|
@ -323,7 +319,6 @@ void pwmWriteServo(uint8_t index, uint16_t value)
|
|||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BEEPER_PWM
|
||||
void pwmWriteBeeper(bool onoffBeep)
|
||||
|
|
|
@ -142,18 +142,6 @@ static void cliBootlog(char *cmdline);
|
|||
|
||||
static const char* const emptyName = "-";
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
// sync this with mixerMode_e
|
||||
static const char * const mixerNames[] = {
|
||||
"TRI", "QUADP", "QUADX", "BI",
|
||||
"GIMBAL", "Y6", "HEX6",
|
||||
"FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
|
||||
"AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
|
||||
"HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
|
||||
"ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
|
||||
};
|
||||
#endif
|
||||
|
||||
// sync this with features_e
|
||||
static const char * const featureNames[] = {
|
||||
"RX_PPM", "VBAT", "TX_PROF_SEL", "", "MOTOR_STOP",
|
||||
|
@ -974,7 +962,6 @@ static void cliAdjustmentRange(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer, const motorMixer_t *defaultCustomMotorMixer)
|
||||
{
|
||||
const char *format = "mmix %d %s %s %s %s";
|
||||
|
@ -1016,7 +1003,6 @@ static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer
|
|||
static void cliMotorMix(char *cmdline)
|
||||
{
|
||||
int check = 0;
|
||||
uint8_t len;
|
||||
const char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
|
@ -1026,23 +1012,6 @@ static void cliMotorMix(char *cmdline)
|
|||
for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
customMotorMixerMutable(i)->throttle = 0.0f;
|
||||
}
|
||||
} else if (sl_strncasecmp(cmdline, "load", 4) == 0) {
|
||||
ptr = nextArg(cmdline);
|
||||
if (ptr) {
|
||||
len = strlen(ptr);
|
||||
for (uint32_t i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL) {
|
||||
cliPrintLine("Invalid name");
|
||||
break;
|
||||
}
|
||||
if (sl_strncasecmp(ptr, mixerNames[i], len) == 0) {
|
||||
mixerLoadMix(i, customMotorMixerMutable(0));
|
||||
cliPrintLinef("Loaded %s", mixerNames[i]);
|
||||
cliMotorMix("");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
uint32_t i = fastA2I(ptr); // get motor number
|
||||
|
@ -1077,7 +1046,6 @@ static void cliMotorMix(char *cmdline)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif // USE_QUAD_MIXER_ONLY
|
||||
|
||||
static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channelRangeConfigs, const rxChannelRangeConfig_t *defaultChannelRangeConfigs)
|
||||
{
|
||||
|
@ -1281,7 +1249,6 @@ static void cliModeColor(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam)
|
||||
{
|
||||
// print out servo settings
|
||||
|
@ -1456,23 +1423,6 @@ static void cliServoMix(char *cmdline)
|
|||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoParamsMutable(i)->reversedSources = 0;
|
||||
}
|
||||
} else if (sl_strncasecmp(cmdline, "load", 4) == 0) {
|
||||
const char *ptr = nextArg(cmdline);
|
||||
if (ptr) {
|
||||
len = strlen(ptr);
|
||||
for (uint32_t i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL) {
|
||||
cliPrintLine("Invalid name");
|
||||
break;
|
||||
}
|
||||
if (sl_strncasecmp(ptr, mixerNames[i], len) == 0) {
|
||||
servoMixerLoadMix(i);
|
||||
cliPrintLinef("Loaded %s", mixerNames[i]);
|
||||
cliServoMix("");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else if (sl_strncasecmp(cmdline, "reverse", 7) == 0) {
|
||||
enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
|
||||
char *ptr = strchr(cmdline, ' ');
|
||||
|
@ -1544,7 +1494,6 @@ static void cliServoMix(char *cmdline)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif // USE_SERVOS
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
|
||||
|
@ -2017,42 +1966,6 @@ static void cliGpsPassthrough(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static void cliMixer(char *cmdline)
|
||||
{
|
||||
int len;
|
||||
|
||||
len = strlen(cmdline);
|
||||
|
||||
if (len == 0) {
|
||||
cliPrintLinef("Mixer: %s", mixerNames[mixerConfigMutable()->mixerMode - 1]);
|
||||
return;
|
||||
} else if (sl_strncasecmp(cmdline, "list", len) == 0) {
|
||||
cliPrint("Available mixers: ");
|
||||
for (uint32_t i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL)
|
||||
break;
|
||||
cliPrintf("%s ", mixerNames[i]);
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint32_t i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL) {
|
||||
cliPrintLine("Invalid name");
|
||||
return;
|
||||
}
|
||||
if (sl_strncasecmp(cmdline, mixerNames[i], len) == 0) {
|
||||
mixerConfigMutable()->mixerMode = i + 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
cliMixer("");
|
||||
}
|
||||
#endif
|
||||
|
||||
static void cliMotor(char *cmdline)
|
||||
{
|
||||
int motor_index = 0;
|
||||
|
@ -2583,18 +2496,11 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
cliPrintHashLine("resources");
|
||||
//printResource(dumpMask, &defaultConfig);
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
cliPrintHashLine("mixer");
|
||||
const bool equalsDefault = mixerConfig_Copy.mixerMode == mixerConfig()->mixerMode;
|
||||
const char *formatMixer = "mixer %s";
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig()->mixerMode - 1]);
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig_Copy.mixerMode - 1]);
|
||||
|
||||
cliDumpPrintLinef(dumpMask, customMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n");
|
||||
|
||||
printMotorMix(dumpMask, customMotorMixer_CopyArray, customMotorMixer(0));
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
// print custom servo mixer if exists
|
||||
cliPrintHashLine("servo mix");
|
||||
cliDumpPrintLinef(dumpMask, customServoMixers(0)->rate == 0, "smix reset\r\n");
|
||||
|
@ -2603,8 +2509,6 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
// print servo parameters
|
||||
cliPrintHashLine("servo");
|
||||
printServo(dumpMask, servoParams_CopyArray, servoParams(0));
|
||||
#endif
|
||||
#endif
|
||||
|
||||
cliPrintHashLine("feature");
|
||||
printFeature(dumpMask, &featureConfig_Copy, featureConfig());
|
||||
|
@ -2755,12 +2659,7 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap),
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
CLI_COMMAND_DEF("mixer", "configure mixer",
|
||||
"list\r\n"
|
||||
"\t<name>", cliMixer),
|
||||
CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor),
|
||||
CLI_COMMAND_DEF("name", "name of craft", NULL, cliName),
|
||||
#ifdef PLAY_SOUND
|
||||
|
@ -2777,17 +2676,13 @@ const clicmd_t cmdTable[] = {
|
|||
#ifdef USE_SERIAL_PASSTHROUGH
|
||||
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
|
||||
#endif
|
||||
#ifdef USE_SERVOS
|
||||
CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet),
|
||||
#ifdef USE_SERVOS
|
||||
CLI_COMMAND_DEF("smix", "servo mixer",
|
||||
"<rule> <servo> <source> <rate> <speed>\r\n"
|
||||
"\treset\r\n"
|
||||
"\tload <mixer>\r\n"
|
||||
"\treverse <servo> <source> r|n", cliServoMix),
|
||||
#endif
|
||||
#ifdef USE_SDCARD
|
||||
CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
|
||||
#endif
|
||||
|
|
|
@ -360,11 +360,6 @@ void validateAndFixConfig(void)
|
|||
pgResetCopy(serialConfigMutable(), PG_SERIAL_CONFIG);
|
||||
}
|
||||
|
||||
// If provided predefined mixer setup is disabled, fallback to default one
|
||||
if (!isMixerEnabled(mixerConfig()->mixerMode)) {
|
||||
mixerConfigMutable()->mixerMode = DEFAULT_MIXER;
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
// Ensure sane values of navConfig settings
|
||||
validateNavConfig();
|
||||
|
|
|
@ -524,7 +524,6 @@ void processRx(timeUs_t currentTimeUs)
|
|||
LED1_OFF;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
/* Flaperon mode */
|
||||
if (IS_RC_MODE_ACTIVE(BOXFLAPERON) && STATE(FLAPERON_AVAILABLE)) {
|
||||
if (!FLIGHT_MODE(FLAPERON)) {
|
||||
|
@ -533,7 +532,6 @@ void processRx(timeUs_t currentTimeUs)
|
|||
} else {
|
||||
DISABLE_FLIGHT_MODE(FLAPERON);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_FLM_TURN_ASSIST
|
||||
/* Turn assistant mode */
|
||||
|
@ -612,7 +610,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
}
|
||||
}
|
||||
|
||||
if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE || mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
|
||||
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
}
|
||||
|
||||
|
@ -756,14 +754,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
// motors do not spin up while we are trying to arm or disarm.
|
||||
// Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
|
||||
if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
#ifdef USE_SERVOS
|
||||
&& !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoConfig()->tri_unarmed_servo)
|
||||
#endif
|
||||
&& mixerConfig()->mixerMode != MIXER_AIRPLANE
|
||||
&& mixerConfig()->mixerMode != MIXER_FLYING_WING
|
||||
&& mixerConfig()->mixerMode != MIXER_CUSTOM_AIRPLANE
|
||||
#endif
|
||||
&& !((mixerConfig()->platformType == PLATFORM_TRICOPTER) && servoConfig()->tri_unarmed_servo)
|
||||
&& mixerConfig()->platformType != PLATFORM_AIRPLANE
|
||||
) {
|
||||
rcCommand[YAW] = 0;
|
||||
}
|
||||
|
@ -805,7 +797,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
|
||||
mixTable();
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (isMixerUsingServos()) {
|
||||
servoMixer(dT);
|
||||
processServoAutotrim();
|
||||
|
@ -820,7 +811,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
if (isServoOutputEnabled()) {
|
||||
writeServos();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (motorControlEnable) {
|
||||
writeMotors();
|
||||
|
|
|
@ -269,10 +269,8 @@ void init(void)
|
|||
debugTraceInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
servosInit();
|
||||
mixerUpdateStateFlags(); // This needs to be called early to allow pwm mapper to use information about FIXED_WING state
|
||||
#endif
|
||||
|
||||
drv_pwm_config_t pwm_params;
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
|
@ -290,7 +288,7 @@ void init(void)
|
|||
#endif
|
||||
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
pwm_params.flyingPlatformType = getFlyingPlatformType();
|
||||
pwm_params.flyingPlatformType = mixerConfig()->platformType;
|
||||
|
||||
#if defined(USE_UART2) && defined(STM32F10X)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
|
@ -314,12 +312,10 @@ void init(void)
|
|||
pwm_params.usePPM = (rxConfig()->receiverType == RX_TYPE_PPM);
|
||||
pwm_params.useSerialRx = (rxConfig()->receiverType == RX_TYPE_SERIAL);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
pwm_params.useServoOutputs = isMixerUsingServos();
|
||||
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||
pwm_params.servoCenterPulse = servoConfig()->servoCenterPulse;
|
||||
pwm_params.servoPwmRate = servoConfig()->servoPwmRate;
|
||||
#endif
|
||||
|
||||
pwm_params.pwmProtocolType = motorConfig()->motorPwmProtocol;
|
||||
#ifndef BRUSHED_MOTORS
|
||||
|
|
|
@ -345,7 +345,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
// DEPRECATED - Use MSP_API_VERSION
|
||||
case MSP_IDENT:
|
||||
sbufWriteU8(dst, MW_VERSION);
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
sbufWriteU8(dst, 3); //We no longer have mixerMode, just sent 3 (QuadX) as fallback
|
||||
sbufWriteU8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbufWriteU32(dst, CAP_PLATFORM_32BIT | CAP_DYNBALANCE | CAP_FLAPS | CAP_NAVCAP | CAP_EXTAUX); // "capability"
|
||||
break;
|
||||
|
@ -439,7 +439,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
}
|
||||
break;
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
case MSP_SERVO:
|
||||
sbufWriteData(dst, &servo, MAX_SUPPORTED_SERVOS * 2);
|
||||
break;
|
||||
|
@ -466,14 +465,12 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, 0);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP2_COMMON_MOTOR_MIXER:
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
sbufWriteU16(dst, customMotorMixer(i)->throttle * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->roll + 1.0f, 0.0f, 2.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->pitch + 1.0f, 0.0f, 2.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->yaw + 1.0f, 0.0f, 2.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->roll + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->pitch + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(customMotorMixer(i)->yaw + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -824,7 +821,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_MIXER:
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback
|
||||
break;
|
||||
|
||||
case MSP_RX_CONFIG:
|
||||
|
@ -870,7 +867,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_BF_CONFIG:
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback
|
||||
|
||||
sbufWriteU32(dst, featureMask());
|
||||
|
||||
|
@ -1009,11 +1006,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, 1); // BF: motorConfig()->useUnsyncedPwm
|
||||
sbufWriteU8(dst, motorConfig()->motorPwmProtocol);
|
||||
sbufWriteU16(dst, motorConfig()->motorPwmRate);
|
||||
#ifdef USE_SERVOS
|
||||
sbufWriteU16(dst, servoConfig()->servoPwmRate);
|
||||
#else
|
||||
sbufWriteU16(dst, 0);
|
||||
#endif
|
||||
sbufWriteU8(dst, gyroConfig()->gyroSync);
|
||||
break;
|
||||
|
||||
|
@ -1302,6 +1295,16 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
break;
|
||||
|
||||
case MSP2_INAV_MIXER:
|
||||
sbufWriteU8(dst, mixerConfig()->yaw_motor_direction);
|
||||
sbufWriteU16(dst, mixerConfig()->yaw_jump_prevention_limit);
|
||||
sbufWriteU8(dst, mixerConfig()->platformType);
|
||||
sbufWriteU8(dst, mixerConfig()->hasFlaps);
|
||||
sbufWriteU16(dst, mixerConfig()->appliedMixerPreset);
|
||||
sbufWriteU8(dst, MAX_SUPPORTED_MOTORS);
|
||||
sbufWriteU8(dst, MAX_SUPPORTED_SERVOS);
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -1651,7 +1654,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
case MSP_SET_SERVO_CONFIGURATION:
|
||||
if (dataSize != (1 + 14)) {
|
||||
return MSP_RESULT_ERROR;
|
||||
|
@ -1671,9 +1673,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
servoComputeScalingFactors(tmp_u8);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
case MSP_SET_SERVO_MIX_RULE:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize >= 8) && (tmp_u8 < MAX_SERVO_RULES)) {
|
||||
|
@ -1687,15 +1687,14 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP2_COMMON_SET_MOTOR_MIXER:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 9) && (tmp_u8 < MAX_SUPPORTED_MOTORS)) {
|
||||
customMotorMixerMutable(tmp_u8)->throttle = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 1.0f);
|
||||
customMotorMixerMutable(tmp_u8)->roll = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 2.0f) - 1.0f;
|
||||
customMotorMixerMutable(tmp_u8)->pitch = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 2.0f) - 1.0f;
|
||||
customMotorMixerMutable(tmp_u8)->yaw = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 2.0f) - 1.0f;
|
||||
customMotorMixerMutable(tmp_u8)->roll = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
customMotorMixerMutable(tmp_u8)->pitch = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
customMotorMixerMutable(tmp_u8)->yaw = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
@ -1743,11 +1742,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // BF: motorConfig()->useUnsyncedPwm
|
||||
motorConfigMutable()->motorPwmProtocol = sbufReadU8(src);
|
||||
motorConfigMutable()->motorPwmRate = sbufReadU16(src);
|
||||
#ifdef USE_SERVOS
|
||||
servoConfigMutable()->servoPwmRate = sbufReadU16(src);
|
||||
#else
|
||||
sbufReadU16(src);
|
||||
#endif
|
||||
gyroConfigMutable()->gyroSync = sbufReadU8(src);
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
|
@ -2175,15 +2170,13 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
case MSP_SET_MIXER:
|
||||
if (dataSize >= 1) {
|
||||
mixerConfigMutable()->mixerMode = sbufReadU8(src);
|
||||
sbufReadU8(src); //This is ignored, no longer supporting mixerMode
|
||||
mixerUpdateStateFlags(); // Required for correct preset functionality
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_SET_RX_CONFIG:
|
||||
if (dataSize >= 24) {
|
||||
|
@ -2244,12 +2237,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
|
||||
case MSP_SET_BF_CONFIG:
|
||||
if (dataSize >= 16) {
|
||||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
sbufReadU8(src); // mixerMode ignored
|
||||
#else
|
||||
mixerConfigMutable()->mixerMode = sbufReadU8(src); // mixerMode
|
||||
sbufReadU8(src); // mixerMode no longer supported, just swallow
|
||||
mixerUpdateStateFlags(); // Required for correct preset functionality
|
||||
#endif
|
||||
|
||||
featureClearAll();
|
||||
featureSet(sbufReadU32(src)); // features bitmap
|
||||
|
@ -2389,6 +2378,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SET_MIXER:
|
||||
mixerConfigMutable()->yaw_motor_direction = sbufReadU8(src);
|
||||
mixerConfigMutable()->yaw_jump_prevention_limit = sbufReadU16(src);
|
||||
mixerConfigMutable()->platformType = sbufReadU8(src);
|
||||
mixerConfigMutable()->hasFlaps = sbufReadU8(src);
|
||||
mixerConfigMutable()->appliedMixerPreset = sbufReadU16(src);
|
||||
sbufReadU8(src); //Read and ignore MAX_SUPPORTED_MOTORS
|
||||
sbufReadU8(src); //Read and ignore MAX_SUPPORTED_SERVOS
|
||||
mixerUpdateStateFlags();
|
||||
break;
|
||||
|
||||
default:
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
|
|
@ -199,7 +199,6 @@ void initActiveBoxIds(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
/*
|
||||
* FLAPERON mode active only in case of airplane and custom airplane. Activating on
|
||||
* flying wing can cause bad thing
|
||||
|
@ -207,7 +206,6 @@ void initActiveBoxIds(void)
|
|||
if (STATE(FLAPERON_AVAILABLE)) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXFLAPERON;
|
||||
}
|
||||
#endif
|
||||
|
||||
activeBoxIds[activeBoxIdCount++] = BOXBEEPERON;
|
||||
|
||||
|
|
|
@ -90,6 +90,9 @@ tables:
|
|||
- name: smartport_fuel_unit
|
||||
values: ["PERCENT", "MAH", "MWH"]
|
||||
enum: smartportFuelUnit_e
|
||||
- name: platform_type
|
||||
values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
|
||||
enum: flyingPlatformType_e
|
||||
|
||||
groups:
|
||||
- name: PG_GYRO_CONFIG
|
||||
|
@ -484,7 +487,6 @@ groups:
|
|||
- name: PG_GIMBAL_CONFIG
|
||||
type: gimbalConfig_t
|
||||
headers: ["io/gimbal.h"]
|
||||
condition: USE_SERVOS
|
||||
members:
|
||||
- name: gimbal_mode
|
||||
field: mode
|
||||
|
@ -552,6 +554,17 @@ groups:
|
|||
- name: yaw_jump_prevention_limit
|
||||
min: YAW_JUMP_PREVENTION_LIMIT_LOW
|
||||
max: YAW_JUMP_PREVENTION_LIMIT_HIGH
|
||||
- name: platform_type
|
||||
field: platformType
|
||||
type: uint8_t
|
||||
table: platform_type
|
||||
- name: has_flaps
|
||||
field: hasFlaps
|
||||
type: bool
|
||||
- name: model_preview_type
|
||||
field: appliedMixerPreset
|
||||
min: -1
|
||||
max: INT16_MAX
|
||||
|
||||
- name: PG_MOTOR_3D_CONFIG
|
||||
type: flight3DConfig_t
|
||||
|
@ -572,7 +585,6 @@ groups:
|
|||
- name: PG_SERVO_CONFIG
|
||||
type: servoConfig_t
|
||||
headers: ["flight/servos.h"]
|
||||
condition: USE_SERVOS
|
||||
members:
|
||||
- name: servo_center_pulse
|
||||
field: servoCenterPulse
|
||||
|
@ -870,17 +882,14 @@ groups:
|
|||
max: 2
|
||||
- name: fw_iterm_throw_limit
|
||||
field: fixedWingItermThrowLimit
|
||||
condition: USE_SERVOS
|
||||
min: FW_ITERM_THROW_LIMIT_MIN
|
||||
max: FW_ITERM_THROW_LIMIT_MAX
|
||||
- name: fw_reference_airspeed
|
||||
field: fixedWingReferenceAirspeed
|
||||
condition: USE_SERVOS
|
||||
min: 1
|
||||
max: 5000
|
||||
- name: fw_turn_assist_yaw_gain
|
||||
field: fixedWingCoordinatedYawGain
|
||||
condition: USE_SERVOS
|
||||
min: 0
|
||||
max: 2
|
||||
- name: dterm_notch_hz
|
||||
|
|
|
@ -68,13 +68,14 @@ PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig,
|
|||
.neutral3d = 1460
|
||||
);
|
||||
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 0);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 1);
|
||||
|
||||
PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
|
||||
.mixerMode = MIXER_QUADX,
|
||||
.yaw_motor_direction = 1,
|
||||
.yaw_jump_prevention_limit = 200
|
||||
.yaw_jump_prevention_limit = 200,
|
||||
.platformType = PLATFORM_MULTIROTOR,
|
||||
.hasFlaps = false,
|
||||
.appliedMixerPreset = -1 //This flag is not available in CLI and used by Configurator only
|
||||
);
|
||||
|
||||
#ifdef BRUSHED_MOTORS
|
||||
|
@ -101,199 +102,6 @@ static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
|||
|
||||
PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR_MIXER, 0);
|
||||
|
||||
static const motorMixer_t mixerQuadX[] = {
|
||||
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
|
||||
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
|
||||
};
|
||||
|
||||
#define DEF_MIXER(_mixerMode, _flyingPlatformType, _motorCount, _useServos, _hasFlaps, _motorMap) \
|
||||
{ .mixerMode=_mixerMode, .flyingPlatformType=_flyingPlatformType, .motorCount=_motorCount, .useServos=_useServos, .hasFlaps=_hasFlaps, .motor=_motorMap }
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static const motorMixer_t mixerTricopter[] = {
|
||||
{ 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR
|
||||
{ 1.0f, -1.0f, -0.666667f, 0.0f }, // RIGHT
|
||||
{ 1.0f, 1.0f, -0.666667f, 0.0f }, // LEFT
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerQuadP[] = {
|
||||
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR
|
||||
{ 1.0f, -1.0f, 0.0f, 1.0f }, // RIGHT
|
||||
{ 1.0f, 1.0f, 0.0f, 1.0f }, // LEFT
|
||||
{ 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT
|
||||
};
|
||||
|
||||
#ifndef DISABLE_UNCOMMON_MIXERS
|
||||
static const motorMixer_t mixerVtail4[] = {
|
||||
{ 1.0f, -0.58f, 0.58f, 1.0f }, // REAR_R
|
||||
{ 1.0f, -0.46f, -0.39f, -0.5f }, // FRONT_R
|
||||
{ 1.0f, 0.58f, 0.58f, -1.0f }, // REAR_L
|
||||
{ 1.0f, 0.46f, -0.39f, 0.5f }, // FRONT_L
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerAtail4[] = {
|
||||
{ 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_R
|
||||
{ 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R
|
||||
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerY4[] = {
|
||||
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_TOP CW
|
||||
{ 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R CCW
|
||||
{ 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_BOTTOM CCW
|
||||
{ 1.0f, 1.0f, -1.0f, 0.0f }, // FRONT_L CW
|
||||
};
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
static const motorMixer_t mixerHex6H[] = {
|
||||
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
|
||||
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
|
||||
{ 1.0f, 0.0f, 0.0f, 0.0f }, // RIGHT
|
||||
{ 1.0f, 0.0f, 0.0f, 0.0f }, // LEFT
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerY6[] = {
|
||||
{ 1.0f, 0.0f, 1.333333f, 1.0f }, // REAR
|
||||
{ 1.0f, -1.0f, -0.666667f, -1.0f }, // RIGHT
|
||||
{ 1.0f, 1.0f, -0.666667f, -1.0f }, // LEFT
|
||||
{ 1.0f, 0.0f, 1.333333f, -1.0f }, // UNDER_REAR
|
||||
{ 1.0f, -1.0f, -0.666667f, 1.0f }, // UNDER_RIGHT
|
||||
{ 1.0f, 1.0f, -0.666667f, 1.0f }, // UNDER_LEFT
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerHex6P[] = {
|
||||
{ 1.0f, -0.866025f, 0.5f, 1.0f }, // REAR_R
|
||||
{ 1.0f, -0.866025f, -0.5f, -1.0f }, // FRONT_R
|
||||
{ 1.0f, 0.866025f, 0.5f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 0.866025f, -0.5f, -1.0f }, // FRONT_L
|
||||
{ 1.0f, 0.0f, -1.0f, 1.0f }, // FRONT
|
||||
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR
|
||||
};
|
||||
#endif
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 8)
|
||||
static const motorMixer_t mixerOctoFlatP[] = {
|
||||
{ 1.0f, 0.707107f, -0.707107f, 1.0f }, // FRONT_L
|
||||
{ 1.0f, -0.707107f, -0.707107f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, -0.707107f, 0.707107f, 1.0f }, // REAR_R
|
||||
{ 1.0f, 0.707107f, 0.707107f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT
|
||||
{ 1.0f, -1.0f, 0.0f, -1.0f }, // RIGHT
|
||||
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR
|
||||
{ 1.0f, 1.0f, 0.0f, -1.0f }, // LEFT
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerOctoFlatX[] = {
|
||||
{ 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
|
||||
{ 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
|
||||
{ 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
|
||||
{ 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
|
||||
{ 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
|
||||
{ 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
|
||||
};
|
||||
|
||||
static const motorMixer_t mixerOctoX8[] = {
|
||||
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
|
||||
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
|
||||
{ 1.0f, -1.0f, 1.0f, 1.0f }, // UNDER_REAR_R
|
||||
{ 1.0f, -1.0f, -1.0f, -1.0f }, // UNDER_FRONT_R
|
||||
{ 1.0f, 1.0f, 1.0f, -1.0f }, // UNDER_REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, 1.0f }, // UNDER_FRONT_L
|
||||
};
|
||||
#endif
|
||||
#endif //DISABLE_UNCOMMON_MIXERS
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
static const motorMixer_t mixerHex6X[] = {
|
||||
{ 1.0f, -0.5f, 0.866025f, 1.0f }, // REAR_R
|
||||
{ 1.0f, -0.5f, -0.866025f, 1.0f }, // FRONT_R
|
||||
{ 1.0f, 0.5f, 0.866025f, -1.0f }, // REAR_L
|
||||
{ 1.0f, 0.5f, -0.866025f, -1.0f }, // FRONT_L
|
||||
{ 1.0f, -1.0f, 0.0f, -1.0f }, // RIGHT
|
||||
{ 1.0f, 1.0f, 0.0f, 1.0f }, // LEFT
|
||||
};
|
||||
#endif
|
||||
|
||||
static const motorMixer_t mixerDualProp[] = {
|
||||
{ 1.0f, 0.0f, 0.0f, 0.0f },
|
||||
{ 1.0f, 0.0f, 0.0f, 0.0f },
|
||||
};
|
||||
|
||||
static const mixer_t mixerTable[] = {
|
||||
// motors, use servo, motor mixer
|
||||
// mixerMode flyingPlatformType motorCount useServos hasFlaps motorMap
|
||||
DEF_MIXER( MIXER_TRI, PLATFORM_MULTIROTOR, 3, true, false, mixerTricopter ),
|
||||
DEF_MIXER( MIXER_CUSTOM_TRI, PLATFORM_MULTIROTOR, 3, false, false, NULL ),
|
||||
|
||||
DEF_MIXER( MIXER_QUADP, PLATFORM_MULTIROTOR, 4, false, false, mixerQuadP ),
|
||||
DEF_MIXER( MIXER_QUADX, PLATFORM_MULTIROTOR, 4, false, false, mixerQuadX ),
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
DEF_MIXER( MIXER_HEX6X, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6X ),
|
||||
#endif
|
||||
|
||||
DEF_MIXER( MIXER_CUSTOM, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_BICOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
//DEF_MIXER( MIXER_GIMBAL, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
DEF_MIXER( MIXER_FLYING_WING, PLATFORM_AIRPLANE, 2, true, false, mixerDualProp ),
|
||||
DEF_MIXER( MIXER_AIRPLANE, PLATFORM_AIRPLANE, 2, true, true, mixerDualProp ),
|
||||
DEF_MIXER( MIXER_CUSTOM_AIRPLANE, PLATFORM_AIRPLANE, 2, true, true, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_HELI_120_CCPM, PLATFORM_HELICOPTER, 1, true, false, NULL ),
|
||||
//DEF_MIXER( MIXER_HELI_90_DEG, PLATFORM_HELICOPTER, 1, true, false, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_PPM_TO_SERVO, PLATFORM_MULTIROTOR, 0, true, false, NULL ),
|
||||
//DEF_MIXER( MIXER_DUALCOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
//DEF_MIXER( MIXER_SINGLECOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
DEF_MIXER( MIXER_Y4, PLATFORM_MULTIROTOR, 4, false, false, mixerY4 ),
|
||||
DEF_MIXER( MIXER_ATAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerAtail4 ),
|
||||
DEF_MIXER( MIXER_VTAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerVtail4 ),
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
DEF_MIXER( MIXER_Y6, PLATFORM_MULTIROTOR, 6, false, false, mixerY6 ),
|
||||
DEF_MIXER( MIXER_HEX6, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6P ),
|
||||
DEF_MIXER( MIXER_HEX6H, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6H ),
|
||||
#endif
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 8)
|
||||
DEF_MIXER( MIXER_OCTOX8, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoX8 ),
|
||||
DEF_MIXER( MIXER_OCTOFLATP, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoFlatP ),
|
||||
DEF_MIXER( MIXER_OCTOFLATX, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoFlatX ),
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
#else
|
||||
static const mixer_t quadMixerDescriptor = DEF_MIXER( MIXER_QUADX, PLATFORM_MULTIROTOR, 4, false, false, mixerQuadX );
|
||||
#endif // USE_QUAD_MIXER_ONLY
|
||||
|
||||
const mixer_t * findMixer(mixerMode_e mixerMode)
|
||||
{
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
for (unsigned ii = 0; ii < sizeof(mixerTable)/sizeof(mixerTable[0]); ii++) {
|
||||
if (mixerTable[ii].mixerMode == mixerMode)
|
||||
return &mixerTable[ii];
|
||||
}
|
||||
#else
|
||||
if (mixerMode == MIXER_QUADX)
|
||||
return &quadMixerDescriptor;
|
||||
#endif
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
uint8_t getMotorCount(void)
|
||||
{
|
||||
return motorCount;
|
||||
|
@ -304,37 +112,13 @@ bool mixerIsOutputSaturated(void)
|
|||
return motorLimitReached;
|
||||
}
|
||||
|
||||
bool isMixerEnabled(mixerMode_e mixerMode)
|
||||
{
|
||||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
UNUSED(mixerMode);
|
||||
return true;
|
||||
#else
|
||||
const mixer_t * mixer = findMixer(mixerMode);
|
||||
return (mixer != NULL) ? true : false;
|
||||
#endif
|
||||
}
|
||||
|
||||
int getFlyingPlatformType(void)
|
||||
{
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
if (mixer)
|
||||
return mixer->flyingPlatformType;
|
||||
else
|
||||
return PLATFORM_MULTIROTOR; // safe default
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
void mixerUpdateStateFlags(void)
|
||||
{
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
// set flag that we're on something with wings
|
||||
if (mixer->flyingPlatformType == PLATFORM_AIRPLANE) {
|
||||
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
|
||||
ENABLE_STATE(FIXED_WING);
|
||||
DISABLE_STATE(HELICOPTER);
|
||||
} else if (mixer->flyingPlatformType == PLATFORM_HELICOPTER) {
|
||||
} else if (mixerConfig()->platformType == PLATFORM_HELICOPTER) {
|
||||
DISABLE_STATE(FIXED_WING);
|
||||
ENABLE_STATE(HELICOPTER);
|
||||
} else {
|
||||
|
@ -342,7 +126,7 @@ void mixerUpdateStateFlags(void)
|
|||
DISABLE_STATE(HELICOPTER);
|
||||
}
|
||||
|
||||
if (mixer->hasFlaps) {
|
||||
if (mixerConfig()->hasFlaps) {
|
||||
ENABLE_STATE(FLAPERON_AVAILABLE);
|
||||
} else {
|
||||
DISABLE_STATE(FLAPERON_AVAILABLE);
|
||||
|
@ -353,28 +137,15 @@ void mixerUsePWMIOConfiguration(void)
|
|||
{
|
||||
motorCount = 0;
|
||||
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
// load custom mixer into currentMixer
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
// check if done
|
||||
if (customMotorMixer(i)->throttle == 0.0f)
|
||||
break;
|
||||
currentMixer[i] = *customMotorMixer(i);
|
||||
motorCount++;
|
||||
}
|
||||
} else {
|
||||
motorCount = MIN(mixer->motorCount, pwmGetOutputConfiguration()->motorCount);
|
||||
// copy motor-based mixer
|
||||
if (mixer->motor) {
|
||||
for (int i = 0; i < motorCount; i++) {
|
||||
currentMixer[i] = mixer->motor[i];
|
||||
}
|
||||
}
|
||||
// load custom mixer into currentMixer
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
// check if done
|
||||
if (customMotorMixer(i)->throttle == 0.0f)
|
||||
break;
|
||||
currentMixer[i] = *customMotorMixer(i);
|
||||
motorCount++;
|
||||
}
|
||||
|
||||
|
||||
// in 3D mode, mixer gain has to be halved
|
||||
if (feature(FEATURE_3D)) {
|
||||
if (motorCount > 1) {
|
||||
|
@ -388,38 +159,6 @@ void mixerUsePWMIOConfiguration(void)
|
|||
|
||||
mixerResetDisarmedMotors();
|
||||
}
|
||||
#else
|
||||
void mixerUsePWMIOConfiguration(void)
|
||||
{
|
||||
motorCount = 4;
|
||||
for (int i = 0; i < motorCount; i++) {
|
||||
currentMixer[i] = mixerQuadX[i];
|
||||
}
|
||||
mixerResetDisarmedMotors();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers)
|
||||
{
|
||||
// we're 1-based
|
||||
index++;
|
||||
// clear existing
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
customMixers[i].throttle = 0.0f;
|
||||
}
|
||||
|
||||
// do we have anything here to begin with?
|
||||
const mixer_t * mixer = findMixer(index);
|
||||
if (mixer->motor != NULL) {
|
||||
for (int i = 0; i < mixer->motorCount; i++) {
|
||||
customMixers[i] = mixer->motor[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void mixerResetDisarmedMotors(void)
|
||||
{
|
||||
|
|
|
@ -19,9 +19,7 @@
|
|||
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#if defined(USE_QUAD_MIXER_ONLY)
|
||||
#define MAX_SUPPORTED_MOTORS 4
|
||||
#elif defined(TARGET_MOTOR_COUNT)
|
||||
#if defined(TARGET_MOTOR_COUNT)
|
||||
#define MAX_SUPPORTED_MOTORS TARGET_MOTOR_COUNT
|
||||
#else
|
||||
#define MAX_SUPPORTED_MOTORS 12
|
||||
|
@ -30,38 +28,15 @@
|
|||
#define YAW_JUMP_PREVENTION_LIMIT_LOW 80
|
||||
#define YAW_JUMP_PREVENTION_LIMIT_HIGH 500
|
||||
|
||||
|
||||
// Note: this is called MultiType/MULTITYPE_* in baseflight.
|
||||
typedef enum mixerMode
|
||||
{
|
||||
MIXER_TRI = 1,
|
||||
MIXER_QUADP = 2,
|
||||
MIXER_QUADX = 3,
|
||||
MIXER_BICOPTER = 4,
|
||||
MIXER_GIMBAL = 5,
|
||||
MIXER_Y6 = 6,
|
||||
MIXER_HEX6 = 7,
|
||||
MIXER_FLYING_WING = 8,
|
||||
MIXER_Y4 = 9,
|
||||
MIXER_HEX6X = 10,
|
||||
MIXER_OCTOX8 = 11,
|
||||
MIXER_OCTOFLATP = 12,
|
||||
MIXER_OCTOFLATX = 13,
|
||||
MIXER_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported)
|
||||
MIXER_HELI_120_CCPM = 15,
|
||||
MIXER_HELI_90_DEG = 16,
|
||||
MIXER_VTAIL4 = 17,
|
||||
MIXER_HEX6H = 18,
|
||||
MIXER_PPM_TO_SERVO = 19, // PPM -> servo relay
|
||||
MIXER_DUALCOPTER = 20,
|
||||
MIXER_SINGLECOPTER = 21,
|
||||
MIXER_ATAIL4 = 22,
|
||||
MIXER_CUSTOM = 23,
|
||||
MIXER_CUSTOM_AIRPLANE = 24,
|
||||
MIXER_CUSTOM_TRI = 25
|
||||
} mixerMode_e;
|
||||
|
||||
#define DEFAULT_MIXER MIXER_QUADX
|
||||
typedef enum {
|
||||
PLATFORM_MULTIROTOR = 0,
|
||||
PLATFORM_AIRPLANE = 1,
|
||||
PLATFORM_HELICOPTER = 2,
|
||||
PLATFORM_TRICOPTER = 3,
|
||||
PLATFORM_ROVER = 4,
|
||||
PLATFORM_BOAT = 5,
|
||||
PLATFORM_OTHER = 6
|
||||
} flyingPlatformType_e;
|
||||
|
||||
typedef struct motorAxisCorrectionLimits_s {
|
||||
int16_t min;
|
||||
|
@ -78,20 +53,12 @@ typedef struct motorMixer_s {
|
|||
|
||||
PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer);
|
||||
|
||||
// Custom mixer configuration
|
||||
typedef struct mixer_s {
|
||||
mixerMode_e mixerMode;
|
||||
const motorMixer_t *motor;
|
||||
uint8_t flyingPlatformType; // MC, FW or HELI
|
||||
uint8_t motorCount;
|
||||
bool useServos;
|
||||
bool hasFlaps;
|
||||
} mixer_t;
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
uint8_t mixerMode;
|
||||
int8_t yaw_motor_direction;
|
||||
uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100)
|
||||
uint8_t platformType;
|
||||
bool hasFlaps;
|
||||
int16_t appliedMixerPreset;
|
||||
} mixerConfig_t;
|
||||
|
||||
PG_DECLARE(mixerConfig_t, mixerConfig);
|
||||
|
@ -124,7 +91,6 @@ uint8_t getMotorCount(void);
|
|||
bool mixerIsOutputSaturated(void);
|
||||
|
||||
void writeAllMotors(int16_t mc);
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||
void mixerUsePWMIOConfiguration(void);
|
||||
void mixerUpdateStateFlags(void);
|
||||
void mixerResetDisarmedMotors(void);
|
||||
|
@ -133,8 +99,4 @@ void writeMotors(void);
|
|||
void processServoTilt(void);
|
||||
void processServoAutotrim(void);
|
||||
void stopMotors(void);
|
||||
void stopPwmAllMotors(void);
|
||||
|
||||
int getFlyingPlatformType(void);
|
||||
|
||||
bool isMixerEnabled(mixerMode_e mixerMode);
|
||||
void stopPwmAllMotors(void);
|
|
@ -443,7 +443,6 @@ static void pidApplySetpointRateLimiting(pidState_t *pidState, flight_dynamics_i
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
static void pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamics_index_t axis)
|
||||
{
|
||||
const float rateError = pidState->rateTarget - pidState->gyroRate;
|
||||
|
@ -485,7 +484,6 @@ static void pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamic
|
|||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
static void pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis)
|
||||
{
|
||||
|
@ -761,15 +759,11 @@ void pidController(void)
|
|||
// Step 4: Run gyro-driven control
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
// Apply PID setpoint controller
|
||||
#ifdef USE_SERVOS
|
||||
if (STATE(FIXED_WING)) {
|
||||
pidApplyFixedWingRateController(&pidState[axis], axis);
|
||||
}
|
||||
else {
|
||||
pidApplyMulticopterRateController(&pidState[axis], axis);
|
||||
}
|
||||
#else
|
||||
pidApplyMulticopterRateController(&pidState[axis], axis);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
@ -56,8 +54,6 @@
|
|||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
extern const mixer_t * findMixer(mixerMode_e mixerMode);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(servoConfig_t, servoConfig,
|
||||
|
@ -104,65 +100,6 @@ static bool servoFilterIsSet;
|
|||
static servoMetadata_t servoMetadata[MAX_SUPPORTED_SERVOS];
|
||||
static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES];
|
||||
|
||||
#define COUNT_SERVO_RULES(rules) (sizeof(rules) / sizeof(servoMixer_t))
|
||||
// mixer rule format servo, input, rate, speed
|
||||
static const servoMixer_t servoMixerAirplane[] = {
|
||||
{ SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0 },
|
||||
{ SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0 },
|
||||
{ SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, -100, 0 },
|
||||
{ SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0 },
|
||||
{ SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0 },
|
||||
{ SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0 },
|
||||
};
|
||||
|
||||
static const servoMixer_t servoMixerFlyingWing[] = {
|
||||
{ SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 50, 0 },
|
||||
{ SERVO_FLAPPERON_1, INPUT_STABILIZED_PITCH, 50, 0 },
|
||||
{ SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, -50, 0 },
|
||||
{ SERVO_FLAPPERON_2, INPUT_STABILIZED_PITCH, 50, 0 },
|
||||
};
|
||||
|
||||
static const servoMixer_t servoMixerTri[] = {
|
||||
{ SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0 },
|
||||
};
|
||||
|
||||
// Custom mixer configuration
|
||||
typedef struct mixerRules_s {
|
||||
uint8_t servoRuleCount;
|
||||
uint8_t minServoIndex;
|
||||
uint8_t maxServoIndex;
|
||||
const servoMixer_t *rule;
|
||||
} mixerRules_t;
|
||||
|
||||
const mixerRules_t servoMixers[] = {
|
||||
{ 0, 0, 0, NULL }, // entry 0
|
||||
{ COUNT_SERVO_RULES(servoMixerTri), SERVO_RUDDER, SERVO_RUDDER, servoMixerTri }, // MULTITYPE_TRI
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_QUADP
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_QUADX
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_BI
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_GIMBAL / MIXER_GIMBAL -> disabled
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_Y6
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_HEX6
|
||||
{ COUNT_SERVO_RULES(servoMixerFlyingWing), SERVO_FLAPPERONS_MIN, SERVO_FLAPPERONS_MAX, servoMixerFlyingWing },// * MULTITYPE_FLYING_WING
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_Y4
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_HEX6X
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_OCTOX8
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_OCTOFLATP
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_OCTOFLATX
|
||||
{ COUNT_SERVO_RULES(servoMixerAirplane), SERVO_PLANE_INDEX_MIN, SERVO_PLANE_INDEX_MAX, servoMixerAirplane }, // * MULTITYPE_AIRPLANE
|
||||
{ 0, 0, 0, NULL }, // * MIXER_HELI_120_CCPM -> disabled, never fully implemented in CF
|
||||
{ 0, 0, 0, NULL }, // * MIXER_HELI_90_DEG -> disabled, never fully implemented in CF
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_VTAIL4
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_HEX6H
|
||||
{ 0, 0, 0, NULL }, // * MULTITYPE_PPM_TO_SERVO
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_DUALCOPTER
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_SINGLECOPTER
|
||||
{ 0, 0, 0, NULL }, // MULTITYPE_ATAIL4
|
||||
{ 0, 2, 5, NULL }, // MULTITYPE_CUSTOM
|
||||
{ 0, SERVO_PLANE_INDEX_MIN, SERVO_PLANE_INDEX_MAX, NULL }, // MULTITYPE_CUSTOM_PLANE
|
||||
{ 0, SERVO_RUDDER, SERVO_RUDDER, NULL }, // MULTITYPE_CUSTOM_TRI
|
||||
};
|
||||
|
||||
int16_t getFlaperonDirection(uint8_t servoPin)
|
||||
{
|
||||
if (servoPin == SERVO_FLAPPERON_2) {
|
||||
|
@ -202,59 +139,35 @@ void servoComputeScalingFactors(uint8_t servoIndex) {
|
|||
|
||||
void servosInit(void)
|
||||
{
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
const mixer_t * motorMixer = findMixer(currentMixerMode);
|
||||
|
||||
minServoIndex = servoMixers[currentMixerMode].minServoIndex;
|
||||
maxServoIndex = servoMixers[currentMixerMode].maxServoIndex;
|
||||
|
||||
// enable servos for mixes that require them. note, this shifts motor counts.
|
||||
mixerUsesServos = motorMixer->useServos || feature(FEATURE_SERVO_TILT);
|
||||
|
||||
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
||||
servoOutputEnabled = motorMixer->useServos || feature(FEATURE_SERVO_TILT) || feature(FEATURE_CHANNEL_FORWARDING);
|
||||
|
||||
// give all servos a default command
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servo[i] = DEFAULT_SERVO_MIDDLE;
|
||||
}
|
||||
|
||||
/*
|
||||
* If mixer has predefined servo mixes, load them
|
||||
* load mixer
|
||||
*/
|
||||
if (mixerUsesServos) {
|
||||
servoRuleCount = servoMixers[currentMixerMode].servoRuleCount;
|
||||
if (servoMixers[currentMixerMode].rule) {
|
||||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
currentServoMixer[i] = servoMixers[currentMixerMode].rule[i];
|
||||
}
|
||||
}
|
||||
loadCustomServoMixer();
|
||||
|
||||
// If there are servo rules after all, update variables
|
||||
if (servoRuleCount > 0) {
|
||||
servoOutputEnabled = 1;
|
||||
mixerUsesServos = 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* When we are dealing with CUSTOM mixers, load mixes defined with
|
||||
* smix and update internal variables
|
||||
*/
|
||||
if (loadCustomServoMixer()) {
|
||||
// If there are servo rules after all, update variables
|
||||
if (servoRuleCount > 0) {
|
||||
servoOutputEnabled = 1;
|
||||
mixerUsesServos = 1;
|
||||
}
|
||||
}
|
||||
// enable servos for mixes that require them. note, this shifts motor counts.
|
||||
mixerUsesServos = mixerUsesServos || feature(FEATURE_SERVO_TILT);
|
||||
|
||||
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
||||
servoOutputEnabled = mixerUsesServos || feature(FEATURE_CHANNEL_FORWARDING);
|
||||
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++)
|
||||
servoComputeScalingFactors(i);
|
||||
|
||||
}
|
||||
|
||||
bool loadCustomServoMixer(void)
|
||||
void loadCustomServoMixer(void)
|
||||
{
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
if (!(currentMixerMode == MIXER_CUSTOM_AIRPLANE || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// reset settings
|
||||
servoRuleCount = 0;
|
||||
minServoIndex = 255;
|
||||
|
@ -278,22 +191,6 @@ bool loadCustomServoMixer(void)
|
|||
memcpy(¤tServoMixer[i], customServoMixers(i), sizeof(servoMixer_t));
|
||||
servoRuleCount++;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void servoMixerLoadMix(int index)
|
||||
{
|
||||
// we're 1-based
|
||||
index++;
|
||||
// clear existing
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
customServoMixersMutable(i)->targetChannel = customServoMixersMutable(i)->inputSource = customServoMixersMutable(i)->rate = 0;
|
||||
}
|
||||
|
||||
for (int i = 0; i < servoMixers[index].servoRuleCount; i++) {
|
||||
*customServoMixersMutable(i) = servoMixers[index].rule[i];
|
||||
}
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED void forwardAuxChannelsToServos(uint8_t firstServoIndex)
|
||||
|
@ -338,8 +235,7 @@ void writeServos(void)
|
|||
/*
|
||||
* in case of tricopters, there might me a need to zero servo output when unarmed
|
||||
*/
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
if ((currentMixerMode == MIXER_TRI || currentMixerMode == MIXER_CUSTOM_TRI) && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) {
|
||||
if (mixerConfig()->platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) {
|
||||
zeroServoValue = true;
|
||||
}
|
||||
|
||||
|
@ -568,5 +464,4 @@ bool isServoOutputEnabled(void)
|
|||
bool isMixerUsingServos(void)
|
||||
{
|
||||
return mixerUsesServos;
|
||||
}
|
||||
#endif
|
||||
}
|
|
@ -19,11 +19,7 @@
|
|||
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#if defined(USE_QUAD_MIXER_ONLY)
|
||||
#define MAX_SUPPORTED_SERVOS 1
|
||||
#else
|
||||
#define MAX_SUPPORTED_SERVOS 8
|
||||
#endif
|
||||
|
||||
// These must be consecutive, see 'reversedSources'
|
||||
enum {
|
||||
|
@ -132,8 +128,7 @@ extern int16_t servo[MAX_SUPPORTED_SERVOS];
|
|||
bool isServoOutputEnabled(void);
|
||||
bool isMixerUsingServos(void);
|
||||
void writeServos(void);
|
||||
void servoMixerLoadMix(int index);
|
||||
bool loadCustomServoMixer(void);
|
||||
void loadCustomServoMixer(void);
|
||||
int servoDirection(int servoIndex, int fromChannel);
|
||||
void servoMixer(float dT);
|
||||
void servoComputeScalingFactors(uint8_t servoIndex);
|
||||
|
|
|
@ -60,7 +60,7 @@
|
|||
#define MSP_PROTOCOL_VERSION 0 // Same version over MSPv1 & MSPv2 - message format didn't change and it backward compatible
|
||||
|
||||
#define API_VERSION_MAJOR 2 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 1 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
#define API_VERSION_MINOR 2 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
|
|
@ -28,3 +28,6 @@
|
|||
#define MSP2_INAV_RATE_PROFILE 0x2007
|
||||
#define MSP2_INAV_SET_RATE_PROFILE 0x2008
|
||||
#define MSP2_INAV_AIR_SPEED 0x2009
|
||||
|
||||
#define MSP2_INAV_MIXER 0x2010
|
||||
#define MSP2_INAV_SET_MIXER 0x2011
|
||||
|
|
|
@ -31,7 +31,6 @@
|
|||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
mixerConfigMutable()->mixerMode = MIXER_HEX6X;
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
|
||||
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
void targetConfiguration(void)
|
||||
{
|
||||
systemConfigMutable()->asyncMode = ASYNC_MODE_NONE;
|
||||
mixerConfigMutable()->mixerMode = MIXER_QUADX;
|
||||
mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR;
|
||||
|
||||
featureSet(FEATURE_VBAT);
|
||||
featureSet(FEATURE_GPS);
|
||||
|
|
|
@ -50,5 +50,5 @@ void targetConfiguration(void)
|
|||
serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
telemetryConfigMutable()->smartportUartUnidirectional = 1;
|
||||
|
||||
mixerConfigMutable()->mixerMode = MIXER_AIRPLANE;
|
||||
mixerConfigMutable()->platformType = PLATFORM_AIRPLANE;
|
||||
}
|
||||
|
|
|
@ -136,7 +136,6 @@
|
|||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
#define TARGET_MOTOR_COUNT 10
|
||||
#define USE_SERVOS
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
|
@ -34,7 +34,7 @@ void targetConfiguration(void)
|
|||
|
||||
//featureSet(FEATURE_PWM_OUTPUT_ENABLE); // enable PWM outputs by default
|
||||
//mixerConfigMutable()->mixerMode = MIXER_FLYING_WING; // default mixer to flying wing
|
||||
mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; // default mixer to Airplane
|
||||
mixerConfigMutable()->platformType = PLATFORM_AIRPLANE; // default mixer to Airplane
|
||||
|
||||
serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
}
|
|
@ -67,7 +67,6 @@
|
|||
#define USE_TELEMETRY
|
||||
#define USE_BLACKBOX
|
||||
#define USE_SERIAL_RX
|
||||
#define USE_SERVOS
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define USE_ADC
|
||||
|
|
|
@ -21,7 +21,6 @@
|
|||
#define I2C2_OVERCLOCK false
|
||||
#define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week
|
||||
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define USE_RX_PWM
|
||||
|
@ -120,7 +119,6 @@
|
|||
#define SKIP_TASK_STATISTICS
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
#define SKIP_CLI_RESOURCES
|
||||
#define DISABLE_UNCOMMON_MIXERS
|
||||
#define NAV_MAX_WAYPOINTS 30
|
||||
#define MAX_BOOTLOG_ENTRIES 32
|
||||
#endif
|
||||
|
|
|
@ -428,34 +428,24 @@ void mavlinkSendHUDAndHeartbeat(void)
|
|||
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
|
||||
uint8_t mavSystemType;
|
||||
switch (mixerConfig()->mixerMode)
|
||||
switch (mixerConfig()->platformType)
|
||||
{
|
||||
case MIXER_TRI:
|
||||
mavSystemType = MAV_TYPE_TRICOPTER;
|
||||
break;
|
||||
case MIXER_QUADP:
|
||||
case MIXER_QUADX:
|
||||
case MIXER_Y4:
|
||||
case MIXER_VTAIL4:
|
||||
case PLATFORM_MULTIROTOR:
|
||||
mavSystemType = MAV_TYPE_QUADROTOR;
|
||||
break;
|
||||
case MIXER_Y6:
|
||||
case MIXER_HEX6:
|
||||
case MIXER_HEX6X:
|
||||
mavSystemType = MAV_TYPE_HEXAROTOR;
|
||||
case PLATFORM_TRICOPTER:
|
||||
mavSystemType = MAV_TYPE_TRICOPTER;
|
||||
break;
|
||||
case MIXER_OCTOX8:
|
||||
case MIXER_OCTOFLATP:
|
||||
case MIXER_OCTOFLATX:
|
||||
mavSystemType = MAV_TYPE_OCTOROTOR;
|
||||
break;
|
||||
case MIXER_FLYING_WING:
|
||||
case MIXER_AIRPLANE:
|
||||
case MIXER_CUSTOM_AIRPLANE:
|
||||
case PLATFORM_AIRPLANE:
|
||||
mavSystemType = MAV_TYPE_FIXED_WING;
|
||||
break;
|
||||
case MIXER_HELI_120_CCPM:
|
||||
case MIXER_HELI_90_DEG:
|
||||
case PLATFORM_ROVER:
|
||||
mavSystemType = MAV_TYPE_GROUND_ROVER;
|
||||
break;
|
||||
case PLATFORM_BOAT:
|
||||
mavSystemType = MAV_TYPE_SURFACE_BOAT;
|
||||
break;
|
||||
case PLATFORM_HELICOPTER:
|
||||
mavSystemType = MAV_TYPE_HELICOPTER;
|
||||
break;
|
||||
default:
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
#define USE_TELEMETRY_SMARTPORT
|
||||
#define USE_TELEMETRY_LTM
|
||||
#define USE_LED_STRIP
|
||||
#define USE_SERVOS
|
||||
#define TRANSPONDER
|
||||
#define USE_FAKE_GYRO
|
||||
#define USE_VCP
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue