1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-24 16:55:22 +03:00

Merge remote-tracking branch 'origin/master' into osd-support

This commit is contained in:
Pawel Spychalski (DzikuVx) 2016-12-15 00:18:35 +01:00
commit 1bb6850c24
38 changed files with 899 additions and 628 deletions

506
js/fc.js
View file

@ -41,43 +41,52 @@ var ADVANCED_CONFIG;
var INAV_PID_CONFIG;
var PID_ADVANCED;
var FILTER_CONFIG;
var SENSOR_STATUS;
var FC = {
isRatesInDps: function () {
if (typeof CONFIG != "undefined" && CONFIG.flightControllerIdentifier == "INAV" && semver.gt(CONFIG.flightControllerVersion, "1.1.0")) {
return true;
} else {
return false;
}
return !!(typeof CONFIG != "undefined" && CONFIG.flightControllerIdentifier == "INAV" && semver.gt(CONFIG.flightControllerVersion, "1.1.0"));
},
resetState: function() {
SENSOR_STATUS = {
isHardwareHealthy: 0,
gyroHwStatus: 0,
accHwStatus: 0,
magHwStatus: 0,
baroHwStatus: 0,
gpsHwStatus: 0,
rangeHwStatus: 0,
speedHwStatus: 0,
flowHwStatus: 0
};
CONFIG = {
apiVersion: "0.0.0",
apiVersion: "0.0.0",
flightControllerIdentifier: '',
flightControllerVersion: '',
version: 0,
buildInfo: '',
multiType: 0,
msp_version: 0, // not specified using semantic versioning
capability: 0,
cycleTime: 0,
i2cError: 0,
version: 0,
buildInfo: '',
multiType: 0,
msp_version: 0, // not specified using semantic versioning
capability: 0,
cycleTime: 0,
i2cError: 0,
activeSensors: 0,
mode: 0,
profile: 0,
uid: [0, 0, 0],
mode: 0,
profile: 0,
uid: [0, 0, 0],
accelerometerTrims: [0, 0]
};
BF_CONFIG = {
mixerConfiguration: 0,
features: 0,
serialrx_type: 0,
board_align_roll: 0,
board_align_pitch: 0,
board_align_yaw: 0,
currentscale: 0,
currentoffset: 0
mixerConfiguration: 0,
features: 0,
serialrx_type: 0,
board_align_roll: 0,
board_align_pitch: 0,
board_align_yaw: 0,
currentscale: 0,
currentoffset: 0
};
LED_STRIP = [];
@ -103,17 +112,17 @@ var FC = {
};
RC_tuning = {
RC_RATE: 0,
RC_EXPO: 0,
RC_RATE: 0,
RC_EXPO: 0,
roll_pitch_rate: 0, // pre 1.7 api only
roll_rate: 0,
pitch_rate: 0,
yaw_rate: 0,
roll_rate: 0,
pitch_rate: 0,
yaw_rate: 0,
dynamic_THR_PID: 0,
throttle_MID: 0,
throttle_EXPO: 0,
throttle_MID: 0,
throttle_EXPO: 0,
dynamic_THR_breakpoint: 0,
RC_YAW_EXPO: 0
RC_YAW_EXPO: 0
};
AUX_CONFIG = [];
@ -132,52 +141,52 @@ var FC = {
mspBaudRate: 0,
gpsBaudRate: 0,
gpsPassthroughBaudRate: 0,
cliBaudRate: 0,
cliBaudRate: 0
};
SENSOR_DATA = {
gyroscope: [0, 0, 0],
gyroscope: [0, 0, 0],
accelerometer: [0, 0, 0],
magnetometer: [0, 0, 0],
altitude: 0,
sonar: 0,
kinematics: [0.0, 0.0, 0.0],
debug: [0, 0, 0, 0]
magnetometer: [0, 0, 0],
altitude: 0,
sonar: 0,
kinematics: [0.0, 0.0, 0.0],
debug: [0, 0, 0, 0]
};
MOTOR_DATA = new Array(8);
SERVO_DATA = new Array(8);
GPS_DATA = {
fix: 0,
numSat: 0,
lat: 0,
lon: 0,
alt: 0,
speed: 0,
ground_course: 0,
distanceToHome: 0,
fix: 0,
numSat: 0,
lat: 0,
lon: 0,
alt: 0,
speed: 0,
ground_course: 0,
distanceToHome: 0,
ditectionToHome: 0,
update: 0,
hdop: 0,
eph: 0,
epv: 0,
messageDt: 0,
errors: 0,
timeouts: 0,
packetCount: 0
update: 0,
hdop: 0,
eph: 0,
epv: 0,
messageDt: 0,
errors: 0,
timeouts: 0,
packetCount: 0
};
ANALOG = {
voltage: 0,
mAhdrawn: 0,
rssi: 0,
amperage: 0
voltage: 0,
mAhdrawn: 0,
rssi: 0,
amperage: 0
};
ARMING_CONFIG = {
auto_disarm_delay: 0,
disarm_kill_switch: 0
auto_disarm_delay: 0,
disarm_kill_switch: 0
};
FC_CONFIG = {
@ -185,21 +194,21 @@ var FC = {
};
MISC = {
midrc: 0,
minthrottle: 0,
maxthrottle: 0,
mincommand: 0,
failsafe_throttle: 0,
gps_type: 0,
gps_baudrate: 0,
gps_ubx_sbas: 0,
multiwiicurrentoutput: 0,
rssi_channel: 0,
placeholder2: 0,
mag_declination: 0, // not checked
vbatscale: 0,
vbatmincellvoltage: 0,
vbatmaxcellvoltage: 0,
midrc: 0,
minthrottle: 0,
maxthrottle: 0,
mincommand: 0,
failsafe_throttle: 0,
gps_type: 0,
gps_baudrate: 0,
gps_ubx_sbas: 0,
multiwiicurrentoutput: 0,
rssi_channel: 0,
placeholder2: 0,
mag_declination: 0, // not checked
vbatscale: 0,
vbatmincellvoltage: 0,
vbatmaxcellvoltage: 0,
vbatwarningcellvoltage: 0
};
@ -217,7 +226,7 @@ var FC = {
gyroSoftLpfHz: null,
dtermLpfHz: null,
yawLpfHz: null
}
};
PID_ADVANCED = {
rollPitchItermIgnoreRate: null,
@ -225,7 +234,7 @@ var FC = {
yawPLimit: null,
axisAccelerationLimitRollPitch: null,
axisAccelerationLimitYaw: null
}
};
INAV_PID_CONFIG = {
asynchronousMode: null,
@ -236,13 +245,13 @@ var FC = {
yawJumpPreventionLimit: null,
gyroscopeLpf: null,
accSoftLpfHz: null
}
};
_3D = {
deadband3d_low: 0,
deadband3d_high: 0,
neutral3d: 0,
deadband3d_throttle: 0
deadband3d_low: 0,
deadband3d_high: 0,
neutral3d: 0,
deadband3d_throttle: 0
};
DATAFLASH = {
@ -258,7 +267,7 @@ var FC = {
state: 0,
filesystemLastError: 0,
freeSizeKB: 0,
totalSizeKB: 0,
totalSizeKB: 0
};
BLACKBOX = {
@ -274,36 +283,36 @@ var FC = {
};
RC_deadband = {
deadband: 0,
yaw_deadband: 0,
alt_hold_deadband: 0
deadband: 0,
yaw_deadband: 0,
alt_hold_deadband: 0
};
SENSOR_ALIGNMENT = {
align_gyro: 0,
align_acc: 0,
align_mag: 0
align_gyro: 0,
align_acc: 0,
align_mag: 0
};
RX_CONFIG = {
serialrx_provider: 0,
maxcheck: 0,
midrc: 0,
mincheck: 0,
spektrum_sat_bind: 0,
rx_min_usec: 0,
rx_max_usec: 0,
nrf24rx_protocol: 0,
nrf24rx_id: 0
serialrx_provider: 0,
maxcheck: 0,
midrc: 0,
mincheck: 0,
spektrum_sat_bind: 0,
rx_min_usec: 0,
rx_max_usec: 0,
nrf24rx_protocol: 0,
nrf24rx_id: 0
};
FAILSAFE_CONFIG = {
failsafe_delay: 0,
failsafe_off_delay: 0,
failsafe_throttle: 0,
failsafe_kill_switch: 0,
failsafe_throttle_low_delay: 0,
failsafe_procedure: 0
failsafe_delay: 0,
failsafe_off_delay: 0,
failsafe_throttle: 0,
failsafe_kill_switch: 0,
failsafe_throttle_low_delay: 0,
failsafe_procedure: 0
};
RXFAIL_CONFIG = [];
@ -371,7 +380,7 @@ var FC = {
}
return features;
},
isFeatureEnabled: function(featureName, features) {
isFeatureEnabled: function (featureName, features) {
for (var i = 0; i < features.length; i++) {
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
return true;
@ -384,56 +393,237 @@ var FC = {
},
getLooptimes: function () {
return {
125: {
defaultLooptime: 2000,
looptimes: {
4000: "250Hz",
3000: "334Hz",
2000: "500Hz",
1500: "667Hz",
1000: "1kHz",
500: "2kHz",
250: "4kHz",
125: "8kHz"
}
},
1000: {
defaultLooptime: 2000,
looptimes: {
4000: "250Hz",
2000: "500Hz",
1000: "1kHz"
}
}
};
},
getGyroLpfValues: function () {
return [
{
tick: 125,
defaultDenominator: 16,
label: "256Hz"
}, {
tick: 1000,
defaultDenominator: 2,
label: "188Hz"
}, {
tick: 1000,
defaultDenominator: 2,
label: "98Hz"
}, {
tick: 1000,
defaultDenominator: 2,
label: "42Hz"
}, {
tick: 1000,
defaultDenominator: 2,
label: "20Hz"
}, {
tick: 1000,
defaultDenominator: 2,
label: "10Hz"
}
];
}
125: {
defaultLooptime: 2000,
looptimes: {
4000: "250Hz",
3000: "334Hz",
2000: "500Hz",
1500: "667Hz",
1000: "1kHz",
500: "2kHz",
250: "4kHz",
125: "8kHz"
}
},
1000: {
defaultLooptime: 2000,
looptimes: {
4000: "250Hz",
2000: "500Hz",
1000: "1kHz"
}
}
};
},
getGyroFrequencies: function () {
return {
125: {
defaultLooptime: 1000,
looptimes: {
4000: "250Hz",
3000: "334Hz",
2000: "500Hz",
1500: "667Hz",
1000: "1kHz",
500: "2kHz",
250: "4kHz",
125: "8kHz"
}
},
1000: {
defaultLooptime: 1000,
looptimes: {
4000: "250Hz",
2000: "500Hz",
1000: "1kHz"
}
}
};
},
getGyroLpfValues: function () {
return [
{
tick: 125,
defaultDenominator: 16,
label: "256Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "188Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "98Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "42Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "20Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "10Hz"
}
];
},
getGpsProtocols: function () {
return [
'NMEA',
'UBLOX',
'I2C-NAV',
'DJI NAZA'
]
},
getGpsBaudRates: function () {
return [
'115200',
'57600',
'38400',
'19200',
'9600'
];
},
getGpsSbasProviders: function () {
return [
'Autodetect',
'European EGNOS',
'North American WAAS',
'Japanese MSAS',
'Indian GAGAN',
'Disabled'
];
},
getSerialRxTypes: function () {
return [
'SPEKTRUM1024',
'SPEKTRUM2048',
'SBUS',
'SUMD',
'SUMH',
'XBUS_MODE_B',
'XBUS_MODE_B_RJ01',
'IBUS'
];
},
getNrf24ProtocolTypes: function () {
return [
'V202 250Kbps',
'V202 1Mbps',
'Syma X',
'Syma X5C',
'Cheerson CX10',
'Cheerson CX10A',
'JJRC H8_3D',
'iNav Reference protocol'
];
},
getSensorAlignments: function () {
return [
'CW 0°',
'CW 90°',
'CW 180°',
'CW 270°',
'CW 0° flip',
'CW 90° flip',
'CW 180° flip',
'CW 270° flip'
];
},
getEscProtocols: function () {
return {
0: {
name: "STANDARD",
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
defaultRate: 1000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "ONESHOT42",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
3: {
name: "MULTISHOT",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
4: {
name: "BRUSHED",
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
}
};
},
getServoRates: function () {
return {
50: "50Hz",
60: "60Hz",
100: "100Hz",
200: "200Hz",
400: "400Hz"
};
},
getAsyncModes: function () {
return [
'Disabled',
'Gyro',
'All'
]
},
getAccelerometerTaskFrequencies: function () {
return {
100: '100Hz',
200: '200Hz',
250: '250Hz',
500: '500Hz',
750: '750Hz',
1000: '1kHz'
}
},
getAttitudeTaskFrequencies: function () {
return {
100: '100Hz',
200: '200Hz',
250: '250Hz',
500: '500Hz',
750: '750Hz',
1000: '1kHz'
}
}
};

View file

@ -9,28 +9,42 @@ function localize() {
return chrome.i18n.getMessage(messageID);
};
$('[i18n]:not(.i18n-replaced').each(function() {
$('[i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
element.html(translate(element.attr('i18n')));
element.addClass('i18n-replaced');
});
$('[i18n_title]:not(.i18n_title-replaced').each(function() {
$('[data-i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
element.html(translate(element.data('i18n')));
element.addClass('i18n-replaced');
});
$('[i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
element.attr('title', translate(element.attr('i18n_title')));
element.addClass('i18n_title-replaced');
});
$('[i18n_value]:not(.i18n_value-replaced').each(function() {
$('[data-i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
element.attr('title', translate(element.data('i18n_title')));
element.addClass('i18n_title-replaced');
});
$('[i18n_value]:not(.i18n_value-replaced)').each(function() {
var element = $(this);
element.val(translate(element.attr('i18n_value')));
element.addClass('i18n_value-replaced');
});
$('[i18n_placeholder]:not(.i18n_placeholder-replaced').each(function() {
$('[i18n_placeholder]:not(.i18n_placeholder-replaced)').each(function() {
var element = $(this);
element.attr('placeholder', translate(element.attr('i18n_placeholder')));

View file

@ -82,6 +82,7 @@ var MSPCodes = {
MSP_SENSOR_ALIGNMENT: 126,
MSP_LED_STRIP_MODECOLOR:127,
MSP_STATUS_EX: 150,
MSP_SENSOR_STATUS: 151,
MSP_SET_RAW_RC: 200,
MSP_SET_RAW_GPS: 201,

View file

@ -69,6 +69,19 @@ var mspHelper = (function (gui) {
gui.updateStatusBar();
break;
case MSPCodes.MSP_SENSOR_STATUS:
SENSOR_STATUS.isHardwareHealthy = data.getUint8(0);
SENSOR_STATUS.gyroHwStatus = data.getUint8(1);
SENSOR_STATUS.accHwStatus = data.getUint8(2);
SENSOR_STATUS.magHwStatus = data.getUint8(3);
SENSOR_STATUS.baroHwStatus = data.getUint8(4);
SENSOR_STATUS.gpsHwStatus = data.getUint8(5);
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
sensor_status_ex(SENSOR_STATUS);
break;
case MSPCodes.MSP_RAW_IMU:
// 512 for mpu6050, 256 for mma
// currently we are unable to differentiate between the sensor types, so we are goign with 512

View file

@ -308,79 +308,72 @@ function read_serial(info) {
}
}
//FIXME move it into GUI
function sensor_status(sensors_detected) {
// initialize variable (if it wasn't)
if (!sensor_status.previous_sensors_detected) {
sensor_status.previous_sensors_detected = -1; // Otherwise first iteration will not be run if sensors_detected == 0
}
function sensor_status_ex(hw_status)
{
var statusHash = sensor_status_hash(hw_status);
// update UI (if necessary)
if (sensor_status.previous_sensors_detected == sensors_detected) {
if (sensor_status_ex.previousHash == statusHash) {
return;
}
// set current value
sensor_status.previous_sensors_detected = sensors_detected;
sensor_status_ex.previousHash = statusHash;
sensor_status_update_icon('.gyro', '.gyroicon', hw_status.gyroHwStatus);
sensor_status_update_icon('.accel', '.accicon', hw_status.accHwStatus);
sensor_status_update_icon('.mag', '.magicon', hw_status.magHwStatus);
sensor_status_update_icon('.baro', '.baroicon', hw_status.baroHwStatus);
sensor_status_update_icon('.gps', '.gpsicon', hw_status.gpsHwStatus);
sensor_status_update_icon('.sonar', '.sonaricon', hw_status.rangeHwStatus);
sensor_status_update_icon('.airspeed', '.airspeedicon', hw_status.speedHwStatus);
sensor_status_update_icon('.opflow', '.opflowicon', hw_status.flowHwStatus);
}
function sensor_status_update_icon(sensId, sensIconId, status)
{
var e_sensor_status = $('#sensor-status');
if (have_sensor(sensors_detected, 'acc')) {
$('.accel', e_sensor_status).addClass('on');
$('.accicon', e_sensor_status).addClass('active');
} else {
$('.accel', e_sensor_status).removeClass('on');
$('.accicon', e_sensor_status).removeClass('active');
if (status == 0) {
$(sensId, e_sensor_status).removeClass('on');
$(sensIconId, e_sensor_status).removeClass('active');
$(sensIconId, e_sensor_status).removeClass('error');
}
if (have_sensor(sensors_detected, 'gyro')) {
$('.gyro', e_sensor_status).addClass('on');
$('.gyroicon', e_sensor_status).addClass('active');
} else {
$('.gyro', e_sensor_status).removeClass('on');
$('.gyroicon', e_sensor_status).removeClass('active');
else if (status == 1) {
$(sensId, e_sensor_status).addClass('on');
$(sensIconId, e_sensor_status).addClass('active');
$(sensIconId, e_sensor_status).removeClass('error');
}
if (have_sensor(sensors_detected, 'baro')) {
$('.baro', e_sensor_status).addClass('on');
$('.baroicon', e_sensor_status).addClass('active');
} else {
$('.baro', e_sensor_status).removeClass('on');
$('.baroicon', e_sensor_status).removeClass('active');
else {
$(sensId, e_sensor_status).removeClass('on');
$(sensIconId, e_sensor_status).removeClass('active');
$(sensIconId, e_sensor_status).addClass('error');
}
}
if (have_sensor(sensors_detected, 'mag')) {
$('.mag', e_sensor_status).addClass('on');
$('.magicon', e_sensor_status).addClass('active');
} else {
$('.mag', e_sensor_status).removeClass('on');
$('.magicon', e_sensor_status).removeClass('active');
}
function sensor_status_hash(hw_status)
{
return "S" +
hw_status.isHardwareHealthy +
hw_status.gyroHwStatus +
hw_status.accHwStatus +
hw_status.magHwStatus +
hw_status.baroHwStatus +
hw_status.gpsHwStatus +
hw_status.rangeHwStatus +
hw_status.speedHwStatus +
hw_status.flowHwStatus;
}
if (have_sensor(sensors_detected, 'gps')) {
$('.gps', e_sensor_status).addClass('on');
$('.gpsicon', e_sensor_status).addClass('active');
} else {
$('.gps', e_sensor_status).removeClass('on');
$('.gpsicon', e_sensor_status).removeClass('active');
}
if (have_sensor(sensors_detected, 'sonar')) {
$('.sonar', e_sensor_status).addClass('on');
$('.sonaricon', e_sensor_status).addClass('active');
} else {
$('.sonar', e_sensor_status).removeClass('on');
$('.sonaricon', e_sensor_status).removeClass('active');
}
if (have_sensor(sensors_detected, 'opflow')) {
$('.opflow', e_sensor_status).addClass('on');
$('.opflowicon', e_sensor_status).addClass('active');
} else {
$('.opflow', e_sensor_status).removeClass('on');
$('.opflowicon', e_sensor_status).removeClass('active');
}
function sensor_status(sensors_detected) {
SENSOR_STATUS.isHardwareHealthy = 1;
SENSOR_STATUS.gyroHwStatus = have_sensor(sensors_detected, 'gyro') ? 1 : 0;
SENSOR_STATUS.accHwStatus = have_sensor(sensors_detected, 'acc') ? 1 : 0;
SENSOR_STATUS.magHwStatus = have_sensor(sensors_detected, 'mag') ? 1 : 0;
SENSOR_STATUS.baroHwStatus = have_sensor(sensors_detected, 'baro') ? 1 : 0;
SENSOR_STATUS.gpsHwStatus = have_sensor(sensors_detected, 'gps') ? 1 : 0;
SENSOR_STATUS.rangeHwStatus = have_sensor(sensors_detected, 'sonar') ? 1 : 0;
SENSOR_STATUS.speedHwStatus = have_sensor(sensors_detected, 'airspeed') ? 1 : 0;
SENSOR_STATUS.flowHwStatus = have_sensor(sensors_detected, 'opflow') ? 1 : 0;
sensor_status_ex(SENSOR_STATUS);
}
function have_sensor(sensors_detected, sensor_code) {
@ -398,6 +391,8 @@ function have_sensor(sensors_detected, sensor_code) {
return bit_check(sensors_detected, 4);
case 'opflow':
return bit_check(sensors_detected, 5);
case 'airspeed':
return bit_check(sensors_detected, 6);
}
return false;
}