Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
eb6daf3
commit d9d5b30
Showing
3 changed files
with
134 additions
and
2 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -11,7 +11,7 @@ export default { | |
props: { | ||
filter: { | ||
type: RegExp, | ||
default: '', | ||
default: /.*/, | ||
}, | ||
}, | ||
data() { | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
127 changes: 127 additions & 0 deletions
127
...src/components/vehiclesetup/configuration/accelerometer/QuickAccelerometerCalibration.vue
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,127 @@ | ||
<template> | ||
<v-dialog | ||
v-model="dialog" | ||
width="500" | ||
> | ||
<template #activator="{ on, attrs }"> | ||
<v-btn | ||
color="primary" | ||
v-bind="attrs" | ||
v-on="on" | ||
> | ||
Quick Calibration | ||
</v-btn> | ||
</template> | ||
|
||
<v-card> | ||
<v-card-title class="text-h5 grey lighten-2"> | ||
Accelerometer Calibration | ||
</v-card-title> | ||
<v-card-text> | ||
<div> | ||
Quick calibration requires that you place the vehicle on a level surface and keep it still for a few seconds. | ||
It is usually enough if your vehicle is generally leveled while in use. | ||
<StatusTextWatcher /> | ||
</div> | ||
</v-card-text> | ||
<v-card-actions> | ||
<v-btn v-if="state === states.IDLE" class="primary" @click="doCalibration"> | ||
Start Calibration | ||
</v-btn> | ||
<v-btn v-if="state === states.CALIBRATION_STARTED" class="primary" @click="nextStep"> | ||
Next | ||
</v-btn> | ||
<v-spacer /> | ||
</v-card-actions> | ||
</v-card> | ||
</v-dialog> | ||
</template> | ||
|
||
<script lang="ts"> | ||
import StatusTextWatcher from '@/components/common/StatusTextWatcher.vue' | ||
import mavlink2rest from '@/libs/MAVLink2Rest' | ||
import { MavCmd, MAVLinkType } from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum' | ||
import autopilot_data from '@/store/autopilot' | ||
const states = { | ||
IDLE: 0, | ||
WAITING_FOR_RESPONSE: 1, | ||
CALIBRATION_STARTED: 2, | ||
CALIBRATED: 3, | ||
} | ||
export default { | ||
name: 'QuickAccelerometerCalibration', | ||
components: { | ||
StatusTextWatcher, | ||
}, | ||
data() { | ||
return { | ||
dialog: false, | ||
calibrating: false, | ||
state: states.IDLE, | ||
latest_status: '', | ||
} | ||
}, | ||
computed: { | ||
states() { | ||
return states | ||
}, | ||
}, | ||
methods: { | ||
nextStep() { | ||
}, | ||
startCalibrationManager() { | ||
mavlink2rest.startListening('STATUSTEXT').setCallback((message) => { | ||
this.latest_status = message.message.text.join('') | ||
}) | ||
}, | ||
doCalibration() { | ||
this.calibrating = true | ||
mavlink2rest.sendMessage({ | ||
header: { | ||
system_id: 255, | ||
component_id: 1, | ||
sequence: 1, | ||
}, | ||
message: { | ||
type: 'COMMAND_LONG', | ||
param1: 0, | ||
param2: 0, | ||
param3: 0, | ||
param4: 0, | ||
param5: 4, // see https://mavlink.io/en/messages/common.html#MAV_CMD_PREFLIGHT_CALIBRATION | ||
param6: 0, | ||
param7: 0, | ||
command: { | ||
type: MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION, | ||
}, | ||
target_system: autopilot_data.system_id, | ||
target_component: 1, | ||
confirmation: 1, | ||
}, | ||
}) | ||
this.state = states.WAITING_FOR_RESPONSE | ||
let timeout = 0 | ||
const ack_listener = mavlink2rest.startListening('COMMAND_ACK').setCallback((message) => { | ||
if (message.message.command.type === 'MAV_CMD_PREFLIGHT_CALIBRATION') { | ||
clearTimeout(timeout) | ||
this.state = states.CALIBRATION_STARTED | ||
this.startCalibrationManager() | ||
ack_listener.discard() | ||
} | ||
}) | ||
timeout = setTimeout(() => { | ||
ack_listener.discard() | ||
this.state = states.IDLE | ||
}, 2000) | ||
}, | ||
}, | ||
} | ||
</script> | ||
|
||
<style scoped> | ||
</style> |