diff --git a/core/frontend/src/components/vehiclesetup/PwmSetup.vue b/core/frontend/src/components/vehiclesetup/PwmSetup.vue index 66a4227c58..797054ac40 100644 --- a/core/frontend/src/components/vehiclesetup/PwmSetup.vue +++ b/core/frontend/src/components/vehiclesetup/PwmSetup.vue @@ -248,25 +248,38 @@ export default Vue.extend({ } }) }, + vehicle_id(): number { + return autopilot_data.system_id + }, is_armed(): boolean { - const heartbeat = mavlink_store_get(mavlink, 'HEARTBEAT.messageData.message') as Message.Heartbeat - return Boolean(heartbeat.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_SAFETY_ARMED) + const heartbeat = mavlink_store_get( + mavlink, + 'HEARTBEAT.messageData.message', + this.vehicle_id, + 1, + ) as Message.Heartbeat + return Boolean(heartbeat?.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_SAFETY_ARMED) }, is_manual(): boolean { - const heartbeat = mavlink_store_get(mavlink, 'HEARTBEAT.messageData.message') as Message.Heartbeat + const heartbeat = mavlink_store_get( + mavlink, + 'HEARTBEAT.messageData.message', + this.vehicle_id, + 1, + ) as Message.Heartbeat // Legacy manual mode - if (!(heartbeat.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) { - return Boolean(heartbeat.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) + if (!(heartbeat?.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) { + return Boolean(heartbeat?.base_mode.bits & MavModeFlag.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) } if (this.is_rover) { const rover_custom_mode_manual = 0 - return Boolean(heartbeat.custom_mode === rover_custom_mode_manual) + return Boolean(heartbeat?.custom_mode === rover_custom_mode_manual) } if (this.is_sub) { const sub_custom_mode_manual = 19 - return Boolean(heartbeat.custom_mode === sub_custom_mode_manual) + return Boolean(heartbeat?.custom_mode === sub_custom_mode_manual) } return false diff --git a/core/frontend/src/store/mavlink.ts b/core/frontend/src/store/mavlink.ts index b3db98e2bb..8e10f9f954 100644 --- a/core/frontend/src/store/mavlink.ts +++ b/core/frontend/src/store/mavlink.ts @@ -24,6 +24,7 @@ interface messsageRefreshRate { class MavlinkStore extends VuexModule { available_messages: Dictionary = {} + available_identified_messages: Dictionary> = {} message_listeners: Dictionary = {} @@ -64,6 +65,13 @@ class MavlinkStore extends VuexModule { // TODO: Check if this is the best possible way to update `available_messages` // Reference: https://github.com/bluerobotics/blueos-docker/pull/508#discussion_r718729077 Vue.set(this.available_messages, message.messageName, message) + const header = message.messageData.header + const identifier = `${header.system_id}_${header.component_id}` + // make sure identifier exists + if (!(identifier in this.available_identified_messages)) { + Vue.set(this.available_identified_messages, identifier, {}) + } + Vue.set(this.available_identified_messages[identifier], message.messageName, message) } } } diff --git a/core/frontend/src/utils/mavlink.ts b/core/frontend/src/utils/mavlink.ts index b121b76ef3..51bd740c51 100644 --- a/core/frontend/src/utils/mavlink.ts +++ b/core/frontend/src/utils/mavlink.ts @@ -1,5 +1,8 @@ import { get } from 'lodash' -export default function mavlink_store_get(storage: T, path: string): unknown { +export default function mavlink_store_get(storage: T, path: string, system_id? :number, component_id?: number): unknown { + if (system_id !== undefined && component_id !== undefined) { + return get(storage, `available_identified_messages.${system_id}_${component_id}.${path}`) + } return get(storage, `available_messages.${path}`) }