mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-25 01:05:12 +03:00
Merge remote-tracking branch 'origin/master' into dzikuvx-simplify-receiver-tab
This commit is contained in:
commit
fd467974b7
86 changed files with 67833 additions and 2052 deletions
|
@ -224,10 +224,6 @@ $(function() {
|
|||
require('./../tabs/receiver');
|
||||
TABS.receiver.initialize(content_ready);
|
||||
break;
|
||||
case 'modes':
|
||||
require('./../tabs/modes');
|
||||
TABS.modes.initialize(content_ready);
|
||||
break;
|
||||
case 'gps':
|
||||
require('./../tabs/gps');
|
||||
TABS.gps.initialize(content_ready);
|
||||
|
|
30
js/fc.js
30
js/fc.js
|
@ -14,6 +14,7 @@ const FwApproachCollection = require('./fwApproachCollection')
|
|||
const { PLATFORM } = require('./model')
|
||||
const VTX = require('./vtx');
|
||||
const BitHelper = require('./bitHelper');
|
||||
const { FLIGHT_MODES } = require('./flightModes');
|
||||
|
||||
|
||||
var FC = {
|
||||
|
@ -28,8 +29,8 @@ var FC = {
|
|||
RC_MAP: null,
|
||||
RC: null,
|
||||
RC_tuning: null,
|
||||
AUX_CONFIG: null,
|
||||
AUX_CONFIG_IDS: null,
|
||||
AUX_CONFIG: [],
|
||||
AUX_CONFIG_IDS: [],
|
||||
MODE_RANGES: null,
|
||||
ADJUSTMENT_RANGES: null,
|
||||
SERVO_CONFIG: null,
|
||||
|
@ -85,6 +86,7 @@ var FC = {
|
|||
FEATURES: null,
|
||||
RATE_DYNAMICS: null,
|
||||
EZ_TUNE: null,
|
||||
FLIGHT_MODES: null,
|
||||
|
||||
restartRequired: false,
|
||||
MAX_SERVO_RATE: 125,
|
||||
|
@ -198,8 +200,16 @@ var FC = {
|
|||
manual_yaw_rate: 0,
|
||||
};
|
||||
|
||||
this.AUX_CONFIG = [];
|
||||
this.AUX_CONFIG_IDS = [];
|
||||
this.generateAuxConfig = function () {
|
||||
console.log('Generating AUX_CONFIG');
|
||||
this.AUX_CONFIG = [];
|
||||
for ( let i = 0; i < this.AUX_CONFIG_IDS.length; i++ ) {
|
||||
let found = FLIGHT_MODES.find( mode => mode.permanentId === this.AUX_CONFIG_IDS[i] );
|
||||
if (found) {
|
||||
this.AUX_CONFIG.push(found.boxName);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
this.MODE_RANGES = [];
|
||||
this.ADJUSTMENT_RANGES = [];
|
||||
|
@ -940,11 +950,13 @@ var FC = {
|
|||
return this.getServoMixInputNames()[input];
|
||||
},
|
||||
getModeId: function (name) {
|
||||
for (var i = 0; i < this.AUX_CONFIG.length; i++) {
|
||||
if (this.AUX_CONFIG[i] == name)
|
||||
return i;
|
||||
|
||||
let mode = FLIGHT_MODES.find( mode => mode.boxName === name );
|
||||
if (mode) {
|
||||
return mode.permanentId;
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
return -1;
|
||||
},
|
||||
isModeBitSet: function (i) {
|
||||
return BitHelper.bit_check(this.CONFIG.mode[Math.trunc(i / 32)], i % 32);
|
||||
|
@ -1376,7 +1388,7 @@ var FC = {
|
|||
default: 0
|
||||
},
|
||||
5: {
|
||||
name: "Global Variable",
|
||||
name: "Get Global Variable",
|
||||
type: "range",
|
||||
range: [0, 7],
|
||||
default: 0
|
||||
|
|
286
js/flightModes.js
Normal file
286
js/flightModes.js
Normal file
|
@ -0,0 +1,286 @@
|
|||
'use strict';
|
||||
|
||||
var FLIGHT_MODES = [
|
||||
{
|
||||
boxId: 0,
|
||||
boxName: "ARM",
|
||||
permanentId: 0
|
||||
},
|
||||
{
|
||||
boxId: 1,
|
||||
boxName: "ANGLE",
|
||||
permanentId: 1
|
||||
},
|
||||
{
|
||||
boxId: 2,
|
||||
boxName: "HORIZON",
|
||||
permanentId: 2
|
||||
},
|
||||
{
|
||||
boxId: 3,
|
||||
boxName: "NAV ALTHOLD",
|
||||
permanentId: 3
|
||||
},
|
||||
{
|
||||
boxId: 4,
|
||||
boxName: "HEADING HOLD",
|
||||
permanentId: 5
|
||||
},
|
||||
{
|
||||
boxId: 5,
|
||||
boxName: "HEADFREE",
|
||||
permanentId: 6
|
||||
},
|
||||
{
|
||||
boxId: 6,
|
||||
boxName: "HEADADJ",
|
||||
permanentId: 7
|
||||
},
|
||||
{
|
||||
boxId: 7,
|
||||
boxName: "CAMSTAB",
|
||||
permanentId: 8
|
||||
},
|
||||
{
|
||||
boxId: 8,
|
||||
boxName: "NAV RTH",
|
||||
permanentId: 10
|
||||
},
|
||||
{
|
||||
boxId: 9,
|
||||
boxName: "NAV POSHOLD",
|
||||
permanentId: 11
|
||||
},
|
||||
{
|
||||
boxId: 10,
|
||||
boxName: "MANUAL",
|
||||
permanentId: 12
|
||||
},
|
||||
{
|
||||
boxId: 11,
|
||||
boxName: "BEEPER",
|
||||
permanentId: 13
|
||||
},
|
||||
{
|
||||
boxId: 12,
|
||||
boxName: "LEDS OFF",
|
||||
permanentId: 15
|
||||
},
|
||||
{
|
||||
boxId: 13,
|
||||
boxName: "LIGHTS",
|
||||
permanentId: 16
|
||||
},
|
||||
{
|
||||
boxId: 15,
|
||||
boxName: "OSD OFF",
|
||||
permanentId: 19
|
||||
},
|
||||
{
|
||||
boxId: 16,
|
||||
boxName: "TELEMETRY",
|
||||
permanentId: 20
|
||||
},
|
||||
{
|
||||
boxId: 28,
|
||||
boxName: "AUTO TUNE",
|
||||
permanentId: 21
|
||||
},
|
||||
{
|
||||
boxId: 17,
|
||||
boxName: "BLACKBOX",
|
||||
permanentId: 26
|
||||
},
|
||||
{
|
||||
boxId: 18,
|
||||
boxName: "FAILSAFE",
|
||||
permanentId: 27
|
||||
},
|
||||
{
|
||||
boxId: 19,
|
||||
boxName: "NAV WP",
|
||||
permanentId: 28
|
||||
},
|
||||
{
|
||||
boxId: 20,
|
||||
boxName: "AIR MODE",
|
||||
permanentId: 29
|
||||
},
|
||||
{
|
||||
boxId: 21,
|
||||
boxName: "HOME RESET",
|
||||
permanentId: 30
|
||||
},
|
||||
{
|
||||
boxId: 22,
|
||||
boxName: "GCS NAV",
|
||||
permanentId: 31
|
||||
},
|
||||
{
|
||||
boxId: 39,
|
||||
boxName: "FPV ANGLE MIX",
|
||||
permanentId: 32
|
||||
},
|
||||
{
|
||||
boxId: 24,
|
||||
boxName: "SURFACE",
|
||||
permanentId: 33
|
||||
},
|
||||
{
|
||||
boxId: 25,
|
||||
boxName: "FLAPERON",
|
||||
permanentId: 34
|
||||
},
|
||||
{
|
||||
boxId: 26,
|
||||
boxName: "TURN ASSIST",
|
||||
permanentId: 35
|
||||
},
|
||||
{
|
||||
boxId: 14,
|
||||
boxName: "NAV LAUNCH",
|
||||
permanentId: 36
|
||||
},
|
||||
{
|
||||
boxId: 27,
|
||||
boxName: "SERVO AUTOTRIM",
|
||||
permanentId: 37
|
||||
},
|
||||
{
|
||||
boxId: 23,
|
||||
boxName: "KILLSWITCH",
|
||||
permanentId: 38
|
||||
},
|
||||
{
|
||||
boxId: 29,
|
||||
boxName: "CAMERA CONTROL 1",
|
||||
permanentId: 39
|
||||
},
|
||||
{
|
||||
boxId: 30,
|
||||
boxName: "CAMERA CONTROL 2",
|
||||
permanentId: 40
|
||||
},
|
||||
{
|
||||
boxId: 31,
|
||||
boxName: "CAMERA CONTROL 3",
|
||||
permanentId: 41
|
||||
},
|
||||
{
|
||||
boxId: 32,
|
||||
boxName: "OSD ALT 1",
|
||||
permanentId: 42
|
||||
},
|
||||
{
|
||||
boxId: 33,
|
||||
boxName: "OSD ALT 2",
|
||||
permanentId: 43
|
||||
},
|
||||
{
|
||||
boxId: 34,
|
||||
boxName: "OSD ALT 3",
|
||||
permanentId: 44
|
||||
},
|
||||
{
|
||||
boxId: 35,
|
||||
boxName: "NAV COURSE HOLD",
|
||||
permanentId: 45
|
||||
},
|
||||
{
|
||||
boxId: 36,
|
||||
boxName: "MC BRAKING",
|
||||
permanentId: 46
|
||||
},
|
||||
{
|
||||
boxId: 37,
|
||||
boxName: "USER1",
|
||||
permanentId: 47
|
||||
},
|
||||
{
|
||||
boxId: 38,
|
||||
boxName: "USER2",
|
||||
permanentId: 48
|
||||
},
|
||||
{
|
||||
boxId: 48,
|
||||
boxName: "USER3",
|
||||
permanentId: 57
|
||||
},
|
||||
{
|
||||
boxId: 49,
|
||||
boxName: "USER4",
|
||||
permanentId: 58
|
||||
},
|
||||
{
|
||||
boxId: 40,
|
||||
boxName: "LOITER CHANGE",
|
||||
permanentId: 49
|
||||
},
|
||||
{
|
||||
boxId: 41,
|
||||
boxName: "MSP RC OVERRIDE",
|
||||
permanentId: 50
|
||||
},
|
||||
{
|
||||
boxId: 42,
|
||||
boxName: "PREARM",
|
||||
permanentId: 51
|
||||
},
|
||||
{
|
||||
boxId: 43,
|
||||
boxName: "TURTLE",
|
||||
permanentId: 52
|
||||
},
|
||||
{
|
||||
boxId: 44,
|
||||
boxName: "NAV CRUISE",
|
||||
permanentId: 53
|
||||
},
|
||||
{
|
||||
boxId: 45,
|
||||
boxName: "AUTO LEVEL TRIM",
|
||||
permanentId: 54
|
||||
},
|
||||
{
|
||||
boxId: 46,
|
||||
boxName: "WP PLANNER",
|
||||
permanentId: 55
|
||||
},
|
||||
{
|
||||
boxId: 47,
|
||||
boxName: "SOARING",
|
||||
permanentId: 56
|
||||
},
|
||||
{
|
||||
boxId: 50,
|
||||
boxName: "MISSION CHANGE",
|
||||
permanentId: 59
|
||||
},
|
||||
{
|
||||
boxId: 51,
|
||||
boxName: "BEEPER MUTE",
|
||||
permanentId: 60
|
||||
},
|
||||
{
|
||||
boxId: 52,
|
||||
boxName: "MULTI FUNCTION",
|
||||
permanentId: 61
|
||||
},
|
||||
{
|
||||
boxId: 53,
|
||||
boxName: "MIXER PROFILE 2",
|
||||
permanentId: 62
|
||||
},
|
||||
{
|
||||
boxId: 54,
|
||||
boxName: "MIXER TRANSITION",
|
||||
permanentId: 63
|
||||
},
|
||||
{
|
||||
boxId: 55,
|
||||
boxName: "ANGLE HOLD",
|
||||
permanentId: 64
|
||||
}
|
||||
];
|
||||
|
||||
module.exports = {FLIGHT_MODES};
|
|
@ -37,7 +37,6 @@ var GUI_control = function () {
|
|||
'led_strip',
|
||||
'logging',
|
||||
'onboard_logging',
|
||||
'modes',
|
||||
'outputs',
|
||||
'pid_tuning',
|
||||
'ports',
|
||||
|
|
|
@ -24,17 +24,17 @@ function zeroPad(value, width) {
|
|||
return value;
|
||||
}
|
||||
|
||||
function generateFilename(prefix, suffix) {
|
||||
function generateFilename(config, prefix, suffix) {
|
||||
var date = new Date();
|
||||
var filename = prefix;
|
||||
|
||||
if (CONFIG) {
|
||||
if (CONFIG.flightControllerIdentifier) {
|
||||
filename = CONFIG.flightControllerIdentifier + '_' + CONFIG.flightControllerVersion + "_" + filename;
|
||||
if (config) {
|
||||
if (config.flightControllerIdentifier) {
|
||||
filename = config.flightControllerIdentifier + '_' + config.flightControllerVersion + "_" + filename;
|
||||
}
|
||||
|
||||
if (CONFIG.name && CONFIG.name.trim() !== '') {
|
||||
filename = filename + '_' + CONFIG.name.trim().replace(' ', '_');
|
||||
|
||||
if (config.name && config.name.trim() !== '') {
|
||||
filename = filename + '_' + config.name.trim().replace(' ', '_');
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -65,7 +65,7 @@ function distanceOnLine(start, end, distance)
|
|||
var px = start[0] + vx * (mag + distance);
|
||||
var py = start[1] + vy * (mag + distance);
|
||||
|
||||
return [px, py];
|
||||
return [px, py];
|
||||
}
|
||||
|
||||
function wrap_360(angle)
|
||||
|
@ -77,7 +77,7 @@ function wrap_360(angle)
|
|||
return angle;
|
||||
}
|
||||
|
||||
function rad2Deg(rad)
|
||||
function rad2Deg(rad)
|
||||
{
|
||||
return rad * (180 / Math.PI);
|
||||
}
|
||||
|
@ -92,8 +92,8 @@ function calculate_new_cooridatnes(coord, bearing, distance)
|
|||
var lat = deg2Rad(coord.lat);
|
||||
var lon = deg2Rad(coord.lon);
|
||||
bearing = deg2Rad(bearing);
|
||||
var delta = distance / 637100000; // Earth radius in cm
|
||||
|
||||
var delta = distance / 637100000; // Earth radius in cm
|
||||
|
||||
var latNew = Math.asin(Math.sin(lat) * Math.cos(delta) + Math.cos(lat) * Math.sin(delta) * Math.cos(bearing));
|
||||
var lonNew = lon + Math.atan2(Math.sin(bearing) * Math.sin(delta) * Math.cos(lat), Math.cos(delta) - Math.sin(lat) * Math.sin(lat));
|
||||
return {
|
||||
|
|
|
@ -84,7 +84,6 @@ var MSPCodes = {
|
|||
MSP_PID: 112,
|
||||
MSP_ACTIVEBOXES: 113,
|
||||
MSP_MOTOR_PINS: 115,
|
||||
MSP_BOXNAMES: 116,
|
||||
MSP_PIDNAMES: 117,
|
||||
MSP_WP: 118,
|
||||
MSP_BOXIDS: 119,
|
||||
|
|
|
@ -386,21 +386,6 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP_MOTOR_PINS:
|
||||
console.log(data);
|
||||
break;
|
||||
case MSPCodes.MSP_BOXNAMES:
|
||||
//noinspection JSUndeclaredVariable
|
||||
FC.AUX_CONFIG = []; // empty the array as new data is coming in
|
||||
buff = [];
|
||||
for (let i = 0; i < data.byteLength; i++) {
|
||||
if (data.getUint8(i) == 0x3B) { // ; (delimeter char)
|
||||
FC.AUX_CONFIG.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
|
||||
|
||||
// empty buffer
|
||||
buff = [];
|
||||
} else {
|
||||
buff.push(data.getUint8(i));
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_PIDNAMES:
|
||||
//noinspection JSUndeclaredVariable
|
||||
FC.PID_names = []; // empty the array as new data is coming in
|
||||
|
@ -3075,7 +3060,6 @@ var mspHelper = (function () {
|
|||
};
|
||||
|
||||
self._getSetting = function (name) {
|
||||
console.log("Getting setting " + name);
|
||||
if (FC.SETTINGS[name]) {
|
||||
return Promise.resolve(FC.SETTINGS[name]);
|
||||
}
|
||||
|
|
|
@ -460,27 +460,22 @@ var SerialBackend = (function () {
|
|||
$('#dataflash_wrapper_global').show();
|
||||
|
||||
/*
|
||||
* Get BOXNAMES since it is used for some reason....
|
||||
* Init PIDs bank with a length that depends on the version
|
||||
*/
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, function () {
|
||||
/*
|
||||
* Init PIDs bank with a length that depends on the version
|
||||
*/
|
||||
let pidCount = 11;
|
||||
let pidCount = 11;
|
||||
|
||||
for (let i = 0; i < pidCount; i++) {
|
||||
FC.PIDs.push(new Array(4));
|
||||
}
|
||||
for (let i = 0; i < pidCount; i++) {
|
||||
FC.PIDs.push(new Array(4));
|
||||
}
|
||||
|
||||
interval.add('msp-load-update', function () {
|
||||
$('#msp-version').text("MSP version: " + MSP.protocolVersion.toFixed(0));
|
||||
$('#msp-load').text("MSP load: " + mspQueue.getLoad().toFixed(1));
|
||||
$('#msp-roundtrip').text("MSP round trip: " + mspQueue.getRoundtrip().toFixed(0));
|
||||
$('#hardware-roundtrip').text("HW round trip: " + mspQueue.getHardwareRoundtrip().toFixed(0));
|
||||
}, 100);
|
||||
interval.add('msp-load-update', function () {
|
||||
$('#msp-version').text("MSP version: " + MSP.protocolVersion.toFixed(0));
|
||||
$('#msp-load').text("MSP load: " + mspQueue.getLoad().toFixed(1));
|
||||
$('#msp-roundtrip').text("MSP round trip: " + mspQueue.getRoundtrip().toFixed(0));
|
||||
$('#hardware-roundtrip').text("HW round trip: " + mspQueue.getHardwareRoundtrip().toFixed(0));
|
||||
}, 100);
|
||||
|
||||
interval.add('global_data_refresh', periodicStatusUpdater.run, periodicStatusUpdater.getUpdateInterval(CONFIGURATOR.connection.bitrate), false);
|
||||
});
|
||||
interval.add('global_data_refresh', periodicStatusUpdater.run, periodicStatusUpdater.getUpdateInterval(CONFIGURATOR.connection.bitrate), false);
|
||||
});
|
||||
|
||||
}
|
||||
|
|
|
@ -53,6 +53,16 @@ var Settings = (function () {
|
|||
var settingName = input.data('setting');
|
||||
var inputUnit = input.data('unit');
|
||||
|
||||
let elementId = input.attr('id');
|
||||
if (elementId === undefined) {
|
||||
|
||||
// If the element ID is not defined, we need to create one
|
||||
// based on the setting name. If this ID exists, we will not create it
|
||||
if ($('#' + settingName).length === 0) {
|
||||
input.attr('id', settingName);
|
||||
}
|
||||
}
|
||||
|
||||
if (globalSettings.showProfileParameters) {
|
||||
if (FC.isBatteryProfileParameter(settingName)) {
|
||||
input.css("background-color","#fef2d5");
|
||||
|
@ -149,7 +159,8 @@ var Settings = (function () {
|
|||
input.data('setting-info', s.setting);
|
||||
if (input.data('live')) {
|
||||
input.on('change', function () {
|
||||
self.saveInput(input);
|
||||
const settingPair = self.processInput(input);
|
||||
return mspHelper.setSetting(settingPair.setting, settingPair.value);
|
||||
});
|
||||
}
|
||||
});
|
||||
|
@ -528,7 +539,7 @@ var Settings = (function () {
|
|||
};
|
||||
}
|
||||
|
||||
self.saveInput = function(input) {
|
||||
self.processInput = function(input) {
|
||||
var settingName = input.data('setting');
|
||||
var setting = input.data('setting-info');
|
||||
var value;
|
||||
|
@ -536,7 +547,6 @@ var Settings = (function () {
|
|||
if (typeof setting == 'undefined') {
|
||||
return null;
|
||||
}
|
||||
|
||||
if (setting.table) {
|
||||
if (input.attr('type') == 'checkbox') {
|
||||
value = input.prop('checked') ? 1 : 0;
|
||||
|
@ -585,8 +595,7 @@ var Settings = (function () {
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
return mspHelper.setSetting(settingName, value);
|
||||
return {setting: settingName, value: value};
|
||||
};
|
||||
|
||||
self.countDecimals = function(value) {
|
||||
|
@ -604,14 +613,26 @@ var Settings = (function () {
|
|||
return 0;
|
||||
};
|
||||
|
||||
self.saveInputs = function() {
|
||||
self.pickAndSaveSingleInput = function(inputs, finalCallback) {
|
||||
if (inputs.length > 0) {
|
||||
var input = inputs.shift();
|
||||
var settingPair = self.processInput(input);
|
||||
return mspHelper.setSetting(settingPair.setting, settingPair.value, function() {
|
||||
return self.pickAndSaveSingleInput(inputs, finalCallback);
|
||||
});
|
||||
} else {
|
||||
if (finalCallback) {
|
||||
finalCallback();
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
self.saveInputs = function(finalCallback) {
|
||||
var inputs = [];
|
||||
$('[data-setting!=""][data-setting]').each(function() {
|
||||
inputs.push($(this));
|
||||
});
|
||||
return mapSeries(inputs, function (input, ii) {
|
||||
return self.saveInput(input);
|
||||
});
|
||||
self.pickAndSaveSingleInput(inputs, finalCallback);
|
||||
};
|
||||
|
||||
self.processHtml = function(callback) {
|
||||
|
|
|
@ -972,7 +972,7 @@
|
|||
"message": "Minimum Command"
|
||||
},
|
||||
"configurationVoltageCurrentSensor": {
|
||||
"message": "Voltage and Current Sensors"
|
||||
"message": "Voltage & Current Sensors"
|
||||
},
|
||||
"configurationBatteryCurrent": {
|
||||
"message": "Battery Current"
|
||||
|
@ -1347,10 +1347,10 @@
|
|||
"message": "Show all PIDs"
|
||||
},
|
||||
"pidTuning_PIDmain": {
|
||||
"message": "Main PID gains"
|
||||
"message": "Main PID Gains"
|
||||
},
|
||||
"pidTuning_PIDother": {
|
||||
"message": "Additional PID gains"
|
||||
"message": "Additional PID Gains"
|
||||
},
|
||||
"pidTuning_SelectNewDefaults": {
|
||||
"message": "Select New Defaults"
|
||||
|
@ -1359,7 +1359,7 @@
|
|||
"message": "Reset PID Controller"
|
||||
},
|
||||
"pidTuning_PIDgains": {
|
||||
"message": "PID gains"
|
||||
"message": "PID Gains"
|
||||
},
|
||||
"pidTuning_Name": {
|
||||
"message": "Name"
|
||||
|
@ -1545,7 +1545,7 @@
|
|||
"message": "Mechanics"
|
||||
},
|
||||
"pidTuning_ITermMechanics": {
|
||||
"message": "I-term mechanics"
|
||||
"message": "I-term Mechanics"
|
||||
},
|
||||
"pidTuning_itermRelaxCutoff": {
|
||||
"message": "I-term Relax Cutoff Frequency"
|
||||
|
@ -1569,7 +1569,7 @@
|
|||
"message": "Freeze yaw Iterm when plane is banked more than this many degrees. This helps to stop the rudder from counteracting turn. 0 disables this feature. Applies only to fixed wing aircraft."
|
||||
},
|
||||
"pidTuning_dTermMechanics": {
|
||||
"message": "D-term mechanics"
|
||||
"message": "D-term Mechanics"
|
||||
},
|
||||
"pidTuning_d_boost_min": {
|
||||
"message": "D-Boost Min. Scale"
|
||||
|
@ -1596,7 +1596,7 @@
|
|||
"message": "Should be set to the frequency of propeller wash oscillations. 5-inch quads work best at around 80Hz, 7-inch quads at around 50Hz"
|
||||
},
|
||||
"pidTuning_tpaMechanics": {
|
||||
"message": "Thrust PID attenuation"
|
||||
"message": "Thrust PID Attenuation"
|
||||
},
|
||||
"pidTuning_TPA": {
|
||||
"message": "Thrust PID Attenuation (TPA)"
|
||||
|
@ -1611,7 +1611,7 @@
|
|||
"message": "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane."
|
||||
},
|
||||
"pidTuning_fwLevelTrimMechanics": {
|
||||
"message": "Fixed Wing mechanics"
|
||||
"message": "Fixed Wing Mechanics"
|
||||
},
|
||||
"pidTuning_fw_level_pitch_trim": {
|
||||
"message": "Level Trim [deg]"
|
||||
|
@ -1765,7 +1765,9 @@
|
|||
"auxiliaryEepromSaved": {
|
||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
||||
},
|
||||
|
||||
"eepromSaved": {
|
||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
||||
},
|
||||
"adjustmentsHelp": {
|
||||
"message": "Configure adjustment switches. See the 'in-flight adjustments' section of the manual for details. The changes that adjustment functions make are not saved automatically. There are 4 slots. Each switch used to concurrently make adjustments requires exclusive use of a slot."
|
||||
},
|
||||
|
@ -2139,10 +2141,10 @@
|
|||
"message": "Baud Rate"
|
||||
},
|
||||
"magnetometerHead": {
|
||||
"message": "Alignment tool"
|
||||
"message": "Alignment Tool"
|
||||
},
|
||||
"magnetometerHelp": {
|
||||
"message": "1. Adjust Flight Controller orientation to match physical orientation on the aircraft <u>according to \"direction\" arrow on Flight Controller</u>.<br/>2. Adjust magnetometer orientation to match physical orientation on the aircraft <u>according to \"compass direction\" arrow or axis markings on magnetometer</u>.<br/><strong>Note:</strong> Magnetometer orientation preset (align_mag) is relative to FC. Make sure to align FC first (align_board_pitch, align_board_roll, align_board_yaw).<br/>If preset is not used (orientation is set using align_mag_roll, align_mag_pitch and align_mag_yaw), then magnetometer orientation is independent."
|
||||
"message": "1. Adjust Flight Controller orientation to match physical orientation on the aircraft <u>according to \"direction\" arrow on the Flight Controller</u>.<br/>2. Adjust magnetometer model, or magnetometer chip, or magnetometer axes orientation to match physical orientation on the aircraft.<br/><strong>Note:</strong> Magnetometer orientation preset (align_mag) is relative to FC. Make sure to align FC first (align_board_pitch, align_board_roll, align_board_yaw).<br/>If preset is not used (orientation is set using align_mag_roll, align_mag_pitch and align_mag_yaw), then magnetometer orientation is independent."
|
||||
},
|
||||
"magnetometerOrientationPreset": {
|
||||
"message": "Orientation preset (align_mag). Relative to FC orientation"
|
||||
|
@ -2154,19 +2156,23 @@
|
|||
"message": "2. Select a preset (align_mag) or create a custom configuration using the sliders<br>(align_mag_roll, align_mag_pitch, align_mag_yaw)"
|
||||
},
|
||||
"magnetometerElementToShow": {
|
||||
"message": "Element to show: Magnetometer model or axes"
|
||||
"message": "Element to show: Magnetometer model or chip or axes"
|
||||
},
|
||||
"magnetometerAxes": {
|
||||
"message": "XYZ (Magnetometer Axes)"
|
||||
},
|
||||
|
||||
"axisTableTitleAxis": {
|
||||
"message": "Axis"
|
||||
},
|
||||
"axisTableTitleSlider": {
|
||||
"message": "Slider"
|
||||
},
|
||||
"axisTableTitleValue": {
|
||||
"message": "Value [degree]"
|
||||
},
|
||||
|
||||
"configurationSensorMagPreset": {
|
||||
"message": "Orientation is set by: PRESET (align_mag)"
|
||||
},
|
||||
"configurationSensorMagAngles": {
|
||||
"message": "Orientation is set by: ANGLES (align_mag_roll, align_mag_pitch ,align_mag_yaw)"
|
||||
},
|
||||
"configurationMagnetometerHelp": {
|
||||
"message": "<strong>Note:</strong> Remember to configure a Serial Port (via Ports tab) when using the Magnetometer feature."
|
||||
},
|
||||
|
@ -2174,7 +2180,7 @@
|
|||
"message": "Mag Statistics"
|
||||
},
|
||||
"tabMAGNETOMETER": {
|
||||
"message": "Alignment tool"
|
||||
"message": "Alignment Tool"
|
||||
},
|
||||
"motors": {
|
||||
"message": "Motors"
|
||||
|
@ -2303,7 +2309,7 @@
|
|||
"message": "Your flight controller's firmware does not support Blackbox logging or Blackbox feature is not enabled"
|
||||
},
|
||||
"blackboxConfiguration": {
|
||||
"message": "Blackbox configuration"
|
||||
"message": "Blackbox Configuration"
|
||||
},
|
||||
"blackboxButtonSave": {
|
||||
"message": "Save and Reboot"
|
||||
|
@ -2806,7 +2812,7 @@
|
|||
"message": "OSD"
|
||||
},
|
||||
"configurationSensors": {
|
||||
"message": "Sensors & buses"
|
||||
"message": "Sensors & Buses"
|
||||
},
|
||||
"sensorAccelerometer": {
|
||||
"message": "Accelerometer"
|
||||
|
@ -3116,10 +3122,10 @@
|
|||
"message": "Wireless mode"
|
||||
},
|
||||
"rthConfiguration": {
|
||||
"message": "RTH settings"
|
||||
"message": "RTH Settings"
|
||||
},
|
||||
"autoLandingSettings": {
|
||||
"message": "Automatic landing settings"
|
||||
"message": "Automatic Landing Settings"
|
||||
},
|
||||
"minRthDistance": {
|
||||
"message": "Min. RTH distance"
|
||||
|
@ -3581,7 +3587,7 @@
|
|||
"message": "Home Position on Arming Screen"
|
||||
},
|
||||
"osd_hud_settings": {
|
||||
"message": "Heads up Display settings"
|
||||
"message": "Heads-up Display settings"
|
||||
},
|
||||
"osd_custom_element_settings": {
|
||||
"message": "Custom OSD elements"
|
||||
|
@ -3809,13 +3815,13 @@
|
|||
"message": "GPS"
|
||||
},
|
||||
"osdGroupPowerLimits": {
|
||||
"message": "Power limits"
|
||||
"message": "Power Limits"
|
||||
},
|
||||
"osdGroupPIDs": {
|
||||
"message": "RC Adjustable Values"
|
||||
},
|
||||
"osdGroupPIDOutputs": {
|
||||
"message": "PID controllers outputs"
|
||||
"message": "PID Controllers Outputs"
|
||||
},
|
||||
"osdGroupVTX": {
|
||||
"message": "VTX"
|
||||
|
@ -3824,10 +3830,10 @@
|
|||
"message": "CRSF RX Statistics"
|
||||
},
|
||||
"osdGroupMapsAndRadars": {
|
||||
"message": "Maps and Radars"
|
||||
"message": "Maps & Radars"
|
||||
},
|
||||
"osdGroupMapsAndRadars_HELP": {
|
||||
"message": "Maps and radars allow laying out additional elements on top of them as long as they don't overlap any of the map parts visible in the preview."
|
||||
"message": "Maps & radars allow laying out additional elements on top of them as long as they don't overlap any of the map parts visible in the preview."
|
||||
},
|
||||
"osdElement_ONTIME_FLYTIME": {
|
||||
"message": "On Time / Fly Time"
|
||||
|
@ -3842,7 +3848,7 @@
|
|||
"message": "Battery Voltage"
|
||||
},
|
||||
"osdElement_SAG_COMP_MAIN_BATT_VOLTAGE": {
|
||||
"message": "Sag Compensated Battery Voltage"
|
||||
"message": "Sag-compensated Battery Voltage"
|
||||
},
|
||||
"osdElement_SAG_COMP_MAIN_BATT_VOLTAGE_HELP": {
|
||||
"message": "Calculated voltage the battery should be at without load (simulates ideal battery)"
|
||||
|
@ -3857,7 +3863,7 @@
|
|||
"message": "Battery Cell Voltage"
|
||||
},
|
||||
"osdElement_SAG_COMP_MAIN_BATT_CELL_VOLTAGE": {
|
||||
"message": "Sag Compensated Battery Cell Voltage"
|
||||
"message": "Sag-compensated Battery Cell Voltage"
|
||||
},
|
||||
"osdElement_SAG_COMP_MAIN_BATT_CELL_VOLTAGE_HELP": {
|
||||
"message": "Calculated average cell voltage the battery should be at without load (simulates ideal battery)"
|
||||
|
@ -4637,7 +4643,7 @@
|
|||
"message": "Warning:value beyond normal operation range."
|
||||
},
|
||||
"servoMixer": {
|
||||
"message": "Servo mixer"
|
||||
"message": "Servo Mixer"
|
||||
},
|
||||
"servoMixerDelete": {
|
||||
"message": "Delete"
|
||||
|
@ -4649,13 +4655,13 @@
|
|||
"message": "Platform type"
|
||||
},
|
||||
"platformConfiguration": {
|
||||
"message": "Platform configuration"
|
||||
"message": "Platform Configuration"
|
||||
},
|
||||
"output_modeTitle": {
|
||||
"message": "Output mode"
|
||||
},
|
||||
"mixerPreset": {
|
||||
"message": "Mixer preset"
|
||||
"message": "Mixer Preset"
|
||||
},
|
||||
"mixerNotLoaded": {
|
||||
"message": "Mixer not loaded.<br />Click <b>Load and apply</b> or <b>Load mixer</b> to use the selected mixer.<br />Or click <b>Refresh mixer</b> to use your current mixer."
|
||||
|
@ -5444,28 +5450,28 @@
|
|||
"message": "Dataflash: free space"
|
||||
},
|
||||
"mixerProfile1": {
|
||||
"message": "Mixer profile 1"
|
||||
"message": "Mixer Profile 1"
|
||||
},
|
||||
"mixerProfile2": {
|
||||
"message": "Mixer profile 2"
|
||||
"message": "Mixer Profile 2"
|
||||
},
|
||||
"sensorProfile1": {
|
||||
"message": "PID profile 1"
|
||||
"message": "PID Profile 1"
|
||||
},
|
||||
"sensorProfile2": {
|
||||
"message": "PID profile 2"
|
||||
"message": "PID Profile 2"
|
||||
},
|
||||
"sensorProfile3": {
|
||||
"message": "PID profile 3"
|
||||
"message": "PID Profile 3"
|
||||
},
|
||||
"sensorBatteryProfile1": {
|
||||
"message": "Battery profile 1"
|
||||
"message": "Battery Profile 1"
|
||||
},
|
||||
"sensorBatteryProfile2": {
|
||||
"message": "Battery profile 2"
|
||||
"message": "Battery Profile 2"
|
||||
},
|
||||
"sensorBatteryProfile3": {
|
||||
"message": "Battery profile 3"
|
||||
"message": "Battery Profile 3"
|
||||
},
|
||||
"sensorStatusGyro": {
|
||||
"message": "Gyroscope"
|
||||
|
@ -5745,7 +5751,7 @@
|
|||
"message": "Cannot prefetch target: No port"
|
||||
},
|
||||
"timerOutputs": {
|
||||
"message": "Timer outputs"
|
||||
"message": "Timer Outputs"
|
||||
},
|
||||
"ezTuneFilterHz": {
|
||||
"message": "Filter Hz"
|
||||
|
|
58
manifest.json
Normal file
58
manifest.json
Normal file
|
@ -0,0 +1,58 @@
|
|||
{
|
||||
"manifest_version": 2,
|
||||
"minimum_chrome_version": "38",
|
||||
"version": "7.1.1",
|
||||
"author": "Several",
|
||||
"name": "INAV - Configurator",
|
||||
"short_name": "INAV",
|
||||
"description": "Crossplatform configuration tool for INAVFlight flight control system",
|
||||
|
||||
"offline_enabled": true,
|
||||
|
||||
"default_locale": "en",
|
||||
|
||||
"app": {
|
||||
"background": {
|
||||
"scripts": ["eventPage.js"],
|
||||
"persistent": false
|
||||
}
|
||||
},
|
||||
|
||||
"sandbox": {
|
||||
"pages": ["tabs/map.html"]
|
||||
},
|
||||
|
||||
"sockets": {
|
||||
"udp": {
|
||||
"send": ["*"],
|
||||
"bind": ["*"]
|
||||
}
|
||||
},
|
||||
|
||||
"permissions": [
|
||||
"https://www.google-analytics.com/",
|
||||
"https://maps.googleapis.com/*",
|
||||
"https://*.github.com/",
|
||||
"https://*.githubusercontent.com/",
|
||||
"https://*.amazonaws.com/",
|
||||
"https://dev.virtualearth.net/",
|
||||
"serial",
|
||||
"usb",
|
||||
"bluetooth",
|
||||
"sockets",
|
||||
"storage",
|
||||
"fileSystem",
|
||||
"fileSystem.write",
|
||||
"fileSystem.retainEntries",
|
||||
"notifications",
|
||||
"alwaysOnTopWindows",
|
||||
{"usbDevices": [
|
||||
{"vendorId": 1155, "productId": 57105},
|
||||
{"vendorId": 11836, "productId": 57105}
|
||||
]}
|
||||
],
|
||||
|
||||
"icons": {
|
||||
"128": "images/inav_icon_128.png"
|
||||
}
|
||||
}
|
BIN
resources/models/ak8963c.bin
Normal file
BIN
resources/models/ak8963c.bin
Normal file
Binary file not shown.
938
resources/models/ak8963c.gltf
Normal file
938
resources/models/ak8963c.gltf
Normal file
|
@ -0,0 +1,938 @@
|
|||
{
|
||||
"asset": {
|
||||
"copyright": "",
|
||||
"generator": "SharpGLTF 1.0.0",
|
||||
"version": "2.0"
|
||||
},
|
||||
"accessors": [
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12840,
|
||||
"componentType": 5126,
|
||||
"count": 372,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7272,
|
||||
"componentType": 5123,
|
||||
"count": 1236,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"componentType": 5126,
|
||||
"count": 1070,
|
||||
"max": [
|
||||
4.9953060150146484,
|
||||
0.5,
|
||||
8.0056905746459961
|
||||
],
|
||||
"min": [
|
||||
-5.0046939849853516,
|
||||
-0.80099999904632568,
|
||||
-7.9943099021911621
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"componentType": 5123,
|
||||
"count": 3636,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23436,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
-0.10000000149011612,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
-0.10000000149011612,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12720,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23580,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
0.5,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
0.5,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12780,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24732,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
-0.10000000149011612,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
-0.10000000149011612,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13260,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24840,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
0.5,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
0.5,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13302,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23724,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
-0.10000000149011612,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
-0.10000000149011612,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12840,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23868,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
0.5,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
0.5,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12900,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23100,
|
||||
"componentType": 5126,
|
||||
"count": 14,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12576,
|
||||
"componentType": 5123,
|
||||
"count": 36,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24948,
|
||||
"componentType": 5126,
|
||||
"count": 7,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13344,
|
||||
"componentType": 5123,
|
||||
"count": 15,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 23268,
|
||||
"componentType": 5126,
|
||||
"count": 14,
|
||||
"max": [
|
||||
-2.0546939373016357,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12648,
|
||||
"componentType": 5123,
|
||||
"count": 36,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 25032,
|
||||
"componentType": 5126,
|
||||
"count": 7,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
1.3436071872711182
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13374,
|
||||
"componentType": 5123,
|
||||
"count": 15,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 17304,
|
||||
"componentType": 5126,
|
||||
"count": 99,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
4.8689289093017578
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
4.3929481506347656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9744,
|
||||
"componentType": 5123,
|
||||
"count": 303,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21420,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.2678921222686768,
|
||||
-0.80000001192092896,
|
||||
4.7072749137878418
|
||||
],
|
||||
"min": [
|
||||
1.1062382459640503,
|
||||
-0.80000001192092896,
|
||||
4.5546021461486816
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11790,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 22464,
|
||||
"componentType": 5126,
|
||||
"count": 28,
|
||||
"max": [
|
||||
0.98050755262374878,
|
||||
-0.80000001192092896,
|
||||
4.7431983947753906
|
||||
],
|
||||
"min": [
|
||||
0.78293061256408691,
|
||||
-0.80000001192092896,
|
||||
4.518679141998291
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12276,
|
||||
"componentType": 5123,
|
||||
"count": 78,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19500,
|
||||
"componentType": 5126,
|
||||
"count": 56,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
4.2941598892211914
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
3.8630828857421875
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10842,
|
||||
"componentType": 5123,
|
||||
"count": 168,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21768,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.2678921222686768,
|
||||
-0.80000001192092896,
|
||||
4.168428897857666
|
||||
],
|
||||
"min": [
|
||||
1.0703152418136597,
|
||||
-0.80000001192092896,
|
||||
3.9888136386871338
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11952,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20172,
|
||||
"componentType": 5126,
|
||||
"count": 56,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
3.7553136348724365
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
3.3242366313934326
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11178,
|
||||
"componentType": 5123,
|
||||
"count": 168,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 22116,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
0.98050755262374878,
|
||||
-0.80000001192092896,
|
||||
3.6295828819274902
|
||||
],
|
||||
"min": [
|
||||
0.78293061256408691,
|
||||
-0.80000001192092896,
|
||||
3.4499673843383789
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12114,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18492,
|
||||
"componentType": 5126,
|
||||
"count": 84,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
3.2254481315612793
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
2.7494673728942871
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10350,
|
||||
"componentType": 5123,
|
||||
"count": 246,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20844,
|
||||
"componentType": 5126,
|
||||
"count": 48,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
2.6596596240997314
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
1.9950827360153198
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11514,
|
||||
"componentType": 5123,
|
||||
"count": 138,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24012,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
5.0061497688293457
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
4.386476993560791
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12960,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24156,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
4.3505535125732422
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
3.7308807373046875
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13020,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24300,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
3.6949574947357178
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
3.075284481048584
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13080,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24444,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
3.0393614768981934
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
2.4196884632110596
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13140,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 24588,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
2.3837652206420898
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
1.7640922069549561
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 13200,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 22800,
|
||||
"componentType": 5126,
|
||||
"count": 25,
|
||||
"max": [
|
||||
-1.0421727895736694,
|
||||
-0.80099999904632568,
|
||||
2.3097355365753174
|
||||
],
|
||||
"min": [
|
||||
-1.7367434501647949,
|
||||
-0.80099999904632568,
|
||||
1.6151648759841919
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12432,
|
||||
"componentType": 5123,
|
||||
"count": 72,
|
||||
"type": "SCALAR"
|
||||
}
|
||||
],
|
||||
"bufferViews": [
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 25116,
|
||||
"byteStride": 12,
|
||||
"target": 34962
|
||||
},
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 13404,
|
||||
"byteOffset": 25116,
|
||||
"target": 34963
|
||||
}
|
||||
],
|
||||
"buffers": [
|
||||
{
|
||||
"byteLength": 38520,
|
||||
"uri": "ak8963c.bin"
|
||||
}
|
||||
],
|
||||
"materials": [
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.0431372561,
|
||||
0.0431372561,
|
||||
0.647058845,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {}
|
||||
}
|
||||
],
|
||||
"meshes": [
|
||||
{
|
||||
"primitives": [
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 0
|
||||
},
|
||||
"indices": 1,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 2
|
||||
},
|
||||
"indices": 3,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 4
|
||||
},
|
||||
"indices": 5,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 6
|
||||
},
|
||||
"indices": 7,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 8
|
||||
},
|
||||
"indices": 9,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 10
|
||||
},
|
||||
"indices": 11,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 12
|
||||
},
|
||||
"indices": 13,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 14
|
||||
},
|
||||
"indices": 15,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 16
|
||||
},
|
||||
"indices": 17,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 18
|
||||
},
|
||||
"indices": 19,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 20
|
||||
},
|
||||
"indices": 21,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 22
|
||||
},
|
||||
"indices": 23,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 24
|
||||
},
|
||||
"indices": 25,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 26
|
||||
},
|
||||
"indices": 27,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 28
|
||||
},
|
||||
"indices": 29,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 30
|
||||
},
|
||||
"indices": 31,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 32
|
||||
},
|
||||
"indices": 33,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 34
|
||||
},
|
||||
"indices": 35,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 36
|
||||
},
|
||||
"indices": 37,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 38
|
||||
},
|
||||
"indices": 39,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 40
|
||||
},
|
||||
"indices": 41,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 42
|
||||
},
|
||||
"indices": 43,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 44
|
||||
},
|
||||
"indices": 45,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 46
|
||||
},
|
||||
"indices": 47,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 48
|
||||
},
|
||||
"indices": 49,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 50
|
||||
},
|
||||
"indices": 51,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 52
|
||||
},
|
||||
"indices": 53,
|
||||
"material": 2
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"nodes": [
|
||||
{
|
||||
"mesh": 0
|
||||
}
|
||||
],
|
||||
"scene": 0,
|
||||
"scenes": [
|
||||
{
|
||||
"nodes": [
|
||||
0
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
BIN
resources/models/ak8963n.bin
Normal file
BIN
resources/models/ak8963n.bin
Normal file
Binary file not shown.
1802
resources/models/ak8963n.gltf
Normal file
1802
resources/models/ak8963n.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/ak8975.bin
Normal file
BIN
resources/models/ak8975.bin
Normal file
Binary file not shown.
1514
resources/models/ak8975.gltf
Normal file
1514
resources/models/ak8975.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/ak8975c.bin
Normal file
BIN
resources/models/ak8975c.bin
Normal file
Binary file not shown.
906
resources/models/ak8975c.gltf
Normal file
906
resources/models/ak8975c.gltf
Normal file
|
@ -0,0 +1,906 @@
|
|||
{
|
||||
"asset": {
|
||||
"copyright": "",
|
||||
"generator": "SharpGLTF 1.0.0",
|
||||
"version": "2.0"
|
||||
},
|
||||
"accessors": [
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 10932,
|
||||
"componentType": 5126,
|
||||
"count": 347,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 6318,
|
||||
"componentType": 5123,
|
||||
"count": 1221,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"componentType": 5126,
|
||||
"count": 911,
|
||||
"max": [
|
||||
4.9953060150146484,
|
||||
0.5,
|
||||
8.0056905746459961
|
||||
],
|
||||
"min": [
|
||||
-5.0046939849853516,
|
||||
-0.80099999904632568,
|
||||
-7.9943099021911621
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"componentType": 5123,
|
||||
"count": 3159,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19824,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
-0.10000000149011612,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
-0.10000000149011612,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11046,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19968,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
0.5,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
0.5,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11106,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21120,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
-0.10000000149011612,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
-0.10000000149011612,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11586,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21228,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
0.5,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
0.5,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11628,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20112,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
-0.10000000149011612,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
-0.10000000149011612,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11166,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20256,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
0.5,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
0.5,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11226,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19488,
|
||||
"componentType": 5126,
|
||||
"count": 14,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10902,
|
||||
"componentType": 5123,
|
||||
"count": 36,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21336,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11670,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19656,
|
||||
"componentType": 5126,
|
||||
"count": 14,
|
||||
"max": [
|
||||
-2.0546939373016357,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10974,
|
||||
"componentType": 5123,
|
||||
"count": 36,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21444,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
1.3436071872711182
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11712,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 15096,
|
||||
"componentType": 5126,
|
||||
"count": 99,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
4.8689289093017578
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
4.3929481506347656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 8760,
|
||||
"componentType": 5123,
|
||||
"count": 303,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18156,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.2678921222686768,
|
||||
-0.80000001192092896,
|
||||
4.7072749137878418
|
||||
],
|
||||
"min": [
|
||||
1.1062382459640503,
|
||||
-0.80000001192092896,
|
||||
4.5546021461486816
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10278,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18852,
|
||||
"componentType": 5126,
|
||||
"count": 28,
|
||||
"max": [
|
||||
0.98050755262374878,
|
||||
-0.80000001192092896,
|
||||
4.7431983947753906
|
||||
],
|
||||
"min": [
|
||||
0.78293061256408691,
|
||||
-0.80000001192092896,
|
||||
4.518679141998291
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10602,
|
||||
"componentType": 5123,
|
||||
"count": 78,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 16284,
|
||||
"componentType": 5126,
|
||||
"count": 56,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
4.2941598892211914
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
3.8630828857421875
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9366,
|
||||
"componentType": 5123,
|
||||
"count": 168,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18504,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.2678921222686768,
|
||||
-0.80000001192092896,
|
||||
4.168428897857666
|
||||
],
|
||||
"min": [
|
||||
1.0703152418136597,
|
||||
-0.80000001192092896,
|
||||
3.9888136386871338
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10440,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21552,
|
||||
"componentType": 5126,
|
||||
"count": 7,
|
||||
"max": [
|
||||
1.3756613731384277,
|
||||
-0.80099999904632568,
|
||||
3.7463328838348389
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
3.2972943782806396
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11754,
|
||||
"componentType": 5123,
|
||||
"count": 15,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 16956,
|
||||
"componentType": 5126,
|
||||
"count": 52,
|
||||
"max": [
|
||||
1.3756613731384277,
|
||||
-0.80099999904632568,
|
||||
3.234428882598877
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
2.7674288749694824
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9702,
|
||||
"componentType": 5123,
|
||||
"count": 150,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 17580,
|
||||
"componentType": 5126,
|
||||
"count": 48,
|
||||
"max": [
|
||||
1.393622875213623,
|
||||
-0.80099999904632568,
|
||||
2.6596596240997314
|
||||
],
|
||||
"min": [
|
||||
0.65719985961914063,
|
||||
-0.80099999904632568,
|
||||
1.9950827360153198
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10002,
|
||||
"componentType": 5123,
|
||||
"count": 138,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20400,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
5.0061497688293457
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
4.386476993560791
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11286,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20544,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
4.3505535125732422
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
3.7308807373046875
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11346,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20688,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
3.6949574947357178
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
3.075284481048584
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11406,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20832,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
3.0393614768981934
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
2.4196884632110596
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11466,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20976,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
0.026193868368864059,
|
||||
-0.80099999904632568,
|
||||
2.3837652206420898
|
||||
],
|
||||
"min": [
|
||||
-0.67430615425109863,
|
||||
-0.80099999904632568,
|
||||
1.7640922069549561
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11526,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19188,
|
||||
"componentType": 5126,
|
||||
"count": 25,
|
||||
"max": [
|
||||
-1.0421727895736694,
|
||||
-0.80099999904632568,
|
||||
2.3097355365753174
|
||||
],
|
||||
"min": [
|
||||
-1.7367434501647949,
|
||||
-0.80099999904632568,
|
||||
1.6151648759841919
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10758,
|
||||
"componentType": 5123,
|
||||
"count": 72,
|
||||
"type": "SCALAR"
|
||||
}
|
||||
],
|
||||
"bufferViews": [
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 21636,
|
||||
"byteStride": 12,
|
||||
"target": 34962
|
||||
},
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 11784,
|
||||
"byteOffset": 21636,
|
||||
"target": 34963
|
||||
}
|
||||
],
|
||||
"buffers": [
|
||||
{
|
||||
"byteLength": 33420,
|
||||
"uri": "ak8975c.bin"
|
||||
}
|
||||
],
|
||||
"materials": [
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.0431372561,
|
||||
0.0431372561,
|
||||
0.647058845,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {}
|
||||
}
|
||||
],
|
||||
"meshes": [
|
||||
{
|
||||
"primitives": [
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 0
|
||||
},
|
||||
"indices": 1,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 2
|
||||
},
|
||||
"indices": 3,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 4
|
||||
},
|
||||
"indices": 5,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 6
|
||||
},
|
||||
"indices": 7,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 8
|
||||
},
|
||||
"indices": 9,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 10
|
||||
},
|
||||
"indices": 11,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 12
|
||||
},
|
||||
"indices": 13,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 14
|
||||
},
|
||||
"indices": 15,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 16
|
||||
},
|
||||
"indices": 17,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 18
|
||||
},
|
||||
"indices": 19,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 20
|
||||
},
|
||||
"indices": 21,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 22
|
||||
},
|
||||
"indices": 23,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 24
|
||||
},
|
||||
"indices": 25,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 26
|
||||
},
|
||||
"indices": 27,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 28
|
||||
},
|
||||
"indices": 29,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 30
|
||||
},
|
||||
"indices": 31,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 32
|
||||
},
|
||||
"indices": 33,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 34
|
||||
},
|
||||
"indices": 35,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 36
|
||||
},
|
||||
"indices": 37,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 38
|
||||
},
|
||||
"indices": 39,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 40
|
||||
},
|
||||
"indices": 41,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 42
|
||||
},
|
||||
"indices": 43,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 44
|
||||
},
|
||||
"indices": 45,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 46
|
||||
},
|
||||
"indices": 47,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 48
|
||||
},
|
||||
"indices": 49,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 50
|
||||
},
|
||||
"indices": 51,
|
||||
"material": 2
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"nodes": [
|
||||
{
|
||||
"mesh": 0
|
||||
}
|
||||
],
|
||||
"scene": 0,
|
||||
"scenes": [
|
||||
{
|
||||
"nodes": [
|
||||
0
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
BIN
resources/models/bn_880.bin
Normal file
BIN
resources/models/bn_880.bin
Normal file
Binary file not shown.
2291
resources/models/bn_880.gltf
Normal file
2291
resources/models/bn_880.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/diatone_mamba_m10_pro.bin
Normal file
BIN
resources/models/diatone_mamba_m10_pro.bin
Normal file
Binary file not shown.
3104
resources/models/diatone_mamba_m10_pro.gltf
Normal file
3104
resources/models/diatone_mamba_m10_pro.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/flywoo_goku_m10_pro_v3.bin
Normal file
BIN
resources/models/flywoo_goku_m10_pro_v3.bin
Normal file
Binary file not shown.
3403
resources/models/flywoo_goku_m10_pro_v3.gltf
Normal file
3403
resources/models/flywoo_goku_m10_pro_v3.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/foxeer_m10q_120.bin
Normal file
BIN
resources/models/foxeer_m10q_120.bin
Normal file
Binary file not shown.
2945
resources/models/foxeer_m10q_120.gltf
Normal file
2945
resources/models/foxeer_m10q_120.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/foxeer_m10q_180.bin
Normal file
BIN
resources/models/foxeer_m10q_180.bin
Normal file
Binary file not shown.
3158
resources/models/foxeer_m10q_180.gltf
Normal file
3158
resources/models/foxeer_m10q_180.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/foxeer_m10q_250.bin
Normal file
BIN
resources/models/foxeer_m10q_250.bin
Normal file
Binary file not shown.
3158
resources/models/foxeer_m10q_250.gltf
Normal file
3158
resources/models/foxeer_m10q_250.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/geprc_gep_m10_dq.bin
Normal file
BIN
resources/models/geprc_gep_m10_dq.bin
Normal file
Binary file not shown.
3083
resources/models/geprc_gep_m10_dq.gltf
Normal file
3083
resources/models/geprc_gep_m10_dq.gltf
Normal file
File diff suppressed because it is too large
Load diff
File diff suppressed because one or more lines are too long
BIN
resources/models/gy271.bin
Normal file
BIN
resources/models/gy271.bin
Normal file
Binary file not shown.
5867
resources/models/gy271.gltf
Normal file
5867
resources/models/gy271.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/gy273.bin
Normal file
BIN
resources/models/gy273.bin
Normal file
Binary file not shown.
4821
resources/models/gy273.gltf
Normal file
4821
resources/models/gy273.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/hglrc_m100.bin
Normal file
BIN
resources/models/hglrc_m100.bin
Normal file
Binary file not shown.
3286
resources/models/hglrc_m100.gltf
Normal file
3286
resources/models/hglrc_m100.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/holybro_m9n_micro.bin
Normal file
BIN
resources/models/holybro_m9n_micro.bin
Normal file
Binary file not shown.
3798
resources/models/holybro_m9n_micro.gltf
Normal file
3798
resources/models/holybro_m9n_micro.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/ist8308.bin
Normal file
BIN
resources/models/ist8308.bin
Normal file
Binary file not shown.
1034
resources/models/ist8308.gltf
Normal file
1034
resources/models/ist8308.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/ist8310.bin
Normal file
BIN
resources/models/ist8310.bin
Normal file
Binary file not shown.
970
resources/models/ist8310.gltf
Normal file
970
resources/models/ist8310.gltf
Normal file
|
@ -0,0 +1,970 @@
|
|||
{
|
||||
"asset": {
|
||||
"copyright": "",
|
||||
"generator": "SharpGLTF 1.0.0",
|
||||
"version": "2.0"
|
||||
},
|
||||
"accessors": [
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11472,
|
||||
"componentType": 5126,
|
||||
"count": 245,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7104,
|
||||
"componentType": 5123,
|
||||
"count": 876,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"componentType": 5126,
|
||||
"count": 956,
|
||||
"max": [
|
||||
4.9953060150146484,
|
||||
0.5,
|
||||
8.0056905746459961
|
||||
],
|
||||
"min": [
|
||||
-5.0046939849853516,
|
||||
-0.80099999904632568,
|
||||
-7.9943099021911621
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"componentType": 5123,
|
||||
"count": 3552,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20028,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
-0.10000000149011612,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
-0.10000000149011612,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11598,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20172,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
0.5,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
0.5,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11658,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21132,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.956756591796875,
|
||||
-0.10000000149011612,
|
||||
-3.8916456699371338
|
||||
],
|
||||
"min": [
|
||||
2.1567566394805908,
|
||||
-0.10000000149011612,
|
||||
-5.2531838417053223
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12054,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21240,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.956756591796875,
|
||||
0.5,
|
||||
-3.8916456699371338
|
||||
],
|
||||
"min": [
|
||||
2.1567566394805908,
|
||||
0.5,
|
||||
-5.2531838417053223
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12096,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20316,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
-0.10000000149011612,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
-0.10000000149011612,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11718,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20460,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
0.5,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
0.5,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11778,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21420,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
3.2300682067871094,
|
||||
-0.10000000149011612,
|
||||
-3.41383957862854
|
||||
],
|
||||
"min": [
|
||||
2.9323132038116455,
|
||||
-0.10000000149011612,
|
||||
-4.0331988334655762
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12162,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21468,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
3.2300682067871094,
|
||||
0.5,
|
||||
-3.41383957862854
|
||||
],
|
||||
"min": [
|
||||
2.9323132038116455,
|
||||
0.5,
|
||||
-4.0331988334655762
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12174,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20604,
|
||||
"componentType": 5126,
|
||||
"count": 11,
|
||||
"max": [
|
||||
-2.0546939373016357,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11838,
|
||||
"componentType": 5123,
|
||||
"count": 27,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20736,
|
||||
"componentType": 5126,
|
||||
"count": 11,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
1.3436071872711182
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11892,
|
||||
"componentType": 5123,
|
||||
"count": 27,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 20868,
|
||||
"componentType": 5126,
|
||||
"count": 11,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11946,
|
||||
"componentType": 5123,
|
||||
"count": 27,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21000,
|
||||
"componentType": 5126,
|
||||
"count": 11,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12000,
|
||||
"componentType": 5123,
|
||||
"count": 27,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 16500,
|
||||
"componentType": 5126,
|
||||
"count": 56,
|
||||
"max": [
|
||||
0.017961539328098297,
|
||||
-0.80099999904632568,
|
||||
2.8317668437957764
|
||||
],
|
||||
"min": [
|
||||
-0.71846151351928711,
|
||||
-0.80099999904632568,
|
||||
2.4006898403167725
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9900,
|
||||
"componentType": 5123,
|
||||
"count": 168,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 17832,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
-0.39515385031700134,
|
||||
-0.80000001192092896,
|
||||
2.7060360908508301
|
||||
],
|
||||
"min": [
|
||||
-0.59273076057434082,
|
||||
-0.80000001192092896,
|
||||
2.5264205932617188
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10566,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19860,
|
||||
"componentType": 5126,
|
||||
"count": 14,
|
||||
"max": [
|
||||
0,
|
||||
-0.80099999904632568,
|
||||
3.3975551128387451
|
||||
],
|
||||
"min": [
|
||||
-0.71846151351928711,
|
||||
-0.80099999904632568,
|
||||
2.9125936031341553
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11514,
|
||||
"componentType": 5123,
|
||||
"count": 42,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21516,
|
||||
"componentType": 5126,
|
||||
"count": 3,
|
||||
"max": [
|
||||
-0.26044231653213501,
|
||||
-0.80000001192092896,
|
||||
3.2089591026306152
|
||||
],
|
||||
"min": [
|
||||
-0.4988536536693573,
|
||||
-0.80000001192092896,
|
||||
3.0539004802703857
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12186,
|
||||
"componentType": 5123,
|
||||
"count": 3,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 17172,
|
||||
"componentType": 5126,
|
||||
"count": 55,
|
||||
"max": [
|
||||
0.017961539328098297,
|
||||
-0.80099999904632568,
|
||||
3.9184398651123047
|
||||
],
|
||||
"min": [
|
||||
-0.71846151351928711,
|
||||
-0.80099999904632568,
|
||||
3.4873628616333008
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10236,
|
||||
"componentType": 5123,
|
||||
"count": 165,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19224,
|
||||
"componentType": 5126,
|
||||
"count": 28,
|
||||
"max": [
|
||||
-0.10776922851800919,
|
||||
-0.80000001192092896,
|
||||
3.7927091121673584
|
||||
],
|
||||
"min": [
|
||||
-0.30534616112709045,
|
||||
-0.80000001192092896,
|
||||
3.6130936145782471
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11214,
|
||||
"componentType": 5123,
|
||||
"count": 78,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 14412,
|
||||
"componentType": 5126,
|
||||
"count": 58,
|
||||
"max": [
|
||||
0.017961539328098297,
|
||||
-0.80099999904632568,
|
||||
4.4932088851928711
|
||||
],
|
||||
"min": [
|
||||
-0.71846151351928711,
|
||||
-0.80099999904632568,
|
||||
4.0172281265258789
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 8856,
|
||||
"componentType": 5123,
|
||||
"count": 174,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18180,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
-0.10776922851800919,
|
||||
-0.80000001192092896,
|
||||
4.3674783706665039
|
||||
],
|
||||
"min": [
|
||||
-0.59273076057434082,
|
||||
-0.80000001192092896,
|
||||
4.1429591178894043
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10728,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 15108,
|
||||
"componentType": 5126,
|
||||
"count": 58,
|
||||
"max": [
|
||||
1.2303953170776367,
|
||||
-0.80099999904632568,
|
||||
2.9386186599731445
|
||||
],
|
||||
"min": [
|
||||
0.4939723014831543,
|
||||
-0.80099999904632568,
|
||||
2.4626379013061523
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9204,
|
||||
"componentType": 5123,
|
||||
"count": 174,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18528,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.1046645641326904,
|
||||
-0.80000001192092896,
|
||||
2.8128879070281982
|
||||
],
|
||||
"min": [
|
||||
0.61970305442810059,
|
||||
-0.80000001192092896,
|
||||
2.5883686542510986
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 10890,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 21348,
|
||||
"componentType": 5126,
|
||||
"count": 6,
|
||||
"max": [
|
||||
1.2124338150024414,
|
||||
-0.80099999904632568,
|
||||
3.3337724208831787
|
||||
],
|
||||
"min": [
|
||||
0.51193386316299438,
|
||||
-0.80099999904632568,
|
||||
3.0643494129180908
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 12138,
|
||||
"componentType": 5123,
|
||||
"count": 12,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 15804,
|
||||
"componentType": 5126,
|
||||
"count": 58,
|
||||
"max": [
|
||||
1.2303953170776367,
|
||||
-0.80099999904632568,
|
||||
4.0342726707458496
|
||||
],
|
||||
"min": [
|
||||
0.4939723014831543,
|
||||
-0.80099999904632568,
|
||||
3.5582916736602783
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 9552,
|
||||
"componentType": 5123,
|
||||
"count": 174,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 18876,
|
||||
"componentType": 5126,
|
||||
"count": 29,
|
||||
"max": [
|
||||
1.1046645641326904,
|
||||
-0.80000001192092896,
|
||||
3.9085416793823242
|
||||
],
|
||||
"min": [
|
||||
0.61970305442810059,
|
||||
-0.80000001192092896,
|
||||
3.6840224266052246
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11052,
|
||||
"componentType": 5123,
|
||||
"count": 81,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 19560,
|
||||
"componentType": 5126,
|
||||
"count": 25,
|
||||
"max": [
|
||||
1.2916426658630371,
|
||||
-0.80099999904632568,
|
||||
4.8460783958435059
|
||||
],
|
||||
"min": [
|
||||
0.70874124765396118,
|
||||
-0.80099999904632568,
|
||||
4.2631773948669434
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 11370,
|
||||
"componentType": 5123,
|
||||
"count": 72,
|
||||
"type": "SCALAR"
|
||||
}
|
||||
],
|
||||
"bufferViews": [
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 21552,
|
||||
"byteStride": 12,
|
||||
"target": 34962
|
||||
},
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 12192,
|
||||
"byteOffset": 21552,
|
||||
"target": 34963
|
||||
}
|
||||
],
|
||||
"buffers": [
|
||||
{
|
||||
"byteLength": 33744,
|
||||
"uri": "ist8310.bin"
|
||||
}
|
||||
],
|
||||
"materials": [
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.0431372561,
|
||||
0.0431372561,
|
||||
0.647058845,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {}
|
||||
}
|
||||
],
|
||||
"meshes": [
|
||||
{
|
||||
"primitives": [
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 0
|
||||
},
|
||||
"indices": 1,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 2
|
||||
},
|
||||
"indices": 3,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 4
|
||||
},
|
||||
"indices": 5,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 6
|
||||
},
|
||||
"indices": 7,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 8
|
||||
},
|
||||
"indices": 9,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 10
|
||||
},
|
||||
"indices": 11,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 12
|
||||
},
|
||||
"indices": 13,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 14
|
||||
},
|
||||
"indices": 15,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 16
|
||||
},
|
||||
"indices": 17,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 18
|
||||
},
|
||||
"indices": 19,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 20
|
||||
},
|
||||
"indices": 21,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 22
|
||||
},
|
||||
"indices": 23,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 24
|
||||
},
|
||||
"indices": 25,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 26
|
||||
},
|
||||
"indices": 27,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 28
|
||||
},
|
||||
"indices": 29,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 30
|
||||
},
|
||||
"indices": 31,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 32
|
||||
},
|
||||
"indices": 33,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 34
|
||||
},
|
||||
"indices": 35,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 36
|
||||
},
|
||||
"indices": 37,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 38
|
||||
},
|
||||
"indices": 39,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 40
|
||||
},
|
||||
"indices": 41,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 42
|
||||
},
|
||||
"indices": 43,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 44
|
||||
},
|
||||
"indices": 45,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 46
|
||||
},
|
||||
"indices": 47,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 48
|
||||
},
|
||||
"indices": 49,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 50
|
||||
},
|
||||
"indices": 51,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 52
|
||||
},
|
||||
"indices": 53,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 54
|
||||
},
|
||||
"indices": 55,
|
||||
"material": 2
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"nodes": [
|
||||
{
|
||||
"mesh": 0
|
||||
}
|
||||
],
|
||||
"scene": 0,
|
||||
"scenes": [
|
||||
{
|
||||
"nodes": [
|
||||
0
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
BIN
resources/models/lis3mdl.bin
Normal file
BIN
resources/models/lis3mdl.bin
Normal file
Binary file not shown.
906
resources/models/lis3mdl.gltf
Normal file
906
resources/models/lis3mdl.gltf
Normal file
|
@ -0,0 +1,906 @@
|
|||
{
|
||||
"asset": {
|
||||
"copyright": "",
|
||||
"generator": "SharpGLTF 1.0.0",
|
||||
"version": "2.0"
|
||||
},
|
||||
"accessors": [
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"componentType": 5126,
|
||||
"count": 577,
|
||||
"max": [
|
||||
4.9953060150146484,
|
||||
0.5,
|
||||
8.0056905746459961
|
||||
],
|
||||
"min": [
|
||||
-5.0046939849853516,
|
||||
-0.80099999904632568,
|
||||
-7.9943099021911621
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"componentType": 5123,
|
||||
"count": 2157,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 6924,
|
||||
"componentType": 5126,
|
||||
"count": 195,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 4314,
|
||||
"componentType": 5123,
|
||||
"count": 690,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11556,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
-0.10000000149011612,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
-0.10000000149011612,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7092,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11700,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.5000522136688232,
|
||||
0.5,
|
||||
-5.6033802032470703
|
||||
],
|
||||
"min": [
|
||||
-0.29994779825210571,
|
||||
0.5,
|
||||
-7.1956877708435059
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7152,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12804,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
-0.10000000149011612,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
-0.10000000149011612,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7608,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12912,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
3.773174524307251,
|
||||
0.5,
|
||||
-3.3956716060638428
|
||||
],
|
||||
"min": [
|
||||
1.9731744527816772,
|
||||
0.5,
|
||||
-4.7572102546691895
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7650,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11844,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
-0.10000000149011612,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
-0.10000000149011612,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7212,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11988,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
3.6567566394805908,
|
||||
0.5,
|
||||
-0.70463287830352783
|
||||
],
|
||||
"min": [
|
||||
-3.2289743423461914,
|
||||
0.5,
|
||||
-7.1797943115234375
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7272,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12564,
|
||||
"componentType": 5126,
|
||||
"count": 10,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
2.0453059673309326,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7512,
|
||||
"componentType": 5123,
|
||||
"count": 24,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13020,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
5.4436073303222656
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7692,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12684,
|
||||
"componentType": 5126,
|
||||
"count": 10,
|
||||
"max": [
|
||||
-2.0546939373016357,
|
||||
0,
|
||||
5.4436073303222656
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7560,
|
||||
"componentType": 5123,
|
||||
"count": 24,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13128,
|
||||
"componentType": 5126,
|
||||
"count": 9,
|
||||
"max": [
|
||||
2.0453059673309326,
|
||||
0,
|
||||
1.3436071872711182
|
||||
],
|
||||
"min": [
|
||||
-2.0546939373016357,
|
||||
-0.80000001192092896,
|
||||
1.3436071872711182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7734,
|
||||
"componentType": 5123,
|
||||
"count": 21,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13236,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
-1.04770827293396,
|
||||
-0.80099999904632568,
|
||||
2.9754443168640137
|
||||
],
|
||||
"min": [
|
||||
-1.7482082843780518,
|
||||
-0.80099999904632568,
|
||||
2.8497135639190674
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7776,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11400,
|
||||
"componentType": 5126,
|
||||
"count": 13,
|
||||
"max": [
|
||||
-1.04770827293396,
|
||||
-0.80099999904632568,
|
||||
3.8914828300476074
|
||||
],
|
||||
"min": [
|
||||
-1.7482082843780518,
|
||||
-0.80099999904632568,
|
||||
3.074232816696167
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7026,
|
||||
"componentType": 5123,
|
||||
"count": 33,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12132,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.7195684909820557,
|
||||
-0.80099999904632568,
|
||||
3.018822193145752
|
||||
],
|
||||
"min": [
|
||||
1.0190684795379639,
|
||||
-0.80099999904632568,
|
||||
2.3991491794586182
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7332,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12276,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.7195684909820557,
|
||||
-0.80099999904632568,
|
||||
3.6744182109832764
|
||||
],
|
||||
"min": [
|
||||
1.0190684795379639,
|
||||
-0.80099999904632568,
|
||||
3.0547451972961426
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7392,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 12420,
|
||||
"componentType": 5126,
|
||||
"count": 12,
|
||||
"max": [
|
||||
1.7195684909820557,
|
||||
-0.80099999904632568,
|
||||
4.3300142288208008
|
||||
],
|
||||
"min": [
|
||||
1.0190684795379639,
|
||||
-0.80099999904632568,
|
||||
3.7103414535522461
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7452,
|
||||
"componentType": 5123,
|
||||
"count": 30,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 11100,
|
||||
"componentType": 5126,
|
||||
"count": 25,
|
||||
"max": [
|
||||
-1.0421727895736694,
|
||||
-0.80099999904632568,
|
||||
2.3097355365753174
|
||||
],
|
||||
"min": [
|
||||
-1.7367434501647949,
|
||||
-0.80099999904632568,
|
||||
1.6151648759841919
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 6882,
|
||||
"componentType": 5123,
|
||||
"count": 72,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 9264,
|
||||
"componentType": 5126,
|
||||
"count": 153,
|
||||
"max": [
|
||||
0.66008853912353516,
|
||||
-0.80099999904632568,
|
||||
4.0759797096252441
|
||||
],
|
||||
"min": [
|
||||
-0.62536025047302246,
|
||||
-0.80099999904632568,
|
||||
2.584604024887085
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 5694,
|
||||
"componentType": 5123,
|
||||
"count": 594,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13284,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
-0.079109802842140198,
|
||||
-0.80000001192092896,
|
||||
3.7902491092681885
|
||||
],
|
||||
"min": [
|
||||
-0.25318238139152527,
|
||||
-0.80000001192092896,
|
||||
3.6522059440612793
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7788,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13332,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
0.3052651584148407,
|
||||
-0.80000001192092896,
|
||||
3.4653904438018799
|
||||
],
|
||||
"min": [
|
||||
0.11779748648405075,
|
||||
-0.80000001192092896,
|
||||
3.2625560760498047
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7800,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13380,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
0.3052651584148407,
|
||||
-0.80000001192092896,
|
||||
3.829012393951416
|
||||
],
|
||||
"min": [
|
||||
0.080602861940860748,
|
||||
-0.80000001192092896,
|
||||
3.6522059440612793
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7812,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13428,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
0.3052651584148407,
|
||||
-0.80000001192092896,
|
||||
3.0599777698516846
|
||||
],
|
||||
"min": [
|
||||
0.15448287129402161,
|
||||
-0.80000001192092896,
|
||||
2.8839287757873535
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7824,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13476,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
0.034518804401159286,
|
||||
-0.80000001192092896,
|
||||
3.104076623916626
|
||||
],
|
||||
"min": [
|
||||
-0.16614609956741333,
|
||||
-0.80000001192092896,
|
||||
2.9584465026855469
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7836,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13524,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
-0.065813645720481873,
|
||||
-0.80000001192092896,
|
||||
3.4653904438018799
|
||||
],
|
||||
"min": [
|
||||
-0.22635035216808319,
|
||||
-0.80000001192092896,
|
||||
3.3302919864654541
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7848,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
},
|
||||
{
|
||||
"name": "POSITION",
|
||||
"bufferView": 0,
|
||||
"byteOffset": 13572,
|
||||
"componentType": 5126,
|
||||
"count": 4,
|
||||
"max": [
|
||||
-0.36765891313552856,
|
||||
-0.80000001192092896,
|
||||
3.6211795806884766
|
||||
],
|
||||
"min": [
|
||||
-0.51925498247146606,
|
||||
-0.80000001192092896,
|
||||
3.4653904438018799
|
||||
],
|
||||
"type": "VEC3"
|
||||
},
|
||||
{
|
||||
"bufferView": 1,
|
||||
"byteOffset": 7860,
|
||||
"componentType": 5123,
|
||||
"count": 6,
|
||||
"type": "SCALAR"
|
||||
}
|
||||
],
|
||||
"bufferViews": [
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 13620,
|
||||
"byteStride": 12,
|
||||
"target": 34962
|
||||
},
|
||||
{
|
||||
"buffer": 0,
|
||||
"byteLength": 7872,
|
||||
"byteOffset": 13620,
|
||||
"target": 34963
|
||||
}
|
||||
],
|
||||
"buffers": [
|
||||
{
|
||||
"byteLength": 21492,
|
||||
"uri": "lis3mdl.bin"
|
||||
}
|
||||
],
|
||||
"materials": [
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.0431372561,
|
||||
0.0431372561,
|
||||
0.647058845,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {
|
||||
"baseColorFactor": [
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
0.125490203,
|
||||
1
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"doubleSided": true,
|
||||
"pbrMetallicRoughness": {}
|
||||
}
|
||||
],
|
||||
"meshes": [
|
||||
{
|
||||
"primitives": [
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 0
|
||||
},
|
||||
"indices": 1,
|
||||
"material": 0
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 2
|
||||
},
|
||||
"indices": 3,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 4
|
||||
},
|
||||
"indices": 5,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 6
|
||||
},
|
||||
"indices": 7,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 8
|
||||
},
|
||||
"indices": 9,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 10
|
||||
},
|
||||
"indices": 11,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 12
|
||||
},
|
||||
"indices": 13,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 14
|
||||
},
|
||||
"indices": 15,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 16
|
||||
},
|
||||
"indices": 17,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 18
|
||||
},
|
||||
"indices": 19,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 20
|
||||
},
|
||||
"indices": 21,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 22
|
||||
},
|
||||
"indices": 23,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 24
|
||||
},
|
||||
"indices": 25,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 26
|
||||
},
|
||||
"indices": 27,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 28
|
||||
},
|
||||
"indices": 29,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 30
|
||||
},
|
||||
"indices": 31,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 32
|
||||
},
|
||||
"indices": 33,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 34
|
||||
},
|
||||
"indices": 35,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 36
|
||||
},
|
||||
"indices": 37,
|
||||
"material": 2
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 38
|
||||
},
|
||||
"indices": 39,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 40
|
||||
},
|
||||
"indices": 41,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 42
|
||||
},
|
||||
"indices": 43,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 44
|
||||
},
|
||||
"indices": 45,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 46
|
||||
},
|
||||
"indices": 47,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 48
|
||||
},
|
||||
"indices": 49,
|
||||
"material": 1
|
||||
},
|
||||
{
|
||||
"attributes": {
|
||||
"POSITION": 50
|
||||
},
|
||||
"indices": 51,
|
||||
"material": 1
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"nodes": [
|
||||
{
|
||||
"mesh": 0
|
||||
}
|
||||
],
|
||||
"scene": 0,
|
||||
"scenes": [
|
||||
{
|
||||
"nodes": [
|
||||
0
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
BIN
resources/models/mag3110.bin
Normal file
BIN
resources/models/mag3110.bin
Normal file
Binary file not shown.
1034
resources/models/mag3110.gltf
Normal file
1034
resources/models/mag3110.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/matek_m10q.bin
Normal file
BIN
resources/models/matek_m10q.bin
Normal file
Binary file not shown.
3902
resources/models/matek_m10q.gltf
Normal file
3902
resources/models/matek_m10q.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/matek_m8q.bin
Normal file
BIN
resources/models/matek_m8q.bin
Normal file
Binary file not shown.
3678
resources/models/matek_m8q.gltf
Normal file
3678
resources/models/matek_m8q.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/matek_m9n.bin
Normal file
BIN
resources/models/matek_m9n.bin
Normal file
Binary file not shown.
3478
resources/models/matek_m9n.gltf
Normal file
3478
resources/models/matek_m9n.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/mlx90393.bin
Normal file
BIN
resources/models/mlx90393.bin
Normal file
Binary file not shown.
1130
resources/models/mlx90393.gltf
Normal file
1130
resources/models/mlx90393.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/mp9250.bin
Normal file
BIN
resources/models/mp9250.bin
Normal file
Binary file not shown.
1930
resources/models/mp9250.gltf
Normal file
1930
resources/models/mp9250.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/qmc5883.bin
Normal file
BIN
resources/models/qmc5883.bin
Normal file
Binary file not shown.
1674
resources/models/qmc5883.gltf
Normal file
1674
resources/models/qmc5883.gltf
Normal file
File diff suppressed because it is too large
Load diff
BIN
resources/models/ws_m181.bin
Normal file
BIN
resources/models/ws_m181.bin
Normal file
Binary file not shown.
3318
resources/models/ws_m181.gltf
Normal file
3318
resources/models/ws_m181.gltf
Normal file
File diff suppressed because it is too large
Load diff
|
@ -119,6 +119,7 @@
|
|||
width: 100%;
|
||||
table-layout: auto;
|
||||
text-align: center;
|
||||
border-bottom: 1px solid #ddd;
|
||||
}
|
||||
|
||||
.tab-magnetometer .slider {
|
||||
|
@ -137,7 +138,7 @@
|
|||
.tab-magnetometer #interactive_block {
|
||||
position: absolute;
|
||||
width: calc(100% - 655px);
|
||||
height: 771px;
|
||||
height: 836px;
|
||||
min-height: calc(100% - 200px);
|
||||
background-color: #f9f9f9;
|
||||
border-radius: 5px;
|
||||
|
@ -176,6 +177,9 @@
|
|||
.tab-magnetometer .table-title {
|
||||
font-weight: bold;
|
||||
}
|
||||
#align_mag_xxx {
|
||||
font-weight: normal;
|
||||
}
|
||||
/*noinspection ALL*/
|
||||
progress[value]::-webkit-progress-bar {
|
||||
background-color: #d2d2d2;
|
||||
|
@ -211,3 +215,14 @@ progress[value]::-webkit-progress-value {
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
.tab-magnetometer .cli-box {
|
||||
display:flex;
|
||||
justify-content: center;
|
||||
align-items: end;
|
||||
font-style: italic;
|
||||
margin-top: 5px;
|
||||
.cli-settings-title {
|
||||
font-weight: bold;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -28,4 +28,13 @@
|
|||
font-size: 2em;
|
||||
color:#fff;
|
||||
font-weight: bold;
|
||||
}
|
||||
|
||||
.logic__table select,
|
||||
.logic__table input {
|
||||
width: auto;
|
||||
margin: 0;
|
||||
padding: 2px;
|
||||
margin-right: 1em;
|
||||
font-size: 13px;
|
||||
}
|
|
@ -17,13 +17,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
GUI.active_tab_ref = this;
|
||||
GUI.active_tab = 'adjustments';
|
||||
|
||||
function get_adjustment_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_ADJUSTMENT_RANGES, false, false, get_rc_data);
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
|
@ -33,8 +27,6 @@ TABS.adjustments.initialize = function (callback) {
|
|||
GUI.load(path.join(__dirname, "adjustments.html"), process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_adjustment_ranges);
|
||||
|
||||
function addAdjustment(adjustmentIndex, adjustmentRange, auxChannelCount) {
|
||||
|
||||
var template = $('#tab-adjustments-templates').find('.adjustments .adjustment');
|
||||
|
|
|
@ -216,7 +216,7 @@
|
|||
</div>
|
||||
|
||||
<div class="number">
|
||||
<input type="number" id="cruiseYawRate" data-setting="nav_fw_cruise_yaw_rate" data-setting-multiplier="1" step="1" min="0" max="60" />
|
||||
<input type="number" id="cruiseYawRate" data-setting="nav_cruise_yaw_rate" data-setting-multiplier="1" step="1" min="0" max="60" />
|
||||
<label for="cruiseYawRate"><span data-i18n="cruiseYawRateLabel"></span></label>
|
||||
<div for="cruiseYawRate" class="helpicon cf_tip" data-i18n_title="cruiseYawRateHelp"></div>
|
||||
</div>
|
||||
|
|
|
@ -19,6 +19,20 @@ TABS.advanced_tuning.initialize = function (callback) {
|
|||
|
||||
loadHtml();
|
||||
|
||||
function save_to_eeprom() {
|
||||
console.log('save_to_eeprom');
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(i18n.getMessage('eepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
|
||||
GUI.log(i18n.getMessage('deviceRebooting'));
|
||||
GUI.handleReconnect($('.tab_advanced_tuning a'));
|
||||
});
|
||||
});
|
||||
});
|
||||
}
|
||||
|
||||
function loadHtml() {
|
||||
GUI.load(path.join(__dirname, "advanced_tuning.html"), Settings.processHtml(function () {
|
||||
|
||||
|
@ -68,35 +82,12 @@ TABS.advanced_tuning.initialize = function (callback) {
|
|||
TABS.advanced_tuning.checkRequirements_LinearDescent();
|
||||
|
||||
$('a.save').on('click', function () {
|
||||
Settings.saveInputs().then(function () {
|
||||
var self = this;
|
||||
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||
var oldText = $(this).text();
|
||||
$(this).html("Saved");
|
||||
setTimeout(function () {
|
||||
$(self).html(oldText);
|
||||
}, 2000);
|
||||
reboot();
|
||||
});
|
||||
Settings.saveInputs(save_to_eeprom);
|
||||
});
|
||||
GUI.content_ready(callback);
|
||||
|
||||
}));
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
//noinspection JSUnresolvedVariable
|
||||
GUI.log(i18n.getMessage('configurationEepromSaved'));
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
function reinitialize() {
|
||||
//noinspection JSUnresolvedVariable
|
||||
GUI.log(i18n.getMessage('deviceRebooting'));
|
||||
GUI.handleReconnect($('.tab_advanced_tuning a'));
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -22,24 +22,26 @@ TABS.auxiliary = {};
|
|||
TABS.auxiliary.initialize = function (callback) {
|
||||
GUI.active_tab_ref = this;
|
||||
GUI.active_tab = 'auxiliary';
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
let LOCAL_AUX_CONFIG = [];
|
||||
let LOCAL_AUX_CONFIG_IDS = [];
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, function () {
|
||||
FC.generateAuxConfig();
|
||||
|
||||
//Copy global settings into local ones
|
||||
LOCAL_AUX_CONFIG = Array.from(FC.AUX_CONFIG);
|
||||
LOCAL_AUX_CONFIG_IDS = Array.from(FC.AUX_CONFIG_IDS);
|
||||
|
||||
get_rc_data();
|
||||
});
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
if (FC.SERIAL_CONFIG.ports.length == 0) {
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_ports_data);
|
||||
} else {
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
}
|
||||
}
|
||||
|
||||
function get_ports_data() {
|
||||
MSP.send_message(MSPCodes.MSP2_CF_SERIAL_CONFIG, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
|
@ -47,8 +49,6 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
GUI.load(path.join(__dirname, "auxiliary.html"), process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||
|
||||
// This object separates out the dividers. This is also used to order the modes
|
||||
const modeSections = {};
|
||||
modeSections["Arming"] = ["ARM", "PREARM"];
|
||||
|
@ -68,21 +68,21 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
var found = false;
|
||||
var sortedID = 0;
|
||||
|
||||
for (let i=0; i<FC.AUX_CONFIG.length; i++) {
|
||||
tmpAUX_CONFIG[i] = FC.AUX_CONFIG[i];
|
||||
tmpAUX_CONFIG_IDS[i] = FC.AUX_CONFIG_IDS[i];
|
||||
for (let i=0; i<LOCAL_AUX_CONFIG.length; i++) {
|
||||
tmpAUX_CONFIG[i] = LOCAL_AUX_CONFIG[i];
|
||||
tmpAUX_CONFIG_IDS[i] = LOCAL_AUX_CONFIG_IDS[i];
|
||||
}
|
||||
|
||||
FC.AUX_CONFIG = [];
|
||||
FC.AUX_CONFIG_IDS = [];
|
||||
LOCAL_AUX_CONFIG = [];
|
||||
LOCAL_AUX_CONFIG_IDS = [];
|
||||
|
||||
for (let categoryModesIndex in modeSections) {
|
||||
let categoryModes = modeSections[categoryModesIndex];
|
||||
for (let cM=0; cM<categoryModes.length; cM++){
|
||||
for(let j=0; j<tmpAUX_CONFIG.length; j++) {
|
||||
if (categoryModes[cM] === tmpAUX_CONFIG[j]) {
|
||||
FC.AUX_CONFIG[sortedID] = tmpAUX_CONFIG[j];
|
||||
FC.AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[j];
|
||||
LOCAL_AUX_CONFIG[sortedID] = tmpAUX_CONFIG[j];
|
||||
LOCAL_AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[j];
|
||||
ORIG_AUX_CONFIG_IDS[sortedID++] = j;
|
||||
|
||||
break;
|
||||
|
@ -92,19 +92,19 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// There are modes that are missing from the modeSections object. Add them to the end until they are ordered correctly.
|
||||
if (tmpAUX_CONFIG.length > FC.AUX_CONFIG.length) {
|
||||
if (tmpAUX_CONFIG.length > LOCAL_AUX_CONFIG.length) {
|
||||
for (let i=0; i<tmpAUX_CONFIG.length; i++) {
|
||||
found = false;
|
||||
for (let j=0; j<FC.AUX_CONFIG.length; j++) {
|
||||
if (tmpAUX_CONFIG[i] === FC.AUX_CONFIG[j]) {
|
||||
for (let j=0; j<LOCAL_AUX_CONFIG.length; j++) {
|
||||
if (tmpAUX_CONFIG[i] === LOCAL_AUX_CONFIG[j]) {
|
||||
found = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (!found) {
|
||||
FC.AUX_CONFIG[sortedID] = tmpAUX_CONFIG[i];
|
||||
FC.AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[i];
|
||||
LOCAL_AUX_CONFIG[sortedID] = tmpAUX_CONFIG[i];
|
||||
LOCAL_AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[i];
|
||||
ORIG_AUX_CONFIG_IDS[sortedID++] = i;
|
||||
}
|
||||
}
|
||||
|
@ -123,7 +123,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
function createMode(modeIndex, modeId) {
|
||||
var modeTemplate = $('#tab-auxiliary-templates .mode');
|
||||
var newMode = modeTemplate.clone();
|
||||
var modeName = FC.AUX_CONFIG[modeIndex];
|
||||
var modeName = LOCAL_AUX_CONFIG[modeIndex];
|
||||
|
||||
// If the runcam split peripheral is used, then adjust the boxname(BOXCAMERA1, BOXCAMERA2, BOXCAMERA3)
|
||||
// If platform is fixed wing, rename POS HOLD to LOITER
|
||||
|
@ -135,7 +135,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
$(newMode).data('index', modeIndex);
|
||||
$(newMode).data('id', modeId);
|
||||
$(newMode).data('origId', ORIG_AUX_CONFIG_IDS[modeIndex]);
|
||||
$(newMode).data('modeName', FC.AUX_CONFIG[modeIndex]);
|
||||
$(newMode).data('modeName', LOCAL_AUX_CONFIG[modeIndex]);
|
||||
|
||||
$(newMode).find('.name').data('modeElement', newMode);
|
||||
$(newMode).find('a.addRange').data('modeElement', newMode);
|
||||
|
@ -230,10 +230,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
let modeSelectionID = "";
|
||||
let modeSelectionRange = "";
|
||||
|
||||
for (var modeIndex = 0; modeIndex < FC.AUX_CONFIG.length; modeIndex++) {
|
||||
for (var modeIndex = 0; modeIndex < LOCAL_AUX_CONFIG.length; modeIndex++) {
|
||||
// Get current mode category
|
||||
for (modeSelectionRange in modeSections) {
|
||||
if (modeSections[modeSelectionRange].indexOf(FC.AUX_CONFIG[modeIndex]) != -1) {
|
||||
if (modeSections[modeSelectionRange].indexOf(LOCAL_AUX_CONFIG[modeIndex]) != -1) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -245,7 +245,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
modeTableBodyElement.append(newSection);
|
||||
}
|
||||
|
||||
var modeId = FC.AUX_CONFIG_IDS[modeIndex];
|
||||
var modeId = LOCAL_AUX_CONFIG_IDS[modeIndex];
|
||||
var newMode = createMode(modeIndex, modeId);
|
||||
modeTableBodyElement.append(newMode);
|
||||
|
||||
|
@ -387,7 +387,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
update_marker(i, FC.RC.channels[i + 4]);
|
||||
}
|
||||
|
||||
for (var i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
for (var i = 0; i < LOCAL_AUX_CONFIG.length; i++) {
|
||||
var modeElement = $('#mode-' + i);
|
||||
let inRange = false;
|
||||
|
||||
|
@ -442,7 +442,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
let hideUnused = hideUnusedModes && hasUsedMode;
|
||||
for (let i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
for (let i = 0; i < LOCAL_AUX_CONFIG.length; i++) {
|
||||
let modeElement = $('#mode-' + i);
|
||||
if (modeElement.find(' .range').length == 0) {
|
||||
modeElement.toggle(!hideUnused);
|
||||
|
|
|
@ -1 +0,0 @@
|
|||
<div class="tab-adjustments" style="width: 100%; height: 100%; background-color: #000000;"></div>
|
29
tabs/cli.js
29
tabs/cli.js
|
@ -15,6 +15,8 @@ const CliAutoComplete = require('./../js/CliAutoComplete');
|
|||
const { ConnectionType } = require('./../js/connection/connection');
|
||||
const jBox = require('./../js/libraries/jBox/jBox.min');
|
||||
const mspDeduplicationQueue = require('./../js/msp/mspDeduplicationQueue');
|
||||
const FC = require('./../js/fc');
|
||||
const { generateFilename } = require('./../js/helpers');
|
||||
|
||||
TABS.cli = {
|
||||
lineDelayMs: 50,
|
||||
|
@ -82,7 +84,7 @@ function copyToClipboard(text) {
|
|||
function onCopyFailed(ex) {
|
||||
console.warn(ex);
|
||||
}
|
||||
|
||||
|
||||
navigator.clipboard.writeText(text)
|
||||
.then(onCopySuccessful, onCopyFailed);
|
||||
}
|
||||
|
@ -115,8 +117,8 @@ TABS.cli.initialize = function (callback) {
|
|||
self.history.add(out_string.trim());
|
||||
|
||||
var outputArray = out_string.split("\n");
|
||||
return outputArray.reduce((p, line, index) =>
|
||||
p.then((delay) =>
|
||||
return outputArray.reduce((p, line, index) =>
|
||||
p.then((delay) =>
|
||||
new Promise((resolve) => {
|
||||
timeout.add('CLI_send_slowly', () => {
|
||||
let processingDelay = TABS.cli.lineDelayMs;
|
||||
|
@ -160,11 +162,14 @@ TABS.cli.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('.tab-cli .save').on('click', function () {
|
||||
|
||||
var prefix = 'cli';
|
||||
var suffix = 'txt';
|
||||
var filename = generateFilename(FC.CONFIG, prefix, suffix);
|
||||
var options = {
|
||||
filters: [
|
||||
{ name: 'CLI', extensions: ['cli'] } ,
|
||||
{ name: 'TXT', extensions: ['txt'] }
|
||||
defaultPath: filename,
|
||||
filters: [
|
||||
{ name: suffix.toUpperCase(), extensions: [suffix] },
|
||||
{ name: prefix.toUpperCase(), extensions: [prefix] }
|
||||
],
|
||||
};
|
||||
dialog.showSaveDialog(options).then(result => {
|
||||
|
@ -172,7 +177,7 @@ TABS.cli.initialize = function (callback) {
|
|||
GUI.log(i18n.getMessage('cliSaveToFileAborted'));
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
fs.writeFile(result.filePath, self.outputHistory, (err) => {
|
||||
if (err) {
|
||||
GUI.log(i18n.getMessage('ErrorWritingFile'));
|
||||
|
@ -219,7 +224,7 @@ TABS.cli.initialize = function (callback) {
|
|||
|
||||
$('.tab-cli .load').on('click', function () {
|
||||
var options = {
|
||||
filters: [
|
||||
filters: [
|
||||
{ name: 'CLI/TXT', extensions: ['cli', 'txt'] },
|
||||
{ name: 'ALL', extensions: ['*'] }
|
||||
],
|
||||
|
@ -353,14 +358,14 @@ TABS.cli.initialize = function (callback) {
|
|||
|
||||
if (CONFIGURATOR.connection.type == ConnectionType.BLE) {
|
||||
let delay = CONFIGURATOR.connection.deviceDescription.delay;
|
||||
if (delay > 0) {
|
||||
if (delay > 0) {
|
||||
timeout.add('cli_delay', () => {
|
||||
self.send(getCliCommand("cli_delay " + delay + '\n', TABS.cli.cliBuffer));
|
||||
self.send(getCliCommand('# ' + i18n.getMessage('connectionBleCliEnter') + '\n', TABS.cli.cliBuffer));
|
||||
}, 400);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
GUI.content_ready(callback);
|
||||
});
|
||||
};
|
||||
|
|
|
@ -52,7 +52,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
];
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
Settings.saveInputs().then(onComplete);
|
||||
Settings.saveInputs(onComplete);
|
||||
}
|
||||
|
||||
saveChainer.setChain(saveChain);
|
||||
|
|
|
@ -127,29 +127,22 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
|
||||
load_failssafe_config();
|
||||
|
||||
function save_to_eeprom() {
|
||||
console.log('save_to_eeprom');
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(i18n.getMessage('eepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
|
||||
GUI.log(i18n.getMessage('deviceRebooting'));
|
||||
GUI.handleReconnect($('.tab_failsafe a'));
|
||||
});
|
||||
});
|
||||
});
|
||||
}
|
||||
|
||||
function savePhaseTwo() {
|
||||
Settings.saveInputs().then(function () {
|
||||
var self = this;
|
||||
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||
setTimeout(function () {
|
||||
$(self).html('');
|
||||
}, 2000);
|
||||
reboot();
|
||||
});
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
//noinspection JSUnresolvedVariable
|
||||
GUI.log(i18n.getMessage('configurationEepromSaved'));
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
function reinitialize() {
|
||||
//noinspection JSUnresolvedVariable
|
||||
GUI.log(i18n.getMessage('deviceRebooting'));
|
||||
GUI.handleReconnect($('.tab_failsafe a'));
|
||||
Settings.saveInputs(save_to_eeprom);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -73,7 +73,7 @@ TABS.gps.initialize = function (callback) {
|
|||
];
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
Settings.saveInputs().then(onComplete);
|
||||
Settings.saveInputs(onComplete);
|
||||
}
|
||||
|
||||
saveChainer.setChain(saveChain);
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
</td>
|
||||
<td style="width: 90%; padding-bottom: 10px;">
|
||||
<p class="table-title">
|
||||
<span data-i18n="axisTableTitleSlider"></span>
|
||||
<span style="font-weight:normal;">align_board_roll, align_board_pitch, align_board_yaw</span>
|
||||
</p>
|
||||
</td>
|
||||
<td style="width: 5%; padding-bottom: 10px;">
|
||||
|
@ -91,6 +91,9 @@
|
|||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
<div class="cli-box">
|
||||
<span class="cli-settings-title">CLI: </span><span id="cli_settings_fc"></span>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
|
@ -100,16 +103,44 @@
|
|||
<span data-i18n="magnetometerInfo"></span>
|
||||
</div>
|
||||
<div class="select" style="display: flex; justify-content: left;">
|
||||
<select id="magalign" class="magalign">
|
||||
<select id="magalign" class="magalign" style="width: 210px; flex-grow: 0; flex-shrink: 0">
|
||||
<option value="0">Default</option>
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
<label for="magalign" data-i18n="magnetometerOrientationPreset"></label>
|
||||
</div>
|
||||
<div class="select" style="display: flex; justify-content: left;">
|
||||
<select id="element_to_show">
|
||||
<option value="0" selected>Magnetometer</option>
|
||||
<option value="1">XYZ</option>
|
||||
<select id="element_to_show" style="width: 210px; flex-grow: 0; flex-shrink: 0">
|
||||
<option value="0" selected data-i18n="magnetometerAxes"></option>
|
||||
<option value="1">AK8963C</option>
|
||||
<option value="2">AK8963N</option>
|
||||
<option value="3">AK8975</option>
|
||||
<option value="4">AK8975C</option>
|
||||
<option value="5">BN-880</option>
|
||||
<option value="6">DIATONE Mamba M10 PRO</option>
|
||||
<option value="7">FLYWOO GOKU M10 PRO V3</option>
|
||||
<option value="8">FOXEER-M10Q-120</option>
|
||||
<option value="9">FOXEER-M10Q-180</option>
|
||||
<option value="10">FOXEER-M10Q-250</option>
|
||||
<option value="11">GEPRC GEP-M10-DQ</option>
|
||||
<option value="12">GY-271</option>
|
||||
<option value="13">GY-273</option>
|
||||
<option value="14">HGLRC-M100-5883</option>
|
||||
<option value="15">HMC5833</option>
|
||||
<option value="16">HOLYBRO Micro M9N IST8310</option>
|
||||
<option value="17">HOLYBRO Micro M10 IST8310</option>
|
||||
<option value="18">IST8308</option>
|
||||
<option value="19">IST8310</option>
|
||||
<option value="20">LIS3MDL</option>
|
||||
<option value="21">MAG3110</option>
|
||||
<option value="22">MATEK M8Q-5833</option>
|
||||
<option value="23">MATEK M9N-5833</option>
|
||||
<option value="24">MATEK M10Q-5833</option>
|
||||
<option value="25">MLX90393</option>
|
||||
<option value="26">MP9250</option>
|
||||
<option value="27">QMC5833</option>
|
||||
<option value="28">SPEEDYEBEE BZ-251</option>
|
||||
<option value="29">WS-M181</option>
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
<label for="element_to_show" data-i18n="magnetometerElementToShow"></label>
|
||||
|
@ -125,7 +156,7 @@
|
|||
</td>
|
||||
<td style="width: 90%; padding-bottom: 10px;">
|
||||
<p class="table-title">
|
||||
<span data-i18n="axisTableTitleSlider"></span>
|
||||
<span id="align_mag_xxx">align_mag_roll, align_mag_pitch, align_mag_yaw</span>
|
||||
</p>
|
||||
</td>
|
||||
<td style="width: 5%; padding-bottom: 10px;">
|
||||
|
@ -172,6 +203,13 @@
|
|||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
<div class="cli-box">
|
||||
<span class="cli-settings-title">CLI: </span><span id="cli_settings_mag"></span>
|
||||
</div>
|
||||
<div class="cli-box" style="font-style:normal;">
|
||||
<span id="comment_sensor_mag_preset" data-i18n="configurationSensorMagPreset"></span>
|
||||
<span id="comment_sensor_mag_angles" data-i18n="configurationSensorMagAngles"></span>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
|
@ -36,7 +36,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
|
||||
self.pageElements = {};
|
||||
self.isSavePreset = true;
|
||||
self.showMagnetometer = true;
|
||||
self.elementToShow = 0;
|
||||
//========================
|
||||
// Load chain
|
||||
// =======================
|
||||
|
@ -161,6 +161,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function toUpperRange(input, max) {
|
||||
if (!Number.isFinite(input)) return 0;
|
||||
while (input > max) input -= 360;
|
||||
while (input + 360 <= max) input += 360;
|
||||
return input;
|
||||
|
@ -189,7 +190,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
return [180, 0, 180];
|
||||
case 0: //ALIGN_DEFAULT = 0
|
||||
case 8: //CW270_DEG_FLIP = 5
|
||||
default://If not recognized, returns defualt
|
||||
default://If not recognized, returns default
|
||||
return [180, 0, 270];
|
||||
}
|
||||
}
|
||||
|
@ -230,11 +231,19 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
}
|
||||
}
|
||||
|
||||
function updateFCCliString() {
|
||||
var s = " align_board_roll=" + (self.boardAlignmentConfig.roll * 10) +
|
||||
" align_board_pitch=" + (self.boardAlignmentConfig.pitch * 10) +
|
||||
" align_board_yaw=" + (self.boardAlignmentConfig.yaw * 10);
|
||||
self.pageElements.cli_settings_fc.text(s);
|
||||
}
|
||||
|
||||
function updateBoardRollAxis(value) {
|
||||
self.boardAlignmentConfig.roll = Number(value);
|
||||
self.pageElements.board_roll_slider.val(self.boardAlignmentConfig.roll);
|
||||
self.pageElements.orientation_board_roll.val(self.boardAlignmentConfig.roll);
|
||||
updateMagOrientationWithPreset();
|
||||
updateFCCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
|
@ -243,6 +252,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.pageElements.board_pitch_slider.val(self.boardAlignmentConfig.pitch);
|
||||
self.pageElements.orientation_board_pitch.val(self.boardAlignmentConfig.pitch);
|
||||
updateMagOrientationWithPreset();
|
||||
updateFCCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
|
@ -251,14 +261,31 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.pageElements.board_yaw_slider.val(self.boardAlignmentConfig.yaw);
|
||||
self.pageElements.orientation_board_yaw.val(self.boardAlignmentConfig.yaw);
|
||||
updateMagOrientationWithPreset();
|
||||
updateFCCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
function updateMagCliString() {
|
||||
var fix = 0;
|
||||
if ( areAnglesZero() ) {
|
||||
fix = 1; //if all angles are 0, then we have to save yaw = 1 (0.1 deg) to enforce usage of angles, not a usage of preset
|
||||
}
|
||||
var names = ['DEFAULT', 'CW0', 'CW90', 'CW180', 'CW270', 'CW0FLIP', 'CW90FLIP', 'CW180FLIP', 'CW270FLIP'];
|
||||
var s = "align_mag=" + names[FC.SENSOR_ALIGNMENT.align_mag] +
|
||||
" align_mag_roll=" + (self.isSavePreset ? 0 : self.alignmentConfig.roll * 10) +
|
||||
" align_mag_pitch=" + (self.isSavePreset ? 0 : self.alignmentConfig.pitch * 10) +
|
||||
" align_mag_yaw=" + (self.isSavePreset ? 0 : self.alignmentConfig.yaw * 10 + fix);
|
||||
self.pageElements.cli_settings_mag.text(s);
|
||||
self.pageElements.comment_sensor_mag_preset.css("display", !self.isSavePreset ? "none" : "");
|
||||
self.pageElements.comment_sensor_mag_angles.css("display", self.isSavePreset ? "none" : "");
|
||||
}
|
||||
|
||||
//Called when roll values change
|
||||
function updateRollAxis(value) {
|
||||
self.alignmentConfig.roll = Number(value);
|
||||
self.pageElements.roll_slider.val(self.alignmentConfig.roll);
|
||||
self.pageElements.orientation_mag_roll.val(self.alignmentConfig.roll);
|
||||
updateMagCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
|
@ -267,6 +294,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.alignmentConfig.pitch = Number(value);
|
||||
self.pageElements.pitch_slider.val(self.alignmentConfig.pitch);
|
||||
self.pageElements.orientation_mag_pitch.val(self.alignmentConfig.pitch);
|
||||
updateMagCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
|
@ -275,6 +303,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.alignmentConfig.yaw = Number(value);
|
||||
self.pageElements.yaw_slider.val(self.alignmentConfig.yaw);
|
||||
self.pageElements.orientation_mag_yaw.val(self.alignmentConfig.yaw);
|
||||
updateMagCliString();
|
||||
self.render3D();
|
||||
}
|
||||
|
||||
|
@ -282,12 +311,16 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.isSavePreset = true;
|
||||
self.pageElements.orientation_mag_e.css("opacity", 1);
|
||||
self.pageElements.orientation_mag_e.css("text-decoration", "");
|
||||
self.pageElements.align_mag_xxx_e.css("opacity", "0.65");
|
||||
self.pageElements.align_mag_xxx_e.css("text-decoration", "line-through");
|
||||
}
|
||||
|
||||
function disableSavePreset() {
|
||||
self.isSavePreset = false;
|
||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
||||
self.pageElements.orientation_mag_e.css("text-decoration", "line-through");
|
||||
self.pageElements.align_mag_xxx_e.css("opacity", "1");
|
||||
self.pageElements.align_mag_xxx_e.css("text-decoration", "");
|
||||
}
|
||||
|
||||
|
||||
|
@ -297,6 +330,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
updatePitchAxis(degrees[0]);
|
||||
updateRollAxis(degrees[1]);
|
||||
updateYawAxis(degrees[2]);
|
||||
updateMagCliString();
|
||||
}
|
||||
|
||||
|
||||
|
@ -324,6 +358,14 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
self.pageElements.pitch_slider = $('#pitch_slider');
|
||||
self.pageElements.yaw_slider = $('#yaw_slider');
|
||||
|
||||
self.pageElements.align_mag_xxx_e = $('#align_mag_xxx');
|
||||
|
||||
self.pageElements.cli_settings_fc = $('#cli_settings_fc');
|
||||
self.pageElements.cli_settings_mag = $('#cli_settings_mag');
|
||||
|
||||
self.pageElements.comment_sensor_mag_preset = $('#comment_sensor_mag_preset');
|
||||
self.pageElements.comment_sensor_mag_angles = $('#comment_sensor_mag_angles');
|
||||
|
||||
self.roll_e = $('dd.roll'),
|
||||
self.pitch_e = $('dd.pitch'),
|
||||
self.heading_e = $('dd.heading');
|
||||
|
@ -418,7 +460,7 @@ TABS.magnetometer.initialize = function (callback) {
|
|||
const elementToShow = $("#element_to_show");
|
||||
elementToShow.on('change', function () {
|
||||
const value = parseInt($(this).val());
|
||||
self.showMagnetometer = (value == 0);
|
||||
self.elementToShow = value;
|
||||
self.render3D();
|
||||
});
|
||||
|
||||
|
@ -550,8 +592,7 @@ TABS.magnetometer.initialize3D = function () {
|
|||
model_file,
|
||||
camera,
|
||||
scene,
|
||||
gps,
|
||||
xyz,
|
||||
magModels,
|
||||
fc,
|
||||
useWebGlRenderer = false;
|
||||
|
||||
|
@ -597,11 +638,10 @@ TABS.magnetometer.initialize3D = function () {
|
|||
|
||||
this.render3D = function () {
|
||||
|
||||
if (!gps || !xyz || !fc)
|
||||
if (!magModels || !fc)
|
||||
return;
|
||||
|
||||
gps.visible = self.showMagnetometer;
|
||||
xyz.visible = !self.showMagnetometer;
|
||||
magModels.forEach( (m,i) => m.visible = i == self.elementToShow );
|
||||
fc.visible = true;
|
||||
|
||||
var magRotation = new THREE.Euler(-THREE.Math.degToRad(self.alignmentConfig.pitch-180), THREE.Math.degToRad(-180 - self.alignmentConfig.yaw), THREE.Math.degToRad(self.alignmentConfig.roll), 'YXZ');
|
||||
|
@ -615,8 +655,7 @@ TABS.magnetometer.initialize3D = function () {
|
|||
matrix.premultiply(matrix1); //preset specifies orientation relative to FC, align_max_xxx specify absolute orientation
|
||||
}
|
||||
*/
|
||||
gps.rotation.setFromRotationMatrix(matrix);
|
||||
xyz.rotation.setFromRotationMatrix(matrix);
|
||||
magModels.forEach( (m,i) => m.rotation.setFromRotationMatrix(matrix) );
|
||||
fc.rotation.setFromRotationMatrix(matrix1);
|
||||
|
||||
// draw
|
||||
|
@ -691,6 +730,11 @@ TABS.magnetometer.initialize3D = function () {
|
|||
const manager = new THREE.LoadingManager();
|
||||
const loader = new THREE.GLTFLoader(manager);
|
||||
|
||||
const magModelNames = ['xyz', 'ak8963c', 'ak8963n', 'ak8975', 'ak8975c', 'bn_880', 'diatone_mamba_m10_pro', 'flywoo_goku_m10_pro_v3', 'foxeer_m10q_120', 'foxeer_m10q_180', 'foxeer_m10q_250',
|
||||
'geprc_gep_m10_dq', 'gy271', 'gy273', 'hglrc_m100', 'qmc5883', 'holybro_m9n_micro', 'holybro_m9n_micro', 'ist8308', 'ist8310', 'lis3mdl',
|
||||
'mag3110', 'matek_m8q', 'matek_m9n', 'matek_m10q', 'mlx90393', 'mp9250', 'qmc5883', 'flywoo_goku_m10_pro_v3', 'ws_m181'];
|
||||
magModels = [];
|
||||
|
||||
//Load the UAV model
|
||||
loader.load('./resources/models/' + model_file + '.gltf', (obj) => {
|
||||
const model = obj.scene;
|
||||
|
@ -700,30 +744,22 @@ TABS.magnetometer.initialize3D = function () {
|
|||
|
||||
const gpsOffset = getDistanceByModelName(model_file);
|
||||
|
||||
//Load the GPS model
|
||||
loader.load('./resources/models/gps.gltf', (obj) => {
|
||||
gps = obj.scene;
|
||||
const scaleFactor = 0.04;
|
||||
gps.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||
gps.position.set(gpsOffset[0], gpsOffset[1] + 0.5, gpsOffset[2]);
|
||||
gps.traverse(child => {
|
||||
if (child.material) child.material.metalness = 0;
|
||||
magModelNames.forEach( (name, i) =>
|
||||
{
|
||||
loader.load('./resources/models/' + name + '.gltf', (obj) => {
|
||||
const gps = obj.scene;
|
||||
const scaleFactor = i==0 ? 0.03 : 0.04;
|
||||
gps.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||
gps.position.set(gpsOffset[0], gpsOffset[1] + 0.5, gpsOffset[2]);
|
||||
gps.traverse(child => {
|
||||
if (child.material) child.material.metalness = 0;
|
||||
});
|
||||
gps.rotation.y = 3 * Math.PI / 2;
|
||||
model.add(gps);
|
||||
magModels[i]=gps;
|
||||
this.resize3D();
|
||||
});
|
||||
gps.rotation.y = 3 * Math.PI / 2;
|
||||
model.add(gps);
|
||||
this.resize3D();
|
||||
});
|
||||
|
||||
//Load the XYZ model
|
||||
loader.load('./resources/models/xyz.gltf', (obj) => {
|
||||
xyz = obj.scene;
|
||||
const scaleFactor = 0.04;
|
||||
xyz.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||
xyz.position.set(gpsOffset[0], gpsOffset[1] + 0.5, gpsOffset[2]);
|
||||
xyz.rotation.y = 3 * Math.PI / 2;
|
||||
model.add(xyz);
|
||||
this.render3D();
|
||||
});
|
||||
});
|
||||
|
||||
//Load the FC model
|
||||
loader.load('./resources/models/fc.gltf', (obj) => {
|
||||
|
|
|
@ -13,6 +13,8 @@ const { mixer, platform, PLATFORM, INPUT, STABILIZED } = require('./../js/model'
|
|||
const Settings = require('./../js/settings');
|
||||
const jBox = require('../js/libraries/jBox/jBox.min');
|
||||
const interval = require('./../js/intervals');
|
||||
const ServoMixRule = require('./../js/servoMixRule');
|
||||
const MotorMixRule = require('./../js/motorMixRule');
|
||||
|
||||
TABS.mixer = {};
|
||||
|
||||
|
@ -58,7 +60,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
saveChainer.setExitPoint(reboot);
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
Settings.saveInputs().then(onComplete);
|
||||
Settings.saveInputs(onComplete);
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
|
|
|
@ -1,17 +0,0 @@
|
|||
<div class="tab-modes toolbar_fixed_bottom">
|
||||
<div class="content_wrapper">
|
||||
<table class="boxes">
|
||||
<tr class="heads">
|
||||
<th class="partone"></th>
|
||||
</tr>
|
||||
<tr class="main">
|
||||
<th i18n="auxiliaryName"></th>
|
||||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
<div class="content_toolbar">
|
||||
<div class="btn save_btn">
|
||||
<a class="update" href="#" i18n="auxiliaryButtonSave"></a>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
163
tabs/modes.js
163
tabs/modes.js
|
@ -1,163 +0,0 @@
|
|||
// Disabled via main.js/main.html, cleanflight does not use MSP_BOX.
|
||||
|
||||
'use strict';
|
||||
|
||||
const path = require('path');
|
||||
|
||||
const mspHelper = require('./../js/msp/MSPHelper');
|
||||
const MSPCodes = require('./../js/msp/MSPCodes');
|
||||
const MSP = require('./../js/msp');
|
||||
const { GUI, TABS } = require('./../js/gui');
|
||||
const FC = require('./../js/fc');
|
||||
const interval = require('./../js/intervals');
|
||||
const BitHelper = require('./../js/bitHelper');
|
||||
const i18n = require('./../js/localization');
|
||||
|
||||
TABS.modes = {};
|
||||
TABS.modes.initialize = function (callback) {
|
||||
var self = this;
|
||||
|
||||
if (GUI.active_tab != 'modes') {
|
||||
GUI.active_tab = 'modes';
|
||||
}
|
||||
|
||||
function get_active_box_data() {
|
||||
MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
GUI.load(path.join(__dirname, "modes.html"), process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_active_box_data);
|
||||
|
||||
function process_html() {
|
||||
// generate heads according to RC count
|
||||
var table_head = $('table.boxes .heads');
|
||||
var main_head = $('table.boxes .main');
|
||||
for (var i = 0; i < (FC.RC.active_channels - 4); i++) {
|
||||
table_head.append('<th colspan="3">AUX ' + (i + 1) + '</th>');
|
||||
|
||||
// 3 columns per aux channel (this might be requested to change to 6 in the future, so watch out)
|
||||
main_head.append('\
|
||||
<th i18n="auxiliaryLow"></th>\
|
||||
<th i18n="auxiliaryMed"></th>\
|
||||
<th i18n="auxiliaryHigh"></th>\
|
||||
');
|
||||
}
|
||||
|
||||
// translate to user-selected language
|
||||
i18n.localize();;
|
||||
|
||||
// generate table from the supplied AUX names and AUX data
|
||||
for (var i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
var line = '<tr class="switches">';
|
||||
line += '<td class="name">' + FC.AUX_CONFIG[i] + '</td>';
|
||||
|
||||
for (var j = 0; j < (RC.active_channels - 4) * 3; j++) {
|
||||
if (BitHelper.bit_check(FC.AUX_CONFIG_values[i], j)) {
|
||||
line += '<td><input type="checkbox" checked="checked" /></td>';
|
||||
} else {
|
||||
line += '<td><input type="checkbox" /></td>';
|
||||
}
|
||||
}
|
||||
|
||||
line += '</tr>';
|
||||
|
||||
$('.boxes > tbody:last').append(line);
|
||||
}
|
||||
|
||||
// UI Hooks
|
||||
$('a.update').on('click', function () {
|
||||
// catch the input changes
|
||||
var main_needle = 0,
|
||||
needle = 0;
|
||||
|
||||
$('.boxes input').each(function () {
|
||||
if ($(this).is(':checked')) {
|
||||
FC.AUX_CONFIG_values[main_needle] = BitHelper.bit_set(FC.AUX_CONFIG_values[main_needle], needle);
|
||||
} else {
|
||||
FC.AUX_CONFIG_values[main_needle] = BitHelper.bit_clear(FC.AUX_CONFIG_values[main_needle], needle);
|
||||
}
|
||||
|
||||
needle++;
|
||||
|
||||
if (needle >= (FC.RC.active_channels - 4) * 3) { // 1 aux * 3 checkboxes, 4 AUX = 12 bits per line
|
||||
main_needle++;
|
||||
needle = 0;
|
||||
}
|
||||
});
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(i18n.getMessage('auxiliaryEepromSaved'));
|
||||
});
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_SET_BOX, mspHelper.crunch(MSPCodes.MSP_SET_BOX), false, save_to_eeprom);
|
||||
});
|
||||
|
||||
// val = channel value
|
||||
// aux_num = position of corresponding aux channel in the html table
|
||||
var switches_e = $('table.boxes .switches');
|
||||
function box_highlight(aux_num, val) {
|
||||
var pos = 0; // < 1300
|
||||
|
||||
if (val > 1300 && val < 1700) {
|
||||
pos = 1;
|
||||
} else if (val > 1700) {
|
||||
pos = 2;
|
||||
}
|
||||
|
||||
var highlight_column = (aux_num * 3) + pos + 2; // +2 to skip name column and index starting on 1 instead of 0
|
||||
var erase_columns = (aux_num * 3) + 2;
|
||||
|
||||
$('td:nth-child(n+' + erase_columns + '):nth-child(-n+' + (erase_columns + 2) + ')', switches_e).css('background-color', 'transparent');
|
||||
$('td:nth-child(' + highlight_column + ')', switches_e).css('background-color', 'orange');
|
||||
}
|
||||
|
||||
// data pulling functions used inside interval timer
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui);
|
||||
}
|
||||
|
||||
function update_ui() {
|
||||
for (var i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
if (FC.isModeBitSet(i)) {
|
||||
$('td.name').eq(i).addClass('on').removeClass('off');
|
||||
} else {
|
||||
$('td.name').eq(i).removeClass('on').removeClass('off');
|
||||
|
||||
if (FC.AUX_CONFIG_values[i] > 0) {
|
||||
$('td.name').eq(i).addClass('off');
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
for (var i = 0; i < (FC.RC.active_channels - 4); i++) {
|
||||
box_highlight(i, FC.RC.channels[i + 4]);
|
||||
}
|
||||
}
|
||||
|
||||
// update ui instantly on first load
|
||||
update_ui();
|
||||
|
||||
// enable data pulling
|
||||
interval.add('aux_data_pull', get_rc_data, 50);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
}
|
||||
};
|
||||
|
||||
TABS.modes.cleanup = function (callback) {
|
||||
if (callback) callback();
|
||||
};
|
|
@ -152,6 +152,7 @@
|
|||
<div class="legend"></div>
|
||||
</li>
|
||||
</ul><bbr />
|
||||
<a class="require-msc-ready regular-button onboardLoggingRebootMsc" href="#" i18n="cliMscBtn"></a>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
18
tabs/osd.js
18
tabs/osd.js
|
@ -3256,6 +3256,13 @@ TABS.osd.initialize = function (callback) {
|
|||
GUI.active_tab = 'osd';
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
console.log('save_to_eeprom');
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(i18n.getMessage('eepromSaved'));
|
||||
});
|
||||
}
|
||||
|
||||
GUI.load(path.join(__dirname, "osd.html"), Settings.processHtml(function () {
|
||||
// translate to user-selected language
|
||||
i18n.localize();
|
||||
|
@ -3274,16 +3281,7 @@ TABS.osd.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('a.save').on('click', function () {
|
||||
Settings.saveInputs().then(function () {
|
||||
var self = this;
|
||||
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||
GUI.log(i18n.getMessage('osdSettingsSaved'));
|
||||
var oldText = $(this).text();
|
||||
$(this).html("Saved");
|
||||
setTimeout(function () {
|
||||
$(self).html(oldText);
|
||||
}, 2000);
|
||||
});
|
||||
Settings.saveInputs(save_to_eeprom);
|
||||
});
|
||||
|
||||
// Initialise guides checkbox
|
||||
|
|
|
@ -79,7 +79,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
Settings.saveInputs().then(onComplete);
|
||||
Settings.saveInputs(onComplete);
|
||||
}
|
||||
|
||||
function onLoad() {
|
||||
|
|
|
@ -122,8 +122,8 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
FC.RC_tuning.RC_EXPO = parseFloat($('#rate_rollpitch_expo').val()) / 100;
|
||||
FC.RC_tuning.RC_YAW_EXPO = parseFloat($('#rate_yaw_expo').val()) / 100;
|
||||
|
||||
FC.RC_tuning.dynamic_THR_PID = parseInt($('#tpa').val());
|
||||
FC.RC_tuning.dynamic_THR_breakpoint = parseInt($('#tpa-breakpoint').val());
|
||||
FC.RC_tuning.dynamic_THR_PID = parseInt($('#tpaRate').val());
|
||||
FC.RC_tuning.dynamic_THR_breakpoint = parseInt($('#tpaBreakpoint').val());
|
||||
|
||||
FC.RC_tuning.manual_roll_rate = $('#rate_manual_roll').val();
|
||||
FC.RC_tuning.manual_pitch_rate = $('#rate_manual_pitch').val();
|
||||
|
@ -390,7 +390,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function saveSettings() {
|
||||
Settings.saveInputs().then(save_to_eeprom);
|
||||
Settings.saveInputs(save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
|
|
|
@ -44,7 +44,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
Settings.saveInputs().then(onComplete);
|
||||
Settings.saveInputs(onComplete);
|
||||
}
|
||||
|
||||
function drawRollPitchExpo() {
|
||||
|
|
|
@ -1,11 +0,0 @@
|
|||
<div class="head" i18n="reviewhead"></div>
|
||||
<div class="wrapper">
|
||||
<p class="initial" i18n="reviewInitial"></p>
|
||||
<p class="storeReview" i18n="reviewStore"></p>
|
||||
<p class="bugTicket" i18n="reviewBug"></p>
|
||||
<div class="buttons">
|
||||
<div class="yes" i18n="reviewYes"></div>
|
||||
<div class="no" i18n="reviewNo"></div>
|
||||
</div>
|
||||
<div class="clear-both"></div>
|
||||
</div>
|
Loading…
Add table
Add a link
Reference in a new issue