mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 21:05:30 +03:00
Merge pull request #359 from basdelfos/battery_meter_type
Added dropdown for current and battery meter selection to configuration tab
This commit is contained in:
commit
acb7a84422
7 changed files with 410 additions and 212 deletions
|
@ -665,6 +665,9 @@
|
||||||
"configurationBatteryCurrent": {
|
"configurationBatteryCurrent": {
|
||||||
"message": "Battery Current"
|
"message": "Battery Current"
|
||||||
},
|
},
|
||||||
|
"configurationBatteryMeterType": {
|
||||||
|
"message": "Battery Meter Type"
|
||||||
|
},
|
||||||
"configurationBatteryMinimum": {
|
"configurationBatteryMinimum": {
|
||||||
"message": "Minimum Cell Voltage"
|
"message": "Minimum Cell Voltage"
|
||||||
},
|
},
|
||||||
|
@ -677,6 +680,9 @@
|
||||||
"configurationBatteryScale": {
|
"configurationBatteryScale": {
|
||||||
"message": "Voltage Scale"
|
"message": "Voltage Scale"
|
||||||
},
|
},
|
||||||
|
"configurationCurrentMeterType": {
|
||||||
|
"message": "Current Meter Type"
|
||||||
|
},
|
||||||
"configurationCurrent": {
|
"configurationCurrent": {
|
||||||
"message": "Current Sensor"
|
"message": "Current Sensor"
|
||||||
},
|
},
|
||||||
|
|
73
js/fc.js
73
js/fc.js
|
@ -65,7 +65,7 @@ var FC = {
|
||||||
numProfiles: 3,
|
numProfiles: 3,
|
||||||
rateProfile: 0
|
rateProfile: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
BF_CONFIG = {
|
BF_CONFIG = {
|
||||||
mixerConfiguration: 0,
|
mixerConfiguration: 0,
|
||||||
features: new Features(CONFIG),
|
features: new Features(CONFIG),
|
||||||
|
@ -74,37 +74,39 @@ var FC = {
|
||||||
board_align_pitch: 0,
|
board_align_pitch: 0,
|
||||||
board_align_yaw: 0,
|
board_align_yaw: 0,
|
||||||
currentscale: 0,
|
currentscale: 0,
|
||||||
currentoffset: 0
|
currentoffset: 0,
|
||||||
|
currentmetertype: 0,
|
||||||
|
batterycapacity: 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
LED_STRIP = [];
|
LED_STRIP = [];
|
||||||
LED_COLORS = [];
|
LED_COLORS = [];
|
||||||
LED_MODE_COLORS = [];
|
LED_MODE_COLORS = [];
|
||||||
|
|
||||||
PID = {
|
PID = {
|
||||||
controller: 0
|
controller: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
PID_names = [];
|
PID_names = [];
|
||||||
PIDs = new Array(10);
|
PIDs = new Array(10);
|
||||||
for (var i = 0; i < 10; i++) {
|
for (var i = 0; i < 10; i++) {
|
||||||
PIDs[i] = new Array(3);
|
PIDs[i] = new Array(3);
|
||||||
}
|
}
|
||||||
|
|
||||||
RC_MAP = [];
|
RC_MAP = [];
|
||||||
|
|
||||||
// defaults
|
// defaults
|
||||||
// roll, pitch, yaw, throttle, aux 1, ... aux n
|
// roll, pitch, yaw, throttle, aux 1, ... aux n
|
||||||
RC = {
|
RC = {
|
||||||
active_channels: 0,
|
active_channels: 0,
|
||||||
channels: new Array(32)
|
channels: new Array(32)
|
||||||
};
|
};
|
||||||
|
|
||||||
RC_tuning = {
|
RC_tuning = {
|
||||||
RC_RATE: 0,
|
RC_RATE: 0,
|
||||||
RC_EXPO: 0,
|
RC_EXPO: 0,
|
||||||
roll_pitch_rate: 0, // pre 1.7 api only
|
roll_pitch_rate: 0, // pre 1.7 api only
|
||||||
roll_rate: 0,
|
roll_rate: 0,
|
||||||
pitch_rate: 0,
|
pitch_rate: 0,
|
||||||
yaw_rate: 0,
|
yaw_rate: 0,
|
||||||
dynamic_THR_PID: 0,
|
dynamic_THR_PID: 0,
|
||||||
|
@ -114,26 +116,26 @@ var FC = {
|
||||||
RC_YAW_EXPO: 0,
|
RC_YAW_EXPO: 0,
|
||||||
rcYawRate: 0
|
rcYawRate: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
AUX_CONFIG = [];
|
AUX_CONFIG = [];
|
||||||
AUX_CONFIG_IDS = [];
|
AUX_CONFIG_IDS = [];
|
||||||
|
|
||||||
MODE_RANGES = [];
|
MODE_RANGES = [];
|
||||||
ADJUSTMENT_RANGES = [];
|
ADJUSTMENT_RANGES = [];
|
||||||
|
|
||||||
SERVO_CONFIG = [];
|
SERVO_CONFIG = [];
|
||||||
SERVO_RULES = [];
|
SERVO_RULES = [];
|
||||||
|
|
||||||
SERIAL_CONFIG = {
|
SERIAL_CONFIG = {
|
||||||
ports: [],
|
ports: [],
|
||||||
|
|
||||||
// pre 1.6 settings
|
// pre 1.6 settings
|
||||||
mspBaudRate: 0,
|
mspBaudRate: 0,
|
||||||
gpsBaudRate: 0,
|
gpsBaudRate: 0,
|
||||||
gpsPassthroughBaudRate: 0,
|
gpsPassthroughBaudRate: 0,
|
||||||
cliBaudRate: 0,
|
cliBaudRate: 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
SENSOR_DATA = {
|
SENSOR_DATA = {
|
||||||
gyroscope: [0, 0, 0],
|
gyroscope: [0, 0, 0],
|
||||||
accelerometer: [0, 0, 0],
|
accelerometer: [0, 0, 0],
|
||||||
|
@ -143,10 +145,10 @@ var FC = {
|
||||||
kinematics: [0.0, 0.0, 0.0],
|
kinematics: [0.0, 0.0, 0.0],
|
||||||
debug: [0, 0, 0, 0]
|
debug: [0, 0, 0, 0]
|
||||||
};
|
};
|
||||||
|
|
||||||
MOTOR_DATA = new Array(8);
|
MOTOR_DATA = new Array(8);
|
||||||
SERVO_DATA = new Array(8);
|
SERVO_DATA = new Array(8);
|
||||||
|
|
||||||
GPS_DATA = {
|
GPS_DATA = {
|
||||||
fix: 0,
|
fix: 0,
|
||||||
numSat: 0,
|
numSat: 0,
|
||||||
|
@ -158,14 +160,14 @@ var FC = {
|
||||||
distanceToHome: 0,
|
distanceToHome: 0,
|
||||||
ditectionToHome: 0,
|
ditectionToHome: 0,
|
||||||
update: 0,
|
update: 0,
|
||||||
|
|
||||||
// baseflight specific gps stuff
|
// baseflight specific gps stuff
|
||||||
chn: [],
|
chn: [],
|
||||||
svid: [],
|
svid: [],
|
||||||
quality: [],
|
quality: [],
|
||||||
cno: []
|
cno: []
|
||||||
};
|
};
|
||||||
|
|
||||||
ANALOG = {
|
ANALOG = {
|
||||||
voltage: 0,
|
voltage: 0,
|
||||||
mAhdrawn: 0,
|
mAhdrawn: 0,
|
||||||
|
@ -173,16 +175,16 @@ var FC = {
|
||||||
amperage: 0,
|
amperage: 0,
|
||||||
last_received_timestamp: Date.now()
|
last_received_timestamp: Date.now()
|
||||||
};
|
};
|
||||||
|
|
||||||
ARMING_CONFIG = {
|
ARMING_CONFIG = {
|
||||||
auto_disarm_delay: 0,
|
auto_disarm_delay: 0,
|
||||||
disarm_kill_switch: 0
|
disarm_kill_switch: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
FC_CONFIG = {
|
FC_CONFIG = {
|
||||||
loopTime: 0
|
loopTime: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
MISC = {
|
MISC = {
|
||||||
midrc: 0,
|
midrc: 0,
|
||||||
minthrottle: 0,
|
minthrottle: 0,
|
||||||
|
@ -199,16 +201,17 @@ var FC = {
|
||||||
vbatscale: 0,
|
vbatscale: 0,
|
||||||
vbatmincellvoltage: 0,
|
vbatmincellvoltage: 0,
|
||||||
vbatmaxcellvoltage: 0,
|
vbatmaxcellvoltage: 0,
|
||||||
vbatwarningcellvoltage: 0
|
vbatwarningcellvoltage: 0,
|
||||||
|
batterymetertype: 1, // 1=ADC, 2=ESC
|
||||||
};
|
};
|
||||||
|
|
||||||
_3D = {
|
_3D = {
|
||||||
deadband3d_low: 0,
|
deadband3d_low: 0,
|
||||||
deadband3d_high: 0,
|
deadband3d_high: 0,
|
||||||
neutral3d: 0,
|
neutral3d: 0,
|
||||||
deadband3d_throttle: 0
|
deadband3d_throttle: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
DATAFLASH = {
|
DATAFLASH = {
|
||||||
ready: false,
|
ready: false,
|
||||||
supported: false,
|
supported: false,
|
||||||
|
@ -216,7 +219,7 @@ var FC = {
|
||||||
totalSize: 0,
|
totalSize: 0,
|
||||||
usedSize: 0
|
usedSize: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
SDCARD = {
|
SDCARD = {
|
||||||
supported: false,
|
supported: false,
|
||||||
state: 0,
|
state: 0,
|
||||||
|
@ -224,31 +227,31 @@ var FC = {
|
||||||
freeSizeKB: 0,
|
freeSizeKB: 0,
|
||||||
totalSizeKB: 0,
|
totalSizeKB: 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
BLACKBOX = {
|
BLACKBOX = {
|
||||||
supported: false,
|
supported: false,
|
||||||
blackboxDevice: 0,
|
blackboxDevice: 0,
|
||||||
blackboxRateNum: 1,
|
blackboxRateNum: 1,
|
||||||
blackboxRateDenom: 1
|
blackboxRateDenom: 1
|
||||||
};
|
};
|
||||||
|
|
||||||
TRANSPONDER = {
|
TRANSPONDER = {
|
||||||
supported: false,
|
supported: false,
|
||||||
data: []
|
data: []
|
||||||
};
|
};
|
||||||
|
|
||||||
RC_deadband = {
|
RC_deadband = {
|
||||||
deadband: 0,
|
deadband: 0,
|
||||||
yaw_deadband: 0,
|
yaw_deadband: 0,
|
||||||
alt_hold_deadband: 0
|
alt_hold_deadband: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
SENSOR_ALIGNMENT = {
|
SENSOR_ALIGNMENT = {
|
||||||
align_gyro: 0,
|
align_gyro: 0,
|
||||||
align_acc: 0,
|
align_acc: 0,
|
||||||
align_mag: 0
|
align_mag: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
PID_ADVANCED_CONFIG = {
|
PID_ADVANCED_CONFIG = {
|
||||||
gyro_sync_denom: 0,
|
gyro_sync_denom: 0,
|
||||||
pid_process_denom: 0,
|
pid_process_denom: 0,
|
||||||
|
@ -256,7 +259,7 @@ var FC = {
|
||||||
fast_pwm_protocol: 0,
|
fast_pwm_protocol: 0,
|
||||||
motor_pwm_rate: 0
|
motor_pwm_rate: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
FILTER_CONFIG = {
|
FILTER_CONFIG = {
|
||||||
gyro_soft_lpf_hz: 0,
|
gyro_soft_lpf_hz: 0,
|
||||||
dterm_lpf_hz: 0,
|
dterm_lpf_hz: 0,
|
||||||
|
@ -268,7 +271,7 @@ var FC = {
|
||||||
gyro_soft_notch_hz_2: 0,
|
gyro_soft_notch_hz_2: 0,
|
||||||
gyro_soft_notch_cutoff_2: 0
|
gyro_soft_notch_cutoff_2: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
ADVANCED_TUNING = {
|
ADVANCED_TUNING = {
|
||||||
rollPitchItermIgnoreRate: 0,
|
rollPitchItermIgnoreRate: 0,
|
||||||
yawItermIgnoreRate: 0,
|
yawItermIgnoreRate: 0,
|
||||||
|
@ -306,7 +309,7 @@ var FC = {
|
||||||
rcInterpolationInterval:0,
|
rcInterpolationInterval:0,
|
||||||
airModeActivateThreshold: 0
|
airModeActivateThreshold: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
FAILSAFE_CONFIG = {
|
FAILSAFE_CONFIG = {
|
||||||
failsafe_delay: 0,
|
failsafe_delay: 0,
|
||||||
failsafe_off_delay: 0,
|
failsafe_off_delay: 0,
|
||||||
|
@ -315,7 +318,7 @@ var FC = {
|
||||||
failsafe_throttle_low_delay: 0,
|
failsafe_throttle_low_delay: 0,
|
||||||
failsafe_procedure: 0
|
failsafe_procedure: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
RXFAIL_CONFIG = [];
|
RXFAIL_CONFIG = [];
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
|
@ -2,129 +2,134 @@
|
||||||
|
|
||||||
//MSPCodes needs to be re-integrated inside MSP object
|
//MSPCodes needs to be re-integrated inside MSP object
|
||||||
var MSPCodes = {
|
var MSPCodes = {
|
||||||
MSP_API_VERSION: 1,
|
MSP_API_VERSION: 1,
|
||||||
MSP_FC_VARIANT: 2,
|
MSP_FC_VARIANT: 2,
|
||||||
MSP_FC_VERSION: 3,
|
MSP_FC_VERSION: 3,
|
||||||
MSP_BOARD_INFO: 4,
|
MSP_BOARD_INFO: 4,
|
||||||
MSP_BUILD_INFO: 5,
|
MSP_BUILD_INFO: 5,
|
||||||
|
|
||||||
MSP_NAME: 10,
|
MSP_NAME: 10,
|
||||||
MSP_SET_NAME: 11,
|
MSP_SET_NAME: 11,
|
||||||
|
|
||||||
MSP_CHANNEL_FORWARDING: 32,
|
MSP_CHANNEL_FORWARDING: 32,
|
||||||
MSP_SET_CHANNEL_FORWARDING: 33,
|
MSP_SET_CHANNEL_FORWARDING: 33,
|
||||||
MSP_MODE_RANGES: 34,
|
MSP_MODE_RANGES: 34,
|
||||||
MSP_SET_MODE_RANGE: 35,
|
MSP_SET_MODE_RANGE: 35,
|
||||||
|
|
||||||
MSP_RX_CONFIG: 44,
|
MSP_CURRENT_METER_CONFIG: 40,
|
||||||
MSP_SET_RX_CONFIG: 45,
|
MSP_SET_CURRENT_METER_CONFIG: 41,
|
||||||
MSP_LED_COLORS: 46,
|
|
||||||
MSP_SET_LED_COLORS: 47,
|
|
||||||
MSP_LED_STRIP_CONFIG: 48,
|
|
||||||
MSP_SET_LED_STRIP_CONFIG: 49,
|
|
||||||
|
|
||||||
MSP_ADJUSTMENT_RANGES: 52,
|
MSP_RX_CONFIG: 44,
|
||||||
MSP_SET_ADJUSTMENT_RANGE: 53,
|
MSP_SET_RX_CONFIG: 45,
|
||||||
MSP_CF_SERIAL_CONFIG: 54,
|
MSP_LED_COLORS: 46,
|
||||||
MSP_SET_CF_SERIAL_CONFIG: 55,
|
MSP_SET_LED_COLORS: 47,
|
||||||
MSP_SONAR: 58,
|
MSP_LED_STRIP_CONFIG: 48,
|
||||||
MSP_PID_CONTROLLER: 59,
|
MSP_SET_LED_STRIP_CONFIG: 49,
|
||||||
MSP_SET_PID_CONTROLLER: 60,
|
|
||||||
MSP_ARMING_CONFIG: 61,
|
|
||||||
MSP_SET_ARMING_CONFIG: 62,
|
|
||||||
MSP_RX_MAP: 64,
|
|
||||||
MSP_SET_RX_MAP: 65,
|
|
||||||
MSP_BF_CONFIG: 66,
|
|
||||||
MSP_SET_BF_CONFIG: 67,
|
|
||||||
MSP_SET_REBOOT: 68,
|
|
||||||
MSP_BF_BUILD_INFO: 69, // Not used
|
|
||||||
MSP_DATAFLASH_SUMMARY: 70,
|
|
||||||
MSP_DATAFLASH_READ: 71,
|
|
||||||
MSP_DATAFLASH_ERASE: 72,
|
|
||||||
MSP_LOOP_TIME: 73,
|
|
||||||
MSP_SET_LOOP_TIME: 74,
|
|
||||||
MSP_FAILSAFE_CONFIG: 75,
|
|
||||||
MSP_SET_FAILSAFE_CONFIG: 76,
|
|
||||||
MSP_RXFAIL_CONFIG: 77,
|
|
||||||
MSP_SET_RXFAIL_CONFIG: 78,
|
|
||||||
MSP_SDCARD_SUMMARY: 79,
|
|
||||||
MSP_BLACKBOX_CONFIG: 80,
|
|
||||||
MSP_SET_BLACKBOX_CONFIG: 81,
|
|
||||||
MSP_TRANSPONDER_CONFIG: 82,
|
|
||||||
MSP_SET_TRANSPONDER_CONFIG: 83,
|
|
||||||
MSP_OSD_CONFIG: 84,
|
|
||||||
MSP_SET_OSD_CONFIG: 85,
|
|
||||||
MSP_OSD_CHAR_READ: 86,
|
|
||||||
MSP_OSD_CHAR_WRITE: 87,
|
|
||||||
MSP_VTX_CONFIG: 88,
|
|
||||||
MSP_SET_VTX_CONFIG: 89,
|
|
||||||
MSP_ADVANCED_CONFIG: 90,
|
|
||||||
MSP_SET_ADVANCED_CONFIG: 91,
|
|
||||||
MSP_FILTER_CONFIG: 92,
|
|
||||||
MSP_SET_FILTER_CONFIG: 93,
|
|
||||||
MSP_PID_ADVANCED: 94,
|
|
||||||
MSP_SET_PID_ADVANCED: 95,
|
|
||||||
MSP_SENSOR_CONFIG: 96,
|
|
||||||
MSP_SET_SENSOR_CONFIG: 97,
|
|
||||||
MSP_SPECIAL_PARAMETERS: 98,
|
|
||||||
MSP_SET_SPECIAL_PARAMETERS: 99,
|
|
||||||
MSP_IDENT: 100, // Not used
|
|
||||||
MSP_STATUS: 101,
|
|
||||||
MSP_RAW_IMU: 102,
|
|
||||||
MSP_SERVO: 103,
|
|
||||||
MSP_MOTOR: 104,
|
|
||||||
MSP_RC: 105,
|
|
||||||
MSP_RAW_GPS: 106,
|
|
||||||
MSP_COMP_GPS: 107,
|
|
||||||
MSP_ATTITUDE: 108,
|
|
||||||
MSP_ALTITUDE: 109,
|
|
||||||
MSP_ANALOG: 110,
|
|
||||||
MSP_RC_TUNING: 111,
|
|
||||||
MSP_PID: 112,
|
|
||||||
MSP_BOX: 113, // Not used
|
|
||||||
MSP_MISC: 114,
|
|
||||||
MSP_MOTOR_PINS: 115, // Not used
|
|
||||||
MSP_BOXNAMES: 116,
|
|
||||||
MSP_PIDNAMES: 117,
|
|
||||||
MSP_WP: 118, // Not used
|
|
||||||
MSP_BOXIDS: 119,
|
|
||||||
MSP_SERVO_CONFIGURATIONS: 120,
|
|
||||||
MSP_3D: 124,
|
|
||||||
MSP_RC_DEADBAND: 125,
|
|
||||||
MSP_SENSOR_ALIGNMENT: 126,
|
|
||||||
MSP_LED_STRIP_MODECOLOR: 127,
|
|
||||||
|
|
||||||
MSP_STATUS_EX: 150,
|
MSP_ADJUSTMENT_RANGES: 52,
|
||||||
|
MSP_SET_ADJUSTMENT_RANGE: 53,
|
||||||
|
MSP_CF_SERIAL_CONFIG: 54,
|
||||||
|
MSP_SET_CF_SERIAL_CONFIG: 55,
|
||||||
|
MSP_VOLTAGE_METER_CONFIG: 56,
|
||||||
|
MSP_SET_VOLTAGE_METER_CONFIG: 57,
|
||||||
|
MSP_SONAR: 58,
|
||||||
|
MSP_PID_CONTROLLER: 59,
|
||||||
|
MSP_SET_PID_CONTROLLER: 60,
|
||||||
|
MSP_ARMING_CONFIG: 61,
|
||||||
|
MSP_SET_ARMING_CONFIG: 62,
|
||||||
|
MSP_RX_MAP: 64,
|
||||||
|
MSP_SET_RX_MAP: 65,
|
||||||
|
MSP_BF_CONFIG: 66,
|
||||||
|
MSP_SET_BF_CONFIG: 67,
|
||||||
|
MSP_SET_REBOOT: 68,
|
||||||
|
MSP_BF_BUILD_INFO: 69, // Not used
|
||||||
|
MSP_DATAFLASH_SUMMARY: 70,
|
||||||
|
MSP_DATAFLASH_READ: 71,
|
||||||
|
MSP_DATAFLASH_ERASE: 72,
|
||||||
|
MSP_LOOP_TIME: 73,
|
||||||
|
MSP_SET_LOOP_TIME: 74,
|
||||||
|
MSP_FAILSAFE_CONFIG: 75,
|
||||||
|
MSP_SET_FAILSAFE_CONFIG: 76,
|
||||||
|
MSP_RXFAIL_CONFIG: 77,
|
||||||
|
MSP_SET_RXFAIL_CONFIG: 78,
|
||||||
|
MSP_SDCARD_SUMMARY: 79,
|
||||||
|
MSP_BLACKBOX_CONFIG: 80,
|
||||||
|
MSP_SET_BLACKBOX_CONFIG: 81,
|
||||||
|
MSP_TRANSPONDER_CONFIG: 82,
|
||||||
|
MSP_SET_TRANSPONDER_CONFIG: 83,
|
||||||
|
MSP_OSD_CONFIG: 84,
|
||||||
|
MSP_SET_OSD_CONFIG: 85,
|
||||||
|
MSP_OSD_CHAR_READ: 86,
|
||||||
|
MSP_OSD_CHAR_WRITE: 87,
|
||||||
|
MSP_VTX_CONFIG: 88,
|
||||||
|
MSP_SET_VTX_CONFIG: 89,
|
||||||
|
MSP_ADVANCED_CONFIG: 90,
|
||||||
|
MSP_SET_ADVANCED_CONFIG: 91,
|
||||||
|
MSP_FILTER_CONFIG: 92,
|
||||||
|
MSP_SET_FILTER_CONFIG: 93,
|
||||||
|
MSP_PID_ADVANCED: 94,
|
||||||
|
MSP_SET_PID_ADVANCED: 95,
|
||||||
|
MSP_SENSOR_CONFIG: 96,
|
||||||
|
MSP_SET_SENSOR_CONFIG: 97,
|
||||||
|
MSP_SPECIAL_PARAMETERS: 98,
|
||||||
|
MSP_SET_SPECIAL_PARAMETERS: 99,
|
||||||
|
MSP_IDENT: 100, // Not used
|
||||||
|
MSP_STATUS: 101,
|
||||||
|
MSP_RAW_IMU: 102,
|
||||||
|
MSP_SERVO: 103,
|
||||||
|
MSP_MOTOR: 104,
|
||||||
|
MSP_RC: 105,
|
||||||
|
MSP_RAW_GPS: 106,
|
||||||
|
MSP_COMP_GPS: 107,
|
||||||
|
MSP_ATTITUDE: 108,
|
||||||
|
MSP_ALTITUDE: 109,
|
||||||
|
MSP_ANALOG: 110,
|
||||||
|
MSP_RC_TUNING: 111,
|
||||||
|
MSP_PID: 112,
|
||||||
|
MSP_BOX: 113, // Not used
|
||||||
|
MSP_MISC: 114,
|
||||||
|
MSP_MOTOR_PINS: 115, // Not used
|
||||||
|
MSP_BOXNAMES: 116,
|
||||||
|
MSP_PIDNAMES: 117,
|
||||||
|
MSP_WP: 118, // Not used
|
||||||
|
MSP_BOXIDS: 119,
|
||||||
|
MSP_SERVO_CONFIGURATIONS: 120,
|
||||||
|
MSP_3D: 124,
|
||||||
|
MSP_RC_DEADBAND: 125,
|
||||||
|
MSP_SENSOR_ALIGNMENT: 126,
|
||||||
|
MSP_LED_STRIP_MODECOLOR: 127,
|
||||||
|
|
||||||
MSP_UID: 160,
|
MSP_STATUS_EX: 150,
|
||||||
MSP_GPS_SV_INFO: 164,
|
|
||||||
|
|
||||||
MSP_SET_RAW_RC: 200,
|
MSP_UID: 160,
|
||||||
MSP_SET_RAW_GPS: 201, // Not used
|
MSP_GPS_SV_INFO: 164,
|
||||||
MSP_SET_PID: 202,
|
|
||||||
MSP_SET_BOX: 203,
|
|
||||||
MSP_SET_RC_TUNING: 204,
|
|
||||||
MSP_ACC_CALIBRATION: 205,
|
|
||||||
MSP_MAG_CALIBRATION: 206,
|
|
||||||
MSP_SET_MISC: 207,
|
|
||||||
MSP_RESET_CONF: 208,
|
|
||||||
MSP_SET_WP: 209, // Not used
|
|
||||||
MSP_SELECT_SETTING: 210,
|
|
||||||
MSP_SET_HEAD: 211, // Not used
|
|
||||||
MSP_SET_SERVO_CONFIGURATION:212,
|
|
||||||
MSP_SET_MOTOR: 214,
|
|
||||||
MSP_SET_3D: 217,
|
|
||||||
MSP_SET_RC_DEADBAND: 218,
|
|
||||||
MSP_SET_RESET_CURR_PID: 219,
|
|
||||||
MSP_SET_SENSOR_ALIGNMENT: 220,
|
|
||||||
MSP_SET_LED_STRIP_MODECOLOR:221,
|
|
||||||
|
|
||||||
MSP_SET_ACC_TRIM: 239,
|
MSP_SET_RAW_RC: 200,
|
||||||
MSP_ACC_TRIM: 240,
|
MSP_SET_RAW_GPS: 201, // Not used
|
||||||
MSP_SERVO_MIX_RULES: 241,
|
MSP_SET_PID: 202,
|
||||||
MSP_SET_SERVO_MIX_RULE: 242, // Not used
|
MSP_SET_BOX: 203,
|
||||||
|
MSP_SET_RC_TUNING: 204,
|
||||||
|
MSP_ACC_CALIBRATION: 205,
|
||||||
|
MSP_MAG_CALIBRATION: 206,
|
||||||
|
MSP_SET_MISC: 207,
|
||||||
|
MSP_RESET_CONF: 208,
|
||||||
|
MSP_SET_WP: 209, // Not used
|
||||||
|
MSP_SELECT_SETTING: 210,
|
||||||
|
MSP_SET_HEAD: 211, // Not used
|
||||||
|
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||||
|
MSP_SET_MOTOR: 214,
|
||||||
|
MSP_SET_3D: 217,
|
||||||
|
MSP_SET_RC_DEADBAND: 218,
|
||||||
|
MSP_SET_RESET_CURR_PID: 219,
|
||||||
|
MSP_SET_SENSOR_ALIGNMENT: 220,
|
||||||
|
MSP_SET_LED_STRIP_MODECOLOR: 221,
|
||||||
|
|
||||||
MSP_EEPROM_WRITE: 250,
|
MSP_SET_ACC_TRIM: 239,
|
||||||
MSP_DEBUGMSG: 253, // Not used
|
MSP_ACC_TRIM: 240,
|
||||||
MSP_DEBUG: 254
|
MSP_SERVO_MIX_RULES: 241,
|
||||||
};
|
MSP_SET_SERVO_MIX_RULE: 242, // Not used
|
||||||
|
|
||||||
|
MSP_EEPROM_WRITE: 250,
|
||||||
|
MSP_DEBUGMSG: 253, // Not used
|
||||||
|
MSP_DEBUG: 254
|
||||||
|
};
|
||||||
|
|
|
@ -203,6 +203,21 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
||||||
MISC.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
MISC.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
||||||
break;
|
break;
|
||||||
|
case MSPCodes.MSP_VOLTAGE_METER_CONFIG:
|
||||||
|
MISC.vbatscale = data.readU8(); // 10-200
|
||||||
|
MISC.vbatmincellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
MISC.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.23.0")) {
|
||||||
|
MISC.batterymetertype = data.readU8();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_CURRENT_METER_CONFIG:
|
||||||
|
BF_CONFIG.currentscale = data.readU16();
|
||||||
|
BF_CONFIG.currentoffset = data.readU16();
|
||||||
|
BF_CONFIG.currentmetertype = data.readU8();
|
||||||
|
BF_CONFIG.batterycapacity = data.readU16();
|
||||||
|
break;
|
||||||
case MSPCodes.MSP_3D:
|
case MSPCodes.MSP_3D:
|
||||||
_3D.deadband3d_low = data.readU16();
|
_3D.deadband3d_low = data.readU16();
|
||||||
_3D.deadband3d_high = data.readU16();
|
_3D.deadband3d_high = data.readU16();
|
||||||
|
@ -342,6 +357,11 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
case MSPCodes.MSP_EEPROM_WRITE:
|
case MSPCodes.MSP_EEPROM_WRITE:
|
||||||
console.log('Settings Saved in EEPROM');
|
console.log('Settings Saved in EEPROM');
|
||||||
break;
|
break;
|
||||||
|
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
console.log('Current Settings saved');
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
||||||
|
console.log('Voltage config saved');
|
||||||
case MSPCodes.MSP_DEBUG:
|
case MSPCodes.MSP_DEBUG:
|
||||||
for (var i = 0; i < 4; i++)
|
for (var i = 0; i < 4; i++)
|
||||||
SENSOR_DATA.debug[i] = data.read16();
|
SENSOR_DATA.debug[i] = data.read16();
|
||||||
|
@ -1009,7 +1029,21 @@ MspHelper.prototype.crunch = function(code) {
|
||||||
.push8(Math.round(MISC.vbatmaxcellvoltage * 10))
|
.push8(Math.round(MISC.vbatmaxcellvoltage * 10))
|
||||||
.push8(Math.round(MISC.vbatwarningcellvoltage * 10));
|
.push8(Math.round(MISC.vbatwarningcellvoltage * 10));
|
||||||
break;
|
break;
|
||||||
|
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
||||||
|
buffer.push8(MISC.vbatscale)
|
||||||
|
.push8(Math.round(MISC.vbatmincellvoltage * 10))
|
||||||
|
.push8(Math.round(MISC.vbatmaxcellvoltage * 10))
|
||||||
|
.push8(Math.round(MISC.vbatwarningcellvoltage * 10));
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.23.0")) {
|
||||||
|
buffer.push8(MISC.batterymetertype);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
buffer.push16(BF_CONFIG.currentscale)
|
||||||
|
.push16(BF_CONFIG.currentoffset)
|
||||||
|
.push8(BF_CONFIG.currentmetertype)
|
||||||
|
.push16(BF_CONFIG.batterycapacity)
|
||||||
|
break;
|
||||||
case MSPCodes.MSP_SET_RX_CONFIG:
|
case MSPCodes.MSP_SET_RX_CONFIG:
|
||||||
buffer.push8(RX_CONFIG.serialrx_provider)
|
buffer.push8(RX_CONFIG.serialrx_provider)
|
||||||
.push16(RX_CONFIG.maxcheck)
|
.push16(RX_CONFIG.maxcheck)
|
||||||
|
|
|
@ -295,6 +295,20 @@
|
||||||
width: 30px;
|
width: 30px;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.tab-configuration .batterymetertype {
|
||||||
|
border: 1px solid silver;
|
||||||
|
margin-right: 5px;
|
||||||
|
float: left;
|
||||||
|
width: 150px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-configuration .currentmetertype {
|
||||||
|
border: 1px solid silver;
|
||||||
|
margin-right: 5px;
|
||||||
|
float: left;
|
||||||
|
width: 150px;
|
||||||
|
}
|
||||||
|
|
||||||
.tab-configuration .rssi td:nth-child(2) {
|
.tab-configuration .rssi td:nth-child(2) {
|
||||||
width: 30px;
|
width: 30px;
|
||||||
}
|
}
|
||||||
|
@ -463,7 +477,7 @@
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-configuration .sensoralignment {
|
.tab-configuration .sensoralignment {
|
||||||
width: 50%;
|
width: 50%;
|
||||||
float: left;
|
float: left;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -339,6 +339,12 @@
|
||||||
<!-- table generated here -->
|
<!-- table generated here -->
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
|
<div class="select">
|
||||||
|
<label>
|
||||||
|
<select class="batterymetertype"><!-- list generated here --></select>
|
||||||
|
<span i18n="configurationBatteryMeterType"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<label> <input type="number" name="mincellvoltage" step="0.1" min="1" max="5" /> <span
|
<label> <input type="number" name="mincellvoltage" step="0.1" min="1" max="5" /> <span
|
||||||
i18n="configurationBatteryMinimum"></span>
|
i18n="configurationBatteryMinimum"></span>
|
||||||
|
@ -383,6 +389,12 @@
|
||||||
<!-- table generated here -->
|
<!-- table generated here -->
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
|
<div class="select">
|
||||||
|
<label>
|
||||||
|
<select class="currentmetertype"><!-- list generated here --></select>
|
||||||
|
<span i18n="configurationCurrentMeterType"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<label> <input type="number" name="currentscale" step="1" min="-16000" max="16000" /> <span
|
<label> <input type="number" name="currentscale" step="1" min="-16000" max="16000" /> <span
|
||||||
i18n="configurationCurrentScale"></span>
|
i18n="configurationCurrentScale"></span>
|
||||||
|
|
|
@ -29,7 +29,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
function load_misc() {
|
function load_misc() {
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_acc_trim);
|
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_acc_trim);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_acc_trim() {
|
function load_acc_trim() {
|
||||||
MSP.send_message(MSPCodes.MSP_ACC_TRIM, false, false, load_arming_config);
|
MSP.send_message(MSPCodes.MSP_ACC_TRIM, false, false, load_arming_config);
|
||||||
}
|
}
|
||||||
|
@ -42,7 +42,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_loop_time() {
|
function load_loop_time() {
|
||||||
var next_callback = load_3d;
|
var next_callback = load_3d;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
|
@ -72,22 +72,22 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
function esc_protocol() {
|
function esc_protocol() {
|
||||||
var next_callback = sensor_config;
|
var next_callback = sensor_config;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function sensor_config() {
|
function sensor_config() {
|
||||||
var next_callback = load_sensor_alignment;
|
var next_callback = load_sensor_alignment;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
MSP.send_message(MSPCodes.MSP_SENSOR_CONFIG, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SENSOR_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_sensor_alignment() {
|
function load_sensor_alignment() {
|
||||||
var next_callback = load_name;
|
var next_callback = load_name;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
|
@ -96,17 +96,35 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_name() {
|
function load_name() {
|
||||||
var next_callback = load_html;
|
var next_callback = load_battery;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function load_battery() {
|
||||||
|
var next_callback = load_current;
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_VOLTAGE_METER_CONFIG, false, false, next_callback);
|
||||||
|
} else {
|
||||||
|
next_callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_current() {
|
||||||
|
var next_callback = load_html;
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, next_callback);
|
||||||
|
} else {
|
||||||
|
next_callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
//Update Analog/Battery Data
|
//Update Analog/Battery Data
|
||||||
function load_analog() {
|
function load_analog() {
|
||||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
||||||
|
@ -120,7 +138,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
load_config();
|
load_config();
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
var mixer_list_e = $('select.mixerList');
|
var mixer_list_e = $('select.mixerList');
|
||||||
for (var i = 0; i < mixerList.length; i++) {
|
for (var i = 0; i < mixerList.length; i++) {
|
||||||
|
@ -142,7 +160,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
var features_e = $('.tab-configuration .features');
|
var features_e = $('.tab-configuration .features');
|
||||||
|
|
||||||
BF_CONFIG.features.generateElements(features_e);
|
BF_CONFIG.features.generateElements(features_e);
|
||||||
|
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
|
@ -156,13 +174,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
'CW 180° flip',
|
'CW 180° flip',
|
||||||
'CW 270° flip'
|
'CW 270° flip'
|
||||||
];
|
];
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
var orientation_gyro_e = $('select.gyroalign');
|
var orientation_gyro_e = $('select.gyroalign');
|
||||||
var orientation_acc_e = $('select.accalign');
|
var orientation_acc_e = $('select.accalign');
|
||||||
var orientation_mag_e = $('select.magalign');
|
var orientation_mag_e = $('select.magalign');
|
||||||
|
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||||
$('.tab-configuration .sensoralignment').hide();
|
$('.tab-configuration .sensoralignment').hide();
|
||||||
|
@ -176,16 +194,16 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
|
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
|
||||||
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
||||||
}
|
}
|
||||||
|
|
||||||
// ESC protocols
|
// ESC protocols
|
||||||
|
|
||||||
var escprotocols = [
|
var escprotocols = [
|
||||||
'PWM',
|
'PWM',
|
||||||
'ONESHOT125',
|
'ONESHOT125',
|
||||||
'ONESHOT42',
|
'ONESHOT42',
|
||||||
'MULTISHOT'
|
'MULTISHOT'
|
||||||
];
|
];
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||||
escprotocols.push('BRUSHED');
|
escprotocols.push('BRUSHED');
|
||||||
}
|
}
|
||||||
|
@ -202,8 +220,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
esc_protocol_e.append('<option value="' + (i+1) + '">'+ escprotocols[i] + '</option>');
|
esc_protocol_e.append('<option value="' + (i+1) + '">'+ escprotocols[i] + '</option>');
|
||||||
}
|
}
|
||||||
esc_protocol_e.val(PID_ADVANCED_CONFIG.fast_pwm_protocol+1);
|
esc_protocol_e.val(PID_ADVANCED_CONFIG.fast_pwm_protocol+1);
|
||||||
|
|
||||||
|
|
||||||
$('input[id="unsyncedPWMSwitch"]').prop('checked', PID_ADVANCED_CONFIG.use_unsyncedPwm !== 0);
|
$('input[id="unsyncedPWMSwitch"]').prop('checked', PID_ADVANCED_CONFIG.use_unsyncedPwm !== 0);
|
||||||
$('input[name="unsyncedpwmfreq"]').val(PID_ADVANCED_CONFIG.motor_pwm_rate);
|
$('input[name="unsyncedpwmfreq"]').val(PID_ADVANCED_CONFIG.motor_pwm_rate);
|
||||||
if (PID_ADVANCED_CONFIG.use_unsyncedPwm) {
|
if (PID_ADVANCED_CONFIG.use_unsyncedPwm) {
|
||||||
|
@ -212,26 +230,26 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
else {
|
else {
|
||||||
$('div.unsyncedpwmfreq').hide();
|
$('div.unsyncedpwmfreq').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Gyro and PID update
|
// Gyro and PID update
|
||||||
var gyroFreq = [
|
var gyroFreq = [
|
||||||
"8KHz",
|
"8KHz",
|
||||||
"4KHz",
|
"4KHz",
|
||||||
"2.67KHz",
|
"2.67KHz",
|
||||||
"2KHz",
|
"2KHz",
|
||||||
"1.6KHz",
|
"1.6KHz",
|
||||||
"1.33KHz",
|
"1.33KHz",
|
||||||
"1.14KHz",
|
"1.14KHz",
|
||||||
"1KHz"
|
"1KHz"
|
||||||
];
|
];
|
||||||
|
|
||||||
var gyro_select_e = $('select.gyroSyncDenom');
|
var gyro_select_e = $('select.gyroSyncDenom');
|
||||||
|
|
||||||
for (var i = 0; i < gyroFreq.length; i++) {
|
for (var i = 0; i < gyroFreq.length; i++) {
|
||||||
gyro_select_e.append('<option value="'+(i+1)+'">'+gyroFreq[i]+'</option>');
|
gyro_select_e.append('<option value="'+(i+1)+'">'+gyroFreq[i]+'</option>');
|
||||||
}
|
}
|
||||||
gyro_select_e.val(PID_ADVANCED_CONFIG.gyro_sync_denom);
|
gyro_select_e.val(PID_ADVANCED_CONFIG.gyro_sync_denom);
|
||||||
|
|
||||||
var gyroDenom = PID_ADVANCED_CONFIG.gyro_sync_denom;
|
var gyroDenom = PID_ADVANCED_CONFIG.gyro_sync_denom;
|
||||||
var pidFreq = [
|
var pidFreq = [
|
||||||
8 / (gyroDenom * 1),
|
8 / (gyroDenom * 1),
|
||||||
|
@ -243,7 +261,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
8 / (gyroDenom * 7),
|
8 / (gyroDenom * 7),
|
||||||
8 / (gyroDenom * 8)
|
8 / (gyroDenom * 8)
|
||||||
];
|
];
|
||||||
|
|
||||||
var pid_select_e = $('select.pidProcessDenom');
|
var pid_select_e = $('select.pidProcessDenom');
|
||||||
for (var i = 0; i < pidFreq.length; i++) {
|
for (var i = 0; i < pidFreq.length; i++) {
|
||||||
var pidF = (1000 * pidFreq[i] / 10); // Could be done better
|
var pidF = (1000 * pidFreq[i] / 10); // Could be done better
|
||||||
|
@ -251,7 +269,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
pid_select_e.append('<option value="'+(i+1)+'">'+(pidF / 100).toString()+'KHz</option>');
|
pid_select_e.append('<option value="'+(i+1)+'">'+(pidF / 100).toString()+'KHz</option>');
|
||||||
}
|
}
|
||||||
pid_select_e.val(PID_ADVANCED_CONFIG.pid_process_denom);
|
pid_select_e.val(PID_ADVANCED_CONFIG.pid_process_denom);
|
||||||
|
|
||||||
$('select.gyroSyncDenom').change(function() {
|
$('select.gyroSyncDenom').change(function() {
|
||||||
var gyroDenom = $('select.gyroSyncDenom').val();
|
var gyroDenom = $('select.gyroSyncDenom').val();
|
||||||
var newPidFreq = [
|
var newPidFreq = [
|
||||||
|
@ -268,7 +286,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
var pidF = (1000 * newPidFreq[i] / 10); // Could be done better
|
var pidF = (1000 * newPidFreq[i] / 10); // Could be done better
|
||||||
pidF = pidF.toFixed(0);
|
pidF = pidF.toFixed(0);
|
||||||
$('select.pidProcessDenom option[value="'+(i+1)+'"]').text((pidF / 100).toString()+'KHz');}
|
$('select.pidProcessDenom option[value="'+(i+1)+'"]').text((pidF / 100).toString()+'KHz');}
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
$('input[id="accHardwareSwitch"]').prop('checked', SENSOR_CONFIG.acc_hardware !== 1);
|
$('input[id="accHardwareSwitch"]').prop('checked', SENSOR_CONFIG.acc_hardware !== 1);
|
||||||
|
@ -277,22 +295,22 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
|
|
||||||
// Only show these sections for supported FW
|
// Only show these sections for supported FW
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
$('.selectProtocol').hide();
|
$('.selectProtocol').hide();
|
||||||
$('.checkboxPwm').hide();
|
$('.checkboxPwm').hide();
|
||||||
$('.selectPidProcessDenom').hide();
|
$('.selectPidProcessDenom').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.lt(CONFIG.flightControllerVersion, "2.8.2")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
$('.hardwareSelection').hide();
|
$('.hardwareSelection').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
$('input[name="vesselName"]').val(CONFIG.name);
|
$('input[name="vesselName"]').val(CONFIG.name);
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier != "BTFL" || semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||||
$('.miscSettings').hide();
|
$('.miscSettings').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// generate GPS
|
// generate GPS
|
||||||
|
@ -328,13 +346,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
|
|
||||||
gps_protocol_e.val(MISC.gps_type);
|
gps_protocol_e.val(MISC.gps_type);
|
||||||
|
|
||||||
|
|
||||||
var gps_baudrate_e = $('select.gps_baudrate');
|
var gps_baudrate_e = $('select.gps_baudrate');
|
||||||
for (var i = 0; i < gpsBaudRates.length; i++) {
|
for (var i = 0; i < gpsBaudRates.length; i++) {
|
||||||
gps_baudrate_e.append('<option value="' + gpsBaudRates[i] + '">' + gpsBaudRates[i] + '</option>');
|
gps_baudrate_e.append('<option value="' + gpsBaudRates[i] + '">' + gpsBaudRates[i] + '</option>');
|
||||||
}
|
}
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||||
gps_baudrate_e.change(function () {
|
gps_baudrate_e.change(function () {
|
||||||
SERIAL_CONFIG.gpsBaudRate = parseInt($(this).val());
|
SERIAL_CONFIG.gpsBaudRate = parseInt($(this).val());
|
||||||
|
@ -344,8 +362,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
gps_baudrate_e.prop("disabled", true);
|
gps_baudrate_e.prop("disabled", true);
|
||||||
gps_baudrate_e.parent().hide();
|
gps_baudrate_e.parent().hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
var gps_ubx_sbas_e = $('select.gps_ubx_sbas');
|
var gps_ubx_sbas_e = $('select.gps_ubx_sbas');
|
||||||
for (var i = 0; i < gpsSbas.length; i++) {
|
for (var i = 0; i < gpsSbas.length; i++) {
|
||||||
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
|
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
|
||||||
|
@ -410,28 +428,62 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
// fill magnetometer
|
// fill magnetometer
|
||||||
$('input[name="mag_declination"]').val(MISC.mag_declination.toFixed(2));
|
$('input[name="mag_declination"]').val(MISC.mag_declination.toFixed(2));
|
||||||
|
|
||||||
//fill motor disarm params and FC loop time
|
//fill motor disarm params and FC loop time
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
|
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
|
||||||
$('input[id="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch !== 0);
|
$('input[id="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch !== 0);
|
||||||
$('div.disarm').show();
|
$('div.disarm').show();
|
||||||
|
|
||||||
$('div.cycles').show();
|
$('div.cycles').show();
|
||||||
}
|
}
|
||||||
|
|
||||||
// fill throttle
|
// fill throttle
|
||||||
$('input[name="midrc"]').val(MISC.midrc);
|
$('input[name="midrc"]').val(MISC.midrc);
|
||||||
$('input[name="minthrottle"]').val(MISC.minthrottle);
|
$('input[name="minthrottle"]').val(MISC.minthrottle);
|
||||||
$('input[name="maxthrottle"]').val(MISC.maxthrottle);
|
$('input[name="maxthrottle"]').val(MISC.maxthrottle);
|
||||||
$('input[name="mincommand"]').val(MISC.mincommand);
|
$('input[name="mincommand"]').val(MISC.mincommand);
|
||||||
|
|
||||||
// fill battery
|
// fill battery
|
||||||
|
var batteryMeterTypes = [
|
||||||
|
'Onboard ADC',
|
||||||
|
'ESC Sensor',
|
||||||
|
];
|
||||||
|
|
||||||
|
var batteryMeterType_e = $('select.batterymetertype');
|
||||||
|
for (i = 0; i < batteryMeterTypes.length; i++) {
|
||||||
|
batteryMeterType_e.append('<option value="' + i + '">' + batteryMeterTypes[i] + '</option>');
|
||||||
|
}
|
||||||
|
|
||||||
|
batteryMeterType_e.change(function () {
|
||||||
|
MISC.batterymetertype = parseInt($(this).val());
|
||||||
|
checkDisableVbatControls();
|
||||||
|
});
|
||||||
|
batteryMeterType_e.val(MISC.batterymetertype).change();
|
||||||
|
|
||||||
$('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage);
|
$('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage);
|
||||||
$('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage);
|
$('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage);
|
||||||
$('input[name="warningcellvoltage"]').val(MISC.vbatwarningcellvoltage);
|
$('input[name="warningcellvoltage"]').val(MISC.vbatwarningcellvoltage);
|
||||||
$('input[name="voltagescale"]').val(MISC.vbatscale);
|
$('input[name="voltagescale"]').val(MISC.vbatscale);
|
||||||
|
|
||||||
// fill current
|
// fill current
|
||||||
|
var currentMeterTypes = [
|
||||||
|
'None',
|
||||||
|
'Onboard ADC',
|
||||||
|
'Virtual',
|
||||||
|
'ESC Sensor',
|
||||||
|
];
|
||||||
|
|
||||||
|
var currentMeterType_e = $('select.currentmetertype');
|
||||||
|
for (i = 0; i < currentMeterTypes.length; i++) {
|
||||||
|
currentMeterType_e.append('<option value="' + i + '">' + currentMeterTypes[i] + '</option>');
|
||||||
|
}
|
||||||
|
|
||||||
|
currentMeterType_e.change(function () {
|
||||||
|
BF_CONFIG.currentmetertype = parseInt($(this).val());
|
||||||
|
checkDisableCurrentControls();
|
||||||
|
});
|
||||||
|
currentMeterType_e.val(BF_CONFIG.currentmetertype).change();
|
||||||
|
|
||||||
$('input[name="currentscale"]').val(BF_CONFIG.currentscale);
|
$('input[name="currentscale"]').val(BF_CONFIG.currentscale);
|
||||||
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
||||||
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput !== 0);
|
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput !== 0);
|
||||||
|
@ -475,6 +527,49 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function checkDisableVbatControls() {
|
||||||
|
if (BF_CONFIG.features.isEnabled('VBAT')) {
|
||||||
|
$('select.batterymetertype').prop('disabled', false);
|
||||||
|
if (MISC.batterymetertype == 1) {
|
||||||
|
$('input[name="mincellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="maxcellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="warningcellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="voltagescale"]').prop('disabled', true);
|
||||||
|
} else {
|
||||||
|
$('input[name="mincellvoltage"]').prop('disabled', false);
|
||||||
|
$('input[name="maxcellvoltage"]').prop('disabled', false);
|
||||||
|
$('input[name="warningcellvoltage"]').prop('disabled', false);
|
||||||
|
$('input[name="voltagescale"]').prop('disabled', false);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
$('select.batterymetertype').prop('disabled', true);
|
||||||
|
$('input[name="mincellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="maxcellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="warningcellvoltage"]').prop('disabled', true);
|
||||||
|
$('input[name="voltagescale"]').prop('disabled', true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function checkDisableCurrentControls() {
|
||||||
|
if (BF_CONFIG.features.isEnabled('CURRENT_METER')) {
|
||||||
|
$('select.currentmetertype').prop('disabled', false);
|
||||||
|
if (BF_CONFIG.currentmetertype == 0 || BF_CONFIG.currentmetertype == 3) {
|
||||||
|
$('input[name="currentscale"]').prop('disabled', true);
|
||||||
|
$('input[name="currentoffset"]').prop('disabled', true);
|
||||||
|
$('input[name="multiwiicurrentoutput"]').prop('disabled', true);
|
||||||
|
} else {
|
||||||
|
$('input[name="currentscale"]').prop('disabled', false);
|
||||||
|
$('input[name="currentoffset"]').prop('disabled', false);
|
||||||
|
$('input[name="multiwiicurrentoutput"]').prop('disabled', false);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
$('select.currentmetertype').prop('disabled', true);
|
||||||
|
$('input[name="currentscale"]').prop('disabled', true);
|
||||||
|
$('input[name="currentoffset"]').prop('disabled', true);
|
||||||
|
$('input[name="multiwiicurrentoutput"]').prop('disabled', true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
$(features_e).filter('select').change(function () {
|
$(features_e).filter('select').change(function () {
|
||||||
var element = $(this);
|
var element = $(this);
|
||||||
|
|
||||||
|
@ -485,7 +580,18 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
checkShowSerialRxBox();
|
checkShowSerialRxBox();
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
|
$(features_e).filter('tbody.features.batteryVoltage').change(function() {
|
||||||
|
checkDisableVbatControls();
|
||||||
|
});
|
||||||
|
|
||||||
|
$(features_e).filter('tbody.features.batteryCurrent').change(function() {
|
||||||
|
checkDisableCurrentControls();
|
||||||
|
});
|
||||||
|
|
||||||
checkShowSerialRxBox();
|
checkShowSerialRxBox();
|
||||||
|
checkDisableVbatControls();
|
||||||
|
checkDisableCurrentControls();
|
||||||
|
|
||||||
$("input[id='unsyncedPWMSwitch']").change(function() {
|
$("input[id='unsyncedPWMSwitch']").change(function() {
|
||||||
if ($(this).is(':checked')) {
|
if ($(this).is(':checked')) {
|
||||||
|
@ -504,13 +610,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val());
|
CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val());
|
||||||
CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val());
|
CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val());
|
||||||
MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val());
|
MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val());
|
||||||
|
|
||||||
// motor disarm
|
// motor disarm
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
|
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
|
||||||
ARMING_CONFIG.disarm_kill_switch = $('input[id="disarmkillswitch"]').is(':checked') ? 1 : 0;
|
ARMING_CONFIG.disarm_kill_switch = $('input[id="disarmkillswitch"]').is(':checked') ? 1 : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
MISC.midrc = parseInt($('input[name="midrc"]').val());
|
MISC.midrc = parseInt($('input[name="midrc"]').val());
|
||||||
MISC.minthrottle = parseInt($('input[name="minthrottle"]').val());
|
MISC.minthrottle = parseInt($('input[name="minthrottle"]').val());
|
||||||
MISC.maxthrottle = parseInt($('input[name="maxthrottle"]').val());
|
MISC.maxthrottle = parseInt($('input[name="maxthrottle"]').val());
|
||||||
|
@ -535,7 +641,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
SENSOR_ALIGNMENT.align_gyro = parseInt(orientation_gyro_e.val());
|
SENSOR_ALIGNMENT.align_gyro = parseInt(orientation_gyro_e.val());
|
||||||
SENSOR_ALIGNMENT.align_acc = parseInt(orientation_acc_e.val());
|
SENSOR_ALIGNMENT.align_acc = parseInt(orientation_acc_e.val());
|
||||||
SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val());
|
SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val());
|
||||||
|
|
||||||
PID_ADVANCED_CONFIG.fast_pwm_protocol = parseInt(esc_protocol_e.val()-1);
|
PID_ADVANCED_CONFIG.fast_pwm_protocol = parseInt(esc_protocol_e.val()-1);
|
||||||
PID_ADVANCED_CONFIG.use_unsyncedPwm = $('input[id="unsyncedPWMSwitch"]').is(':checked') ? 1 : 0;
|
PID_ADVANCED_CONFIG.use_unsyncedPwm = $('input[id="unsyncedPWMSwitch"]').is(':checked') ? 1 : 0;
|
||||||
PID_ADVANCED_CONFIG.motor_pwm_rate = parseInt($('input[name="unsyncedpwmfreq"]').val());
|
PID_ADVANCED_CONFIG.motor_pwm_rate = parseInt($('input[name="unsyncedpwmfreq"]').val());
|
||||||
|
@ -578,11 +684,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
function save_esc_protocol() {
|
function save_esc_protocol() {
|
||||||
var next_callback = save_acc_trim;
|
var next_callback = save_acc_trim;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
|
@ -600,7 +706,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
function save_looptime_config() {
|
function save_looptime_config() {
|
||||||
var next_callback = save_sensor_config;
|
var next_callback = save_sensor_config;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
FC_CONFIG.loopTime = PID_ADVANCED_CONFIG.gyro_sync_denom * 125;
|
FC_CONFIG.loopTime = PID_ADVANCED_CONFIG.gyro_sync_denom * 125;
|
||||||
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
|
@ -609,8 +715,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
function save_sensor_config() {
|
function save_sensor_config() {
|
||||||
var next_callback = save_name;
|
var next_callback = save_name;
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
SENSOR_CONFIG.acc_hardware = $('input[id="accHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.acc_hardware = $('input[id="accHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
SENSOR_CONFIG.baro_hardware = $('input[id="baroHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.baro_hardware = $('input[id="baroHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
SENSOR_CONFIG.mag_hardware = $('input[id="magHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.mag_hardware = $('input[id="magHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
|
@ -621,9 +727,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_name() {
|
function save_name() {
|
||||||
var next_callback = save_to_eeprom;
|
var next_callback = save_battery;
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||||
CONFIG.name = $.trim($('input[name="vesselName"]').val());
|
CONFIG.name = $.trim($('input[name="vesselName"]').val());
|
||||||
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
|
@ -631,6 +737,24 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function save_battery() {
|
||||||
|
var next_callback = save_current;
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG), false, next_callback);
|
||||||
|
} else {
|
||||||
|
next_callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_current() {
|
||||||
|
var next_callback = save_to_eeprom;
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, next_callback);
|
||||||
|
} else {
|
||||||
|
next_callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
function save_to_eeprom() {
|
function save_to_eeprom() {
|
||||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||||
}
|
}
|
||||||
|
@ -663,7 +787,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue