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
149 changes: 148 additions & 1 deletion src/components/widgets/Map.vue
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,14 @@
:max-zoom="19"
class="map"
@ready="onLeafletReady"
@click="onMapClick"
>
<!-- Marker bound to clickedLocation -->
<l-marker v-if="clickedLocation" :lat-lng="clickedLocation">
<l-tooltip>
<div>coordinates: {{ clickedLocation }}</div>
</l-tooltip>
</l-marker>
<v-btn
class="absolute left-0 m-3 bottom-12 bg-slate-50"
elevation="2"
Expand All @@ -17,6 +24,12 @@
size="x-small"
@click="whoToFollow = WhoToFollow.HOME"
/>

<div v-if="showContextMenu" class="context-menu" :style="{ top: menuPosition.top, left: menuPosition.left }">
<ul @click.stop="">
<li @click="onMenuOptionSelect('goto')">GoTo</li>
</ul>
</div>
<v-btn
class="absolute m-3 bottom-12 left-10 bg-slate-50"
elevation="2"
Expand Down Expand Up @@ -114,7 +127,18 @@ import { useRefHistory } from '@vueuse/core'
import { formatDistanceToNow } from 'date-fns'
import type { Map } from 'leaflet'
import Swal from 'sweetalert2'
import { type Ref, computed, nextTick, onBeforeMount, onBeforeUnmount, ref, toRefs, watch } from 'vue'
import {
type Ref,
computed,
nextTick,
onBeforeMount,
onBeforeUnmount,
onMounted,
reactive,
ref,
toRefs,
watch,
} from 'vue'

import { datalogger, DatalogVariable } from '@/libs/logging'
import { degrees } from '@/libs/utils'
Expand Down Expand Up @@ -172,22 +196,55 @@ navigator?.geolocation?.watchPosition(
}
)

let leafletMap: L.Map | null = null // eslint-disable-line no-undef

const onLeafletReady = async (): Promise<void> => {
await nextTick()
leafletMap = map.value?.leafletObject

if (!leafletMap) {
console.warn('Failed to get leaflet reference')
return
}
leafletObject.value = map.value?.leafletObject

leafletMap.on('click', onMapClick)

if (leafletObject.value == undefined) {
console.warn('Failed to get leaflet reference')
return
}

leafletObject.value.zoomControl.setPosition('bottomright')

leafletMap.on('contextmenu', () => {
hideContextMenuAndMarker()
})

// It was not possible to find a way to change the position
// automatically besides waiting 2 seconds before changing it
setTimeout(goHome, 2000)
}

const clickedLocation = ref<[number, number] | null>(null)

// hide context menu and marker
const hideContextMenuAndMarker = (): void => {
showContextMenu.value = false
clickedLocation.value = null
}

// Handle the Escape key press
const onKeydown = (event: KeyboardEvent): void => {
if (event.key === 'Escape') {
hideContextMenuAndMarker()
}
}

onMounted(() => {
window.addEventListener('keydown', onKeydown)
})

