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

Adding Slider to Adjust Altitude #721

Merged
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
Binary file modified bun.lockb
Binary file not shown.
1 change: 1 addition & 0 deletions package.json
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
"vue-router": "^4.0.14",
"vue-slide-unlock": "^0.4.8",
"vue-virtual-scroller": "^2.0.0-beta.8",
"vue3-slider": "^1.9.0",
"vuetify": "3.4.7",
"webfontloader": "^1.0.0",
"webrtc-adapter": "^8.2.0"
Expand Down
2 changes: 2 additions & 0 deletions src/App.vue
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@
{{ format(timeNow, 'E LLL do HH:mm') }}
</div>
</div>
<AltitudeSlider />
<Transition name="fade">
<div v-if="showBottomBarNow" class="bottom-container">
<SlideToConfirm />
Expand Down Expand Up @@ -155,6 +156,7 @@ import {
} from '@/libs/joystick/protocols/cockpit-actions'
import { useMissionStore } from '@/stores/mission'

import AltitudeSlider from './components/AltitudeSlider.vue'
import Dialog from './components/Dialog.vue'
import EditMenu from './components/EditMenu.vue'
import MiniWidgetContainer from './components/MiniWidgetContainer.vue'
Expand Down
44 changes: 44 additions & 0 deletions src/components/AltitudeSlider.vue
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<template>
<div v-if="showAltitudeSlider" class="slider-div">
<slider
ericjohnson97 marked this conversation as resolved.
Show resolved Hide resolved
v-model="altitude_setpoint"
orientation="vertical"
width="100%"
height="20"
color="rgb(59 130 246)"
track-color="rgb(59 130 246 / 0.5)"
always-show-handle="true"
step="0.1"
/>
<div class="slider-value"><span>Alt (Rel)</span></div>
<div class="slider-value">{{ formattedValue }}</div>
</div>
</template>

<script setup lang="ts">
import { computed } from 'vue'
import slider from 'vue3-slider'

import { altitude_setpoint, showAltitudeSlider } from '@/libs/altitude-slider'

const formattedValue = computed(() => altitude_setpoint.value.toFixed(1))
</script>
<style scoped>
.slider-value {
white-space: nowrap;
text-align: center;
font-size: 0.8rem;
}
.slider-div {
position: fixed;
right: 2%;
top: 25%;
bottom: 0;
width: 25px;
height: 50%;
display: flex;
flex-direction: column;
justify-content: center;
z-index: 100;
}
</style>
14 changes: 9 additions & 5 deletions src/components/SlideToConfirm.vue
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@
:noanimate="false"
:width="400"
:height="50"
text="slide to confirm"
success-text="action confirmed"
:text="sliderText"
:success-text="confirmationSliderText"
name="slideunlock"
class="slide-unlock"
@completed="onSlideConfirmed()"
Expand All @@ -25,12 +25,16 @@
<script setup lang="ts">
import SlideUnlock from 'vue-slide-unlock'

import { confirmed, showSlideToConfirm } from '@/libs/slide-to-confirm'
import { confirmationSliderText, confirmed, showSlideToConfirm, sliderText } from '@/libs/slide-to-confirm'

const onSlideConfirmed = (): void => {
showSlideToConfirm.value = false
confirmed.value = true
console.log('Slide confirmed!')

// show success message for 1.5 second
setTimeout(() => {
showSlideToConfirm.value = false
console.log('Slide confirmed!')
}, 1500)
}

