Skip to content

Commit

Permalink
change-alt: added functions to command change in altitude
Browse files Browse the repository at this point in the history
  • Loading branch information
ericjohnson97 committed Feb 22, 2024
1 parent 4201bdd commit f0172a8
Show file tree
Hide file tree
Showing 2 changed files with 63 additions and 3 deletions.
44 changes: 41 additions & 3 deletions src/libs/vehicle/ardupilot/ardupilot.ts
Original file line number Diff line number Diff line change
Expand Up @@ -388,6 +388,44 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo
return true
}

/**
* Helper function for changing the altitude of the vehicle
* @param {number} altitude (in meters)
*/
_changeAltitude(altitude: number): void {
const gotoMessage: Message.SetPositionTargetLocalNed = {
time_boot_ms: 0,
type: MAVLinkType.SET_POSITION_TARGET_LOCAL_NED,
target_system: 1,
target_component: 1,
coordinate_frame: { type: MavFrame.MAV_FRAME_LOCAL_OFFSET_NED },
type_mask: { bits: 0b0000111111111000 },
x: 0,
y: 0,
z: altitude,
vx: 0,
vy: 0,
vz: 0,
afx: 0,
afy: 0,
afz: 0,
yaw: 0,
yaw_rate: 0,
}

this.write(gotoMessage)
}

/**
* Change altitude
* @param {number} altitudeSetpoint
* @returns {void}
*/
changeAltitude(altitudeSetpoint: number): void {
this._changeAltitude(altitudeSetpoint)
return
}

/**
* Helper function for commanding takeoff
* @param {number} altitude (in meters)
Expand All @@ -398,18 +436,18 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo

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

this.setMode(guidedMode as Modes)
this.arm()
this._takeoff(altitude_septoint)
this._takeoff(altitudeSetpoint)
this.onTakeoff.emit()
return
}
Expand Down
22 changes: 22 additions & 0 deletions src/stores/mainVehicle.ts
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,27 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
throw new Error('Takeoff cancelled by the user')
}
}
/**
* Change the altitude of the vehicle.
* @returns {Promise<void>} A Promise that resolves when the altitude is changed or rejects if the action is cancelled.
*/
async function changeAlt(): Promise<void> {
if (!mainVehicle.value) {
throw new Error('No vehicle available to change altitude.')
}

showAltitudeSlider.value = true

const confirmed = await slideToConfirm('Confirm Altitude Change', 'Alt Change Cmd Confirmed')
showAltitudeSlider.value = false

if (confirmed) {
mainVehicle.value.changeAltitude(altitude.rel - altitude_setpoint.value)
} else {
console.error('Altitude change cancelled by the user')
throw new Error('Altitude change cancelled by the user')
}
}

/**
* Land the vehicle.
Expand Down Expand Up @@ -463,6 +484,7 @@ export const useMainVehicleStore = defineStore('main-vehicle', () => {
return {
arm,
takeoff,
changeAlt,
land,
disarm,
goTo,
Expand Down

0 comments on commit f0172a8

Please sign in to comment.