Skip to content
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
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,6 @@
[submodule "core/frontend/src/components/vue-tour"]
path = core/frontend/src/components/vue-tour
url = https://github.com/pulsardev/vue-tour
[submodule "core/frontend/src/PX4-parameters"]
path = core/frontend/src/PX4-parameters
url = [email protected]:patrickelectric/PX4-parameters.git
1 change: 1 addition & 0 deletions core/frontend/src/PX4-parameters
Submodule PX4-parameters added at 88ff13
37 changes: 35 additions & 2 deletions core/frontend/src/components/parameter-editor/ParameterEditor.vue
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
:headers="[
{ text: 'Name', value: 'name' },
{ text: 'Description', value: 'description' },
{ text: 'Value', value: 'value', width: '150px' },
{ text: 'Value', value: 'value', width: '170px' },
]"
:loading="!finished_loading"
:items="search && search != '' ? fuse.search(search) : params_no_input"
Expand Down Expand Up @@ -62,7 +62,19 @@
</template>
<!-- eslint-enable -->
<template #item.value="{ item }">
{{ printParam(item.item) }} {{ item.item.units ? `[${item.item.units}]` : '' }}
<div class="value-cell-content">
{{ printParam(item.item) }} {{ item.item.units ? `[${item.item.units}]` : '' }}
<v-btn
v-if="!item.item?.readonly && item.item?.default !== undefined && item.item?.default !== item.item.value"
v-tooltip="item.item?.rebootRequired ? 'Reboot required' : undefined"
icon
:color="item.item?.rebootRequired ? 'warning' : 'primary'"
class="value-cell-content-restore"
@click.stop="setDefaultParamValue(item.item)"
>
<v-icon>mdi-backup-restore</v-icon>
</v-btn>
</div>
</template>
<template #footer.prepend>
<v-btn
Expand Down Expand Up @@ -146,6 +158,7 @@ import { saveAs } from 'file-saver'
import Fuse from 'fuse.js'
import Vue from 'vue'

