diff --git a/core/frontend/src/components/vehiclesetup/configuration/accelerometer/ArdupilotAccelerometerSetup.vue b/core/frontend/src/components/vehiclesetup/configuration/accelerometer/ArdupilotAccelerometerSetup.vue index f209c50b1..b8774f601 100644 --- a/core/frontend/src/components/vehiclesetup/configuration/accelerometer/ArdupilotAccelerometerSetup.vue +++ b/core/frontend/src/components/vehiclesetup/configuration/accelerometer/ArdupilotAccelerometerSetup.vue @@ -66,6 +66,7 @@ import autopilot_data from '@/store/autopilot' import { Dictionary } from '@/types/common' import decode, { deviceId } from '@/utils/deviceid_decoder' +import { imu_is_calibrated, imu_temperature_is_calibrated } from '../common' import QuickAccelerometerCalibration from './QuickAccelerometerCalibration.vue' export default Vue.extend({ @@ -93,42 +94,11 @@ export default Vue.extend({ .filter((param) => param.value !== 0) .map((parameter) => decode(parameter.name, parameter.value)) }, - // TODO: refactor, same code as OnboardSensors.vue imu_is_calibrated(): Dictionary { - const results = {} as Dictionary - for (const imu of this.imus) { - const param_radix = imu.param.split('_ID')[0] - const offset_params_names = [`${param_radix}OFFS_X`, `${param_radix}OFFS_Y`, `${param_radix}OFFS_Z`] - const scale_params_names = [`${param_radix}SCAL_X`, `${param_radix}SCAL_Y`, `${param_radix}SCAL_Z`] - const offset_params = offset_params_names.map( - (name) => autopilot_data.parameter(name), - ) - const scale_params = scale_params_names.map( - (name) => autopilot_data.parameter(name), - ) - const is_at_default_offsets = offset_params.every((param) => param?.value === 0.0) - const is_at_default_scale = scale_params.every((param) => param?.value === 1.0) - results[imu.param] = offset_params.isEmpty() || scale_params.isEmpty() - || !is_at_default_offsets || !is_at_default_scale - } - return results + return imu_is_calibrated(this.imus, autopilot_data) }, imu_temperature_is_calibrated(): Dictionary<{ calibrated: boolean, calibrationTemperature: number }> { - const results = {} as Dictionary<{ calibrated: boolean, calibrationTemperature: number }> - for (const imu of this.imus) { - let param_radix = imu.param.split('_ID')[0] - // CALTEMP parameters contains ID for the first sensor, _ID does not, so we need to add it - if (!/\d$/.test(param_radix)) { - param_radix += '1' - } - const name = `${param_radix}_CALTEMP` - const parameter = autopilot_data.parameter(name) - results[imu.param] = { - calibrated: parameter !== undefined && parameter.value !== -300, - calibrationTemperature: parameter?.value ?? 0, - } - } - return results + return imu_temperature_is_calibrated(this.imus, autopilot_data) }, }, methods: { diff --git a/core/frontend/src/components/vehiclesetup/configuration/common.ts b/core/frontend/src/components/vehiclesetup/configuration/common.ts new file mode 100755 index 000000000..8420584c1 --- /dev/null +++ b/core/frontend/src/components/vehiclesetup/configuration/common.ts @@ -0,0 +1,41 @@ +import { AutopilotStore } from "@/store/autopilot" +import { Dictionary } from "@/types/common" +import { deviceId } from "@/utils/deviceid_decoder" + +export function imu_is_calibrated(imus: deviceId[], autopilot_data: AutopilotStore) { + const results = {} as Dictionary + for (const imu of imus) { + const param_radix = imu.param.split('_ID')[0] + const offset_params_names = [`${param_radix}OFFS_X`, `${param_radix}OFFS_Y`, `${param_radix}OFFS_Z`] + const scale_params_names = [`${param_radix}SCAL_X`, `${param_radix}SCAL_Y`, `${param_radix}SCAL_Z`] + const offset_params = offset_params_names.map( + (name) => autopilot_data.parameter(name), + ) + const scale_params = scale_params_names.map( + (name) => autopilot_data.parameter(name), + ) + const is_at_default_offsets = offset_params.every((param) => param?.value === 0.0) + const is_at_default_scale = scale_params.every((param) => param?.value === 1.0) + results[imu.param] = offset_params.isEmpty() || scale_params.isEmpty() + || !is_at_default_offsets || !is_at_default_scale + } + return results +} + +export function imu_temperature_is_calibrated(imus: deviceId[], autopilot_data: AutopilotStore): Dictionary<{ calibrated: boolean, calibrationTemperature: number }> { + const results = {} as Dictionary<{ calibrated: boolean, calibrationTemperature: number }> + for (const imu of imus) { + let param_radix = imu.param.split('_ID')[0] + // CALTEMP parameters contains ID for the first sensor, _ID does not, so we need to add it + if (!/\d$/.test(param_radix)) { + param_radix += '1' + } + const name = `${param_radix}_CALTEMP` + const parameter = autopilot_data.parameter(name) + results[imu.param] = { + calibrated: parameter !== undefined && parameter.value !== -300, + calibrationTemperature: parameter?.value ?? 0, + } + } + return results +} diff --git a/core/frontend/src/components/vehiclesetup/overview/OnboardSensors.vue b/core/frontend/src/components/vehiclesetup/overview/OnboardSensors.vue index 0f342dca1..d78761319 100755 --- a/core/frontend/src/components/vehiclesetup/overview/OnboardSensors.vue +++ b/core/frontend/src/components/vehiclesetup/overview/OnboardSensors.vue @@ -52,7 +52,7 @@ mdi-emoticon-sad-outline @@ -124,6 +124,8 @@ import { Dictionary } from '@/types/common' import decode, { deviceId } from '@/utils/deviceid_decoder' import mavlink_store_get from '@/utils/mavlink' +import { imu_is_calibrated, imu_temperature_is_calibrated } from '../configuration/common' + export default Vue.extend({ name: 'OnboardSensors', computed: { @@ -211,37 +213,10 @@ export default Vue.extend({ return results }, imu_is_calibrated(): Dictionary { - const results = {} as Dictionary - for (const imu of this.imus) { - const param_radix = imu.param.split('_ID')[0] - const offset_params_names = [`${param_radix}OFFS_X`, `${param_radix}OFFS_Y`, `${param_radix}OFFS_Z`] - const scale_params_names = [`${param_radix}SCAL_X`, `${param_radix}SCAL_Y`, `${param_radix}SCAL_Z`] - const offset_params = offset_params_names.map( - (name) => autopilot_data.parameter(name), - ) - const scale_params = scale_params_names.map( - (name) => autopilot_data.parameter(name), - ) - const is_at_default_offsets = offset_params.every((param) => param?.value === 0.0) - const is_at_default_scale = scale_params.every((param) => param?.value === 1.0) - results[imu.param] = offset_params.isEmpty() || scale_params.isEmpty() - || !is_at_default_offsets || !is_at_default_scale - } - return results + return imu_is_calibrated(this.imus, autopilot_data) }, - imu_temperature_is_calibrated(): Dictionary { - const results = {} as Dictionary - for (const imu of this.imus) { - let param_radix = imu.param.split('_ID')[0] - // CALTEMP parameters contains ID for the first sensor, _ID does not, so we need to add it - if (!/\d$/.test(param_radix)) { - param_radix += '1' - } - const name = `${param_radix}_CALTEMP` - const parameter = autopilot_data.parameter(name) - results[imu.param] = parameter !== undefined && parameter.value !== -300 - } - return results + imu_temperature_is_calibrated(): Dictionary<{ calibrated: boolean, calibrationTemperature: number }> { + return imu_temperature_is_calibrated(this.imus, autopilot_data) }, is_water_baro(): Dictionary { const results = {} as Dictionary