Skip to content

Commit

Permalink
Update added parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
haslinghuis committed May 21, 2024
1 parent 9afc5b4 commit a1dfb48
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 8 deletions.
4 changes: 2 additions & 2 deletions src/js/backup_restore.js
Original file line number Diff line number Diff line change
Expand Up @@ -491,8 +491,8 @@ export function configuration_restore(callback) {

if (configuration.ARMING_CONFIG == undefined) {
configuration.ARMING_CONFIG = {
auto_disarm_delay: 5,
gyro_cal_on_first_arm: 0,
auto_disarm_delay: 5,
disarm_kill_switch: 1,
};
}

Expand Down
3 changes: 2 additions & 1 deletion src/js/fc.js
Original file line number Diff line number Diff line change
Expand Up @@ -390,8 +390,9 @@ const FC = {

this.ARMING_CONFIG = {
auto_disarm_delay: 0,
gyro_cal_on_first_arm: 0,
disarm_kill_switch: 0,
small_angle: 0,
gyro_cal_on_first_arm: 0,
};

this.FC_CONFIG = {
Expand Down
13 changes: 10 additions & 3 deletions src/js/msp/MSPHelper.js
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ import semver from 'semver';
import vtxDeviceStatusFactory from "../utils/VtxDeviceStatus/VtxDeviceStatusFactory";
import MSP from "../msp";
import MSPCodes from "./MSPCodes";
import { API_VERSION_1_42, API_VERSION_1_43, API_VERSION_1_44, API_VERSION_1_45, API_VERSION_1_46 } from '../data_storage';
import { API_VERSION_1_42, API_VERSION_1_43, API_VERSION_1_44, API_VERSION_1_45, API_VERSION_1_46, API_VERSION_1_47 } from '../data_storage';
import EscProtocols from "../utils/EscProtocols";
import huffmanDecodeBuf from "../huffman";
import { defaultHuffmanTree, defaultHuffmanLenIndex } from "../default_huffman_tree";
Expand All @@ -17,6 +17,7 @@ import { showErrorDialog } from "../utils/showErrorDialog";
import GUI, { TABS } from "../gui";
import { OSD } from "../tabs/osd";
import { reinitializeConnection } from "../serial_backend";
import { s } from 'vitest/dist/index-2dd51af4.js';

// Used for LED_STRIP
const ledDirectionLetters = ['n', 'e', 's', 'w', 'u', 'd']; // in LSB bit order
Expand Down Expand Up @@ -466,8 +467,11 @@ MspHelper.prototype.process_data = function(dataHandler) {

case MSPCodes.MSP_ARMING_CONFIG:
FC.ARMING_CONFIG.auto_disarm_delay = data.readU8();
FC.ARMING_CONFIG.gyro_cal_on_first_arm = data.readU8();
FC.ARMING_CONFIG.disarm_kill_switch = data.readU8();
FC.ARMING_CONFIG.small_angle = data.readU8();
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
FC.ARMING_CONFIG.gyro_cal_on_first_arm = data.readU8();
}
break;
case MSPCodes.MSP_LOOP_TIME:
FC.FC_CONFIG.loopTime = data.readU16();
Expand Down Expand Up @@ -1792,8 +1796,11 @@ MspHelper.prototype.crunch = function(code, modifierCode = undefined) {
break;
case MSPCodes.MSP_SET_ARMING_CONFIG:
buffer.push8(FC.ARMING_CONFIG.auto_disarm_delay)
.push8(FC.ARMING_CONFIG.gyro_cal_on_first_arm)
.push8(FC.ARMING_CONFIG.disarm_kill_switch)
.push8(FC.ARMING_CONFIG.small_angle);
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
buffer.push8(FC.ARMING_CONFIG.gyro_cal_on_first_arm);
}
break;
case MSPCodes.MSP_SET_LOOP_TIME:
buffer.push16(FC.FC_CONFIG.loopTime);
Expand Down
7 changes: 5 additions & 2 deletions src/js/tabs/configuration.js
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ import MSPCodes from '../msp/MSPCodes';
import { API_VERSION_1_42, API_VERSION_1_43, API_VERSION_1_45, API_VERSION_1_47 } from '../data_storage';
import { updateTabList } from '../utils/updateTabList';
import $ from 'jquery';
import { s } from 'vitest/dist/index-2dd51af4.js';

const configuration = {
analyticsChanges: {},
Expand Down Expand Up @@ -407,8 +408,10 @@ configuration.initialize = function (callback) {
FC.CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val());
FC.CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val());

FC.ARMING_CONFIG.auto_disarm_delay = parseInt($('input[id="configurationAutoDisarmDelay"]').val());
FC.ARMING_CONFIG.gyro_cal_on_first_arm = $('input[id="configurationGyroCalOnFirstArm"]').is(':checked') ? 1 : 0;
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
FC.ARMING_CONFIG.gyro_cal_on_first_arm = $('input[id="configurationGyroCalOnFirstArm"]').is(':checked') ? 1 : 0;
FC.ARMING_CONFIG.auto_disarm_delay = parseInt($('input[id="configurationAutoDisarmDelay"]').val());
}
FC.ARMING_CONFIG.small_angle = parseInt($('input[id="configurationSmallAngle"]').val());

FC.SENSOR_ALIGNMENT.gyro_to_use = parseInt(orientation_gyro_to_use_e.val());
Expand Down

0 comments on commit a1dfb48

Please sign in to comment.