const cancelAction = (): void => {
Expand Down
11 changes: 11 additions & 0 deletions src/libs/altitude-slider.ts
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
import { ref, watch } from 'vue'

export const showAltitudeSlider = ref(false)
export const altitude_setpoint = ref(0)

/**
* Watches the altitude value for changes and updates the altitude accordingly.
*/
watch(altitude_setpoint, (newValue, oldValue) => {
console.log(`Altitude changed from ${oldValue} to ${newValue}`)
})
31 changes: 14 additions & 17 deletions src/libs/slide-to-confirm.ts
Original file line number Diff line number Diff line change
@@ -1,34 +1,31 @@
import { ref, watch } from 'vue' // Adjust this import based on your Vue version
import { ref, watch } from 'vue'

// Reactive variables (if they are not provided from outside)
export const showSlideToConfirm = ref(false)
export const sliderText = ref('Slide to Confirm')
export const confirmationSliderText = ref('Action Confirm')
export const confirmed = ref(false)

/**
* Calls the provided action function if the user confirms through the slide-to-confirm component.
* @param {() => void} actionFunc - A function representing the action to be confirmed.
* @returns {Promise<void>} A Promise that resolves if the action is successfully executed or rejects in case of cancellation or errors.
* Waits for user confirmation through the slide-to-confirm component.
* @param {string} text - The custom text to display on the slider.
* @param {string} confirmationText - The custom text to display on the confirmation slider after the user slides to confirm.
* @returns {Promise<boolean>} - A promise that resolves with true when the action is confirmed and false when the user cancels the action.
*/
export function slideToConfirm(actionFunc: () => void): Promise<void> {
console.log('slideToConfirm')
return new Promise((resolve, reject) => {
// Show slide to confirm component
export function slideToConfirm(text: string, confirmationText: string): Promise<boolean> {
console.log('slideToConfirm with text:', text)
return new Promise((resolve) => {
sliderText.value = text
confirmationSliderText.value = confirmationText
showSlideToConfirm.value = true

// Watch for changes on confirmed and showSlideToConfirm variables
const stopWatching = watch([confirmed, showSlideToConfirm], ([newConfirmed, newShowSlideToConfirm]) => {
if (newConfirmed) {
stopWatching()
confirmed.value = false
try {
actionFunc()
resolve()
} catch (error) {
reject(error)
}
resolve(true)
} else if (!newShowSlideToConfirm) {
stopWatching()
reject(new Error('User cancelled the action'))
resolve(false)
}
})
})
Expand Down
5 changes: 3 additions & 2 deletions src/libs/vehicle/ardupilot/ardupilot.ts
Original file line number Diff line number Diff line change
Expand Up @@ -398,17 +398,18 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo

/**
* Takeoff
* @param {number} altitude_septoint
* @returns {void}
*/
takeoff(): void {
takeoff(altitude_septoint: number): void {
const guidedMode = this.modesAvailable().get('GUIDED')
if (guidedMode === undefined) {
return
}

this.setMode(guidedMode as Modes)
this.arm()
this._takeoff(10)
this._takeoff(altitude_septoint)
this.onTakeoff.emit()
return
}
Expand Down
135 changes: 83 additions & 52 deletions src/stores/mainVehicle.ts
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ import { defineStore } from 'pinia'
import { computed, reactive, ref, watch } from 'vue'

import { defaultGlobalAddress } from '@/assets/defaults'
import { altitude_setpoint, showAltitudeSlider } from '@/libs/altitude-slider'
import * as Connection from '@/libs/connection/connection'
import { ConnectionManager } from '@/libs/connection/connection-manager'
import type { Package } from '@/libs/connection/m2r/messages/mavlink2rest'
Expand Down Expand Up @@ -125,67 +126,94 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
})

/**
* Arm the vehicle
* @returns { void } A Promise that resolves when arming is successful or rejects if an error occurs or the action is cancelled.
* Arm the vehicle.
* Awaits user confirmation before arming the vehicle. Resolves when arming is successful or rejects if the action is cancelled.
* @returns {Promise<void>}
*/
function arm(): Promise<void> {
return slideToConfirm(() => {
if (!mainVehicle.value) {
throw new Error('action rejected or failed')
}
async function arm(): Promise<void> {
if (!mainVehicle.value) {
throw new Error('No vehicle available to arm.')
}

const confirmed = await slideToConfirm('Confirm Arm', 'Arm Command Confirmed')
if (confirmed) {
mainVehicle.value.arm()
})
} else {
throw new Error('Arming cancelled by the user')
}
}

/**
* Disarm the vehicle
* @returns { void } A Promise that resolves when disarming is successful or rejects if an error occurs or the action is cancelled.
* Disarm the vehicle.
* Awaits user confirmation before disarming the vehicle. Resolves when disarming is successful or rejects if the action is cancelled.
* @returns {Promise<void>}
*/
function disarm(): Promise<void> {
return slideToConfirm(() => {
if (!mainVehicle.value) {
throw new Error('action rejected or failed')
}
async function disarm(): Promise<void> {
if (!mainVehicle.value) {
throw new Error('No vehicle available to disarm.')
}

const confirmed = await slideToConfirm('Confirm Disarm', 'Disarm Command Confirmed')
if (confirmed) {
mainVehicle.value.disarm()
})
} else {
throw new Error('Disarming cancelled by the user')
}
}

/**
* Initiates the takeoff process, requiring user confirmation.
* @returns { void } A Promise that resolves when the takeoff is successful or rejects if an error occurs or the action is cancelled.
* @returns {Promise<void>} A Promise that resolves when the takeoff is successful or rejects if an error occurs or the action is cancelled.
*/
function takeoff(): Promise<void> {
return slideToConfirm(() => {
if (!mainVehicle.value) {
throw new Error('action rejected or failed')
}
mainVehicle.value.takeoff()
})
async function takeoff(): Promise<void> {
if (!mainVehicle.value) {
throw new Error('No vehicle available for takeoff')
}

showAltitudeSlider.value = true

const confirmed = await slideToConfirm('Confirm Takeoff', 'Takeoff Command Confirmed')
showAltitudeSlider.value = false

if (confirmed) {
mainVehicle.value.takeoff(altitude_setpoint.value)
} else {
console.error('Takeoff cancelled by the user')
throw new Error('Takeoff cancelled by the user')
}
}

/**
* Land the vehicle
* @returns { void } A Promise that resolves when landing is successful or rejects if an error occurs or the action is cancelled.
* Land the vehicle.
* @returns {Promise<void>} A Promise that resolves when landing is successful or rejects if the action is cancelled.
*/
function land(): Promise<void> {
return slideToConfirm(() => {
if (!mainVehicle.value) {
throw new Error('action rejected or failed')
}
async function land(): Promise<void> {
if (!mainVehicle.value) {
throw new Error('No vehicle available to land.')
}

const confirmed = await slideToConfirm('Confirm Landing', 'Landing Command Confirmed')
if (confirmed) {
mainVehicle.value.land()
})
} else {
console.error('Landing cancelled by the user')
throw new Error('Landing cancelled by the user')
}
}

/**
* 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
* @returns { void } A Promise that resolves when the vehicle reaches the waypoint or rejects if an error occurs or the action is cancelled.
* Go to a given position.
* Awaits user confirmation before moving the vehicle to a specified waypoint. Resolves when the vehicle reaches the waypoint or rejects if the action is cancelled.
* @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.
* @returns {Promise<void>}
*/
function goTo(
async function goTo(
hold: number,
acceptanceRadius: number,
passRadius: number,
Expand All @@ -194,17 +222,20 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
longitude: number,
alt: number
): Promise<void> {
const waypoint = new Coordinates()
waypoint.latitude = latitude
waypoint.altitude = alt
waypoint.longitude = longitude

return slideToConfirm(() => {
if (!mainVehicle.value) {
throw new Error('action rejected or failed')
}
if (!mainVehicle.value) {
throw new Error('No vehicle available to execute go to command.')
}

const confirmed = await slideToConfirm('Confirm Go To Position', 'Go To Position Command Confirmed')
if (confirmed) {
const waypoint = new Coordinates()
waypoint.latitude = latitude
waypoint.altitude = alt
waypoint.longitude = longitude
mainVehicle.value.goTo(hold, acceptanceRadius, passRadius, yaw, waypoint)
})
} else {
throw new Error('Go to position cancelled by the user')
}
}

/**
Expand Down
Loading