Skip to content
Draft
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
112 changes: 112 additions & 0 deletions core/frontend/src/components/parameter-editor/ParameterCheckbox.vue
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
<template>
<div class="d-flex align-center">
<div class="flex-grow-1">
<v-checkbox
v-model="internal_value"
dense
hide-details
:indeterminate="waiting_for_param_update"
:label="label ?? param?.name ?? 'Parameter not found'"
:true-value="checkedValue"
:false-value="uncheckedValue"
@change="onCheckboxChange"
/>
</div>
</div>
</template>

<script lang="ts">
import Vue, { PropType } from 'vue'

import mavlink2rest from '@/libs/MAVLink2Rest'
import autopilot_data from '@/store/autopilot'
import Parameter from '@/types/autopilot/parameter'

export default Vue.extend({
name: 'ParameterCheckbox',
model: {
prop: 'value',
event: 'change',
},
props: {
param: {
type: Object as PropType<Parameter>,
required: true,
},
label: {
type: String as PropType<string | undefined>,
default: undefined,
},
checkedValue: {
type: Number,
default: 1,
},
uncheckedValue: {
type: Number,
default: 0,
},
},
data() {
return {
internal_value: undefined as number | undefined,
last_sent_value: undefined as number | undefined,
}
},
computed: {
waiting_for_param_update(): boolean {
// Don't show loading state if the value was just set and we're waiting for vehicle to catch up
if (!this.last_sent_value || this.param_value === this.last_sent_value) {
return false
}
return this.param?.value !== this.internal_value
},
param_value(): number {
return this.param?.value ?? this.uncheckedValue
Comment on lines +63 to +64
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

suggestion (bug_risk): Defaulting 'param_value' to 'uncheckedValue' could mask issues.

Defaulting to 'uncheckedValue' when 'param' is undefined may hide errors. Consider returning undefined or throwing to surface issues during development.

Suggested implementation:

    param_value(): number | undefined {
      return this.param?.value
    },

If you prefer to throw an error instead of returning undefined, replace the body of param_value with:

if (!this.param) {
  throw new Error("Parameter 'param' is undefined in ParameterCheckbox");
}
return this.param.value;

You may also need to update any code that uses param_value to handle the possibility of undefined or the thrown error.

},
},
watch: {
param(newParam) {
if (newParam) {
this.internal_value = newParam.value
Comment on lines +68 to +70
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

issue (bug_risk): The watcher on 'param' may overwrite user input.

If 'param' changes during user interaction, 'internal_value' may be reset and overwrite user input. Consider updating 'internal_value' only for external changes, not user actions.

}
},
param_value() {
if (this.last_sent_value === undefined) {
this.internal_value = this.param_value
}
},
},
mounted() {
this.internal_value = this.param?.value ?? this.uncheckedValue
},
methods: {
onCheckboxChange(value: number): void {
if (this.param_value === value) {
return
}
this.internal_value = value
this.saveEditedParam()
},

async saveEditedParam(): Promise<void> {
if (this.param_value === this.internal_value) {
return
}
if (this.param === undefined || this.internal_value === undefined) {
return
}
if (this.param?.rebootRequired) {
autopilot_data.setRebootRequired(true)
}
this.last_sent_value = this.internal_value

await mavlink2rest.setParam(
this.param.name,
this.internal_value,
autopilot_data.system_id,
this.param.paramType.type,
)
Comment on lines +103 to +108
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

suggestion (bug_risk): No error handling for failed parameter save.

Add error handling for 'mavlink2rest.setParam' failures to provide user feedback or implement a retry mechanism.

Suggested change
await mavlink2rest.setParam(
this.param.name,
this.internal_value,
autopilot_data.system_id,
this.param.paramType.type,
)
try {
await mavlink2rest.setParam(
this.param.name,
this.internal_value,
autopilot_data.system_id,
this.param.paramType.type,
)
} catch (error) {
// Provide user feedback on failure
// Replace with your preferred notification system if available
// For now, use alert as a placeholder
alert('Failed to save parameter. Please try again.');
// Optionally, you could implement a retry mechanism here
}

},
},
})
</script>
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,26 @@
<v-icon>mdi-close</v-icon>
</v-btn>
</v-card-title>

<v-card-text>
<inline-parameter-editor
:auto-set="true"
:label="param.name"
:param="param"
/>

<v-row>
<v-col cols="6">
<inline-parameter-editor
:auto-set="true"
:label="param.name"
:param="param"
/>
</v-col>
<v-col cols="6">
<parameter-checkbox
:param="reverse_param"
label="Reverse Direction"
:checked-value="1"
:unchecked-value="0"
/>
</v-col>
Comment on lines +20 to +34
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

suggestion: Splitting the editor and checkbox into two columns may cause layout issues on small screens.

Consider applying Vuetify's grid breakpoints to stack these components vertically on small screens for better responsiveness.

Suggested change
<v-col cols="6">
<inline-parameter-editor
:auto-set="true"
:label="param.name"
:param="param"
/>
</v-col>
<v-col cols="6">
<parameter-checkbox
:param="reverse_param"
label="Reverse Direction"
:checked-value="1"
:unchecked-value="0"
/>
</v-col>
<v-col cols="12" sm="6">
<inline-parameter-editor
:auto-set="true"
:label="param.name"
:param="param"
/>
</v-col>
<v-col cols="12" sm="6">
<parameter-checkbox
:param="reverse_param"
label="Reverse Direction"
:checked-value="1"
:unchecked-value="0"
/>
</v-col>

</v-row>
</v-card-text>
<v-card-text>
<v-card class="mt-4 mb-4">
<v-card-text>
<div class="d-flex align-center mb-4">
Expand Down Expand Up @@ -150,6 +162,7 @@ import autopilot from '@/store/autopilot'
import Parameter from '@/types/autopilot/parameter'

import InlineParameterEditor from './InlineParameterEditor.vue'
import ParameterCheckbox from './ParameterCheckbox.vue'

type ParamType = 'min' | 'trim' | 'max'
type ParamValueKey = 'minValue' | 'trimValue' | 'maxValue'
Expand All @@ -167,6 +180,7 @@ export default Vue.extend({
name: 'ServoFunctionEditorDialog',
components: {
InlineParameterEditor,
ParameterCheckbox,
},
model: {
prop: 'value',
Expand Down Expand Up @@ -202,6 +216,9 @@ export default Vue.extend({
min_param(): Parameter | undefined {
return this.getParamByType('_MIN')
},
reverse_param(): Parameter | undefined {
return this.getParamByType('_REVERSED')
},
minPercent(): number {
return this.calculatePercentage(this.minValue)
},
Expand Down
Loading