mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-15 20:35:19 +03:00
Added 3D configuration parameters so they don't have to be changed in the CLI
This commit is contained in:
parent
716457b0ed
commit
31cd2de3d3
5 changed files with 97 additions and 3 deletions
|
@ -503,6 +503,21 @@
|
||||||
"configurationBatteryMultiwiiCurrent": {
|
"configurationBatteryMultiwiiCurrent": {
|
||||||
"message": "Enable support for legacy Multiwii MSP current output"
|
"message": "Enable support for legacy Multiwii MSP current output"
|
||||||
},
|
},
|
||||||
|
"configuration3d": {
|
||||||
|
"message": "3D"
|
||||||
|
},
|
||||||
|
"configuration3dDeadbandLow": {
|
||||||
|
"message": "3D Deadband Low"
|
||||||
|
},
|
||||||
|
"configuration3dDeadbandHigh": {
|
||||||
|
"message": "3D Deadband High"
|
||||||
|
},
|
||||||
|
"configuration3dNeutral": {
|
||||||
|
"message": "3D Neutral"
|
||||||
|
},
|
||||||
|
"configuration3dDeadbandThrottle": {
|
||||||
|
"message": "3D Deadband Throttle"
|
||||||
|
},
|
||||||
"configurationSystem": {
|
"configurationSystem": {
|
||||||
"message": "System configuration"
|
"message": "System configuration"
|
||||||
},
|
},
|
||||||
|
|
|
@ -165,6 +165,13 @@ var MISC = {
|
||||||
vbatwarningcellvoltage: 0
|
vbatwarningcellvoltage: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
|
var _3D = {
|
||||||
|
deadband3d_low: 0,
|
||||||
|
deadband3d_high: 0,
|
||||||
|
neutral3d: 0,
|
||||||
|
deadband3d_throttle: 0
|
||||||
|
};
|
||||||
|
|
||||||
var DATAFLASH = {
|
var DATAFLASH = {
|
||||||
ready: false,
|
ready: false,
|
||||||
sectors: 0,
|
sectors: 0,
|
||||||
|
|
22
js/msp.js
22
js/msp.js
|
@ -52,6 +52,7 @@ var MSP_codes = {
|
||||||
MSP_WP: 118,
|
MSP_WP: 118,
|
||||||
MSP_BOXIDS: 119,
|
MSP_BOXIDS: 119,
|
||||||
MSP_SERVO_CONFIGURATIONS: 120,
|
MSP_SERVO_CONFIGURATIONS: 120,
|
||||||
|
MSP_3D: 124,
|
||||||
|
|
||||||
MSP_SET_RAW_RC: 200,
|
MSP_SET_RAW_RC: 200,
|
||||||
MSP_SET_RAW_GPS: 201,
|
MSP_SET_RAW_GPS: 201,
|
||||||
|
@ -67,6 +68,7 @@ var MSP_codes = {
|
||||||
MSP_SET_HEAD: 211,
|
MSP_SET_HEAD: 211,
|
||||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||||
MSP_SET_MOTOR: 214,
|
MSP_SET_MOTOR: 214,
|
||||||
|
MSP_SET_3D: 217,
|
||||||
|
|
||||||
// MSP_BIND: 240,
|
// MSP_BIND: 240,
|
||||||
|
|
||||||
|
@ -409,6 +411,16 @@ var MSP = {
|
||||||
MISC.vbatmaxcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
|
MISC.vbatmaxcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
|
||||||
MISC.vbatwarningcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
|
MISC.vbatwarningcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
|
||||||
break;
|
break;
|
||||||
|
case MSP_codes.MSP_3D:
|
||||||
|
var offset = 0;
|
||||||
|
_3D.deadband3d_low = data.getUint16(offset, 1);
|
||||||
|
offset += 2;
|
||||||
|
_3D.deadband3d_high = data.getUint16(offset, 1);
|
||||||
|
offset += 2;
|
||||||
|
_3D.neutral3d = data.getUint16(offset, 1);
|
||||||
|
offset += 2;
|
||||||
|
_3D.deadband3d_throttle = data.getUint16(offset, 1);
|
||||||
|
break;
|
||||||
case MSP_codes.MSP_MOTOR_PINS:
|
case MSP_codes.MSP_MOTOR_PINS:
|
||||||
console.log(data);
|
console.log(data);
|
||||||
break;
|
break;
|
||||||
|
@ -1129,6 +1141,16 @@ MSP.crunch = function (code) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case MSP_codes.MSP_SET_3D:
|
||||||
|
buffer.push(lowByte(_3D.deadband3d_low));
|
||||||
|
buffer.push(highByte(_3D.deadband3d_low));
|
||||||
|
buffer.push(lowByte(_3D.deadband3d_high));
|
||||||
|
buffer.push(highByte(_3D.deadband3d_high));
|
||||||
|
buffer.push(lowByte(_3D.neutral3d));
|
||||||
|
buffer.push(highByte(_3D.neutral3d));
|
||||||
|
buffer.push(lowByte(_3D.deadband3d_throttle));
|
||||||
|
buffer.push(highByte(_3D.deadband3d_throttle));
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -241,6 +241,7 @@
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="rightWrapper system">
|
<div class="rightWrapper system">
|
||||||
<div class="groupTitle" i18n="configurationSystem"></div>
|
<div class="groupTitle" i18n="configurationSystem"></div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
|
@ -303,6 +304,34 @@
|
||||||
<p i18n="configurationGPSHelp"></p>
|
<p i18n="configurationGPSHelp"></p>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<div class="leftWrapper 3d">
|
||||||
|
<div class="groupTitle" i18n="configuration3d"></div>
|
||||||
|
<div class="number">
|
||||||
|
<label>
|
||||||
|
<input type="number" name="3ddeadbandlow" step="1" min="1000" max="2000"/>
|
||||||
|
<span i18n="configuration3dDeadbandLow"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<label>
|
||||||
|
<input type="number" name="3ddeadbandhigh" step="1" min="1000" max="2000"/>
|
||||||
|
<span i18n="configuration3dDeadbandHigh"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<label>
|
||||||
|
<input type="number" name="3dneutral" step="1" min="1000" max="2000"/>
|
||||||
|
<span i18n="configuration3dNeutral"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<label>
|
||||||
|
<input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000"/>
|
||||||
|
<span i18n="configuration3dDeadbandThrottle"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="groupTitle" i18n="configurationFeatures"></div>
|
<div class="groupTitle" i18n="configurationFeatures"></div>
|
||||||
|
@ -320,6 +349,9 @@
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
<div class="buttons">
|
<div class="buttons">
|
||||||
<a class="save" href="#" i18n="configurationButtonSave"></a>
|
<a class="save" href="#" i18n="configurationButtonSave"></a>
|
||||||
|
|
|
@ -27,7 +27,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_misc() {
|
function load_misc() {
|
||||||
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_acc_trim);
|
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_3d);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_3d() {
|
||||||
|
MSP.send_message(MSP_codes.MSP_3D, false, false, load_acc_trim);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_acc_trim() {
|
function load_acc_trim() {
|
||||||
|
@ -313,6 +317,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
||||||
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput);
|
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput);
|
||||||
|
|
||||||
|
//fill 3D
|
||||||
|
$('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low);
|
||||||
|
$('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
|
||||||
|
$('input[name="3dneutral"]').val(_3D.neutral3d);
|
||||||
|
$('input[name="3ddeadbandthrottle"]').val(_3D.deadband3d_throttle);
|
||||||
|
|
||||||
// UI hooks
|
// UI hooks
|
||||||
$('input[name="looptime"]').change(function() {
|
$('input[name="looptime"]').change(function() {
|
||||||
|
@ -384,6 +393,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
MISC.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
MISC.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
||||||
MISC.vbatscale = parseInt($('input[name="voltagescale"]').val());
|
MISC.vbatscale = parseInt($('input[name="voltagescale"]').val());
|
||||||
|
|
||||||
|
_3D.deadband3d_low = parseInt($('input[name="3ddeadbandlow"]').val());
|
||||||
|
_3D.deadband3d_high = parseInt($('input[name="3ddeadbandhigh"]').val());
|
||||||
|
_3D.neutral3d = parseInt($('input[name="3dneutral"]').val());
|
||||||
|
_3D.deadband3d_throttle = ($('input[name="3ddeadbandthrottle"]').val());
|
||||||
|
|
||||||
BF_CONFIG.currentscale = parseInt($('input[name="currentscale"]').val());
|
BF_CONFIG.currentscale = parseInt($('input[name="currentscale"]').val());
|
||||||
BF_CONFIG.currentoffset = parseInt($('input[name="currentoffset"]').val());
|
BF_CONFIG.currentoffset = parseInt($('input[name="currentoffset"]').val());
|
||||||
MISC.multiwiicurrentoutput = ~~$('input[name="multiwiicurrentoutput"]').is(':checked'); // ~~ boolean to decimal conversion
|
MISC.multiwiicurrentoutput = ~~$('input[name="multiwiicurrentoutput"]').is(':checked'); // ~~ boolean to decimal conversion
|
||||||
|
@ -397,7 +411,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_misc() {
|
function save_misc() {
|
||||||
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_acc_trim);
|
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_3d);
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_3d() {
|
||||||
|
MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, save_acc_trim);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_acc_trim() {
|
function save_acc_trim() {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue