VIS LOG DATA DESCRIPTION The VIS string logs for raw doppler data LOG DATA SOURCE: This data string is generated by DVLNAV every time a valid doppler data packet arrives LOG DATA FREQUENCY: Once each doppler ping. Ping frequency is up to 10 hertz at low with a 1200 KHZ dvl, 1-2 hertz at high (175m) with a 300KHZ dvl. Note 1: The DVL can be configured to report in beam coordinates, ship coordinates, instrument coordinates, and earth coordinates. DVLNAV expects and requires that the DVL be configured to report velocities in INSTRUMENT COORDINATES. In this configuration, the DVL's reported bottom track displacements are not meaningful. Bottom track displacement must be computed by first rotating instrument velocities into world coordinates and then integrating. See RDI publication "ADCP Coordinate Transformations" for a detailed explanation. Note 2: The DVL beam range is not the true range, it is the range multiplied by cos(30 degrees), i.e. it has been converted to a sort of "altitude" The Altitude field is the average of the good beam ranges. Note 3: DVLNAV expects and requires that the DVL be configured with no internal local variation or heading offset. In this case: The heading is the magnetic heading of beam 3. The pitch, Tilt 1, is pendulum pitch, not naval architecture pitch. To convert dvl Tilt 1 pitch to naval architecture pitch. Naval Arch Pitch = arctan[tan(Tilt1)*cos(Tilt2)]. The roll, Tilt 2, is naval architecture roll. See RDI publication "ADCP Coordinate Transformations" for a detailed explanation. Note 4: Bottom track course over ground and speed over may not be computed correctly when the DVL is configured in INSTRUMENT coordinates, to compute them the instrument velocities should be converted to earth coordinates, then computed from the horizontal velocities. LOG DATA FIELDS: 1. "VIS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SSS 3. "RDI1 FSH" for Alvin and the DSL120 "RDI1 JAS" for Jason "RDI1 ARG" for Argo 4. bottom track X displacement - see Note 1 5. bottom track Y displacement 6. bottom track Z displacement 7. bottom track ERROR displacement 8. bottom track X velocity - see Note 1 9. bottom track Y velocity 10. bottom track Z velocity 11. bottom track ERROR velocity 12. bottom track ping status integer whose bits indicate bottom track beam status. All zeros means no errors. Bits as follows per RDI manual Appendix page D-24: Bit 0 (lsb) Beam 1 Low Correlation Bit 1 Beam 1 Low Amplitude Bit 2 Beam 2 Low Correlation Bit 3 Beam 2 Low Amplitude Bit 4 Beam 3 Low Correlation Bit 5 Beam 3 Low Amplitude Bit 6 Beam 4 Low Correlation Bit 7 (msb) Beam 4 Low Amplitude 13. water track X displacement - see Note 1 14. water track Y displacement 15. water track Z displacement 16. water track ERROR displacement 17. water track X velocity - see Note 1 18. water track Y velocity 19. water track Z velocity 20. water track ERROR velocity 21. water track ping status integer whose bits indicate water track beam status. All zeros means no errors. Bits as follows per RDI manual Appendix page D-24: Bit 0 (lsb) Beam 1 Low Correlation Bit 1 Beam 1 Low Amplitude Bit 2 Beam 2 Low Correlation Bit 3 Beam 2 Low Amplitude Bit 4 Beam 3 Low Correlation Bit 5 Beam 3 Low Amplitude Bit 6 Beam 4 Low Correlation Bit 7 (msb) Beam 4 Low Amplitude 22. Beam 1 range in meters - see note 2. 23. Beam 2 range in meters 24. Beam 3 range in meters 25. Beam 4 range in meters 26. Altitude in meters - average altitude of good beams. 27. Magnetic Heading of DVL instrument in degrees - see Note 3 28. Tilt 1, Pendulum Pitch of DVL instrument in degrees - see Note 3 29. Tilt 2, Pendulum Roll of DVL instrument in degrees - see Note 3 30. Sound Velocity reported by DVL in meters/second. This is sound velocity the DVL used for this ping. 31. Salinity reported by DVL in parts per thousand. 32. Temperature reported by DVL in Centigrade. This is temp sensor value from the dvl. 33. Depth reported by DVL in meters. This is depth reported by the DVL. 34. Total integer count since DVLNAV program start of bad BOTTOM pings - i.e. pings having 0, 1, or 2 good beams. Timebase is PC clock. 35. Total integer count since DVLNAV program start of good 3-beam bottom pings. 36. Total integer count since DVLNAV program start of good 4-beam bottom pings. 37. Integer number (0,1,2,3,4) of good bottom track beams in this ping. 38. Time in seconds since PREVIOUS good bottom track ping, i.e. the time between the last GOOD ping and this ping. This ping could be bad or good. Timebase is PC clock. 39. Bottom track course over ground in degrees. - See note 4. 40. Bottom track speed over ground in m/s. 41. Total integer count since DVLNAV program start of bad WATER pings - i.e. pings having 0, 1, or 2 good beams. Timebase is PC clock. 42. Total integer count since DVLNAV program start of good 3-beam water pings. 43. Total integer count since DVLNAV program start of good 4-beam water pings. 44. Integer number (0,1,2,3,4) of good water track beams in this ping. 45. Time in seconds since PREVIOUS good water track ping, i.e. the time between the last GOOD ping and this ping. This ping could be bad or good. Timebase is PC clock. 46. Water track course over ground in degrees. - See note 4. 47. Water track speed over ground in m/s. 48. DVL configuration integer code - see DVL manual for details. BIT 76543210 00xxxxxx BEAM-COORDINATE VELOCITIES 01xxxxxx INSTRUMENT-COORDINATE VELOCITIES 10xxxxxx SHIP-COORDINATE VELOCITIES 11xxxxxx EARTH-COORDINATE VELOCITIES xx0xxxxx TILT INFORMATION NOT USED IN CALCULATIONS xx1xxxxx TILT INFORMATION USED IN CALCULATIONS xxx0xxxx 3-BEAM SOLUTIONS NOT COMPUTED xxx1xxxx 3-BEAM SOLUTIONS COMPUTED xxxxx010 300-kHz DVL xxxxx011 600-kHz DVL xxxxx100 1200-kHz DVL 49. DVL BIT integer code - see DVL manual for details. Results These fields contain the results of the ADCP's Built-in Test function. A zero code indi-cates a successful BIT result. BYTE 40 BYTE 41 (BYTE 41 RESERVED FOR FUTURE USE) 1xxxxxxx xxxxxxxx = RESERVED x1xxxxxx xxxxxxxx = RESERVED xx1xxxxx xxxxxxxx = RESERVED xxx1xxxx xxxxxxxx = DEMOD 1 ERROR xxxx1xxx xxxxxxxx = DEMOD 0 ERROR xxxxx1xx xxxxxxxx = RESERVED xxxxxx1x xxxxxxxx = DSP ERROR xxxxxxx1 xxxxxxxx = RESERVED 50. DVL water layer near threshhold - see DVL manual for details. 51. DVL water layer far threshold - see DVL manual for details. 52. Integer number of valid ping data records received by dvlnav. This indicates the number of valid dvl data packets parsed with no error, it does not indicate that the pings were bad or good, just that the data was received with no telemetry errors. 53. Integer number of INVALID data records received by dvlnav. This indicates the number of corrupted dvl data packets not parsed successfully - i.e. the checksums did not match. 52. Time in seconds between the PREVIOUS valid data packet and this data packet. Either or both pings could be bad or good. Timebase is PC clock. 55. Time in seconds between two most recent ping records. Timebase is DVL internal clock which is not synced to PC clock. 56. Seconds since midnight of internal DVL clock Timebase is DVL internal clock which is not synced to PC clock. 57. DVLNAV timestamp (scalar seconds) of this ping data. 58-60. Most recent octans attitude pos in deg, order is heading, pitch, roll, float. 61-63. Most recent octans attitude vel in deg/sec, order is heading, pitch, roll, float. 64. Octans data timestamp, float. 65-67. Most recent crossbow attitude pos in deg, order is heading, pitch, roll, float. 68-70. Most recent crossbow attitude vel in deg/sec, order is heading, pitch, roll, float. 71. crossbow data timestamp, float. LOG DATA STRING SAMPLE: VIS 2001/06/10 09:18:30.107 RDI1 FSH 0.000 0.000 0.000 0.000 0.024 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 1 4 0.020 90 0.024 0 0 1 4 0.020 0 0 83 0 5.00 10.00 1 0 992179110.087 0.000 47910.080 992179110.087 0 0 0 0 0 0 0.000 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.187 RDI1 FSH 0.000 0.000 0.000 0.000 0.047 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 2 4 0.000 90 0.047 0 0 2 4 0.000 0 0 83 0 5.00 10.00 2 0 0.100 0.100 47910.180 992179110.187 0 -0 -0 0 0 0 992179110.117 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.287 RDI1 FSH 0.000 0.000 0.000 0.000 0.069 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 3 4 0.000 90 0.069 0 0 3 4 0.000 0 0 83 0 5.00 10.00 3 0 0.100 0.100 47910.280 992179110.287 0 -0 -0 0 0 0 992179110.197 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.387 RDI1 FSH 0.000 0.000 0.000 0.000 0.090 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 4 4 0.000 90 0.09 0 0 4 4 0.000 0 0 83 0 5.00 10.00 4 0 0.100 0.100 47910.380 992179110.387 0 -0 -0 0 0 0 992179110.287 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.488 RDI1 FSH 0.000 0.000 0.000 0.000 0.110 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 5 4 0.000 90 0.11 0 0 5 4 0.000 0 0 83 0 5.00 10.00 5 0 0.101 0.100 47910.480 992179110.488 0 -0 -0 0 0 0 992179110.387 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.588 RDI1 FSH 0.000 0.000 0.000 0.000 0.129 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 6 4 0.000 90 0.129 0 0 6 4 0.000 0 0 83 0 5.00 10.00 6 0 0.100 0.100 47910.580 992179110.588 0 -0 -0 0 0 0 992179110.488 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.688 RDI1 FSH 0.000 0.000 0.000 0.000 0.147 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 7 4 0.000 90 0.147 0 0 7 4 0.000 0 0 83 0 5.00 10.00 7 0 0.100 0.100 47910.680 992179110.688 0 -0 -0 0 0 0 992179110.588 0 0 0 0 0 0 0.000 VIS 2001/06/10 09:18:30.788 RDI1 FSH 0.000 0.000 0.000 0.000 0.164 0.000 0.000 1.234 0 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0 2.10 1.90 2.20 1.80 2 0 0 0 1500 35 0 0 0 0 8 4 0.000 90 0.164 0 0 8 4 0.000 0 0 83 0 5.00 10.00 8 0 0.100 0.100 47910.780 992179110.788 0 -0 -0 0 0 0 992179110.688 0 0 0 0 0 0 0.000 _____________________________________________________________________ Coordinate Frame Convention Specification ---------------------------------------------------------------------- Attitude Conventions are a right handed, naval architecture standard. Vehicle axes, fixed rigidly in the vehicle are defined as: X forward Y starboard Z down. Heading is TRUE compass heading. Positive roll is starboard side down. Positive pitch is bow up. Heading is positive rotation about the Z axis. Roll is positive rotation about the X axis. Pitch is positive rotation about the Y axis. The rotation matrix from vehicle frame to the ZERO frame defined as: ZERO frame: X North Y East Z Down, normal to earh surface. is computed as follows: /* rotation about X azis by ROLL radians */ n_mat_t rx = {{ 1.0, 0.0, 0.0, 0.0 }, { 0.0, cos(r), -sin(r), 0.0 }, { 0.0, sin(r), cos(r), 0.0 }, { 0.0, 0.0, 0.0, 1.0 }}; /* rotation about Y axis by PITCH radians */ n_mat_t ry = {{ cos(p), 0.0, sin(p), 0.0 }, { 0.0, 1.0, 0.0, 0.0 }, {-sin(p), 0.0, cos(p), 0.0 }, { 0.0, 0.0, 0.0, 1.0 }}; /* rotation about Z axis by HDG radians */ n_mat_t rz = {{ cos(h), -sin(h), 0.0, 0.0 }, { sin(h), cos(h), 0.0, 0.0 }, { 0.0, 0.0, 1.0, 0.0 }, { 0.0, 0.0, 0.0, 1.0 }}; vehicle_to_zero = rx * ry * rx; To compute the transformation from vehicle frame to world local level frame defined as: LL frame: X East Y North Z Up, normal to earh surface. is computed as follows: n_mat_t ll_zero_to_world_xform = {{0.0, 1.0, 0.0, 0.0}, {1.0, 0.0, 0.0, 0.0}, {0.0, 0.0,-1.0, 0.0}, {0.0, 0.0, 0.0, 1.0}}; vehicle_to_world = ll_zero_to_world_xform * vehicle_to_zero; Note that ll_zero_to_world_xform is orthogonal, symmetric, and is its own inverse, i.e. A = A^-1 .