|
| 1 | +<template> |
| 2 | + <v-card-text class="mt-3"> |
| 3 | + <v-tooltip bottom> |
| 4 | + <template #activator="{ on }"> |
| 5 | + <v-icon dense :color="mavlink_lat ? 'green' : 'orange'" v-on="on"> |
| 6 | + {{ mavlink_lat ? "mdi-check-circle" : "mdi-alert-circle" }} |
| 7 | + </v-icon> |
| 8 | + </template> |
| 9 | + <span>{{ mavlink_lat ? "Valid GPS position" : "No valid GPS position" }}</span> |
| 10 | + </v-tooltip> |
| 11 | + <b>Vehicle coordinates:</b> {{ mavlink_lat?.toFixed(5) ?? "N/A" }} {{ mavlink_lon?.toFixed(5) ?? "N/A" }} |
| 12 | + <br> |
| 13 | + <template v-if="!mavlink_lat"> |
| 14 | + <v-icon dense :color="geoip_lat ? 'green' : 'red'"> |
| 15 | + {{ geoip_lat ? "mdi-check-circle" : "mdi-alert-circle" }} |
| 16 | + </v-icon> |
| 17 | + <v-tooltip bottom> |
| 18 | + <template #activator="{ on }"> |
| 19 | + <v-icon dense class="ml-1" v-on="on"> |
| 20 | + mdi-help-circle |
| 21 | + </v-icon> |
| 22 | + </template> |
| 23 | + <span>GeoIP coordinates are estimated based on your IP address.</span> |
| 24 | + </v-tooltip> |
| 25 | + <b>GeoIP coordinates:</b> {{ geoip_lat ?? "N/A" }} {{ geoip_lon ?? "N/A" }} |
| 26 | + <br> |
| 27 | + </template> |
| 28 | + <v-card v-if="!mavlink_lat" class="pa-4"> |
| 29 | + <v-card-text> |
| 30 | + No valid GPS position! |
| 31 | + </v-card-text> |
| 32 | + <v-card-actions> |
| 33 | + <v-btn v-if="!manual_coordinates" small color="primary" @click="setOrigin(geoip_lat ?? 0, geoip_lon ?? 0)"> |
| 34 | + Use GeoIP coordinates |
| 35 | + </v-btn> |
| 36 | + <v-btn v-if="!mavlink_lat && !manual_coordinates" small color="primary" @click="manual_coordinates = true"> |
| 37 | + Enter custom coordinate |
| 38 | + </v-btn> |
| 39 | + <br> |
| 40 | + <div v-if="manual_coordinates"> |
| 41 | + <v-text-field |
| 42 | + v-model="manual_lat" |
| 43 | + label="Latitude" |
| 44 | + type="number" |
| 45 | + required |
| 46 | + /> |
| 47 | + <v-text-field |
| 48 | + v-model="manual_lon" |
| 49 | + label="Longitude" |
| 50 | + type="number" |
| 51 | + required |
| 52 | + /> |
| 53 | + <v-btn small color="primary" @click="setOrigin(manual_lat ?? 0, manual_lon ?? 0)"> |
| 54 | + Use these coordinates |
| 55 | + </v-btn> |
| 56 | + </div> |
| 57 | + </v-card-actions> |
| 58 | + </v-card> |
| 59 | + </v-card-text> |
| 60 | +</template> |
| 61 | + |
| 62 | +<script lang="ts"> |
| 63 | +
|
| 64 | +import { PropType } from 'vue' |
| 65 | +
|
| 66 | +import mavlink2rest from '@/libs/MAVLink2Rest' |
| 67 | +import autopilot_data from '@/store/autopilot' |
| 68 | +
|
| 69 | +export default { |
| 70 | + name: 'AutoCoordinateDetector', |
| 71 | + model: { |
| 72 | + prop: 'inputcoordinates', |
| 73 | + event: 'input', |
| 74 | + }, |
| 75 | + props: { |
| 76 | + inputcoordinates: { |
| 77 | + type: Object as PropType<{ lat: number, lon: number } | undefined>, |
| 78 | + required: false, |
| 79 | + default: undefined, |
| 80 | + }, |
| 81 | + }, |
| 82 | + data() { |
| 83 | + return { |
| 84 | + mavlink_lat: undefined as number | undefined, |
| 85 | + mavlink_lon: undefined as number | undefined, |
| 86 | + geoip_lat: undefined as number | undefined, |
| 87 | + geoip_lon: undefined as number | undefined, |
| 88 | + manual_coordinates: false, |
| 89 | + manual_lat: this.inputcoordinates?.lat, |
| 90 | + manual_lon: this.inputcoordinates?.lon, |
| 91 | + } |
| 92 | + }, |
| 93 | + computed: { |
| 94 | + coordinates() { |
| 95 | + return this.mavlink_lat && this.mavlink_lon ? { lat: this.mavlink_lat, lon: this.mavlink_lon } : undefined |
| 96 | + }, |
| 97 | + }, |
| 98 | + watch: { |
| 99 | + coordinates: { |
| 100 | + deep: true, |
| 101 | + handler() { |
| 102 | + this.$emit('input', this.coordinates) |
| 103 | + }, |
| 104 | + }, |
| 105 | + }, |
| 106 | + mounted() { |
| 107 | + mavlink2rest.startListening('GLOBAL_POSITION_INT').setCallback((receivedMessage) => { |
| 108 | + this.mavlink_lat = receivedMessage.message.lat !== 0 ? receivedMessage.message.lat * 1e-7 : undefined |
| 109 | + this.mavlink_lon = receivedMessage.message.lon !== 0 ? receivedMessage.message.lon * 1e-7 : undefined |
| 110 | + }).setFrequency(0) |
| 111 | + mavlink2rest.requestMessageRate('GLOBAL_POSITION_INT', 1, autopilot_data.system_id) |
| 112 | + this.getGeoIp() |
| 113 | + }, |
| 114 | + methods: { |
| 115 | + getGeoIp() { |
| 116 | + fetch('http://ip-api.com/json/') |
| 117 | + .then((response) => response.json()) |
| 118 | + .then((data) => { |
| 119 | + this.geoip_lat = data.lat |
| 120 | + this.geoip_lon = data.lon |
| 121 | + }) |
| 122 | + .catch((err) => console.error(err)) |
| 123 | + }, |
| 124 | + setOrigin(lat: number, lon:number) { |
| 125 | + mavlink2rest.sendMessage( |
| 126 | + { |
| 127 | + header: { |
| 128 | + system_id: 255, |
| 129 | + component_id: 0, |
| 130 | + sequence: 0, |
| 131 | + }, |
| 132 | + message: { |
| 133 | + type: 'SET_GPS_GLOBAL_ORIGIN', |
| 134 | + latitude: lat * 1e7, |
| 135 | + longitude: lon * 1e7, |
| 136 | + altitude: 0, |
| 137 | + target_system: autopilot_data.system_id, |
| 138 | + time_usec: 0, |
| 139 | + }, |
| 140 | + }, |
| 141 | + ) |
| 142 | + }, |
| 143 | + }, |
| 144 | +} |
| 145 | +</script> |
| 146 | + |
| 147 | +<style scoped> |
| 148 | +
|
| 149 | +</style> |
0 commit comments