import mavlink2rest from '@/libs/MAVLink2Rest'
import autopilot_data from '@/store/autopilot'
import autopilot from '@/store/autopilot_manager'
import Parameter, { printParam } from '@/types/autopilot/parameter'
Expand Down Expand Up @@ -217,6 +230,16 @@ export default Vue.extend({
},
},
methods: {
setDefaultParamValue(param: Parameter) {
if (param.default === undefined || param.readonly) {
return
}
mavlink2rest.setParam(param.name, param.default, autopilot_data.system_id, param.paramType.type)

if (param.rebootRequired) {
autopilot_data.setRebootRequired(true)
}
},
editParam(param: Parameter) {
if (param.readonly) {
return
Expand Down Expand Up @@ -330,4 +353,14 @@ div.v-messages {
.hand-cursor {
cursor: pointer;
}

.value-cell-content {
display: flex;
justify-content: space-between;
align-items: center;
}

.value-cell-content-restore {
margin-left: auto;
}
</style>
94 changes: 75 additions & 19 deletions core/frontend/src/types/autopilot/parameter-table.ts
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
import { isNumber } from 'lodash'

import { fetchVehicleType } from '@/components/autopilot/AutopilotManagerUpdater'
import { MavAutopilot } from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum'
import autopilot_data from '@/store/autopilot'
import autopilot from '@/store/autopilot_manager'
import { Dictionary } from '@/types/common'

import Parameter from './parameter'
import { fetchPX4Metadata, PX4ParametersMetadata } from './px4/metadata-fetcher'

// Parameter metadata as in the JSON files
interface Metadata {
Expand All @@ -21,6 +24,7 @@ interface Metadata {
Values?: {[key:number] : string}
User?: string
Units?: string
Default?: string
}

interface MetadataCategory {
Expand All @@ -29,6 +33,52 @@ interface MetadataCategory {
interface MetadataFile {
[key: string]: MetadataCategory;
}

function fromPX4toArduPilotParametersMetadata(parameters: PX4ParametersMetadata[]): Record<string, Metadata> {
return parameters.reduce((acc, param) => {
acc[param.name] = {
User: param.category,
Description: param.longDesc ?? param.shortDesc,
DisplayName: param.shortDesc,
...param.max && param.min && { Range: { high: param.max.toString(), low: param.min.toString() } },
...param.rebootRequire && { RebootRequired: param.rebootRequire ? 'True' : 'False' },
...param.units && { Units: param.units },
}

// In case default is like 1.0 and got loaded as 1 but should be a float
if (Number.isInteger(param.default) && param.type === 'Float') {
acc[param.name].Default = param.default.toFixed(1)
} else {
acc[param.name].Default = param.default.toString()
}

if (param.increment) {
// In case increment is like 1.0 and got loaded as 1 but should be a float
if (Number.isInteger(param.increment) && param.type === 'Float') {
acc[param.name].Increment = param.increment.toFixed(1)
} else {
acc[param.name].Increment = param.increment.toString()
}
}

if (param.values) {
acc[param.name].Values = param.values.reduce((valuesAcc, val) => {
valuesAcc[val.value] = val.description
return valuesAcc
}, {} as Record<number, string>)
}

if (param.bitmask) {
acc[param.name].Bitmask = param.bitmask.reduce((bitmaskAcc, val) => {
bitmaskAcc[val.index] = val.description
return bitmaskAcc
}, {} as Record<number, string>)
}

return acc
}, {} as Record<string, Metadata>)
}

export default class ParametersTable {
parametersDict: {[key: number] : Parameter} = {}

Expand All @@ -51,26 +101,31 @@ export default class ParametersTable {
setTimeout(() => { this.fetchMetadata() }, 1000)
return
}
let metadata: MetadataFile
if (autopilot.vehicle_type === 'Submarine') {
metadata = await import('@/ArduPilot-Parameter-Repository/Sub-4.1/apm.pdef.json')
}
// This is to avoid importing a 40 lines enum from mavlink and adding a switch case with 40 cases
else if (autopilot.vehicle_type.toLowerCase().includes('copter')
|| autopilot.vehicle_type.toLowerCase().includes('rotor')) {
metadata = await import('@/ArduPilot-Parameter-Repository/Copter-4.3/apm.pdef.json')
} else if (autopilot.vehicle_type.toLowerCase().includes('rover')
|| autopilot.vehicle_type.toLowerCase().includes('boat')) {
metadata = await import('@/ArduPilot-Parameter-Repository/Rover-4.2/apm.pdef.json')
}

for (const category of Object.values(metadata)) {
for (const [name, parameter] of Object.entries(category)) {
if (isNumber(parameter)) { // ignore "json" entry
console.log(`ignoring ${name} : ${parameter}`)
continue
if (autopilot_data.autopilot_type === MavAutopilot.MAV_AUTOPILOT_PX4) {
this.metadata = fromPX4toArduPilotParametersMetadata(await fetchPX4Metadata())
} else {
let metadata: MetadataFile
if (autopilot.vehicle_type === 'Submarine') {
metadata = await import('@/ArduPilot-Parameter-Repository/Sub-4.1/apm.pdef.json')
}
// This is to avoid importing a 40 lines enum from mavlink and adding a switch case with 40 cases
else if (autopilot.vehicle_type.toLowerCase().includes('copter')
|| autopilot.vehicle_type.toLowerCase().includes('rotor')) {
metadata = await import('@/ArduPilot-Parameter-Repository/Copter-4.3/apm.pdef.json')
} else if (autopilot.vehicle_type.toLowerCase().includes('rover')
|| autopilot.vehicle_type.toLowerCase().includes('boat')) {
metadata = await import('@/ArduPilot-Parameter-Repository/Rover-4.2/apm.pdef.json')
}

for (const category of Object.values(metadata)) {
for (const [name, parameter] of Object.entries(category)) {
if (isNumber(parameter)) { // ignore "json" entry
console.log(`ignoring ${name} : ${parameter}`)
continue
}
this.metadata[name] = parameter
}
this.metadata[name] = parameter
}
}

Expand All @@ -90,14 +145,15 @@ export default class ParametersTable {
param.shortDescription = this.metadata[param.name].DisplayName
param.units = this.metadata[param.name].Units
const {
Values, Bitmask, ReadOnly, Increment, RebootRequired, Range,
Values, Bitmask, ReadOnly, Increment, RebootRequired, Range, Default,
} = this.metadata[param.name]
param.options = Values
param.bitmask = Bitmask
param.readonly = ReadOnly === 'True'
param.increment = Increment ? parseFloat(Increment) : undefined
param.rebootRequired = RebootRequired === 'True'
param.range = Range ? { high: parseFloat(Range.high), low: parseFloat(Range.low) } : undefined
param.default = Default ? parseFloat(Default) : undefined
}
this.parametersDict[param.id] = param
}
Expand Down
2 changes: 2 additions & 0 deletions core/frontend/src/types/autopilot/parameter.ts
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ export default interface Parameter {
paramType: { type: ParamType }

units?: string

default?: number
}

export function printParam(param?: Parameter): string {
Expand Down
56 changes: 56 additions & 0 deletions core/frontend/src/types/autopilot/px4/metadata-fetcher.ts
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
interface PX4ParametersMetadataValuesItem {
description: string
value: number
}

interface PX4ParametersMetadataBitmaskItem {
description: string
index: number
}

interface PX4ParametersMetadata {
name: string
category: string
group: string
type: string

shortDesc: string
longDesc?: string

default: number
max?: number
min?: number
increment?: number
units?: string

values?: PX4ParametersMetadataValuesItem[]
bitmask?: PX4ParametersMetadataBitmaskItem[]

decimalPlaces?: number
volatile?: boolean
rebootRequire?: boolean
}

async function fetchPX4MetadataFromBoard(): Promise<PX4ParametersMetadata[]> {
// TODO - Add mav ftp fetch to get parameters.json from board
throw new Error('Not implemented')
}

async function fetchPX4Metadata(): Promise<PX4ParametersMetadata[]> {
let metadata
try {
metadata = await fetchPX4MetadataFromBoard()
} catch (e) {
metadata = (await import('@/PX4-parameters/master/parameters.json')).parameters
}

return metadata as PX4ParametersMetadata[]
}

export {
fetchPX4Metadata,
fetchPX4MetadataFromBoard,
PX4ParametersMetadata,
PX4ParametersMetadataBitmaskItem,
PX4ParametersMetadataValuesItem,
}