Skip to content

Manage disabled fields #460

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 3 commits into from
Jul 28, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 19 additions & 0 deletions index.html
Original file line number Diff line number Diff line change
Expand Up @@ -1506,6 +1506,25 @@ <h5 class="modal-title-craft"></h5>
</table>
</div>
</div>
<div class="gui_box grey disabled_fields">
<div class="gui_box_titlebar">
<div class="spacer_box_title">Disabled Fields</div>
</div>
<div class="spacer_box">
<table cellpadding="0" cellspacing="0">
<thead class="fields_list disabled_fields noline">
<tr>
<th class="checkbox"></th>
<th class="item"></th>
<th class="description"></th>
</tr>
</thead>
<tbody class="fields_list disabled_fields noline">
<!-- table generated here -->
</tbody>
</table>
</div>
</div>
</div>
<div class="cf_column half right">
<div class="spacer_left">
Expand Down
123 changes: 86 additions & 37 deletions js/flightlog.js
Original file line number Diff line number Diff line change
Expand Up @@ -209,27 +209,32 @@ function FlightLog(logData) {
};

function buildFieldNames() {
var
i;

// Make an independent copy
fieldNames = parser.frameDefs.I.name.slice(0);

// Add names of slow fields which we'll merge into the main stream
if (parser.frameDefs.S) {
for (i = 0; i < parser.frameDefs.S.name.length; i++) {
for (let i = 0; i < parser.frameDefs.S.name.length; i++) {
fieldNames.push(parser.frameDefs.S.name[i]);
}
}

// Add names for our ADDITIONAL_COMPUTED_FIELDS
fieldNames.push("heading[0]", "heading[1]", "heading[2]");
fieldNames.push("axisSum[0]", "axisSum[1]", "axisSum[2]");
fieldNames.push("rcCommands[0]", "rcCommands[1]", "rcCommands[2]", "rcCommands[3]"); // Custom calculated scaled rccommand
fieldNames.push("axisError[0]", "axisError[1]", "axisError[2]"); // Custom calculated error field
if (!that.isFieldDisabled().GYRO) {
fieldNames.push("heading[0]", "heading[1]", "heading[2]");
}
if (!that.isFieldDisabled().PID) {
fieldNames.push("axisSum[0]", "axisSum[1]", "axisSum[2]");
}
if (!that.isFieldDisabled().SETPOINT) {
fieldNames.push("rcCommands[0]", "rcCommands[1]", "rcCommands[2]", "rcCommands[3]"); // Custom calculated scaled rccommand
}
if (!(that.isFieldDisabled().GYRO || that.isFieldDisabled().PID)) {
fieldNames.push("axisError[0]", "axisError[1]", "axisError[2]"); // Custom calculated error field
}

fieldNameToIndex = {};
for (i = 0; i < fieldNames.length; i++) {
for (let i = 0; i < fieldNames.length; i++) {
fieldNameToIndex[fieldNames[i]] = i;
}
}
Expand Down Expand Up @@ -537,6 +542,26 @@ function FlightLog(logData) {
magADC = false;
}

if (!gyroADC[0]) {
gyroADC = false;
}

if (!accSmooth[0]) {
accSmooth = false;
}

if (!rcCommand[0]) {
rcCommand = false;
}

if (!setpoint[0]) {
setpoint = false;
}

if (!axisPID[0]) {
axisPID = false;
}

sysConfig = that.getSysConfig();

sourceChunkIndex = 0;
Expand Down Expand Up @@ -564,34 +589,38 @@ function FlightLog(logData) {
destFrame = destChunk.frames[i],
fieldIndex = destFrame.length - ADDITIONAL_COMPUTED_FIELD_COUNT;

attitude = chunkIMU.updateEstimatedAttitude(
[srcFrame[gyroADC[0]], srcFrame[gyroADC[1]], srcFrame[gyroADC[2]]],
[srcFrame[accSmooth[0]], srcFrame[accSmooth[1]], srcFrame[accSmooth[2]]],
srcFrame[FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME],
sysConfig.acc_1G,
sysConfig.gyroScale,
magADC ? [srcFrame[magADC[0]], srcFrame[magADC[1]], srcFrame[magADC[2]]] : false);

destFrame[fieldIndex++] = attitude.roll;
destFrame[fieldIndex++] = attitude.pitch;
destFrame[fieldIndex++] = attitude.heading;
if (gyroADC) { //don't calculate attitude if no gyro data
attitude = chunkIMU.updateEstimatedAttitude(
[srcFrame[gyroADC[0]], srcFrame[gyroADC[1]], srcFrame[gyroADC[2]]],
[srcFrame[accSmooth[0]], srcFrame[accSmooth[1]], srcFrame[accSmooth[2]]],
srcFrame[FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME],
sysConfig.acc_1G,
sysConfig.gyroScale,
magADC);

destFrame[fieldIndex++] = attitude.roll;
destFrame[fieldIndex++] = attitude.pitch;
destFrame[fieldIndex++] = attitude.heading;
}

// Add the Feedforward PID sum (P+I+D+F)
for (var axis = 0; axis < 3; axis++) {
let pidSum =
(axisPID[axis][0] !== undefined ? srcFrame[axisPID[axis][0]] : 0) +
(axisPID[axis][1] !== undefined ? srcFrame[axisPID[axis][1]] : 0) +
(axisPID[axis][2] !== undefined ? srcFrame[axisPID[axis][2]] : 0) +
(axisPID[axis][3] !== undefined ? srcFrame[axisPID[axis][3]] : 0);

// Limit the PID sum by the limits defined in the header
let pidLimit = axis < AXIS.YAW ? sysConfig.pidSumLimit : sysConfig.pidSumLimitYaw;
if (pidLimit != null && pidLimit > 0) {
pidSum = constrain(pidSum, -pidLimit, pidLimit);
}
if (axisPID) {
for (var axis = 0; axis < 3; axis++) {
let pidSum =
(axisPID[axis][0] !== undefined ? srcFrame[axisPID[axis][0]] : 0) +
(axisPID[axis][1] !== undefined ? srcFrame[axisPID[axis][1]] : 0) +
(axisPID[axis][2] !== undefined ? srcFrame[axisPID[axis][2]] : 0) +
(axisPID[axis][3] !== undefined ? srcFrame[axisPID[axis][3]] : 0);

// Limit the PID sum by the limits defined in the header
let pidLimit = axis < AXIS.YAW ? sysConfig.pidSumLimit : sysConfig.pidSumLimitYaw;
if (pidLimit != null && pidLimit > 0) {
pidSum = constrain(pidSum, -pidLimit, pidLimit);
}

// Assign value
destFrame[fieldIndex++] = pidSum;
// Assign value
destFrame[fieldIndex++] = pidSum;
}
}

// Check the current flightmode (we need to know this so that we can correctly calculate the rates)
Expand Down Expand Up @@ -622,9 +651,11 @@ function FlightLog(logData) {
}

// Calculate the PID Error
for (var axis = 0; axis < 3; axis++) {
let gyroADCdegrees = (gyroADC[axis] !== undefined ? that.gyroRawToDegreesPerSecond(srcFrame[gyroADC[axis]]) : 0);
destFrame[fieldIndex++] = gyroADCdegrees - destFrame[fieldIndexRcCommands + axis];
if (axisPID && gyroADC) {
for (var axis = 0; axis < 3; axis++) {
let gyroADCdegrees = (gyroADC[axis] !== undefined ? that.gyroRawToDegreesPerSecond(srcFrame[gyroADC[axis]]) : 0);
destFrame[fieldIndex++] = gyroADCdegrees - destFrame[fieldIndexRcCommands + axis];
}
}

}
Expand Down Expand Up @@ -1221,3 +1252,21 @@ FlightLog.prototype.getFeatures = function(enabledFeatures) {
ANTI_GRAVITY : (enabledFeatures & (1 << 24))!=0,
};
};

FlightLog.prototype.isFieldDisabled = function() {
const disabledFields=this.getSysConfig().fields_disabled_mask;
return {
PID : (disabledFields & (1 << 0))!==0,
RC_COMMANDS : (disabledFields & (1 << 1))!==0,
SETPOINT : (disabledFields & (1 << 2))!==0,
BATTERY : (disabledFields & (1 << 3))!==0,
MAGNETOMETER : (disabledFields & (1 << 4))!==0,
ALTITUDE : (disabledFields & (1 << 5))!==0,
RSSI : (disabledFields & (1 << 6))!==0,
GYRO : (disabledFields & (1 << 7))!==0,
ACC : (disabledFields & (1 << 8))!==0,
DEBUG : (disabledFields & (1 << 9))!==0,
MOTORS : (disabledFields & (1 << 10))!==0,
GPS : (disabledFields & (1 << 11))!==0,
};
};
2 changes: 2 additions & 0 deletions js/flightlog_parser.js
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,7 @@ var FlightLogParser = function(logData) {
dyn_notch_min_hz: null, // Dyn Notch min limit in Hz for the filter
dyn_notch_max_hz: null, // Dyn Notch max limit in Hz for the filter
rates_type: null,
fields_disabled_mask: null,
unknownHeaders : [] // Unknown Extra Headers
},

Expand Down Expand Up @@ -617,6 +618,7 @@ var FlightLogParser = function(logData) {
case "dyn_notch_min_hz":
case "dyn_notch_max_hz":
case "rates_type":
case "fields_disabled_mask":
that.sysConfig[fieldName] = parseInt(fieldValue, 10);
break;
case "rc_expo":
Expand Down
78 changes: 30 additions & 48 deletions js/graph_config.js
Original file line number Diff line number Diff line change
Expand Up @@ -172,54 +172,6 @@ GraphConfig.load = function(config) {
};

(function() {
var
EXAMPLE_GRAPHS = [
{
label: "Motors",
fields: ["motor[all]", "servo[5]"]
},
{
label: "Gyros",
fields: ["gyroADC[all]"]
},
{ /* Add custom graph configurations to the main menu ! */
label: "RC Rates",
fields: ["rcCommands[all]"]
},
{
label: "RC Command",
fields: ["rcCommand[all]"]
},
{
label: "PIDs",
fields: ["axisSum[all]"]
},
{
label: "PID Error",
fields: ["axisError[all]"]
},
{
label: "Gyro + PID roll",
fields: ["axisP[0]", "axisI[0]", "axisD[0]", "axisF[0]", "gyroADC[0]"]
},
{
label: "Gyro + PID pitch",
fields: ["axisP[1]", "axisI[1]", "axisD[1]", "axisF[1]", "gyroADC[1]"]
},
{
label: "Gyro + PID yaw",
fields: ["axisP[2]", "axisI[2]", "axisD[2]", "axisF[2]", "gyroADC[2]"]
},
{
label: "Accelerometers",
fields: ["accSmooth[all]"]
},
{
label: "Debug",
fields: ["debug[all]"]
}
];

GraphConfig.getDefaultSmoothingForField = function(flightLog, fieldName) {
try{
if (fieldName.match(/^motor\[/)) {
Expand Down Expand Up @@ -598,7 +550,37 @@ GraphConfig.load = function(config) {
var
result = [],
i, j;

const EXAMPLE_GRAPHS = [];

if (!flightLog.isFieldDisabled().MOTORS) {
EXAMPLE_GRAPHS.push({label: "Motors",fields: ["motor[all]", "servo[5]"]});
}
if (!flightLog.isFieldDisabled().GYRO) {
EXAMPLE_GRAPHS.push({label: "Gyros",fields: ["gyroADC[all]"]});
}
if (!flightLog.isFieldDisabled().SETPOINT) {
EXAMPLE_GRAPHS.push({label: "RC Rates",fields: ["rcCommands[all]"]});
}
if (!flightLog.isFieldDisabled().RC_COMMANDS) {
EXAMPLE_GRAPHS.push({label: "RC Command",fields: ["rcCommand[all]"]});
}
if (!flightLog.isFieldDisabled().PID) {
EXAMPLE_GRAPHS.push({label: "PIDs",fields: ["axisSum[all]"]});
}
if (!(flightLog.isFieldDisabled().GYRO || flightLog.isFieldDisabled().PID)) {
EXAMPLE_GRAPHS.push({label: "PID Error",fields: ["axisError[all]"]},
{label: "Gyro + PID roll",fields: ["axisP[0]", "axisI[0]", "axisD[0]", "axisF[0]", "gyroADC[0]"]},
{label: "Gyro + PID pitch",fields: ["axisP[1]", "axisI[1]", "axisD[1]", "axisF[1]", "gyroADC[1]"]},
{label: "Gyro + PID yaw",fields: ["axisP[2]", "axisI[2]", "axisD[2]", "axisF[2]", "gyroADC[2]"]});
}
if (!flightLog.isFieldDisabled().ACC) {
EXAMPLE_GRAPHS.push({label: "Accelerometers",fields: ["accSmooth[all]"]});
}
if (!flightLog.isFieldDisabled().DEBUG) {
EXAMPLE_GRAPHS.push({label: "Debug",fields: ["debug[all]"]});
}

for (i = 0; i < EXAMPLE_GRAPHS.length; i++) {
var
srcGraph = EXAMPLE_GRAPHS[i],
Expand Down
Loading