public PowerStatus(MavLinkMessage message) : base(null)
        {
            if (message.messid.Equals(this.MessageID))
            {
                MAVLink.mavlink_power_status_t data = (MAVLink.mavlink_power_status_t)message.data_struct;
                this.Vcc    = data.Vcc;
                this.Vservo = data.Vservo;

                // parse bit masks into lists
                IEnumerable <MAVLink.MAV_POWER_STATUS> values = EnumValues.GetValues <MAVLink.MAV_POWER_STATUS>();
                foreach (MAVLink.MAV_POWER_STATUS status in values)
                {
                    Boolean statusExists = Utilities.BitwiseOperations.bitExistsInValues((int)status, data.flags);
                    if (statusExists)
                    {
                        this.flags.Add(status);
                    }
                }
            }
        }
        public void CheckPowerStatusObject()
        {
            MAVLink.mavlink_power_status_t data = new MAVLink.mavlink_power_status_t();
            data.flags  = 1;
            data.Vcc    = 2;
            data.Vservo = 3;

            MavLinkMessage message = createSampleMessage(MAVLink.MAVLINK_MSG_ID.POWER_STATUS, data);

            PowerStatus obj = new PowerStatus(message);

            Assert.AreEqual(data.Vservo, obj.Vservo);
            Assert.AreEqual(data.Vcc, obj.Vcc);
            Assert.AreEqual(1, obj.flags.Count);

            PowerStatusDTO dto = DTOFactory.createPowerStatusDTO(obj);

            Assert.AreEqual(dto.Vservo, obj.Vservo);
            Assert.AreEqual(dto.Vcc, obj.Vcc);
            Assert.AreEqual(1, dto.flags.Count);
        }