diff --git a/mavutil.py b/mavutil.py index 3637b03e7..a94a58bf3 100644 --- a/mavutil.py +++ b/mavutil.py @@ -423,9 +423,9 @@ def post_message(self, msg): self.flightmode = mode_string_v10(msg) self.mav_type = msg.type self.base_mode = msg.base_mode - self.sysid_state[self.sysid].armed = (msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED) - self.sysid_state[self.sysid].mav_type = msg.type - self.sysid_state[self.sysid].mav_autopilot = msg.autopilot + self.sysid_state[src_system].armed = (msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED) + self.sysid_state[src_system].mav_type = msg.type + self.sysid_state[src_system].mav_autopilot = msg.autopilot elif type == 'HIGH_LATENCY2': if self.sysid == 0: # lock onto id tuple of first vehicle heartbeat @@ -434,9 +434,9 @@ def post_message(self, msg): self.mav_type = msg.type if msg.autopilot == mavlink.MAV_AUTOPILOT_ARDUPILOTMEGA: self.base_mode = msg.custom0 - self.sysid_state[self.sysid].armed = (msg.custom0 & mavlink.MAV_MODE_FLAG_SAFETY_ARMED) - self.sysid_state[self.sysid].mav_type = msg.type - self.sysid_state[self.sysid].mav_autopilot = msg.autopilot + self.sysid_state[src_system].armed = (msg.custom0 & mavlink.MAV_MODE_FLAG_SAFETY_ARMED) + self.sysid_state[src_system].mav_type = msg.type + self.sysid_state[src_system].mav_autopilot = msg.autopilot elif type == 'PARAM_VALUE': if not src_tuple in self.param_state: