@@ -14,6 +14,7 @@ import {
1414 registerActionCallback ,
1515} from '@/libs/joystick/protocols/cockpit-actions'
1616import { MavlinkManualControlManager } from '@/libs/joystick/protocols/mavlink-manual-control'
17+ import { slideToConfirm } from '@/libs/slide-to-confirm'
1718import type { ArduPilot } from '@/libs/vehicle/ardupilot/ardupilot'
1819import type { ArduPilotParameterSetData } from '@/libs/vehicle/ardupilot/types'
1920import * as Protocol from '@/libs/vehicle/protocol/protocol'
@@ -125,29 +126,52 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
125126
126127 /**
127128 * Arm the vehicle
129+ * @returns { void } A Promise that resolves when arming is successful or rejects if an error occurs or the action is cancelled.
128130 */
129- function arm ( ) : void {
130- mainVehicle . value ?. arm ( )
131+ function arm ( ) : Promise < void > {
132+ return slideToConfirm ( ( ) => {
133+ if ( ! mainVehicle . value ) {
134+ throw new Error ( 'action rejected or failed' )
135+ }
136+ mainVehicle . value . arm ( )
137+ } )
131138 }
132139
133140 /**
134141 * Disarm the vehicle
142+ * @returns { void } A Promise that resolves when disarming is successful or rejects if an error occurs or the action is cancelled.
135143 */
136- function disarm ( ) : void {
137- mainVehicle . value ?. disarm ( )
144+ function disarm ( ) : Promise < void > {
145+ return slideToConfirm ( ( ) => {
146+ if ( ! mainVehicle . value ) {
147+ throw new Error ( 'action rejected or failed' )
148+ }
149+ mainVehicle . value . disarm ( )
150+ } )
138151 }
139152 /**
140- * Takeoff the vehicle
153+ * Initiates the takeoff process, requiring user confirmation.
154+ * @returns { void } A Promise that resolves when the takeoff is successful or rejects if an error occurs or the action is cancelled.
141155 */
142- function takeoff ( ) : void {
143- mainVehicle . value ?. takeoff ( )
156+ function takeoff ( ) : Promise < void > {
157+ return slideToConfirm ( ( ) => {
158+ if ( ! mainVehicle . value ) {
159+ throw new Error ( 'action rejected or failed' )
160+ }
161+ mainVehicle . value . takeoff ( )
162+ } )
144163 }
145-
146164 /**
147165 * Land the vehicle
166+ * @returns { void } A Promise that resolves when landing is successful or rejects if an error occurs or the action is cancelled.
148167 */
149- function land ( ) : void {
150- mainVehicle . value ?. land ( )
168+ function land ( ) : Promise < void > {
169+ return slideToConfirm ( ( ) => {
170+ if ( ! mainVehicle . value ) {
171+ throw new Error ( 'action rejected or failed' )
172+ }
173+ mainVehicle . value . land ( )
174+ } )
151175 }
152176
153177 /**
@@ -159,6 +183,7 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
159183 * @param { number } latitude Latitude in degrees
160184 * @param { number } longitude Longitude in degrees
161185 * @param { number } alt Altitude in meters
186+ * @returns { void } A Promise that resolves when the vehicle reaches the waypoint or rejects if an error occurs or the action is cancelled.
162187 */
163188 function goTo (
164189 hold : number ,
@@ -168,13 +193,18 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
168193 latitude : number ,
169194 longitude : number ,
170195 alt : number
171- ) : void {
196+ ) : Promise < void > {
172197 const waypoint = new Coordinates ( )
173198 waypoint . latitude = latitude
174199 waypoint . altitude = alt
175200 waypoint . longitude = longitude
176201
177- mainVehicle . value ?. goTo ( hold , acceptanceRadius , passRadius , yaw , waypoint )
202+ return slideToConfirm ( ( ) => {
203+ if ( ! mainVehicle . value ) {
204+ throw new Error ( 'action rejected or failed' )
205+ }
206+ mainVehicle . value . goTo ( hold , acceptanceRadius , passRadius , yaw , waypoint )
207+ } )
178208 }
179209
180210 /**
0 commit comments