Remove flight_mixer.c's dependency on mw.h/board.h.
This is a large commit, from the commit it is clear that the mixer has many dependencies, this is expected since it is central to the application. To achieve the decoupling many master config and profile members had to be moved into structures. Relocated throttle/pitch curves into rc_curves.c/h since it has nothing to with rx code, this fixed the dependencies inside the rx provider files.
This commit is contained in:
parent
bb91b1f560
commit
695db3523a
1
Makefile
1
Makefile
|
@ -74,6 +74,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
|
|||
gps_common.c \
|
||||
runtime_config.c \
|
||||
rc_controls.c \
|
||||
rc_curves.c \
|
||||
rx_common.c \
|
||||
rx_pwm.c \
|
||||
rx_sbus.c \
|
||||
|
|
50
src/config.c
50
src/config.c
|
@ -7,8 +7,6 @@
|
|||
#include "common/axis.h"
|
||||
#include "flight_common.h"
|
||||
|
||||
|
||||
|
||||
#include "drivers/accgyro_common.h"
|
||||
#include "drivers/system_common.h"
|
||||
|
||||
|
@ -26,7 +24,9 @@
|
|||
#include "boardalignment.h"
|
||||
#include "battery.h"
|
||||
#include "gimbal.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rc_curves.h"
|
||||
#include "rx_common.h"
|
||||
#include "gps_common.h"
|
||||
#include "serial_common.h"
|
||||
|
@ -38,6 +38,8 @@
|
|||
#include "config_master.h"
|
||||
|
||||
void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
|
||||
void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DConfigToUse, escAndServoConfig_t *escAndServoConfigToUse, mixerConfig_t *mixerConfigToUse, airplaneConfig_t *airplaneConfigToUse, rxConfig_t *rxConfig, gimbalConfig_t *gimbalConfigToUse);
|
||||
|
||||
|
||||
#ifndef FLASH_PAGE_COUNT
|
||||
#define FLASH_PAGE_COUNT 128
|
||||
|
@ -87,7 +89,7 @@ static bool isEEPROMContentValid(void)
|
|||
void activateConfig(void)
|
||||
{
|
||||
generatePitchCurve(¤tProfile.controlRateConfig);
|
||||
generateThrottleCurve(¤tProfile.controlRateConfig, masterConfig.minthrottle, masterConfig.maxthrottle);
|
||||
generateThrottleCurve(¤tProfile.controlRateConfig, &masterConfig.escAndServoConfig);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
setPIDController(currentProfile.pidController);
|
||||
|
@ -95,6 +97,15 @@ void activateConfig(void)
|
|||
gpsUsePIDs(¤tProfile.pidProfile);
|
||||
useFailsafeConfig(¤tProfile.failsafeConfig);
|
||||
setAccelerationTrims(&masterConfig.accZero);
|
||||
mixerUseConfigs(
|
||||
currentProfile.servoConf,
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.escAndServoConfig,
|
||||
¤tProfile.mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig,
|
||||
¤tProfile.gimbalConfig
|
||||
);
|
||||
|
||||
#ifdef BARO
|
||||
useBarometerConfig(¤tProfile.barometerConfig);
|
||||
|
@ -245,6 +256,21 @@ void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
|||
sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
|
||||
}
|
||||
|
||||
void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
|
||||
{
|
||||
escAndServoConfig->minthrottle = 1150;
|
||||
escAndServoConfig->maxthrottle = 1850;
|
||||
escAndServoConfig->mincommand = 1000;
|
||||
}
|
||||
|
||||
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
||||
{
|
||||
flight3DConfig->deadband3d_low = 1406;
|
||||
flight3DConfig->deadband3d_high = 1514;
|
||||
flight3DConfig->neutral3d = 1460;
|
||||
flight3DConfig->deadband3d_throttle = 50;
|
||||
}
|
||||
|
||||
// Default settings
|
||||
static void resetConf(void)
|
||||
{
|
||||
|
@ -289,16 +315,12 @@ static void resetConf(void)
|
|||
masterConfig.rxConfig.mincheck = 1100;
|
||||
masterConfig.rxConfig.maxcheck = 1900;
|
||||
masterConfig.retarded_arm = 0; // disable arm/disarm on roll left/right
|
||||
masterConfig.flaps_speed = 0;
|
||||
masterConfig.airplaneConfig.flaps_speed = 0;
|
||||
masterConfig.fixedwing_althold_dir = 1;
|
||||
|
||||
// Motor/ESC/Servo
|
||||
masterConfig.minthrottle = 1150;
|
||||
masterConfig.maxthrottle = 1850;
|
||||
masterConfig.mincommand = 1000;
|
||||
masterConfig.deadband3d_low = 1406;
|
||||
masterConfig.deadband3d_high = 1514;
|
||||
masterConfig.neutral3d = 1460;
|
||||
masterConfig.deadband3d_throttle = 50;
|
||||
resetEscAndServoConfig(&masterConfig.escAndServoConfig);
|
||||
resetFlight3DConfig(&masterConfig.flight3DConfig);
|
||||
masterConfig.motor_pwm_rate = 400;
|
||||
masterConfig.servo_pwm_rate = 50;
|
||||
// gps/nav stuff
|
||||
|
@ -366,11 +388,11 @@ static void resetConf(void)
|
|||
currentProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
}
|
||||
|
||||
currentProfile.yaw_direction = 1;
|
||||
currentProfile.tri_unarmed_servo = 1;
|
||||
currentProfile.mixerConfig.yaw_direction = 1;
|
||||
currentProfile.mixerConfig.tri_unarmed_servo = 1;
|
||||
|
||||
// gimbal
|
||||
currentProfile.gimbal_flags = GIMBAL_NORMAL;
|
||||
currentProfile.gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
|
||||
|
||||
resetGpsProfile(¤tProfile.gpsProfile);
|
||||
|
||||
|
|
|
@ -10,16 +10,12 @@ typedef struct master_t {
|
|||
uint32_t enabledFeatures;
|
||||
uint16_t looptime; // imu loop time in us
|
||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||
|
||||
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
uint16_t deadband3d_low; // min 3d value
|
||||
uint16_t deadband3d_high; // max 3d value
|
||||
uint16_t neutral3d; // center 3d value
|
||||
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
|
||||
escAndServoConfig_t escAndServoConfig;
|
||||
flight3DConfig_t flight3DConfig;
|
||||
|
||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||
|
@ -48,7 +44,8 @@ typedef struct master_t {
|
|||
rxConfig_t rxConfig;
|
||||
|
||||
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
|
||||
uint8_t flaps_speed; // airplane mode flaps, 0 = no flaps, > 0 = flap speed, larger = faster
|
||||
|
||||
airplaneConfig_t airplaneConfig;
|
||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||
|
||||
uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable.
|
||||
|
|
|
@ -42,11 +42,10 @@ typedef struct profile_s {
|
|||
failsafeConfig_t failsafeConfig;
|
||||
|
||||
// mixer-related configuration
|
||||
int8_t yaw_direction;
|
||||
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
|
||||
mixerConfig_t mixerConfig;
|
||||
|
||||
// gimbal-related configuration
|
||||
uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff
|
||||
gimbalConfig_t gimbalConfig;
|
||||
|
||||
gpsProfile_t gpsProfile;
|
||||
} profile_t;
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
#include "bus_i2c.h"
|
||||
|
||||
// FIXME there should be no dependencies on the main source code
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "sensors_common.h"
|
||||
#include "flight_common.h"
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
typedef struct escAndServoConfig_s {
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
} escAndServoConfig_t;
|
|
@ -3,6 +3,7 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
#include "runtime_config.h"
|
||||
|
|
|
@ -20,10 +20,12 @@
|
|||
|
||||
#include "gps_common.h"
|
||||
|
||||
#include "gimbal.h"
|
||||
#include "flight_mixer.h"
|
||||
|
||||
#include "boardalignment.h"
|
||||
#include "battery.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
#include "drivers/serial_common.h"
|
||||
|
|
|
@ -1,12 +1,26 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/pwm_common.h"
|
||||
|
||||
#include "gimbal.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
|
||||
#include "flight_mixer.h"
|
||||
#include "flight_common.h"
|
||||
|
||||
#include "runtime_config.h"
|
||||
#include "config.h"
|
||||
|
||||
|
||||
static uint8_t numberMotor = 0;
|
||||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
@ -14,7 +28,16 @@ int16_t servo[MAX_SUPPORTED_SERVOS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500
|
|||
|
||||
static int useServo;
|
||||
|
||||
servoParam_t *servoConf;
|
||||
mixerConfig_t *mixerConfig;
|
||||
flight3DConfig_t *flight3DConfig;
|
||||
escAndServoConfig_t *escAndServoConfig;
|
||||
airplaneConfig_t *airplaneConfig;
|
||||
rxConfig_t *rxConfig;
|
||||
gimbalConfig_t *gimbalConfig;
|
||||
|
||||
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
||||
static MultiType currentMixerConfiguration;
|
||||
|
||||
static const motorMixer_t mixerTri[] = {
|
||||
{ 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR
|
||||
|
@ -157,16 +180,27 @@ const mixer_t mixers[] = {
|
|||
{ 0, 0, NULL }, // MULTITYPE_CUSTOM
|
||||
};
|
||||
|
||||
void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DConfigToUse, escAndServoConfig_t *escAndServoConfigToUse, mixerConfig_t *mixerConfigToUse, airplaneConfig_t *airplaneConfigToUse, rxConfig_t *rxConfigToUse, gimbalConfig_t *gimbalConfigToUse)
|
||||
{
|
||||
servoConf = servoConfToUse;
|
||||
flight3DConfig = flight3DConfigToUse;
|
||||
escAndServoConfig = escAndServoConfigToUse;
|
||||
mixerConfig = mixerConfigToUse;
|
||||
airplaneConfig = airplaneConfigToUse;
|
||||
rxConfig = rxConfigToUse;
|
||||
gimbalConfig = gimbalConfigToUse;
|
||||
}
|
||||
|
||||
int16_t determineServoMiddleOrForwardFromChannel(int nr)
|
||||
{
|
||||
uint8_t channelToForwardFrom = currentProfile.servoConf[nr].forwardFromChannel;
|
||||
uint8_t channelToForwardFrom = servoConf[nr].forwardFromChannel;
|
||||
|
||||
if (channelToForwardFrom != CHANNEL_FORWARDING_DISABLED && channelToForwardFrom << MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||
return rcData[channelToForwardFrom];
|
||||
}
|
||||
|
||||
if (nr < MAX_SUPPORTED_SERVOS) {
|
||||
return currentProfile.servoConf[nr].middle;
|
||||
return servoConf[nr].middle;
|
||||
}
|
||||
|
||||
return DEFAULT_SERVO_MIDDLE;
|
||||
|
@ -180,37 +214,39 @@ int servoDirection(int nr, int lr)
|
|||
// rate[1] = roll_direction
|
||||
// rate[0] = pitch_direction
|
||||
// servo.rate is also used as gimbal gain multiplier (yeah)
|
||||
if (currentProfile.servoConf[nr].rate & lr)
|
||||
if (servoConf[nr].rate & lr)
|
||||
return -1;
|
||||
else
|
||||
return 1;
|
||||
}
|
||||
|
||||
void mixerInit(void)
|
||||
void mixerInit(MultiType mixerConfiguration, motorMixer_t *customMixers)
|
||||
{
|
||||
int i;
|
||||
|
||||
currentMixerConfiguration = mixerConfiguration;
|
||||
|
||||
// enable servos for mixes that require them. note, this shifts motor counts.
|
||||
useServo = mixers[masterConfig.mixerConfiguration].useServo;
|
||||
useServo = mixers[mixerConfiguration].useServo;
|
||||
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
||||
if (feature(FEATURE_SERVO_TILT))
|
||||
useServo = 1;
|
||||
|
||||
if (masterConfig.mixerConfiguration == MULTITYPE_CUSTOM) {
|
||||
if (mixerConfiguration == MULTITYPE_CUSTOM) {
|
||||
// load custom mixer into currentMixer
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
// check if done
|
||||
if (masterConfig.customMixer[i].throttle == 0.0f)
|
||||
if (customMixers[i].throttle == 0.0f)
|
||||
break;
|
||||
currentMixer[i] = masterConfig.customMixer[i];
|
||||
currentMixer[i] = customMixers[i];
|
||||
numberMotor++;
|
||||
}
|
||||
} else {
|
||||
numberMotor = mixers[masterConfig.mixerConfiguration].numberMotor;
|
||||
numberMotor = mixers[mixerConfiguration].numberMotor;
|
||||
// copy motor-based mixers
|
||||
if (mixers[masterConfig.mixerConfiguration].motor) {
|
||||
if (mixers[mixerConfiguration].motor) {
|
||||
for (i = 0; i < numberMotor; i++)
|
||||
currentMixer[i] = mixers[masterConfig.mixerConfiguration].motor[i];
|
||||
currentMixer[i] = mixers[mixerConfiguration].motor[i];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -226,8 +262,8 @@ void mixerInit(void)
|
|||
}
|
||||
|
||||
// set flag that we're on something with wings
|
||||
if (masterConfig.mixerConfiguration == MULTITYPE_FLYING_WING ||
|
||||
masterConfig.mixerConfiguration == MULTITYPE_AIRPLANE)
|
||||
if (mixerConfiguration == MULTITYPE_FLYING_WING ||
|
||||
mixerConfiguration == MULTITYPE_AIRPLANE)
|
||||
f.FIXED_WING = 1;
|
||||
else
|
||||
f.FIXED_WING = 0;
|
||||
|
@ -240,10 +276,10 @@ void mixerResetMotors(void)
|
|||
int i;
|
||||
// set disarmed motor values
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
motor_disarmed[i] = feature(FEATURE_3D) ? masterConfig.neutral3d : masterConfig.mincommand;
|
||||
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig->neutral3d : escAndServoConfig->mincommand;
|
||||
}
|
||||
|
||||
void mixerLoadMix(int index)
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers)
|
||||
{
|
||||
int i;
|
||||
|
||||
|
@ -251,12 +287,12 @@ void mixerLoadMix(int index)
|
|||
index++;
|
||||
// clear existing
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
masterConfig.customMixer[i].throttle = 0.0f;
|
||||
customMixers[i].throttle = 0.0f;
|
||||
|
||||
// do we have anything here to begin with?
|
||||
if (mixers[index].motor != NULL) {
|
||||
for (i = 0; i < mixers[index].numberMotor; i++)
|
||||
masterConfig.customMixer[i] = mixers[index].motor[i];
|
||||
customMixers[i] = mixers[index].motor[i];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -271,14 +307,14 @@ void writeServos(void)
|
|||
if (!useServo)
|
||||
return;
|
||||
|
||||
switch (masterConfig.mixerConfiguration) {
|
||||
switch (currentMixerConfiguration) {
|
||||
case MULTITYPE_BI:
|
||||
pwmWriteServo(0, servo[4]);
|
||||
pwmWriteServo(1, servo[5]);
|
||||
break;
|
||||
|
||||
case MULTITYPE_TRI:
|
||||
if (currentProfile.tri_unarmed_servo) {
|
||||
if (mixerConfig->tri_unarmed_servo) {
|
||||
// if unarmed flag set, we always move servo
|
||||
pwmWriteServo(0, servo[5]);
|
||||
} else {
|
||||
|
@ -345,33 +381,26 @@ static void airplaneMixer(void)
|
|||
int i;
|
||||
|
||||
if (!f.ARMED)
|
||||
servo[7] = masterConfig.mincommand; // Kill throttle when disarmed
|
||||
servo[7] = escAndServoConfig->mincommand; // Kill throttle when disarmed
|
||||
else
|
||||
servo[7] = constrain(rcCommand[THROTTLE], masterConfig.minthrottle, masterConfig.maxthrottle);
|
||||
servo[7] = constrain(rcCommand[THROTTLE], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
|
||||
motor[0] = servo[7];
|
||||
|
||||
#if 0
|
||||
if (currentProfile.flaperons) {
|
||||
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
if (masterConfig.flaps_speed) {
|
||||
if (airplaneConfig->flaps_speed) {
|
||||
// configure SERVO3 middle point in GUI to using an AUX channel for FLAPS control
|
||||
// use servo min, servo max and servo rate for proper endpoints adjust
|
||||
static int16_t slow_LFlaps;
|
||||
int16_t lFlap = determineServoMiddleOrForwardFromChannel(2);
|
||||
|
||||
lFlap = constrain(lFlap, currentProfile.servoConf[2].min, currentProfile.servoConf[2].max);
|
||||
lFlap = masterConfig.rxConfig.midrc - lFlap; // shouldn't this be servoConf[2].middle?
|
||||
lFlap = constrain(lFlap, servoConf[2].min, servoConf[2].max);
|
||||
lFlap = rxConfig->midrc - lFlap;
|
||||
if (slow_LFlaps < lFlap)
|
||||
slow_LFlaps += masterConfig.flaps_speed;
|
||||
slow_LFlaps += airplaneConfig->flaps_speed;
|
||||
else if (slow_LFlaps > lFlap)
|
||||
slow_LFlaps -= masterConfig.flaps_speed;
|
||||
slow_LFlaps -= airplaneConfig->flaps_speed;
|
||||
|
||||
servo[2] = ((int32_t)currentProfile.servoConf[2].rate * slow_LFlaps) / 100L;
|
||||
servo[2] += masterConfig.rxConfig.midrc;
|
||||
servo[2] = ((int32_t)servoConf[2].rate * slow_LFlaps) / 100L;
|
||||
servo[2] += rxConfig->midrc;
|
||||
}
|
||||
|
||||
if (f.PASSTHRU_MODE) { // Direct passthru from RX
|
||||
|
@ -387,7 +416,7 @@ static void airplaneMixer(void)
|
|||
servo[6] = axisPID[PITCH]; // Elevator
|
||||
}
|
||||
for (i = 3; i < 7; i++) {
|
||||
servo[i] = ((int32_t)currentProfile.servoConf[i].rate * servo[i]) / 100L; // servo rates
|
||||
servo[i] = ((int32_t)servoConf[i].rate * servo[i]) / 100L; // servo rates
|
||||
servo[i] += determineServoMiddleOrForwardFromChannel(i);
|
||||
}
|
||||
}
|
||||
|
@ -405,10 +434,10 @@ void mixTable(void)
|
|||
// motors for non-servo mixes
|
||||
if (numberMotor > 1)
|
||||
for (i = 0; i < numberMotor; i++)
|
||||
motor[i] = rcCommand[THROTTLE] * currentMixer[i].throttle + axisPID[PITCH] * currentMixer[i].pitch + axisPID[ROLL] * currentMixer[i].roll + -currentProfile.yaw_direction * axisPID[YAW] * currentMixer[i].yaw;
|
||||
motor[i] = rcCommand[THROTTLE] * currentMixer[i].throttle + axisPID[PITCH] * currentMixer[i].pitch + axisPID[ROLL] * currentMixer[i].roll + -mixerConfig->yaw_direction * axisPID[YAW] * currentMixer[i].yaw;
|
||||
|
||||
// airplane / servo mixes
|
||||
switch (masterConfig.mixerConfiguration) {
|
||||
switch (currentMixerConfiguration) {
|
||||
case MULTITYPE_BI:
|
||||
servo[4] = (servoDirection(4, 2) * axisPID[YAW]) + (servoDirection(4, 1) * axisPID[PITCH]) + determineServoMiddleOrForwardFromChannel(4); // LEFT
|
||||
servo[5] = (servoDirection(5, 2) * axisPID[YAW]) + (servoDirection(5, 1) * axisPID[PITCH]) + determineServoMiddleOrForwardFromChannel(5); // RIGHT
|
||||
|
@ -419,8 +448,8 @@ void mixTable(void)
|
|||
break;
|
||||
|
||||
case MULTITYPE_GIMBAL:
|
||||
servo[0] = (((int32_t)currentProfile.servoConf[0].rate * angle[PITCH]) / 50) + determineServoMiddleOrForwardFromChannel(0);
|
||||
servo[1] = (((int32_t)currentProfile.servoConf[1].rate * angle[ROLL]) / 50) + determineServoMiddleOrForwardFromChannel(1);
|
||||
servo[0] = (((int32_t)servoConf[0].rate * angle[PITCH]) / 50) + determineServoMiddleOrForwardFromChannel(0);
|
||||
servo[1] = (((int32_t)servoConf[1].rate * angle[ROLL]) / 50) + determineServoMiddleOrForwardFromChannel(1);
|
||||
break;
|
||||
|
||||
case MULTITYPE_AIRPLANE:
|
||||
|
@ -429,9 +458,9 @@ void mixTable(void)
|
|||
|
||||
case MULTITYPE_FLYING_WING:
|
||||
if (!f.ARMED)
|
||||
servo[7] = masterConfig.mincommand;
|
||||
servo[7] = escAndServoConfig->mincommand;
|
||||
else
|
||||
servo[7] = constrain(rcCommand[THROTTLE], masterConfig.minthrottle, masterConfig.maxthrottle);
|
||||
servo[7] = constrain(rcCommand[THROTTLE], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
|
||||
motor[0] = servo[7];
|
||||
if (f.PASSTHRU_MODE) {
|
||||
// do not use sensors for correction, simple 2 channel mixing
|
||||
|
@ -460,6 +489,9 @@ void mixTable(void)
|
|||
}
|
||||
motor[0] = rcCommand[THROTTLE];
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// do camstab
|
||||
|
@ -469,28 +501,28 @@ void mixTable(void)
|
|||
servo[1] = determineServoMiddleOrForwardFromChannel(1);
|
||||
|
||||
if (rcOptions[BOXCAMSTAB]) {
|
||||
if (currentProfile.gimbal_flags & GIMBAL_MIXTILT) {
|
||||
servo[0] -= (-(int32_t)currentProfile.servoConf[0].rate) * angle[PITCH] / 50 - (int32_t)currentProfile.servoConf[1].rate * angle[ROLL] / 50;
|
||||
servo[1] += (-(int32_t)currentProfile.servoConf[0].rate) * angle[PITCH] / 50 + (int32_t)currentProfile.servoConf[1].rate * angle[ROLL] / 50;
|
||||
if (gimbalConfig->gimbal_flags & GIMBAL_MIXTILT) {
|
||||
servo[0] -= (-(int32_t)servoConf[0].rate) * angle[PITCH] / 50 - (int32_t)servoConf[1].rate * angle[ROLL] / 50;
|
||||
servo[1] += (-(int32_t)servoConf[0].rate) * angle[PITCH] / 50 + (int32_t)servoConf[1].rate * angle[ROLL] / 50;
|
||||
} else {
|
||||
servo[0] += (int32_t)currentProfile.servoConf[0].rate * angle[PITCH] / 50;
|
||||
servo[1] += (int32_t)currentProfile.servoConf[1].rate * angle[ROLL] / 50;
|
||||
servo[0] += (int32_t)servoConf[0].rate * angle[PITCH] / 50;
|
||||
servo[1] += (int32_t)servoConf[1].rate * angle[ROLL] / 50;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// constrain servos
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++)
|
||||
servo[i] = constrain(servo[i], currentProfile.servoConf[i].min, currentProfile.servoConf[i].max); // limit the values
|
||||
servo[i] = constrain(servo[i], servoConf[i].min, servoConf[i].max); // limit the values
|
||||
|
||||
// forward AUX1-4 to servo outputs (not constrained)
|
||||
if (currentProfile.gimbal_flags & GIMBAL_FORWARDAUX) {
|
||||
if (gimbalConfig->gimbal_flags & GIMBAL_FORWARDAUX) {
|
||||
int offset = 0;
|
||||
// offset servos based off number already used in mixer types
|
||||
// airplane and servo_tilt together can't be used
|
||||
if (masterConfig.mixerConfiguration == MULTITYPE_AIRPLANE || masterConfig.mixerConfiguration == MULTITYPE_FLYING_WING)
|
||||
if (currentMixerConfiguration == MULTITYPE_AIRPLANE || currentMixerConfiguration == MULTITYPE_FLYING_WING)
|
||||
offset = 4;
|
||||
else if (mixers[masterConfig.mixerConfiguration].useServo)
|
||||
else if (mixers[currentMixerConfiguration].useServo)
|
||||
offset = 2;
|
||||
for (i = 0; i < 4; i++)
|
||||
pwmWriteServo(i + offset, rcData[AUX1 + i]);
|
||||
|
@ -501,21 +533,21 @@ void mixTable(void)
|
|||
if (motor[i] > maxMotor)
|
||||
maxMotor = motor[i];
|
||||
for (i = 0; i < numberMotor; i++) {
|
||||
if (maxMotor > masterConfig.maxthrottle) // this is a way to still have good gyro corrections if at least one motor reaches its max.
|
||||
motor[i] -= maxMotor - masterConfig.maxthrottle;
|
||||
if (maxMotor > escAndServoConfig->maxthrottle) // this is a way to still have good gyro corrections if at least one motor reaches its max.
|
||||
motor[i] -= maxMotor - escAndServoConfig->maxthrottle;
|
||||
if (feature(FEATURE_3D)) {
|
||||
if ((rcData[THROTTLE]) > 1500) {
|
||||
motor[i] = constrain(motor[i], masterConfig.deadband3d_high, masterConfig.maxthrottle);
|
||||
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, escAndServoConfig->maxthrottle);
|
||||
} else {
|
||||
motor[i] = constrain(motor[i], masterConfig.mincommand, masterConfig.deadband3d_low);
|
||||
motor[i] = constrain(motor[i], escAndServoConfig->mincommand, flight3DConfig->deadband3d_low);
|
||||
}
|
||||
} else {
|
||||
motor[i] = constrain(motor[i], masterConfig.minthrottle, masterConfig.maxthrottle);
|
||||
if ((rcData[THROTTLE]) < masterConfig.rxConfig.mincheck) {
|
||||
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
|
||||
if ((rcData[THROTTLE]) < rxConfig->mincheck) {
|
||||
if (!feature(FEATURE_MOTOR_STOP))
|
||||
motor[i] = masterConfig.minthrottle;
|
||||
motor[i] = escAndServoConfig->minthrottle;
|
||||
else
|
||||
motor[i] = masterConfig.mincommand;
|
||||
motor[i] = escAndServoConfig->mincommand;
|
||||
}
|
||||
}
|
||||
if (!f.ARMED) {
|
||||
|
|
|
@ -46,6 +46,22 @@ typedef struct mixer_t {
|
|||
const motorMixer_t *motor;
|
||||
} mixer_t;
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
int8_t yaw_direction;
|
||||
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
|
||||
} mixerConfig_t;
|
||||
|
||||
typedef struct flight3DConfig_s {
|
||||
uint16_t deadband3d_low; // min 3d value
|
||||
uint16_t deadband3d_high; // max 3d value
|
||||
uint16_t neutral3d; // center 3d value
|
||||
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
|
||||
} flight3DConfig_t;
|
||||
|
||||
typedef struct airplaneConfig_t {
|
||||
uint8_t flaps_speed; // airplane mode flaps, 0 = no flaps, > 0 = flap speed, larger = faster
|
||||
} airplaneConfig_t;
|
||||
|
||||
#define CHANNEL_FORWARDING_DISABLED 0xFF
|
||||
|
||||
typedef struct servoParam_t {
|
||||
|
@ -61,9 +77,9 @@ extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
|||
extern int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
|
||||
bool isMixerUsingServos(void);
|
||||
void mixerInit(void);
|
||||
void mixerInit(MultiType mixerConfiguration, motorMixer_t *customMixers);
|
||||
void writeAllMotors(int16_t mc);
|
||||
void mixerLoadMix(int index);
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||
void mixerResetMotors(void);
|
||||
|
||||
// from mixer.c
|
||||
|
|
|
@ -5,3 +5,7 @@ typedef enum GimbalFlags {
|
|||
GIMBAL_MIXTILT = 1 << 1,
|
||||
GIMBAL_FORWARDAUX = 1 << 2,
|
||||
} GimbalFlags;
|
||||
|
||||
typedef struct gimbalConfig_s {
|
||||
uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff
|
||||
} gimbalConfig_t;
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
#include "failsafe.h"
|
||||
|
||||
#include "gps_common.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
#include "gimbal.h"
|
||||
|
@ -89,7 +90,7 @@ int main(void)
|
|||
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
|
||||
sensorsSet(SENSORS_SET);
|
||||
|
||||
mixerInit();
|
||||
mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer);
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
if (masterConfig.mixerConfiguration == MULTITYPE_AIRPLANE || masterConfig.mixerConfiguration == MULTITYPE_FLYING_WING)
|
||||
pwm_params.airplane = true;
|
||||
|
@ -100,12 +101,12 @@ int main(void)
|
|||
pwm_params.usePPM = feature(FEATURE_PPM);
|
||||
pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum
|
||||
pwm_params.useServos = isMixerUsingServos();
|
||||
pwm_params.extraServos = currentProfile.gimbal_flags & GIMBAL_FORWARDAUX;
|
||||
pwm_params.extraServos = currentProfile.gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
|
||||
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
||||
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
|
||||
pwm_params.idlePulse = PULSE_1MS; // standard PWM for brushless ESC (default, overridden below)
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.neutral3d;
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
if (pwm_params.motorPwmRate > 500)
|
||||
pwm_params.idlePulse = 0; // brushed motors
|
||||
pwm_params.servoCenterPulse = masterConfig.rxConfig.midrc;
|
||||
|
@ -234,6 +235,6 @@ int main(void)
|
|||
void HardFault_Handler(void)
|
||||
{
|
||||
// fall out of the sky
|
||||
writeAllMotors(masterConfig.mincommand);
|
||||
writeAllMotors(masterConfig.escAndServoConfig.mincommand);
|
||||
while (1);
|
||||
}
|
||||
|
|
4
src/mw.c
4
src/mw.c
|
@ -265,7 +265,7 @@ void loop(void)
|
|||
rcSticks = stTmp;
|
||||
|
||||
// perform actions
|
||||
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (masterConfig.rxConfig.midrc - masterConfig.deadband3d_throttle) && rcData[THROTTLE] < (masterConfig.rxConfig.midrc + masterConfig.deadband3d_throttle)))
|
||||
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (masterConfig.rxConfig.midrc - masterConfig.flight3DConfig.deadband3d_throttle) && rcData[THROTTLE] < (masterConfig.rxConfig.midrc + masterConfig.flight3DConfig.deadband3d_throttle)))
|
||||
isThrottleLow = true;
|
||||
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < masterConfig.rxConfig.mincheck))
|
||||
isThrottleLow = true;
|
||||
|
@ -581,7 +581,7 @@ void loop(void)
|
|||
isAltHoldChanged = 0;
|
||||
}
|
||||
rcCommand[THROTTLE] = initialThrottleHold + BaroPID;
|
||||
rcCommand[THROTTLE] = constrain(rcCommand[THROTTLE], masterConfig.minthrottle + 150, masterConfig.maxthrottle);
|
||||
rcCommand[THROTTLE] = constrain(rcCommand[THROTTLE], masterConfig.escAndServoConfig.minthrottle + 150, masterConfig.escAndServoConfig.maxthrottle);
|
||||
}
|
||||
} else {
|
||||
// handle fixedwing-related althold. UNTESTED! and probably wrong
|
||||
|
|
4
src/mw.h
4
src/mw.h
|
@ -1,6 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "rc_controls.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_curves.h"
|
||||
#include "runtime_config.h"
|
||||
#include "flight_common.h"
|
||||
#include "failsafe.h"
|
||||
|
@ -20,7 +22,6 @@ enum {
|
|||
#include "sensors_barometer.h"
|
||||
#include "sensors_gyro.h"
|
||||
#include "serial_common.h"
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
#include "gps_common.h"
|
||||
#include "config.h"
|
||||
|
@ -64,7 +65,6 @@ int getEstimatedAltitude(void);
|
|||
|
||||
// Output
|
||||
void mixerResetMotors(void);
|
||||
void mixerLoadMix(int index);
|
||||
void writeServos(void);
|
||||
void writeMotors(void);
|
||||
void writeAllMotors(int16_t mc);
|
||||
|
|
|
@ -36,3 +36,4 @@ typedef struct controlRateConfig_s {
|
|||
extern int16_t rcCommand[4];
|
||||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
|
||||
|
|
|
@ -0,0 +1,35 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "rc_controls.h"
|
||||
#include "escservo.h"
|
||||
|
||||
#include "rc_curves.h"
|
||||
|
||||
int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (i * i - 25)) * i * (int32_t) controlRateConfig->rcRate8 / 2500;
|
||||
}
|
||||
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
|
||||
int16_t tmp = 10 * i - controlRateConfig->thrMid8;
|
||||
uint8_t y = 1;
|
||||
if (tmp > 0)
|
||||
y = 100 - controlRateConfig->thrMid8;
|
||||
if (tmp < 0)
|
||||
y = controlRateConfig->thrMid8;
|
||||
lookupThrottleRC[i] = 10 * controlRateConfig->thrMid8 + tmp * (100 - controlRateConfig->thrExpo8 + (int32_t) controlRateConfig->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = escAndServoConfig->minthrottle + (int32_t) (escAndServoConfig->maxthrottle - escAndServoConfig->minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
}
|
||||
}
|
|
@ -0,0 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig);
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig);
|
|
@ -9,7 +9,6 @@
|
|||
#include "config.h"
|
||||
|
||||
#include "failsafe.h"
|
||||
#include "rc_controls.h"
|
||||
|
||||
#include "rx_pwm.h"
|
||||
#include "rx_sbus.h"
|
||||
|
@ -25,8 +24,6 @@ void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe
|
|||
|
||||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
|
||||
#define PPM_AND_PWM_SAMPLE_COUNT 4
|
||||
|
@ -104,30 +101,6 @@ void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
}
|
||||
}
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (i * i - 25)) * i * (int32_t) controlRateConfig->rcRate8 / 2500;
|
||||
}
|
||||
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
|
||||
int16_t tmp = 10 * i - controlRateConfig->thrMid8;
|
||||
uint8_t y = 1;
|
||||
if (tmp > 0)
|
||||
y = 100 - controlRateConfig->thrMid8;
|
||||
if (tmp < 0)
|
||||
y = controlRateConfig->thrMid8;
|
||||
lookupThrottleRC[i] = 10 * controlRateConfig->thrMid8 + tmp * (100 - controlRateConfig->thrExpo8 + (int32_t) controlRateConfig->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = minThrottle + (int32_t) (maxThrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
}
|
||||
}
|
||||
|
||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig)
|
||||
{
|
||||
const char *c, *s;
|
||||
|
|
|
@ -34,19 +34,11 @@ typedef struct rxRuntimeConfig_s {
|
|||
uint8_t channelCount; // number of rc channels as reported by current input driver
|
||||
} rxRuntimeConfig_t;
|
||||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
extern rxRuntimeConfig_t rxRuntimeConfig;
|
||||
|
||||
typedef uint16_t (* rcReadRawDataPtr)(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||
|
||||
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig);
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle);
|
||||
|
||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
|
||||
|
||||
|
|
|
@ -6,13 +6,12 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "rc_controls.h"
|
||||
#include "rx_common.h"
|
||||
#include "config.h"
|
||||
|
||||
#include "drivers/pwm_common.h"
|
||||
|
||||
#include "config.h"
|
||||
|
||||
#include "failsafe.h"
|
||||
|
||||
#include "rx_common.h"
|
||||
#include "rx_pwm.h"
|
||||
|
||||
|
|
|
@ -9,9 +9,7 @@
|
|||
#include "drivers/serial_uart.h"
|
||||
#include "serial_common.h"
|
||||
|
||||
|
||||
#include "failsafe.h"
|
||||
#include "rc_controls.h"
|
||||
|
||||
#include "rx_common.h"
|
||||
#include "rx_sbus.h"
|
||||
|
|
|
@ -10,12 +10,10 @@
|
|||
#include "serial_common.h"
|
||||
|
||||
#include "failsafe.h"
|
||||
#include "rc_controls.h"
|
||||
|
||||
#include "rx_common.h"
|
||||
#include "rx_spektrum.h"
|
||||
|
||||
|
||||
// driver for spektrum satellite receiver / sbus using UART2 (freeing up more motor outputs for stuff)
|
||||
|
||||
#define SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT 12
|
||||
|
|
|
@ -10,7 +10,6 @@
|
|||
#include "serial_common.h"
|
||||
|
||||
#include "failsafe.h"
|
||||
#include "rc_controls.h"
|
||||
|
||||
#include "rx_common.h"
|
||||
#include "rx_sumd.h"
|
||||
|
|
|
@ -19,12 +19,14 @@
|
|||
#include "serial_common.h"
|
||||
#include "flight_common.h"
|
||||
#include "flight_mixer.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "boardalignment.h"
|
||||
#include "telemetry_common.h"
|
||||
#include "gps_common.h"
|
||||
#include "rx_common.h"
|
||||
#include "battery.h"
|
||||
#include "gimbal.h"
|
||||
#include "sensors_common.h"
|
||||
#include "sensors_acceleration.h"
|
||||
#include "sensors_gyro.h"
|
||||
|
@ -140,56 +142,78 @@ typedef struct {
|
|||
const clivalue_t valueTable[] = {
|
||||
{ "looptime", VAR_UINT16, &masterConfig.looptime, 0, 9000 },
|
||||
{ "emf_avoidance", VAR_UINT8, &masterConfig.emf_avoidance, 0, 1 },
|
||||
|
||||
{ "midrc", VAR_UINT16, &masterConfig.rxConfig.midrc, 1200, 1700 },
|
||||
{ "minthrottle", VAR_UINT16, &masterConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "maxthrottle", VAR_UINT16, &masterConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "mincommand", VAR_UINT16, &masterConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "mincheck", VAR_UINT16, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "maxcheck", VAR_UINT16, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "deadband3d_low", VAR_UINT16, &masterConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "deadband3d_high", VAR_UINT16, &masterConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "neutral3d", VAR_UINT16, &masterConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "deadband3d_throttle", VAR_UINT16, &masterConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
||||
{ "minthrottle", VAR_UINT16, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "maxthrottle", VAR_UINT16, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "mincommand", VAR_UINT16, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
||||
{ "deadband3d_low", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME upper limit should match code in the mixer, 1500 currently
|
||||
{ "deadband3d_high", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME lower limit should match code in the mixer, 1500 currently,
|
||||
{ "neutral3d", VAR_UINT16, &masterConfig.flight3DConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "deadband3d_throttle", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
||||
{ "motor_pwm_rate", VAR_UINT16, &masterConfig.motor_pwm_rate, 50, 32000 },
|
||||
{ "servo_pwm_rate", VAR_UINT16, &masterConfig.servo_pwm_rate, 50, 498 },
|
||||
|
||||
{ "retarded_arm", VAR_UINT8, &masterConfig.retarded_arm, 0, 1 },
|
||||
{ "flaps_speed", VAR_UINT8, &masterConfig.flaps_speed, 0, 100 },
|
||||
|
||||
{ "flaps_speed", VAR_UINT8, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
||||
|
||||
{ "fixedwing_althold_dir", VAR_INT8, &masterConfig.fixedwing_althold_dir, -1, 1 },
|
||||
|
||||
{ "reboot_character", VAR_UINT8, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
{ "serial_baudrate", VAR_UINT32, &masterConfig.serialConfig.port1_baudrate, 1200, 115200 },
|
||||
{ "softserial_baudrate", VAR_UINT32, &masterConfig.serialConfig.softserial_baudrate, 1200, 19200 },
|
||||
{ "softserial_1_inverted", VAR_UINT8, &masterConfig.serialConfig.softserial_1_inverted, 0, 1 },
|
||||
{ "softserial_2_inverted", VAR_UINT8, &masterConfig.serialConfig.softserial_2_inverted, 0, 1 },
|
||||
|
||||
{ "gps_type", VAR_UINT8, &masterConfig.gps_type, 0, GPS_HARDWARE_MAX },
|
||||
{ "gps_baudrate", VAR_INT8, &masterConfig.gps_baudrate, 0, GPS_BAUD_MAX },
|
||||
|
||||
{ "serialrx_type", VAR_UINT8, &masterConfig.rxConfig.serialrx_type, 0, 3 },
|
||||
|
||||
{ "telemetry_provider", VAR_UINT8, &masterConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||
{ "telemetry_port", VAR_UINT8, &masterConfig.telemetry_port, 0, TELEMETRY_PORT_MAX },
|
||||
{ "telemetry_switch", VAR_UINT8, &masterConfig.telemetry_switch, 0, 1 },
|
||||
|
||||
{ "vbatscale", VAR_UINT8, &masterConfig.batteryConfig.vbatscale, 10, 200 },
|
||||
{ "vbatmaxcellvoltage", VAR_UINT8, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbatmincellvoltage", VAR_UINT8, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
|
||||
|
||||
{ "power_adc_channel", VAR_UINT8, &masterConfig.power_adc_channel, 0, 9 },
|
||||
|
||||
{ "align_gyro", VAR_UINT8, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
|
||||
{ "align_acc", VAR_UINT8, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },
|
||||
{ "align_mag", VAR_UINT8, &masterConfig.sensorAlignmentConfig.mag_align, 0, 8 },
|
||||
|
||||
{ "align_board_roll", VAR_INT16, &masterConfig.boardAlignment.rollDegrees, -180, 360 },
|
||||
{ "align_board_pitch", VAR_INT16, &masterConfig.boardAlignment.pitchDegrees, -180, 360 },
|
||||
{ "align_board_yaw", VAR_INT16, &masterConfig.boardAlignment.yawDegrees, -180, 360 },
|
||||
{ "yaw_control_direction", VAR_INT8, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
{ "acc_hardware", VAR_UINT8, &masterConfig.acc_hardware, 0, 5 },
|
||||
|
||||
{ "max_angle_inclination", VAR_UINT16, &masterConfig.max_angle_inclination, 100, 900 },
|
||||
{ "moron_threshold", VAR_UINT8, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
|
||||
|
||||
{ "gyro_lpf", VAR_UINT16, &masterConfig.gyro_lpf, 0, 256 },
|
||||
{ "moron_threshold", VAR_UINT8, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16, &masterConfig.gyro_cmpf_factor, 100, 1000 },
|
||||
{ "gyro_cmpfm_factor", VAR_UINT16, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
|
||||
{ "pid_controller", VAR_UINT8, ¤tProfile.pidController, 0, 1 },
|
||||
{ "deadband", VAR_UINT8, ¤tProfile.deadband, 0, 32 },
|
||||
{ "yawdeadband", VAR_UINT8, ¤tProfile.yaw_deadband, 0, 100 },
|
||||
|
||||
{ "alt_hold_throttle_neutral", VAR_UINT8, ¤tProfile.alt_hold_throttle_neutral, 1, 250 },
|
||||
{ "alt_hold_fast_change", VAR_UINT8, ¤tProfile.alt_hold_fast_change, 0, 1 },
|
||||
|
||||
{ "throttle_correction_value", VAR_UINT8, ¤tProfile.throttle_correction_value, 0, 150 },
|
||||
{ "throttle_correction_angle", VAR_UINT16, ¤tProfile.throttle_correction_angle, 1, 900 },
|
||||
|
||||
{ "deadband", VAR_UINT8, ¤tProfile.deadband, 0, 32 },
|
||||
{ "yawdeadband", VAR_UINT8, ¤tProfile.yaw_deadband, 0, 100 },
|
||||
{ "yaw_control_direction", VAR_INT8, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
|
||||
{ "yaw_direction", VAR_INT8, ¤tProfile.mixerConfig.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8, ¤tProfile.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
|
||||
{ "rc_rate", VAR_UINT8, ¤tProfile.controlRateConfig.rcRate8, 0, 250 },
|
||||
{ "rc_expo", VAR_UINT8, ¤tProfile.controlRateConfig.rcExpo8, 0, 100 },
|
||||
{ "thr_mid", VAR_UINT8, ¤tProfile.controlRateConfig.thrMid8, 0, 100 },
|
||||
|
@ -198,25 +222,32 @@ const clivalue_t valueTable[] = {
|
|||
{ "yaw_rate", VAR_UINT8, ¤tProfile.controlRateConfig.yawRate, 0, 100 },
|
||||
{ "tpa_rate", VAR_UINT8, ¤tProfile.dynThrPID, 0, 100},
|
||||
{ "tpa_breakpoint", VAR_UINT16, ¤tProfile.tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||
|
||||
{ "failsafe_delay", VAR_UINT8, ¤tProfile.failsafeConfig.failsafe_delay, 0, 200 },
|
||||
{ "failsafe_off_delay", VAR_UINT8, ¤tProfile.failsafeConfig.failsafe_off_delay, 0, 200 },
|
||||
{ "failsafe_throttle", VAR_UINT16, ¤tProfile.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||
{ "failsafe_detect_threshold", VAR_UINT16, ¤tProfile.failsafeConfig.failsafe_detect_threshold, 100, PWM_RANGE_MAX },
|
||||
|
||||
{ "rssi_aux_channel", VAR_INT8, &masterConfig.rssi_aux_channel, 0, 4 },
|
||||
{ "yaw_direction", VAR_INT8, ¤tProfile.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8, ¤tProfile.tri_unarmed_servo, 0, 1 },
|
||||
{ "gimbal_flags", VAR_UINT8, ¤tProfile.gimbal_flags, 0, 255},
|
||||
|
||||
|
||||
{ "gimbal_flags", VAR_UINT8, ¤tProfile.gimbalConfig.gimbal_flags, 0, 255},
|
||||
|
||||
{ "acc_hardware", VAR_UINT8, &masterConfig.acc_hardware, 0, 5 },
|
||||
{ "acc_lpf_factor", VAR_UINT8, ¤tProfile.acc_lpf_factor, 0, 250 },
|
||||
{ "accxy_deadband", VAR_UINT8, ¤tProfile.accxy_deadband, 0, 100 },
|
||||
{ "accz_deadband", VAR_UINT8, ¤tProfile.accz_deadband, 0, 100 },
|
||||
{ "acc_unarmedcal", VAR_UINT8, ¤tProfile.acc_unarmedcal, 0, 1 },
|
||||
{ "acc_trim_pitch", VAR_INT16, ¤tProfile.accelerometerTrims.trims.pitch, -300, 300 },
|
||||
{ "acc_trim_roll", VAR_INT16, ¤tProfile.accelerometerTrims.trims.roll, -300, 300 },
|
||||
|
||||
{ "baro_tab_size", VAR_UINT8, ¤tProfile.barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
|
||||
{ "baro_noise_lpf", VAR_FLOAT, ¤tProfile.barometerConfig.baro_noise_lpf, 0, 1 },
|
||||
{ "baro_cf_vel", VAR_FLOAT, ¤tProfile.barometerConfig.baro_cf_vel, 0, 1 },
|
||||
{ "baro_cf_alt", VAR_FLOAT, ¤tProfile.barometerConfig.baro_cf_alt, 0, 1 },
|
||||
|
||||
{ "mag_declination", VAR_INT16, ¤tProfile.mag_declination, -18000, 18000 },
|
||||
|
||||
{ "gps_pos_p", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_i", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_d", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDPOS], 0, 200 },
|
||||
|
@ -231,6 +262,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "nav_speed_min", VAR_UINT16, ¤tProfile.gpsProfile.nav_speed_min, 10, 2000 },
|
||||
{ "nav_speed_max", VAR_UINT16, ¤tProfile.gpsProfile.nav_speed_max, 10, 2000 },
|
||||
{ "nav_slew_rate", VAR_UINT8, ¤tProfile.gpsProfile.nav_slew_rate, 0, 100 },
|
||||
|
||||
{ "pid_controller", VAR_UINT8, ¤tProfile.pidController, 0, 1 },
|
||||
{ "p_pitch", VAR_UINT8, ¤tProfile.pidProfile.P8[PITCH], 0, 200 },
|
||||
{ "i_pitch", VAR_UINT8, ¤tProfile.pidProfile.I8[PITCH], 0, 200 },
|
||||
{ "d_pitch", VAR_UINT8, ¤tProfile.pidProfile.D8[PITCH], 0, 200 },
|
||||
|
@ -347,7 +380,7 @@ static void cliCMix(char *cmdline)
|
|||
break;
|
||||
}
|
||||
if (strncasecmp(ptr, mixerNames[i], len) == 0) {
|
||||
mixerLoadMix(i);
|
||||
mixerLoadMix(i, masterConfig.customMixer);
|
||||
printf("Loaded %s mix...\r\n", mixerNames[i]);
|
||||
cliCMix("");
|
||||
break;
|
||||
|
|
|
@ -14,11 +14,13 @@
|
|||
#include "serial_common.h"
|
||||
#include "flight_common.h"
|
||||
#include "flight_mixer.h"
|
||||
#include "escservo.h"
|
||||
#include "rc_controls.h"
|
||||
#include "boardalignment.h"
|
||||
#include "gps_common.h"
|
||||
#include "rx_common.h"
|
||||
#include "battery.h"
|
||||
#include "gimbal.h"
|
||||
#include "sensors_common.h"
|
||||
#include "sensors_acceleration.h"
|
||||
#include "sensors_barometer.h"
|
||||
|
@ -363,9 +365,9 @@ static void evaluateCommand(void)
|
|||
break;
|
||||
case MSP_SET_MISC:
|
||||
read16(); // powerfailmeter
|
||||
masterConfig.minthrottle = read16();
|
||||
masterConfig.maxthrottle = read16();
|
||||
masterConfig.mincommand = read16();
|
||||
masterConfig.escAndServoConfig.minthrottle = read16();
|
||||
masterConfig.escAndServoConfig.maxthrottle = read16();
|
||||
masterConfig.escAndServoConfig.mincommand = read16();
|
||||
currentProfile.failsafeConfig.failsafe_throttle = read16();
|
||||
read16();
|
||||
read32();
|
||||
|
@ -401,7 +403,7 @@ static void evaluateCommand(void)
|
|||
serialize8(VERSION); // multiwii version
|
||||
serialize8(masterConfig.mixerConfiguration); // type of multicopter
|
||||
serialize8(MSP_VERSION); // MultiWii Serial Protocol Version
|
||||
serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE | (masterConfig.flaps_speed ? CAP_FLAPS : 0) | CAP_CHANNEL_FORWARDING); // "capability"
|
||||
serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE | (masterConfig.airplaneConfig.flaps_speed ? CAP_FLAPS : 0) | CAP_CHANNEL_FORWARDING); // "capability"
|
||||
break;
|
||||
case MSP_STATUS:
|
||||
headSerialReply(11);
|
||||
|
@ -570,9 +572,9 @@ static void evaluateCommand(void)
|
|||
case MSP_MISC:
|
||||
headSerialReply(2 * 6 + 4 + 2 + 4);
|
||||
serialize16(0); // intPowerTrigger1 (aka useless trash)
|
||||
serialize16(masterConfig.minthrottle);
|
||||
serialize16(masterConfig.maxthrottle);
|
||||
serialize16(masterConfig.mincommand);
|
||||
serialize16(masterConfig.escAndServoConfig.minthrottle);
|
||||
serialize16(masterConfig.escAndServoConfig.maxthrottle);
|
||||
serialize16(masterConfig.escAndServoConfig.mincommand);
|
||||
serialize16(currentProfile.failsafeConfig.failsafe_throttle);
|
||||
serialize16(0); // plog useless shit
|
||||
serialize32(0); // plog useless shit
|
||||
|
|
Loading…
Reference in New Issue