public static ServoOutputRawDTO createServoOutputRawDTO(ServoOutputRaw source) { if (null == source) { return(null); } ServoOutputRawDTO result = new ServoOutputRawDTO(); Utilities.CopySimilar.CopyAll(source, result); return(result); }
public void CheckServoOutputRawObject() { MAVLink.mavlink_servo_output_raw_t data = new MAVLink.mavlink_servo_output_raw_t(); data.port = 1; data.servo1_raw = 2; data.servo2_raw = 3; data.servo3_raw = 4; data.servo4_raw = 5; data.servo5_raw = 6; data.servo6_raw = 7; data.servo7_raw = 8; data.servo8_raw = 9; data.time_usec = 10; MavLinkMessage message = createSampleMessage(MAVLink.MAVLINK_MSG_ID.SERVO_OUTPUT_RAW, data); ServoOutputRaw obj = new ServoOutputRaw(message); Assert.AreEqual(data.port, obj.port); Assert.AreEqual(data.servo1_raw, obj.servo1_raw); Assert.AreEqual(data.servo2_raw, obj.servo2_raw); Assert.AreEqual(data.servo3_raw, obj.servo3_raw); Assert.AreEqual(data.servo4_raw, obj.servo4_raw); Assert.AreEqual(data.servo5_raw, obj.servo5_raw); Assert.AreEqual(data.servo6_raw, obj.servo6_raw); Assert.AreEqual(data.servo7_raw, obj.servo7_raw); Assert.AreEqual(data.servo8_raw, obj.servo8_raw); Assert.AreEqual(data.time_usec, obj.time_usec); ServoOutputRawDTO dto = DTOFactory.createServoOutputRawDTO(obj); Assert.AreEqual(dto.port, obj.port); Assert.AreEqual(dto.servo1_raw, obj.servo1_raw); Assert.AreEqual(dto.servo2_raw, obj.servo2_raw); Assert.AreEqual(dto.servo3_raw, obj.servo3_raw); Assert.AreEqual(dto.servo4_raw, obj.servo4_raw); Assert.AreEqual(dto.servo5_raw, obj.servo5_raw); Assert.AreEqual(dto.servo6_raw, obj.servo6_raw); Assert.AreEqual(dto.servo7_raw, obj.servo7_raw); Assert.AreEqual(dto.servo8_raw, obj.servo8_raw); Assert.AreEqual(dto.time_usec, obj.time_usec); }