mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-15 04:15:28 +03:00
mixer added to preset
This commit is contained in:
parent
e0c14837a0
commit
b99c5c1bf4
3 changed files with 36 additions and 27 deletions
51
js/model.js
51
js/model.js
|
@ -2,30 +2,29 @@
|
|||
|
||||
// generate mixer
|
||||
var mixerList = [
|
||||
{name: 'Tricopter', model: 'tricopter', image: 'tri'},
|
||||
{name: 'Quad +', model: 'quad_x', image: 'quad_p'},
|
||||
{name: 'Quad X', model: 'quad_x', image: 'quad_x'},
|
||||
{name: 'Bicopter', model: 'custom', image: 'bicopter'},
|
||||
{name: 'Gimbal', model: 'custom', image: 'custom'},
|
||||
{name: 'Y6', model: 'y6', image: 'y6'},
|
||||
{name: 'Hex +', model: 'hex_plus', image: 'hex_p'},
|
||||
{name: 'Flying Wing', model: 'custom', image: 'flying_wing'},
|
||||
{name: 'Y4', model: 'y4', image: 'y4'},
|
||||
{name: 'Hex X', model: 'hex_x', image: 'hex_x'},
|
||||
{name: 'Octo X8', model: 'custom', image: 'octo_x8'},
|
||||
{name: 'Octo Flat +', model: 'custom', image: 'octo_flat_p'},
|
||||
{name: 'Octo Flat X', model: 'custom', image: 'octo_flat_x'},
|
||||
{name: 'Airplane', model: 'custom', image: 'airplane'},
|
||||
{name: 'Heli 120', model: 'custom', image: 'custom'},
|
||||
{name: 'Heli 90', model: 'custom', image: 'custom'},
|
||||
{name: 'V-tail Quad', model: 'quad_vtail', image: 'vtail_quad'},
|
||||
{name: 'Hex H', model: 'custom', image: 'custom'},
|
||||
{name: 'PPM to SERVO', model: 'custom', image: 'custom'},
|
||||
{name: 'Dualcopter', model: 'custom', image: 'custom'},
|
||||
{name: 'Singlecopter', model: 'custom', image: 'custom'},
|
||||
{name: 'A-tail Quad', model: 'quad_atail', image: 'atail_quad'},
|
||||
{name: 'Custom', model: 'custom', image: 'custom'},
|
||||
{name: 'Custom Airplane', model: 'custom', image: 'custom'},
|
||||
{name: 'Custom Tricopter', model: 'custom', image: 'custom'}
|
||||
|
||||
{name: 'Tricopter', model: 'tricopter', image: 'tri'}, // 1
|
||||
{name: 'Quad +', model: 'quad_x', image: 'quad_p'}, // 2
|
||||
{name: 'Quad X', model: 'quad_x', image: 'quad_x'}, // 3
|
||||
{name: 'Bicopter', model: 'custom', image: 'bicopter'}, // 4
|
||||
{name: 'Gimbal', model: 'custom', image: 'custom'}, // 5
|
||||
{name: 'Y6', model: 'y6', image: 'y6'}, // 6
|
||||
{name: 'Hex +', model: 'hex_plus', image: 'hex_p'}, // 7
|
||||
{name: 'Flying Wing', model: 'custom', image: 'flying_wing'}, // 8
|
||||
{name: 'Y4', model: 'y4', image: 'y4'}, // 9
|
||||
{name: 'Hex X', model: 'hex_x', image: 'hex_x'}, // 10
|
||||
{name: 'Octo X8', model: 'custom', image: 'octo_x8'}, // 11
|
||||
{name: 'Octo Flat +', model: 'custom', image: 'octo_flat_p'}, // 12
|
||||
{name: 'Octo Flat X', model: 'custom', image: 'octo_flat_x'}, // 13
|
||||
{name: 'Airplane', model: 'custom', image: 'airplane'}, // 14
|
||||
{name: 'Heli 120', model: 'custom', image: 'custom'}, // 15
|
||||
{name: 'Heli 90', model: 'custom', image: 'custom'}, // 16
|
||||
{name: 'V-tail Quad', model: 'quad_vtail', image: 'vtail_quad'}, // 17
|
||||
{name: 'Hex H', model: 'custom', image: 'custom'}, // 18
|
||||
{name: 'PPM to SERVO', model: 'custom', image: 'custom'}, // 19
|
||||
{name: 'Dualcopter', model: 'custom', image: 'custom'}, // 20
|
||||
{name: 'Singlecopter', model: 'custom', image: 'custom'}, // 21
|
||||
{name: 'A-tail Quad', model: 'quad_atail', image: 'atail_quad'}, // 22
|
||||
{name: 'Custom', model: 'custom', image: 'custom'}, // 23
|
||||
{name: 'Custom Airplane', model: 'custom', image: 'custom'}, // 24
|
||||
{name: 'Custom Tricopter', model: 'custom', image: 'custom'} // 25
|
||||
];
|
||||
|
|
|
@ -1874,5 +1874,9 @@ var mspHelper = (function (gui) {
|
|||
}
|
||||
};
|
||||
|
||||
self.saveBfConfig = function (callback) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, callback);
|
||||
};
|
||||
|
||||
return self;
|
||||
})(GUI);
|
||||
|
|
|
@ -46,6 +46,7 @@ presets.presets = [
|
|||
],
|
||||
applyDefaults: ["PIDs", "INAV_PID_CONFIG", "ADVANCED_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG", "FC_CONFIG"],
|
||||
settings: [
|
||||
presets.elementHelper("BF_CONFIG", "mixerConfiguration", 3),
|
||||
presets.elementHelper("INAV_PID_CONFIG", "asynchronousMode", 2),
|
||||
presets.elementHelper("FC_CONFIG", "loopTime", 1000),
|
||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 0),
|
||||
|
@ -68,10 +69,13 @@ presets.presets = [
|
|||
],
|
||||
applyDefaults: ["PIDs", "INAV_PID_CONFIG", "ADVANCED_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG", "FC_CONFIG"],
|
||||
settings: [
|
||||
presets.elementHelper("BF_CONFIG", "mixerConfiguration", 8),
|
||||
presets.elementHelper("PIDs", 0, [15, 30, 15]), //ROLL PIDs
|
||||
presets.elementHelper("PIDs", 1, [15, 40, 15]), //PITCH PIDs
|
||||
presets.elementHelper("RC_tuning", "roll_rate", 400),
|
||||
presets.elementHelper("RC_tuning", "pitch_rate", 150)
|
||||
presets.elementHelper("RC_tuning", "pitch_rate", 150),
|
||||
presets.elementHelper("ADVANCED_CONFIG", "gyroSync", 1),
|
||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 1)
|
||||
]
|
||||
}
|
||||
];
|
||||
|
@ -134,6 +138,7 @@ TABS.profiles.initialize = function (callback, scrollPosition) {
|
|||
|
||||
loadChainer.setChain([
|
||||
mspHelper.loadMspIdent,
|
||||
mspHelper.loadBfConfig,
|
||||
mspHelper.loadLoopTime,
|
||||
mspHelper.loadINAVPidConfig,
|
||||
mspHelper.loadAdvancedConfig,
|
||||
|
@ -153,6 +158,7 @@ TABS.profiles.initialize = function (callback, scrollPosition) {
|
|||
mspHelper.savePidData,
|
||||
mspHelper.saveRcTuningData,
|
||||
mspHelper.savePidAdvanced,
|
||||
mspHelper.saveBfConfig,
|
||||
mspHelper.saveToEeprom
|
||||
]);
|
||||
saveChainer.setExitPoint(reboot);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue