Merge pull request #1652 from martinbudden/bf_parameter_grouping_into_structs
Move freestanding masterConfig items into structs
This commit is contained in:
commit
abedeb9bcc
|
@ -349,7 +349,7 @@ bool blackboxMayEditConfig()
|
|||
}
|
||||
|
||||
static bool blackboxIsOnlyLoggingIntraframes() {
|
||||
return masterConfig.blackbox_rate_num == 1 && masterConfig.blackbox_rate_denom == 32;
|
||||
return masterConfig.blackboxConfig.rate_num == 1 && masterConfig.blackboxConfig.rate_denom == 32;
|
||||
}
|
||||
|
||||
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||
|
@ -369,7 +369,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
|
||||
return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI;
|
||||
return masterConfig.mixerConfig.mixerMode == MIXER_TRI || masterConfig.mixerConfig.mixerMode == MIXER_CUSTOM_TRI;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
|
@ -407,7 +407,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
return masterConfig.rxConfig.rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
|
||||
return masterConfig.blackbox_rate_num < masterConfig.blackbox_rate_denom;
|
||||
return masterConfig.blackboxConfig.rate_num < masterConfig.blackboxConfig.rate_denom;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
|
||||
return false;
|
||||
|
@ -758,22 +758,22 @@ static void validateBlackboxConfig()
|
|||
{
|
||||
int div;
|
||||
|
||||
if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0
|
||||
|| masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
if (masterConfig.blackboxConfig.rate_num == 0 || masterConfig.blackboxConfig.rate_denom == 0
|
||||
|| masterConfig.blackboxConfig.rate_num >= masterConfig.blackboxConfig.rate_denom) {
|
||||
masterConfig.blackboxConfig.rate_num = 1;
|
||||
masterConfig.blackboxConfig.rate_denom = 1;
|
||||
} else {
|
||||
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
|
||||
* itself more frequently)
|
||||
*/
|
||||
div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
div = gcd(masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
|
||||
|
||||
masterConfig.blackbox_rate_num /= div;
|
||||
masterConfig.blackbox_rate_denom /= div;
|
||||
masterConfig.blackboxConfig.rate_num /= div;
|
||||
masterConfig.blackboxConfig.rate_denom /= div;
|
||||
}
|
||||
|
||||
// If we've chosen an unsupported device, change the device to serial
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
#endif
|
||||
|
@ -785,7 +785,7 @@ static void validateBlackboxConfig()
|
|||
break;
|
||||
|
||||
default:
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -867,7 +867,7 @@ bool startedLoggingInTestMode = false;
|
|||
void startInTestMode(void)
|
||||
{
|
||||
if(!startedLoggingInTestMode) {
|
||||
if (masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL) {
|
||||
if (masterConfig.blackboxConfig.device == BLACKBOX_DEVICE_SERIAL) {
|
||||
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
|
||||
if (sharedBlackboxAndMspPort) {
|
||||
return; // When in test mode, we cannot share the MSP and serial logger port!
|
||||
|
@ -1172,7 +1172,7 @@ static bool blackboxWriteSysinfo()
|
|||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.motorConfig.minthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.motorConfig.maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
|
||||
|
@ -1270,10 +1270,10 @@ static bool blackboxWriteSysinfo()
|
|||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", masterConfig.gyro_soft_notch_cutoff_1,
|
||||
masterConfig.gyro_soft_notch_cutoff_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.sensorSelectionConfig.acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.sensorSelectionConfig.baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.sensorSelectionConfig.mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.armingConfig.gyro_cal_on_first_arm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", masterConfig.rxConfig.rcInterpolation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", masterConfig.rxConfig.rcInterpolationInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
|
||||
|
@ -1376,10 +1376,10 @@ static void blackboxCheckAndLogFlightMode()
|
|||
*/
|
||||
static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
|
||||
{
|
||||
/* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
|
||||
/* Adding a magic shift of "masterConfig.blackboxConfig.rate_num - 1" in here creates a better spread of
|
||||
* recorded / skipped frames when the I frame's position is considered:
|
||||
*/
|
||||
return (pFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
|
||||
return (pFrameIndex + masterConfig.blackboxConfig.rate_num - 1) % masterConfig.blackboxConfig.rate_denom < masterConfig.blackboxConfig.rate_num;
|
||||
}
|
||||
|
||||
static bool blackboxShouldLogIFrame() {
|
||||
|
@ -1595,7 +1595,7 @@ void handleBlackbox(uint32_t currentTime)
|
|||
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
|
||||
} else { // Only log in test mode if there is room!
|
||||
|
||||
if(masterConfig.blackbox_on_motor_test) {
|
||||
if(masterConfig.blackboxConfig.on_motor_test) {
|
||||
// Handle Motor Test Mode
|
||||
if(inMotorTestMode()) {
|
||||
if(blackboxState==BLACKBOX_STATE_STOPPED)
|
||||
|
|
|
@ -19,6 +19,13 @@
|
|||
|
||||
#include "blackbox/blackbox_fielddefs.h"
|
||||
|
||||
typedef struct blackboxConfig_s {
|
||||
uint8_t rate_num;
|
||||
uint8_t rate_denom;
|
||||
uint8_t device;
|
||||
uint8_t on_motor_test;
|
||||
} blackboxConfig_t;
|
||||
|
||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
|
||||
|
||||
void initBlackbox(void);
|
||||
|
@ -26,4 +33,4 @@ void handleBlackbox(uint32_t currentTime);
|
|||
void startBlackbox(void);
|
||||
void finishBlackbox(void);
|
||||
|
||||
bool blackboxMayEditConfig();
|
||||
bool blackboxMayEditConfig(void);
|
||||
|
|
|
@ -65,7 +65,7 @@ static struct {
|
|||
|
||||
void blackboxWrite(uint8_t value)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
flashfsWriteByte(value); // Write byte asynchronously
|
||||
|
@ -137,7 +137,7 @@ int blackboxPrint(const char *s)
|
|||
int length;
|
||||
const uint8_t *pos;
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
|
@ -479,7 +479,7 @@ void blackboxWriteFloat(float value)
|
|||
*/
|
||||
void blackboxDeviceFlush(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
/*
|
||||
* This is our only output device which requires us to call flush() in order for it to write anything. The other
|
||||
|
@ -502,7 +502,7 @@ void blackboxDeviceFlush(void)
|
|||
*/
|
||||
bool blackboxDeviceFlushForce(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
|
||||
return isSerialTransmitBufferEmpty(blackboxPort);
|
||||
|
@ -530,7 +530,7 @@ bool blackboxDeviceFlushForce(void)
|
|||
*/
|
||||
bool blackboxDeviceOpen(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
{
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
|
||||
|
@ -604,7 +604,7 @@ bool blackboxDeviceOpen(void)
|
|||
*/
|
||||
void blackboxDeviceClose(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// Since the serial port could be shared with other processes, we have to give it back here
|
||||
closeSerialPort(blackboxPort);
|
||||
|
@ -748,7 +748,7 @@ static bool blackboxSDCardBeginLog()
|
|||
*/
|
||||
bool blackboxDeviceBeginLog(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
return blackboxSDCardBeginLog();
|
||||
|
@ -772,7 +772,7 @@ bool blackboxDeviceEndLog(bool retainLog)
|
|||
(void) retainLog;
|
||||
#endif
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
// Keep retrying until the close operation queues
|
||||
|
@ -794,7 +794,7 @@ bool blackboxDeviceEndLog(bool retainLog)
|
|||
|
||||
bool isBlackboxDeviceFull(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
return false;
|
||||
|
||||
|
@ -821,7 +821,7 @@ void blackboxReplenishHeaderBudget()
|
|||
{
|
||||
int32_t freeSpace;
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
freeSpace = serialTxBytesFree(blackboxPort);
|
||||
break;
|
||||
|
@ -867,7 +867,7 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
|
|||
}
|
||||
|
||||
// Handle failure:
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
/*
|
||||
* One byte of the tx buffer isn't available for user data (due to its circular list implementation),
|
||||
|
|
|
@ -90,7 +90,7 @@ static OSD_Entry cmsx_menuBlackboxEntries[] =
|
|||
{
|
||||
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
|
||||
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0 },
|
||||
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackbox_rate_denom,1,32,1 }, 0 },
|
||||
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackboxConfig.rate_denom,1,32,1 }, 0 },
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
|
||||
#include "config/config_profile.h"
|
||||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "cms/cms.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
|
@ -57,7 +59,7 @@
|
|||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "sensors/compass.h"
|
||||
|
||||
// System-wide
|
||||
typedef struct master_s {
|
||||
|
@ -65,7 +67,6 @@ typedef struct master_s {
|
|||
uint16_t size;
|
||||
uint8_t magic_be; // magic number, should be 0xBE
|
||||
|
||||
uint8_t mixerMode;
|
||||
uint32_t enabledFeatures;
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
|
@ -84,11 +85,11 @@ typedef struct master_s {
|
|||
#endif
|
||||
|
||||
// global sensor-related stuff
|
||||
sensorSelectionConfig_t sensorSelectionConfig;
|
||||
sensorAlignmentConfig_t sensorAlignmentConfig;
|
||||
boardAlignment_t boardAlignment;
|
||||
|
||||
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
|
||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
|
||||
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||
uint8_t gyro_sync_denom; // Gyro sample divider
|
||||
|
@ -106,11 +107,7 @@ typedef struct master_s {
|
|||
uint8_t debug_mode; // Processing denominator for PID controller vs gyro sampling rate
|
||||
|
||||
gyroConfig_t gyroConfig;
|
||||
|
||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||
uint8_t baro_hardware; // Barometer hardware to use
|
||||
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
||||
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||
compassConfig_t compassConfig;
|
||||
|
||||
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
|
||||
|
||||
|
@ -132,17 +129,12 @@ typedef struct master_s {
|
|||
#endif
|
||||
|
||||
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||
flightDynamicsTrims_t accZero;
|
||||
flightDynamicsTrims_t magZero;
|
||||
sensorTrims_t sensorTrims;
|
||||
|
||||
rxConfig_t rxConfig;
|
||||
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
||||
|
||||
|
||||
uint8_t gyro_cal_on_first_arm; // allow disarm/arm on throttle down + roll left/right
|
||||
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
||||
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
||||
uint8_t small_angle;
|
||||
armingConfig_t armingConfig;
|
||||
|
||||
// mixer-related configuration
|
||||
mixerConfig_t mixerConfig;
|
||||
|
@ -213,10 +205,7 @@ typedef struct master_s {
|
|||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
uint8_t blackbox_rate_num;
|
||||
uint8_t blackbox_rate_denom;
|
||||
uint8_t blackbox_device;
|
||||
uint8_t blackbox_on_motor_test;
|
||||
blackboxConfig_t blackboxConfig;
|
||||
#endif
|
||||
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -16,20 +16,20 @@
|
|||
*/
|
||||
|
||||
// FC configuration
|
||||
#define PG_FAILSAFE_CONFIG 1
|
||||
#define PG_BOARD_ALIGNMENT 2
|
||||
#define PG_GIMBAL_CONFIG 3
|
||||
#define PG_MOTOR_MIXER 4
|
||||
#define PG_BLACKBOX_CONFIG 5
|
||||
#define PG_MOTOR_AND_SERVO_CONFIG 6
|
||||
#define PG_SENSOR_SELECTION_CONFIG 7
|
||||
#define PG_SENSOR_ALIGNMENT_CONFIG 8
|
||||
#define PG_SENSOR_TRIMS 9
|
||||
#define PG_GYRO_CONFIG 10
|
||||
#define PG_BATTERY_CONFIG 11
|
||||
#define PG_CONTROL_RATE_PROFILES 12
|
||||
#define PG_SERIAL_CONFIG 13
|
||||
#define PG_PID_PROFILE 14
|
||||
#define PG_FAILSAFE_CONFIG 1 // strruct OK
|
||||
#define PG_BOARD_ALIGNMENT 2 // struct OK
|
||||
#define PG_GIMBAL_CONFIG 3 // struct OK
|
||||
#define PG_MOTOR_MIXER 4 // two structs mixerConfig_t servoMixerConfig_t
|
||||
#define PG_BLACKBOX_CONFIG 5 // struct OK
|
||||
#define PG_MOTOR_CONFIG 6 // struct OK
|
||||
#define PG_SENSOR_SELECTION_CONFIG 7 // struct OK
|
||||
#define PG_SENSOR_ALIGNMENT_CONFIG 8 // struct OK
|
||||
#define PG_SENSOR_TRIMS 9 // struct OK
|
||||
#define PG_GYRO_CONFIG 10 // PR outstanding, need to think about pid_process_denom
|
||||
#define PG_BATTERY_CONFIG 11 // struct OK
|
||||
#define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h
|
||||
#define PG_SERIAL_CONFIG 13 // struct OK
|
||||
#define PG_PID_PROFILE 14 // struct OK, CF differences
|
||||
#define PG_GTUNE_CONFIG 15
|
||||
#define PG_ARMING_CONFIG 16
|
||||
#define PG_TRANSPONDER_CONFIG 17
|
||||
|
|
|
@ -558,7 +558,7 @@ void createDefaultConfig(master_t *config)
|
|||
#endif
|
||||
|
||||
config->version = EEPROM_CONF_VERSION;
|
||||
config->mixerMode = MIXER_QUADX;
|
||||
config->mixerConfig.mixerMode = MIXER_QUADX;
|
||||
|
||||
// global settings
|
||||
config->current_profile_index = 0; // default profile
|
||||
|
@ -584,22 +584,22 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
config->debug_mode = DEBUG_NONE;
|
||||
|
||||
resetAccelerometerTrims(&config->accZero);
|
||||
resetAccelerometerTrims(&config->sensorTrims.accZero);
|
||||
|
||||
resetSensorAlignment(&config->sensorAlignmentConfig);
|
||||
|
||||
config->boardAlignment.rollDegrees = 0;
|
||||
config->boardAlignment.pitchDegrees = 0;
|
||||
config->boardAlignment.yawDegrees = 0;
|
||||
config->acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
config->sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
config->max_angle_inclination = 700; // 70 degrees
|
||||
config->yaw_control_direction = 1;
|
||||
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
|
||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
||||
config->mag_hardware = 1;
|
||||
config->sensorSelectionConfig.mag_hardware = 1;
|
||||
|
||||
config->baro_hardware = 1;
|
||||
config->sensorSelectionConfig.baro_hardware = 1;
|
||||
|
||||
resetBatteryConfig(&config->batteryConfig);
|
||||
|
||||
|
@ -663,10 +663,10 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
config->inputFilteringMode = INPUT_FILTERING_DISABLED;
|
||||
|
||||
config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||
config->disarm_kill_switch = 1;
|
||||
config->auto_disarm_delay = 5;
|
||||
config->small_angle = 25;
|
||||
config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||
config->armingConfig.disarm_kill_switch = 1;
|
||||
config->armingConfig.auto_disarm_delay = 5;
|
||||
config->armingConfig.small_angle = 25;
|
||||
|
||||
config->airplaneConfig.fixedwing_althold_dir = 1;
|
||||
|
||||
|
@ -697,7 +697,7 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
resetRollAndPitchTrims(&config->accelerometerTrims);
|
||||
|
||||
config->mag_declination = 0;
|
||||
config->compassConfig.mag_declination = 0;
|
||||
config->acc_lpf_hz = 10.0f;
|
||||
config->accDeadband.xy = 40;
|
||||
config->accDeadband.z = 40;
|
||||
|
@ -768,17 +768,17 @@ void createDefaultConfig(master_t *config)
|
|||
#ifdef BLACKBOX
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
|
||||
config->blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
||||
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
|
||||
intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
|
||||
config->blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
|
||||
#else
|
||||
config->blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
|
||||
#endif
|
||||
|
||||
config->blackbox_rate_num = 1;
|
||||
config->blackbox_rate_denom = 1;
|
||||
config->blackbox_on_motor_test = 0; // default off
|
||||
config->blackboxConfig.rate_num = 1;
|
||||
config->blackboxConfig.rate_denom = 1;
|
||||
config->blackboxConfig.on_motor_test = 0; // default off
|
||||
#endif // BLACKBOX
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
|
@ -855,7 +855,7 @@ void activateConfig(void)
|
|||
#endif
|
||||
|
||||
useFailsafeConfig(&masterConfig.failsafeConfig);
|
||||
setAccelerationTrims(&masterConfig.accZero);
|
||||
setAccelerationTrims(&masterConfig.sensorTrims.accZero);
|
||||
setAccelerationFilter(masterConfig.acc_lpf_hz);
|
||||
|
||||
mixerUseConfigs(
|
||||
|
@ -873,7 +873,7 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
|
||||
imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
|
||||
imuRuntimeConfig.acc_unarmedcal = masterConfig.acc_unarmedcal;
|
||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||
imuRuntimeConfig.small_angle = masterConfig.armingConfig.small_angle;
|
||||
|
||||
imuConfigure(
|
||||
&imuRuntimeConfig,
|
||||
|
|
|
@ -313,7 +313,7 @@ void initActiveBoxIds(void)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
||||
}
|
||||
|
||||
if (masterConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerMode == MIXER_AIRPLANE) {
|
||||
if (masterConfig.mixerConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerConfig.mixerMode == MIXER_AIRPLANE) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXPASSTHRU;
|
||||
}
|
||||
|
||||
|
@ -360,7 +360,7 @@ void initActiveBoxIds(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
if (masterConfig.mixerConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSERVO1;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSERVO2;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSERVO3;
|
||||
|
@ -563,7 +563,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
// DEPRECATED - Use MSP_API_VERSION
|
||||
case MSP_IDENT:
|
||||
sbufWriteU8(dst, MW_VERSION);
|
||||
sbufWriteU8(dst, masterConfig.mixerMode);
|
||||
sbufWriteU8(dst, masterConfig.mixerConfig.mixerMode);
|
||||
sbufWriteU8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbufWriteU32(dst, CAP_DYNBALANCE); // "capability"
|
||||
break;
|
||||
|
@ -700,8 +700,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_ARMING_CONFIG:
|
||||
sbufWriteU8(dst, masterConfig.auto_disarm_delay);
|
||||
sbufWriteU8(dst, masterConfig.disarm_kill_switch);
|
||||
sbufWriteU8(dst, masterConfig.armingConfig.auto_disarm_delay);
|
||||
sbufWriteU8(dst, masterConfig.armingConfig.disarm_kill_switch);
|
||||
break;
|
||||
|
||||
case MSP_LOOP_TIME:
|
||||
|
@ -797,7 +797,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, masterConfig.rxConfig.rssi_channel);
|
||||
sbufWriteU8(dst, 0);
|
||||
|
||||
sbufWriteU16(dst, masterConfig.mag_declination / 10);
|
||||
sbufWriteU16(dst, masterConfig.compassConfig.mag_declination / 10);
|
||||
|
||||
sbufWriteU8(dst, masterConfig.batteryConfig.vbatscale);
|
||||
sbufWriteU8(dst, masterConfig.batteryConfig.vbatmincellvoltage);
|
||||
|
@ -886,7 +886,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_MIXER:
|
||||
sbufWriteU8(dst, masterConfig.mixerMode);
|
||||
sbufWriteU8(dst, masterConfig.mixerConfig.mixerMode);
|
||||
break;
|
||||
|
||||
case MSP_RX_CONFIG:
|
||||
|
@ -932,7 +932,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_BF_CONFIG:
|
||||
sbufWriteU8(dst, masterConfig.mixerMode);
|
||||
sbufWriteU8(dst, masterConfig.mixerConfig.mixerMode);
|
||||
|
||||
sbufWriteU32(dst, featureMask());
|
||||
|
||||
|
@ -1005,9 +1005,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
case MSP_BLACKBOX_CONFIG:
|
||||
#ifdef BLACKBOX
|
||||
sbufWriteU8(dst, 1); //Blackbox supported
|
||||
sbufWriteU8(dst, masterConfig.blackbox_device);
|
||||
sbufWriteU8(dst, masterConfig.blackbox_rate_num);
|
||||
sbufWriteU8(dst, masterConfig.blackbox_rate_denom);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.device);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_num);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_denom);
|
||||
#else
|
||||
sbufWriteU8(dst, 0); // Blackbox not supported
|
||||
sbufWriteU8(dst, 0);
|
||||
|
@ -1121,9 +1121,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_SENSOR_CONFIG:
|
||||
sbufWriteU8(dst, masterConfig.acc_hardware);
|
||||
sbufWriteU8(dst, masterConfig.baro_hardware);
|
||||
sbufWriteU8(dst, masterConfig.mag_hardware);
|
||||
sbufWriteU8(dst, masterConfig.sensorSelectionConfig.acc_hardware);
|
||||
sbufWriteU8(dst, masterConfig.sensorSelectionConfig.baro_hardware);
|
||||
sbufWriteU8(dst, masterConfig.sensorSelectionConfig.mag_hardware);
|
||||
break;
|
||||
|
||||
case MSP_REBOOT:
|
||||
|
@ -1247,8 +1247,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
masterConfig.accelerometerTrims.values.roll = sbufReadU16(src);
|
||||
break;
|
||||
case MSP_SET_ARMING_CONFIG:
|
||||
masterConfig.auto_disarm_delay = sbufReadU8(src);
|
||||
masterConfig.disarm_kill_switch = sbufReadU8(src);
|
||||
masterConfig.armingConfig.auto_disarm_delay = sbufReadU8(src);
|
||||
masterConfig.armingConfig.disarm_kill_switch = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_LOOP_TIME:
|
||||
|
@ -1355,7 +1355,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
masterConfig.rxConfig.rssi_channel = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
|
||||
masterConfig.mag_declination = sbufReadU16(src) * 10;
|
||||
masterConfig.compassConfig.mag_declination = sbufReadU16(src) * 10;
|
||||
|
||||
masterConfig.batteryConfig.vbatscale = sbufReadU8(src); // actual vbatscale as intended
|
||||
masterConfig.batteryConfig.vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
|
@ -1476,9 +1476,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
|
||||
case MSP_SET_SENSOR_CONFIG:
|
||||
masterConfig.acc_hardware = sbufReadU8(src);
|
||||
masterConfig.baro_hardware = sbufReadU8(src);
|
||||
masterConfig.mag_hardware = sbufReadU8(src);
|
||||
masterConfig.sensorSelectionConfig.acc_hardware = sbufReadU8(src);
|
||||
masterConfig.sensorSelectionConfig.baro_hardware = sbufReadU8(src);
|
||||
masterConfig.sensorSelectionConfig.mag_hardware = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
case MSP_RESET_CONF:
|
||||
|
@ -1510,9 +1510,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
case MSP_SET_BLACKBOX_CONFIG:
|
||||
// Don't allow config to be updated while Blackbox is logging
|
||||
if (blackboxMayEditConfig()) {
|
||||
masterConfig.blackbox_device = sbufReadU8(src);
|
||||
masterConfig.blackbox_rate_num = sbufReadU8(src);
|
||||
masterConfig.blackbox_rate_denom = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.device = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.rate_num = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.rate_denom = sbufReadU8(src);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
@ -1657,7 +1657,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
case MSP_SET_MIXER:
|
||||
masterConfig.mixerMode = sbufReadU8(src);
|
||||
masterConfig.mixerConfig.mixerMode = sbufReadU8(src);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
@ -1716,7 +1716,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
sbufReadU8(src); // mixerMode ignored
|
||||
#else
|
||||
masterConfig.mixerMode = sbufReadU8(src); // mixerMode
|
||||
masterConfig.mixerConfig.mixerMode = sbufReadU8(src); // mixerMode
|
||||
#endif
|
||||
|
||||
featureClearAll();
|
||||
|
|
|
@ -153,7 +153,7 @@ static void taskUpdateRxMain(uint32_t currentTime)
|
|||
static void taskUpdateCompass(uint32_t currentTime)
|
||||
{
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
compassUpdate(currentTime, &masterConfig.magZero);
|
||||
compassUpdate(currentTime, &masterConfig.sensorTrims.magZero);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -389,7 +389,7 @@ void mwArm(void)
|
|||
{
|
||||
static bool firstArmingCalibrationWasCompleted;
|
||||
|
||||
if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
|
||||
if (masterConfig.armingConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
|
||||
gyroSetCalibrationCycles();
|
||||
armingCalibrationWasInitialised = true;
|
||||
firstArmingCalibrationWasCompleted = true;
|
||||
|
@ -418,7 +418,7 @@ void mwArm(void)
|
|||
startBlackbox();
|
||||
}
|
||||
#endif
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
disarmAt = millis() + masterConfig.armingConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
//beep to indicate arming
|
||||
#ifdef GPS
|
||||
|
@ -548,7 +548,7 @@ void processRx(uint32_t currentTime)
|
|||
) {
|
||||
if (isUsingSticksForArming()) {
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
if (masterConfig.auto_disarm_delay != 0
|
||||
if (masterConfig.armingConfig.auto_disarm_delay != 0
|
||||
&& (int32_t)(disarmAt - millis()) < 0
|
||||
) {
|
||||
// auto-disarm configured and delay is over
|
||||
|
@ -561,9 +561,9 @@ void processRx(uint32_t currentTime)
|
|||
}
|
||||
} else {
|
||||
// throttle is not low
|
||||
if (masterConfig.auto_disarm_delay != 0) {
|
||||
if (masterConfig.armingConfig.auto_disarm_delay != 0) {
|
||||
// extend disarm time
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000;
|
||||
disarmAt = millis() + masterConfig.armingConfig.auto_disarm_delay * 1000;
|
||||
}
|
||||
|
||||
if (armedBeeperOn) {
|
||||
|
@ -583,7 +583,7 @@ void processRx(uint32_t currentTime)
|
|||
}
|
||||
}
|
||||
|
||||
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.disarm_kill_switch);
|
||||
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.armingConfig.disarm_kill_switch);
|
||||
|
||||
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
||||
updateInflightCalibrationState();
|
||||
|
@ -661,7 +661,7 @@ void processRx(uint32_t currentTime)
|
|||
DISABLE_FLIGHT_MODE(PASSTHRU_MODE);
|
||||
}
|
||||
|
||||
if (masterConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerMode == MIXER_AIRPLANE) {
|
||||
if (masterConfig.mixerConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerConfig.mixerMode == MIXER_AIRPLANE) {
|
||||
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
}
|
||||
|
||||
|
@ -735,10 +735,10 @@ void subTaskMainSubprocesses(void)
|
|||
if (isUsingSticksForArming() && rcData[THROTTLE] <= masterConfig.rxConfig.mincheck
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
#ifdef USE_SERVOS
|
||||
&& !((masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI) && masterConfig.servoMixerConfig.tri_unarmed_servo)
|
||||
&& !((masterConfig.mixerConfig.mixerMode == MIXER_TRI || masterConfig.mixerConfig.mixerMode == MIXER_CUSTOM_TRI) && masterConfig.servoMixerConfig.tri_unarmed_servo)
|
||||
#endif
|
||||
&& masterConfig.mixerMode != MIXER_AIRPLANE
|
||||
&& masterConfig.mixerMode != MIXER_FLYING_WING
|
||||
&& masterConfig.mixerConfig.mixerMode != MIXER_AIRPLANE
|
||||
&& masterConfig.mixerConfig.mixerMode != MIXER_FLYING_WING
|
||||
#endif
|
||||
) {
|
||||
rcCommand[YAW] = 0;
|
||||
|
|
|
@ -164,6 +164,13 @@ typedef struct rcControlsConfig_s {
|
|||
uint8_t alt_hold_fast_change; // when disabled, turn off the althold when throttle stick is out of deadband defined with alt_hold_deadband; when enabled, altitude changes slowly proportional to stick movement
|
||||
} rcControlsConfig_t;
|
||||
|
||||
typedef struct armingConfig_s {
|
||||
uint8_t gyro_cal_on_first_arm; // allow disarm/arm on throttle down + roll left/right
|
||||
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
||||
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
||||
uint8_t small_angle;
|
||||
} armingConfig_t;
|
||||
|
||||
bool areUsingSticksToArm(void);
|
||||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
|
|
|
@ -93,6 +93,7 @@ typedef struct mixer_s {
|
|||
} mixer_t;
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
uint8_t mixerMode;
|
||||
int8_t yaw_motor_direction;
|
||||
} mixerConfig_t;
|
||||
|
||||
|
|
|
@ -711,10 +711,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motorConfig.motorPwmProtocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
|
||||
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.motorPwmRate, .config.minmax = { 200, 32000 } },
|
||||
|
||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
|
||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
|
||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.armingConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.armingConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.armingConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
|
||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.armingConfig.small_angle, .config.minmax = { 0, 180 } },
|
||||
|
||||
{ "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
|
||||
|
||||
|
@ -860,7 +860,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
|
||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorSelectionConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
||||
{ "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
|
||||
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
|
||||
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
|
||||
|
@ -873,12 +873,12 @@ const clivalue_t valueTable[] = {
|
|||
{ "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorSelectionConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorSelectionConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.compassConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
||||
#endif
|
||||
{ "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
|
||||
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
||||
|
@ -922,10 +922,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "level_sensitivity", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelSensitivity, .config.minmax = { 0.1, 3.0 } },
|
||||
|
||||
#ifdef BLACKBOX
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
|
||||
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_on_motor_test, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_num, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_denom, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackboxConfig.device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
|
||||
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackboxConfig.on_motor_test, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
|
@ -936,9 +936,9 @@ const clivalue_t valueTable[] = {
|
|||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.sensorTrims.magZero.raw[X], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.sensorTrims.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
|
||||
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.sensorTrims.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
|
||||
#endif
|
||||
#ifdef LED_STRIP
|
||||
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledStripConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
|
||||
|
@ -2774,10 +2774,10 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
#ifndef CLI_MINIMAL_VERBOSITY
|
||||
cliPrint("\r\n# mixer\r\n");
|
||||
#endif
|
||||
const bool equalsDefault = masterConfig.mixerMode == defaultConfig.mixerMode;
|
||||
const bool equalsDefault = masterConfig.mixerConfig.mixerMode == defaultConfig.mixerConfig.mixerMode;
|
||||
const char *formatMixer = "mixer %s\r\n";
|
||||
cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[defaultConfig.mixerMode - 1]);
|
||||
cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[masterConfig.mixerMode - 1]);
|
||||
cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[defaultConfig.mixerConfig.mixerMode - 1]);
|
||||
cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[masterConfig.mixerConfig.mixerMode - 1]);
|
||||
|
||||
cliDumpPrintf(dumpMask, masterConfig.customMotorMixer[0].throttle == 0.0f, "\r\nmmix reset\r\n\r\n");
|
||||
|
||||
|
@ -3072,7 +3072,7 @@ static void cliMixer(char *cmdline)
|
|||
len = strlen(cmdline);
|
||||
|
||||
if (len == 0) {
|
||||
cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
|
||||
cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerConfig.mixerMode - 1]);
|
||||
return;
|
||||
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
||||
cliPrint("Available mixers: ");
|
||||
|
@ -3091,7 +3091,7 @@ static void cliMixer(char *cmdline)
|
|||
return;
|
||||
}
|
||||
if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
|
||||
masterConfig.mixerMode = i + 1;
|
||||
masterConfig.mixerConfig.mixerMode = i + 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -249,7 +249,7 @@ void init(void)
|
|||
serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
||||
#endif
|
||||
|
||||
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
|
||||
mixerInit(masterConfig.mixerConfig.mixerMode, masterConfig.customMotorMixer);
|
||||
#ifdef USE_SERVOS
|
||||
servoMixerInit(masterConfig.customServoMixer);
|
||||
#endif
|
||||
|
@ -418,10 +418,8 @@ void init(void)
|
|||
#endif
|
||||
|
||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
|
||||
masterConfig.acc_hardware,
|
||||
masterConfig.mag_hardware,
|
||||
masterConfig.baro_hardware,
|
||||
masterConfig.mag_declination,
|
||||
&masterConfig.sensorSelectionConfig,
|
||||
masterConfig.compassConfig.mag_declination,
|
||||
masterConfig.gyro_lpf,
|
||||
masterConfig.gyro_sync_denom)) {
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
|
@ -550,7 +548,7 @@ void init(void)
|
|||
initBlackbox();
|
||||
#endif
|
||||
|
||||
if (masterConfig.mixerMode == MIXER_GIMBAL) {
|
||||
if (masterConfig.mixerConfig.mixerMode == MIXER_GIMBAL) {
|
||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
||||
}
|
||||
gyroSetCalibrationCycles();
|
||||
|
|
|
@ -30,6 +30,11 @@ typedef enum {
|
|||
MAG_MAX = MAG_AK8963
|
||||
} magSensor_e;
|
||||
|
||||
typedef struct compassConfig_s {
|
||||
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
||||
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||
} compassConfig_t;
|
||||
|
||||
void compassInit(void);
|
||||
union flightDynamicsTrims_u;
|
||||
void compassUpdate(uint32_t currentTime, union flightDynamicsTrims_u *magZero);
|
||||
|
|
|
@ -623,9 +623,7 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
|||
}
|
||||
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
|
||||
uint8_t accHardwareToUse,
|
||||
uint8_t magHardwareToUse,
|
||||
uint8_t baroHardwareToUse,
|
||||
sensorSelectionConfig_t *sensorSelectionConfig,
|
||||
int16_t magDeclinationFromConfig,
|
||||
uint8_t gyroLpf,
|
||||
uint8_t gyroSyncDenominator)
|
||||
|
@ -651,7 +649,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
|
|||
gyro.init(gyroLpf); // driver initialisation
|
||||
gyroInit(); // sensor initialisation
|
||||
|
||||
if (detectAcc(accHardwareToUse)) {
|
||||
if (detectAcc(sensorSelectionConfig->acc_hardware)) {
|
||||
acc.acc_1G = 256; // set default
|
||||
acc.init(&acc); // driver initialisation
|
||||
accInit(gyro.targetLooptime); // sensor initialisation
|
||||
|
@ -661,21 +659,18 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
|
|||
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
||||
#ifdef MAG
|
||||
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
|
||||
if (detectMag(magHardwareToUse)) {
|
||||
if (detectMag(sensorSelectionConfig->mag_hardware)) {
|
||||
// calculate magnetic declination
|
||||
const int16_t deg = magDeclinationFromConfig / 100;
|
||||
const int16_t min = magDeclinationFromConfig % 100;
|
||||
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
|
||||
}
|
||||
#else
|
||||
UNUSED(magHardwareToUse);
|
||||
UNUSED(magDeclinationFromConfig);
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
detectBaro(baroHardwareToUse);
|
||||
#else
|
||||
UNUSED(baroHardwareToUse);
|
||||
detectBaro(sensorSelectionConfig->baro_hardware);
|
||||
#endif
|
||||
|
||||
reconfigureAlignment(sensorAlignmentConfig);
|
||||
|
|
|
@ -16,5 +16,5 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator);
|
||||
struct sensorSelectionConfig_s;
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, struct sensorSelectionConfig_s *sensorSelectionConfig, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator);
|
||||
|
|
|
@ -69,3 +69,14 @@ typedef struct sensorAlignmentConfig_s {
|
|||
sensor_align_e acc_align; // acc alignment
|
||||
sensor_align_e mag_align; // mag alignment
|
||||
} sensorAlignmentConfig_t;
|
||||
|
||||
typedef struct sensorSelectionConfig_s {
|
||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
uint8_t baro_hardware; // Barometer hardware to use
|
||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||
} sensorSelectionConfig_t;
|
||||
|
||||
typedef struct sensorTrims_s {
|
||||
flightDynamicsTrims_t accZero;
|
||||
flightDynamicsTrims_t magZero;
|
||||
} sensorTrims_t;
|
||||
|
|
|
@ -48,7 +48,7 @@ void targetConfiguration(master_t *config)
|
|||
config->rxConfig.spektrum_sat_bind = 5;
|
||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
config->gyro_sync_denom = 2;
|
||||
config->mag_hardware = MAG_NONE; // disabled by default
|
||||
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
config->pid_process_denom = 1;
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
|
|
|
@ -59,7 +59,7 @@ void targetConfiguration(master_t *config)
|
|||
config->batteryConfig.currentMeterOffset = CURRENTOFFSET;
|
||||
config->batteryConfig.currentMeterScale = CURRENTSCALE;
|
||||
config->gyro_sync_denom = 1;
|
||||
config->mag_hardware = MAG_NONE; // disabled by default
|
||||
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
config->pid_process_denom = 1;
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
|
|
|
@ -51,8 +51,8 @@ void targetValidateConfiguration(master_t *config)
|
|||
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {
|
||||
intFeatureClear(FEATURE_SDCARD, &config->enabledFeatures);
|
||||
|
||||
if (config->blackbox_device == BLACKBOX_DEVICE_SDCARD) {
|
||||
config->blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
if (config->blackboxConfig.device == BLACKBOX_DEVICE_SDCARD) {
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
// alternative defaults settings for Colibri/Gemini targets
|
||||
void targetConfiguration(master_t *config)
|
||||
{
|
||||
config->mixerMode = MIXER_HEX6X;
|
||||
config->mixerConfig.mixerMode = MIXER_HEX6X;
|
||||
config->rxConfig.serialrx_provider = 2;
|
||||
|
||||
config->motorConfig.minthrottle = 1070;
|
||||
|
@ -48,7 +48,7 @@ void targetConfiguration(master_t *config)
|
|||
config->boardAlignment.pitchDegrees = 10;
|
||||
//config->rcControlsConfig.deadband = 10;
|
||||
//config->rcControlsConfig.yaw_deadband = 10;
|
||||
config->mag_hardware = 1;
|
||||
config->sensorSelectionConfig.mag_hardware = 1;
|
||||
|
||||
config->profile[0].controlRateProfile[0].dynThrPID = 45;
|
||||
config->profile[0].controlRateProfile[0].tpa_breakpoint = 1700;
|
||||
|
|
|
@ -556,7 +556,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
// DEPRECATED - Use MSP_API_VERSION
|
||||
case BST_IDENT:
|
||||
bstWrite8(MW_VERSION);
|
||||
bstWrite8(masterConfig.mixerMode);
|
||||
bstWrite8(masterConfig.mixerConfig.mixerMode);
|
||||
bstWrite8(BST_PROTOCOL_VERSION);
|
||||
bstWrite32(CAP_DYNBALANCE); // "capability"
|
||||
break;
|
||||
|
@ -683,8 +683,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
case BST_ARMING_CONFIG:
|
||||
bstWrite8(masterConfig.auto_disarm_delay);
|
||||
bstWrite8(masterConfig.disarm_kill_switch);
|
||||
bstWrite8(masterConfig.armingConfig.auto_disarm_delay);
|
||||
bstWrite8(masterConfig.armingConfig.disarm_kill_switch);
|
||||
break;
|
||||
case BST_LOOP_TIME:
|
||||
//bstWrite16(masterConfig.looptime);
|
||||
|
@ -769,7 +769,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite8(masterConfig.rxConfig.rssi_channel);
|
||||
bstWrite8(0);
|
||||
|
||||
bstWrite16(masterConfig.mag_declination / 10);
|
||||
bstWrite16(masterConfig.compassConfig.mag_declination / 10);
|
||||
|
||||
bstWrite8(masterConfig.batteryConfig.vbatscale);
|
||||
bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage);
|
||||
|
@ -868,7 +868,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
break;
|
||||
|
||||
case BST_MIXER:
|
||||
bstWrite8(masterConfig.mixerMode);
|
||||
bstWrite8(masterConfig.mixerConfig.mixerMode);
|
||||
break;
|
||||
|
||||
case BST_RX_CONFIG:
|
||||
|
@ -904,7 +904,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
break;
|
||||
|
||||
case BST_BF_CONFIG:
|
||||
bstWrite8(masterConfig.mixerMode);
|
||||
bstWrite8(masterConfig.mixerConfig.mixerMode);
|
||||
|
||||
bstWrite32(featureMask());
|
||||
|
||||
|
@ -1033,8 +1033,8 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
masterConfig.accelerometerTrims.values.roll = bstRead16();
|
||||
break;
|
||||
case BST_SET_ARMING_CONFIG:
|
||||
masterConfig.auto_disarm_delay = bstRead8();
|
||||
masterConfig.disarm_kill_switch = bstRead8();
|
||||
masterConfig.armingConfig.auto_disarm_delay = bstRead8();
|
||||
masterConfig.armingConfig.disarm_kill_switch = bstRead8();
|
||||
break;
|
||||
case BST_SET_LOOP_TIME:
|
||||
//masterConfig.looptime = bstRead16();
|
||||
|
@ -1132,7 +1132,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
masterConfig.rxConfig.rssi_channel = bstRead8();
|
||||
bstRead8();
|
||||
|
||||
masterConfig.mag_declination = bstRead16() * 10;
|
||||
masterConfig.compassConfig.mag_declination = bstRead16() * 10;
|
||||
|
||||
masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended
|
||||
masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
|
@ -1273,7 +1273,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
case BST_SET_MIXER:
|
||||
masterConfig.mixerMode = bstRead8();
|
||||
masterConfig.mixerConfig.mixerMode = bstRead8();
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
@ -1319,7 +1319,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
bstRead8(); // mixerMode ignored
|
||||
#else
|
||||
masterConfig.mixerMode = bstRead8(); // mixerMode
|
||||
masterConfig.mixerConfig.mixerMode = bstRead8(); // mixerMode
|
||||
#endif
|
||||
|
||||
featureClearAll();
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
|
||||
// alternative defaults settings for MULTIFLITEPICO targets
|
||||
void targetConfiguration(master_t *config) {
|
||||
config->mag_hardware = MAG_NONE; // disabled by default
|
||||
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
|
||||
config->batteryConfig.vbatscale = 100;
|
||||
config->batteryConfig.vbatresdivval = 15;
|
||||
|
|
|
@ -430,7 +430,7 @@ void mavlinkSendHUDAndHeartbeat(void)
|
|||
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
|
||||
uint8_t mavSystemType;
|
||||
switch(masterConfig.mixerMode)
|
||||
switch(masterConfig.mixerConfig.mixerMode)
|
||||
{
|
||||
case MIXER_TRI:
|
||||
mavSystemType = MAV_TYPE_TRICOPTER;
|
||||
|
|
Loading…
Reference in New Issue