Skip to content
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

Compass refactor #2993

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ import Vue, { PropType } from 'vue'
import mavlink2rest from '@/libs/MAVLink2Rest'
import autopilot_data from '@/store/autopilot'
import Parameter from '@/types/autopilot/parameter'
import { Dictionary } from '@/types/common'

export default Vue.extend({
name: 'InlineParameterEditor',
Expand Down Expand Up @@ -95,6 +96,10 @@ export default Vue.extend({
type: Boolean,
default: false,
},
metadataOverrides: {
type: Object as PropType<Dictionary<string>>,
default: () => ({}),
},
},
data() {
return {
Expand All @@ -111,6 +116,13 @@ export default Vue.extend({
const entries = Object.entries(this.param?.options ?? [])
const value_is_known = Object.keys(this.param?.options ?? []).map(parseFloat).includes(this.param?.value)
const options = entries.map(([value, name]) => ({ text: name, value: parseFloat(value), disabled: false }))
// replace entries in metadataOverrides
for (const [value, _name] of entries) {
if (value in this.metadataOverrides) {
const index = options.findIndex((option) => option.value === parseFloat(value))
options[index].text = this.metadataOverrides[value]
}
}
if (!value_is_known) {
options.push({ text: `Custom: ${this.param?.value}`, value: this.param?.value, disabled: false })
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,30 +1,13 @@
<template>
<div class="pa-3">
<v-card>
<div class="main-container d-flex flex-col">
<v-card outline class="mr-2 mb-2 flex-shrink-1">
<div class="main-container d-flex flex-row">
<v-card outline class="mr-2 mb-2 flex-shrink-1 d-flex flex-col">
<div class="compass-container">
<compass-display :compasses="reordered_compasses" :colors="compass_colors" />
</div>
<v-card class="pa-2 ma-2" width="300px">
<v-card-title>
Declination
</v-card-title>
<v-card-text class="flex-shrink-1">
<parameter-switch label="Auto Declination" :parameter="compass_autodec" />
<p>
If you enable this option, the autopilot will automatically set the declination based on your current
location. A GPS or other absolute positioning system is required.
</p>
<v-text-field
label="Current Declination"
:disabled="compass_autodec?.value !== 0"
:value="printParam(compass_dec)"
@click="openParameterEditor(compass_dec)"
/>
</v-card-text>
</v-card>
</v-card>

<v-card outline class="compass-calib-container mb-2">
<v-card-title>
<h3>Compass Calibration</h3>
Expand Down Expand Up @@ -91,6 +74,45 @@
</div>
</v-card-text>
</v-card>
<v-card outline class="mr-2 ml-2 mb-2">
<div class="d-block ma-3" style="width: 400px;">
<v-expansion-panels focusable>
<v-expansion-panel>
<v-expansion-panel-header>
<b>Declination</b> ({{ declination_short }})
<v-spacer />
</v-expansion-panel-header>
<v-expansion-panel-content>
<parameter-switch label="Auto Declination" :parameter="compass_autodec" />
<p>
If you enable this option, the autopilot will automatically set the
declination based on your current location.
A GPS or other absolute positioning system is required.
</p>
<InlineParameterEditor v-if="compass_autodec?.value === 0" auto-set :param="compass_dec" />
</v-expansion-panel-content>
</v-expansion-panel>
<v-expansion-panel>
<v-expansion-panel-header>
<template #actions>
<v-icon v-if="coordinates_valid" color="success">
mdi-check-circle
</v-icon>
<v-icon v-else color="error">
mdi-alert
</v-icon>
</template>

<b>Global Position</b>
<v-spacer />
</v-expansion-panel-header>
<v-expansion-panel-content>
<auto-coordinate-detector v-model="coordinates" />
</v-expansion-panel-content>
</v-expansion-panel>
</v-expansion-panels>
</div>
</v-card>
</div>
<div class="compass-reorder-container d-flex flex-row">
<v-tabs v-model="tab" vertical color="primary">
Expand Down Expand Up @@ -198,13 +220,15 @@
import Vue from 'vue'
import draggable from 'vuedraggable'
import {
VCardText, VExpansionPanel, VTextField,
VCardText, VExpansionPanel,
} from 'vuetify/lib'

import ParameterSwitch from '@/components/common/ParameterSwitch.vue'
import InlineParameterEditor from '@/components/parameter-editor/InlineParameterEditor.vue'
import CompassDisplay from '@/components/vehiclesetup/configuration/compass/CompassDisplay.vue'
import CompassParams from '@/components/vehiclesetup/configuration/compass/CompassParams.vue'
import mavlink2rest from '@/libs/MAVLink2Rest'
import Listener from '@/libs/MAVLink2Rest/Listener'
import autopilot_data from '@/store/autopilot'
import Parameter, { printParam } from '@/types/autopilot/parameter'
import { Dictionary } from '@/types/common'
Expand Down Expand Up @@ -237,20 +261,23 @@ export default Vue.extend({
CompassLearn,
CompassParams,
draggable,
VTextField,
LargeVehicleCompassCalibrator,
ParameterSwitch,
VCardText,
VExpansionPanel,
FullCompassCalibrator,
InlineParameterEditor,
},
data() {
return {
tab: 0,
color_options: ['green', 'blue', 'purple', 'red', 'orange', 'brown', 'grey', 'black'],
coordinates: undefined as { lat: number, lon: number } | undefined,
coordinates_valid: false,
reordered_compasses: [] as deviceId[],
edited_param: undefined as (undefined | Parameter),
edit_param_dialog: false,
gps_listener: undefined as Listener | undefined,
}
},
computed: {
Expand All @@ -265,6 +292,12 @@ export default Vue.extend({
results.GPS2 = 'black'
return results
},
declination_short(): string {
if (this.compass_autodec?.value === 1) {
return 'Automatic Declination'
}
return `${this.compass_dec?.value.toFixed(2) ?? 'N/A'} rad`
},
compass_autodec(): Parameter | undefined {
return autopilot_data.parameter('COMPASS_AUTODEC')
},
Expand Down Expand Up @@ -437,6 +470,15 @@ export default Vue.extend({
},
mounted() {
this.reordered_compasses = this.compasses
this.gps_listener = mavlink2rest.startListening('GLOBAL_POSITION_INT').setCallback((receivedMessage) => {
if (receivedMessage.message.lat !== 0 || receivedMessage.message.lon !== 0) {
this.coordinates_valid = true
}
}).setFrequency(0)
mavlink2rest.requestMessageRate('GLOBAL_POSITION_INT', 1, autopilot_data.system_id)
},
beforeDestroy() {
this.gps_listener?.discard()
},
methods: {
printParam,
Expand Down
Original file line number Diff line number Diff line change
@@ -1,16 +1,29 @@
<template>
<v-card-text class="mt-3 pa-0">
<v-tooltip bottom>
<template #activator="{ on }">
<v-icon dense :color="mavlink_lat ? 'green' : 'orange'" v-on="on">
{{ mavlink_lat ? "mdi-check-circle" : "mdi-alert-circle" }}
</v-icon>
</template>
<span>{{ mavlink_lat ? "Valid GPS position" : "No valid GPS position" }}</span>
</v-tooltip>
<b>Vehicle coordinates:</b> {{ mavlink_lat?.toFixed(5) ?? "N/A" }} {{ mavlink_lon?.toFixed(5) ?? "N/A" }}
<div>
<v-alert v-if="!mavlink_lat" dense type="error" class="mt-4">
No valid GPS position!
</v-alert>

A valid (usually GPS) position is required for the calibration to estimate the local world magnetic field.
Estimation of the local magnetic field improves the calibration quality as it
allows a 3D fusion of the compass data.
<br>
<br>
<template v-if="!mavlink_lat && supports_setting_position">
<div v-if="!warnonly">
<v-tooltip bottom>
<template #activator="{ on }">
<v-icon dense :color="mavlink_lat ? 'green' : 'orange'" v-on="on">
{{ mavlink_lat ? "mdi-check-circle" : "mdi-alert-circle" }}
</v-icon>
</template>
<span>{{ mavlink_lat ? "Valid GPS position" : "No valid GPS position" }}</span>
</v-tooltip>
<b>Current vehicle coordinates:</b>
<br>
{{ mavlink_lat?.toFixed(5) ?? "N/A" }} {{ mavlink_lon?.toFixed(5) ?? "N/A" }}
<br>
</div>
<template v-if="!mavlink_lat && supports_setting_position && !warnonly">
<v-icon dense :color="geoip_lat ? 'green' : 'red'">
{{ geoip_lat ? "mdi-check-circle" : "mdi-alert-circle" }}
</v-icon>
Expand All @@ -22,41 +35,52 @@
</template>
<span>GeoIP coordinates are estimated based on your IP address.</span>
</v-tooltip>
<b>GeoIP coordinates:</b> {{ geoip_lat ?? "N/A" }} {{ geoip_lon ?? "N/A" }}
<b>GeoIP coordinates:</b>
<br>
{{ geoip_lat ?? "N/A" }} {{ geoip_lon ?? "N/A" }}
<br>
</template>
<v-card v-if="!mavlink_lat && supports_setting_position" class="pa-4">
<v-card-text>
No valid GPS position!
</v-card-text>
<v-card-actions>
<v-btn v-if="!manual_coordinates" small color="primary" @click="setOrigin(geoip_lat ?? 0, geoip_lon ?? 0)">
<v-card v-if="!mavlink_lat && supports_setting_position && !warnonly" class="pa-4">
<div class="d-flex flex-column justify-space-between">
<v-btn
v-if="!manual_coordinates"
class="ma-1"
small
color="primary"
@click="setOrigin(geoip_lat ?? 0, geoip_lon ?? 0)"
>
Use GeoIP coordinates
</v-btn>
<v-btn v-if="!mavlink_lat && !manual_coordinates" small color="primary" @click="manual_coordinates = true">
<v-btn
v-if="!mavlink_lat && !manual_coordinates"
class="ma-1"
small
color="primary"
@click="manual_coordinates = true"
>
Enter custom coordinate
</v-btn>
<br>
<div v-if="manual_coordinates">
<v-text-field
v-model="manual_lat"
label="Latitude"
type="number"
required
/>
<v-text-field
v-model="manual_lon"
label="Longitude"
type="number"
required
/>
<v-btn small color="primary" @click="setOrigin(manual_lat ?? 0, manual_lon ?? 0)">
Use these coordinates
</v-btn>
</div>
</v-card-actions>
</div>

<div v-if="manual_coordinates">
<v-text-field
v-model="manual_lat"
label="Latitude"
type="number"
required
/>
<v-text-field
v-model="manual_lon"
label="Longitude"
type="number"
required
/>
<v-btn small color="primary" @click="setOrigin(manual_lat ?? 0, manual_lon ?? 0)">
Use these coordinates
</v-btn>
</div>
</v-card>
</v-card-text>
</div>
</template>

<script lang="ts">
Expand All @@ -81,6 +105,11 @@ export default {
required: false,
default: undefined,
},
warnonly: {
type: Boolean,
required: false,
default: false,
},
},
data() {
return {
Expand Down Expand Up @@ -188,5 +217,7 @@ export default {
</script>

<style scoped>

.position {
max-width: 300px;
}
</style>
Original file line number Diff line number Diff line change
Expand Up @@ -334,5 +334,6 @@ export default Vue.extend({
.compass canvas {
border-radius: 15%;
border: 1px solid var(--v-primary-base);
background-color: white;
}
</style>
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

<auto-coordinate-detector
v-if="state === states.IDLE"
v-model="coordinates"
warnonly
/>
<compass-mask-picker v-if="state === states.IDLE" v-model="compass_mask" :devices="compasses" />
<v-divider />
Expand Down Expand Up @@ -128,7 +128,6 @@ export default {
data() {
return {
dialog: false,
coordinates: undefined as { lat: number, lon: number } | undefined,
compass_mask: 0,
status_type: '' as string | undefined,
status_text: '' as string | undefined,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
A Valid position is required for Compass Learn to estimate the local world magnetic field.
<auto-coordinate-detector
v-model="coordinates"
warnonly
/>
<compass-mask-picker v-model="compass_mask" :devices="compasses" />
<v-divider />
Expand Down