const goHome = async (): Promise<void> => {
if (home.value === null) {
return
Expand Down Expand Up @@ -265,7 +322,71 @@ onBeforeMount(() => {

onBeforeUnmount(() => {
clearInterval(followInterval)
if (leafletMap) {
leafletMap.off('click', onMapClick)
}
})

onBeforeUnmount(() => {
window.removeEventListener('keydown', onKeydown)
if (leafletMap) {
leafletMap.off('contextmenu')
}
})

const showContextMenu = ref(false)
const menuPosition = reactive({ top: '0px', left: '0px' })

// eslint-disable-next-line no-undef
const onMapClick = (event: L.LeafletMouseEvent): void => {
console.log('Map click event:', event) // Log the event object

// Check if event.latlng is defined and has the required properties
if (event?.latlng?.lat != null && event?.latlng?.lng != null) {
clickedLocation.value = [event.latlng.lat, event.latlng.lng]
showContextMenu.value = true

// Calculate and update menu position
const mapElement = leafletObject.value?.getContainer()
if (mapElement) {
const { x, y } = mapElement.getBoundingClientRect()
menuPosition.left = `${event.originalEvent.clientX - x}px`
menuPosition.top = `${event.originalEvent.clientY - y}px`
}
} else {
console.error('Invalid event structure:', event)
}
}

const onMenuOptionSelect = (option: string): void => {
console.log(`Option selected: ${option}`)

switch (option) {
case 'goto':
if (clickedLocation.value) {
// Define default values
const hold = 0
const acceptanceRadius = 0
const passRadius = 0
const yaw = 0
const altitude = vehicleStore.coordinates.altitude ?? 0

const latitude = clickedLocation.value[0]
const longitude = clickedLocation.value[1]

vehicleStore.goTo(hold, acceptanceRadius, passRadius, yaw, latitude, longitude, altitude)
}
break

// Add more cases for other options if needed in the future

default:
console.warn('Unknown menu option selected:', option)
}

// hide the context menu after an option is selected
showContextMenu.value = false
}
</script>

<style>
Expand All @@ -287,4 +408,30 @@ onBeforeUnmount(() => {
.leaflet-control-zoom {
transform: translateY(-30px);
}
.context-menu {
position: absolute;
z-index: 1003;
background-color: rgba(255, 255, 255, 0.9);
/* White with slight transparency */
border: 1px solid #ccc;
/* Optional: adds a subtle border */
box-shadow: 0 2px 4px rgba(0, 0, 0, 0.2);
/* Optional: adds a slight shadow for depth */
border-radius: 4px;
/* Optional: rounds the corners */
top: 50px;
left: 50px;
}
.context-menu ul {
list-style-type: none;
padding: 0;
margin: 0;
}
.context-menu ul li {
padding: 5px 10px;
cursor: pointer;
}
.context-menu ul li:hover {
background-color: #ddd;
}
</style>
29 changes: 29 additions & 0 deletions src/libs/vehicle/ardupilot/ardupilot.ts
Original file line number Diff line number Diff line change
Expand Up @@ -425,6 +425,35 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo
this.setMode(landMode as Modes)
return
}
/**
* Goto position
* @param {number} hold Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)
* @param {number} acceptanceRadius Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)
* @param {number} passRadius 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.
* @param {number} yaw Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).
* @param {Coordinates} coordinates
*/
goTo(hold: number, acceptanceRadius: number, passRadius: number, yaw: number, coordinates: Coordinates): void {
const gotoMessage: Message.CommandInt = {
type: MAVLinkType.COMMAND_INT,
target_system: 1,
target_component: 1,
seq: 0,
frame: { type: MavFrame.MAV_FRAME_GLOBAL },
command: { type: MavCmd.MAV_CMD_DO_REPOSITION },
current: 0,
autocontinue: 0,
param1: hold,
param2: acceptanceRadius,
param3: passRadius,
param4: yaw,
x: Math.round(coordinates.latitude * 1e7),
y: Math.round(coordinates.longitude * 1e7),
z: coordinates.altitude,
}

this.write(gotoMessage)
}

/**
* Return vehicle altitude-related data
Expand Down
30 changes: 29 additions & 1 deletion src/stores/mainVehicle.ts
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,14 @@ import * as Protocol from '@/libs/vehicle/protocol/protocol'
import type {
Altitude,
Attitude,
Coordinates,
PageDescription,
PowerSupply,
StatusGPS,
StatusText,
VehicleConfigurationSettings,
Velocity,
} from '@/libs/vehicle/types'
import { Coordinates } from '@/libs/vehicle/types'
import * as Vehicle from '@/libs/vehicle/vehicle'
import { VehicleFactory } from '@/libs/vehicle/vehicle-factory'
import type { MissionLoadingCallback, Waypoint } from '@/types/mission'
Expand Down Expand Up @@ -151,6 +151,33 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
mainVehicle.value?.land()
}

/**
* Go to a given position
* @param { number } hold Time to hold position in seconds
* @param { number } acceptanceRadius Radius in meters to consider the waypoint reached
* @param { number } passRadius Radius in meters to pass the waypoint
* @param { number } yaw Yaw angle in degrees
* @param { number } latitude Latitude in degrees
* @param { number } longitude Longitude in degrees
* @param { number } alt Altitude in meters
*/
function goTo(
hold: number,
acceptanceRadius: number,
passRadius: number,
yaw: number,
latitude: number,
longitude: number,
alt: number
): void {
const waypoint = new Coordinates()
waypoint.latitude = latitude
waypoint.altitude = alt
waypoint.longitude = longitude

mainVehicle.value?.goTo(hold, acceptanceRadius, passRadius, yaw, waypoint)
}

/**
* Configure the vehicle somehow
* @param { VehicleConfigurationSettings } settings Configuration data
Expand Down Expand Up @@ -370,6 +397,7 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
takeoff,
land,
disarm,
goTo,
modesAvailable,
setFlightMode,
sendGcsHeartbeat,
Expand Down
Loading