-------------------------------------------------------------------- Title: DVLNAV DATA I/O and LOG FORMAT DOCUMENTATION Author: Louis L. Whitcomb and James Kinsey Department of Mechanical Engineering Johns Hopkins University and Deep Submergence Laboratory Woods Hole Oceanographic Institution Created and Written: 05 June 2001 Rev 01 Abstract: This note documents the dvlnav reatime data Input/output and data log formats. ---------------------------------------------------------------------- ---------------------------------------------------------------------- ---------------------------------------------------------------------- TABLE OF CONTENTS ---------------------------------------------------------------------- PART 0: MODIFICATION HISTORY ---------------------------------------------------------------------- ---------------------------------------------------------------------- PART I: REATIME DATA INPUT/OUTPUT STRING FORMATS PART SECTION SECTION NAME -------- --------- -------------------------------------------------- I 1 Overview I 2 String input from HOST to DVLNAV I.2.1 $PWHDEP NMEA Depth Sensor String I.2.2 $PWHALT NMEA Altitude Sensor String I.2.3 $PWHLBL NMEA LBL Travel Time String I.2.4 $PWHTMP NMEA Water temperature Sensor String I.2.5 $PWHSOS NMEA Sound Velocity Sensor String I.2.6 $PWHCTD NMEA CTD Sensor String I.2.7 $PWHTIM NMEA Time String I.2.8 XBW ASCII Crossbow Gyro String I.2.9 VIS ASCII Magnetomoeter String I.2.10 VIS ASCII CTD String I.2.11 VDS ASCII Depth String String I.2.12 $PWHMAG NMEA Magnetometer String I.2.13 PNS ASCII Platform Navigation String for externally input of vehicle, ship, or depressor position. I.2.14 PAS ASCII Platform Navigation (position) String externally input of vehicle or depressor heading, pith, roll. I 3 String output from DVLNAV to HOST I.3.1 $PWHGYRO NMEA Octans heading and attitude. I.3.2 $PWHMAGD NMEA DVL heading and attitude. I.3.3 $PWHLBX NMEA LBL nav fix. String I.3.4 $PWHDOP NMEA Doppler nav fix, cog, sog, etc. I.3.5 $PWHTRB NMEA Target ID, range, bearing. I.3.6 $PWHTIM NMEA Time I.3.7 VNS ASCII Vehicle pos and vel in UTM. I.3.8 $PWHCFG NMEA Site configuration data. I.3.9 DVX ASCII Doppler navigation string sent to host ---------------------------------------------------------------------- PART II: DSL DATA FORMAT LOG FILE LOG STRING SPECIFICATIONS PART SECTION SECTION NAME -------- --------- -------------------------------------------------- II 1 OVERVIEW OF LOG FILE FORMATS II 2 PNS format for cooked host data II 3 VIS format for cooked octans data II 4.1 OCT format for raw octans ascii NMEA strings II 4.2 OCB format for raw octans BINARY strings II 5 VIS format for cooked doppler data II 6 RDB format for raw doppler data II 7 HST format for raw host strings received from host II 8 HTX format for raw host strings transmitted to host II 9 STD format for stderr log II 10 CPU format for CPU and DISK usage II 11 MSC format for miscellaneous derived realtime nav info II 12 SIM format for simulation data ---------------------------------------------------------------------- Part III: COMMA-DELIMITED LOG FILES SPECIFICATIONS (for SPREADSHEETS) PART SECTION SECTION NAME -------- --------- -------------------------------------------------- III 1 Overview: file content, file name conventions. III 2 Comma-Delimited Log File Format ---------------------------------------------------------------------- Part IV: Vehicle Coordinate Frame Convention Specification PART SECTION SECTION NAME -------- --------- -------------------------------------------------- IV 1 Vehicle Coordinate Frame Convention Specification ---------------------------------------------------------------------- ---------------------------------------------------------------------- Part 0: Modification history ---------------------------------------------------------------------- Rev 1 Jun 5 2001 LLW Created and written Rev 2 Jun 5 2001 LLW Added octans PAS log format, Section 3 Rev 4 Jun 5 2001 LLW Added doppler & host PNS log format, Section 4 Rev 6 Jun 6 2001 LLW & JCK I/O Formats Rev 9 Jun 7 2001 LLW & JCK Host NMEA I/O protocol. Rev 14 Jun 10 2001 LLW & JCK Revised PNS, VIS, and NMEA formats. Added Host VIS dvlnav output format. Rev 18 Jun 10 2001 LLW Added VNS output string format. Implementred and tested Alvin host NMEA output strings. Rev 19 Jun 10 2001 LLW DSL Format (from Jon Howland) for Crossbow Depth, CTD, and Magnetometer Rev 20 Jun 17 2001 LLW & KH Added Lat and Lon to LBX string. Typo corrections. Rev 21 Sept 6 2001 LLW & KH Added $PWHTRB Note. Oct 11 2001 DVLNAV V128 Release to Alvin Rev 23 Jan 10 2002 DAS Corrected errors in $PWHDEP string documentation. Rev 24 Mar 1 2002 LLW $PWHDOP and $PWHLBL implementation have been corrected to report depth as positive, and to confirm to to this documentation. Rev 26 Apr 11 2002 LLW Added new comma-delimited one-hertz output file format, first revision, based on Dan Fornari's specification. Modified filename convention to include year. Rev 28 Apr 14 2002 LLW Added additional unit convention comments to Part III comma delimited log format. Added time zone to comma delimited log format. Added octans status, Maggie time. Rev 29 Apr 17 2002 LLW Added new $PWHCFG string format spec Rev 30 Apr 19 2002 LLW Added lat, lon to $PWHDOP Removed salinity and temp from $PWHCFG Added XY Origin in UTM to $PWHCFG Rev 31 Apr 19 2002 LLW Modified $PWHDOP and $PWHLBL to have identical data fields for first seven fields: $PWHLBX,,,,,,,, $PWHDOP,,,,,,,, Rev 32 Apr 21 2002 LLW Modified $PWHDOP to report FILTERED cog, sog, cow, sow Modified $PWHMTW to $PWHTMP and added string tag field to identify low temp, hi temp, ICL temp, etc. Added $PWHMAG maggie string. Revised $PWHCFG string. Addex X,Y,Z vel to science spreadsheet log. Modified $PWHRB to report NAME or # of origin and destination for range and bearing. Rev 33 Apr 23 2002 LLW Changed .CSV to log both altitude and doppler altitude. Rev 34 Apr 23 2002 LLW Typo corrections in Part III Section II .CSV format pitch data sign definition. April 24 2002 DVLNAV V155 Release to Alvin. Rev 35 May 06 2002 LLW Added DVL temp to .CSV format Rev 36 May 09 2002 LLW DVLNAV V157 Release to Alvin Added logging of targets (both pre-loaded and on-the-fly dropped targets to CSV file. Rev 37 May 20 2002 LLW Changed order from Lon Lat to Lat Lon in .CSV . Fixed sign bug in $PWHLBX and $PWHDOP vertical vel. $PWHLBX and $PWHDOP changed to report Z depth, not Z lbl solution depth. Fixed bracket problem in INI file format. Rev 38 May 21 2002 LLW DVLNAV V159 Release to Alvin Fixed bug in $PWHDOP in which Doppler fix status was always incorrectly reported as zero. Added referenced to DVLNAV version numbers in this modification history. Rev 39 Aug 18 2003 LLW DVLNAV V172.01 Data format revsions: (1) Part II Section 4: Added additional data fields to VIS data string logged on every DVL ping: - Sound velocity and sound velocity source for Doppler fix computation - World Vehicle Position XYZHPR (2) Added additional data fields to PNS data string logged on every LBL fix and at one hertz: - Sound velocity and sound velocity source for Doppler fix computation - Sound velocity and sound velocity source for LBL fix computation - World vehicle top and bottom transducer position Rev 40 Aug 18 2003 LLW&JCk DVLNAV V172.02 Change Doppler VIS string: - octans and xbow attitudes are now cooked vehicle attitude, not raw instrument atitude. - added cooked doppler vehicle attitude Rev 40 Aug 20 2003 LLW&JCk DVLNAV V173 Updated Doppler VIS string documentation Rev 41 Aug 21 2003 LLW DVLNAV V173.01 Created new SIM simulation data log format. This string is logged only when the "simulation mode" is active, at the simulation update rate of 10 Hz. Documented in Part II of this document. Rev 41 Aug 21 2003 LLW DVLNAV V174 Added logging of DVL instrument velocities to SIM log string Rev 41 Aug 21 2003 LLW DVLNAV V174.05 V174.05 added two-transponder-on-the-vehicle LBL, enabling the computation of LBL vehicle haading. The LBL PNS log format string has been revised to delete the four (unused) complementary filter fix pos fields, and instead logs LBL mode and LBL heading information Corrected numbering error in PNS LBL log strings Rev 45 Nov 22 2003 LLW revised to version dvlnav_data_formats_rev_45.txt Added documentation for PNS, PAS, DVX, OCT, OCB, RDB, HST, HTX, STD, and MSC data formats. Rev 46 Dec 07 2003 Corrected error in $PWHALT documentation. Was incorrectly reported as $PWALT. ---------------------------------------------------------------------- Part I Section 1: OVERVIEW ---------------------------------------------------------------------- DVLNAV presently communicates to three devices: 1. Vehicle host computer - as specified in this document 2. Octans gyro - see Octans manual for Octans STD1 NMEA protocol. 3. RDI Doppler - see RDI manual for PD5 Binary protocol. All data is communicated via the ASCII readable data strings via RS232 serial or network UDP sockets as specified in this document. All normal serial port communication settings are supported. All strings are printable ASCII, terminated with in this order. Conventions: denotes carriage return, decimal 13, hex 0D, keyboard CTRL-m denotes line-feed, decimal 10, hex 0A, keyboard CTRL-j Strings are in either of two formats: NMEA or DSL standard NMEA strings have the following format: 1. A leading $ (dollar sign) character 2. A multi character identity string, terminated with a comma (",") 3. Data fields delimited by commas. The final data field has no trailing comma. 4. A * (asterix) character. 5. A two digit hexadecimal checksum. The checksum is computed from all characters between (but not including) the leading $ and trailing * characters. The value of the checksum is the exclusive-or (XOR) of the characters between the $ and the *. Here are some sample valid NMEA strings: $PWHDEP,493.016,2,K*6C $PWHDEP,493.037,1,K*6C $PWHDEP,494.414,2,K*6D $PWHDEP,495.346,1,K*6F $PWHDEP,495.445,2,K*68 $PWHALT,500.000,K*76 $PWHALT,500.376,K*74 $PWHALT,528.488,K*78 $PWHALT,529.076,K*7C $PWHLBL,2059588,1394115,1908726,2997037*0E $PWHLBL,2063857,1397374,1912297,2993600*0C $PWHLBL,2067484,1391127,1909341,2993404*0E $PWHLBL,2071128,1391391,1909711,2992674*00 $PWHLBL,2073126,1388771,1908596,2992443*04 $PWHMTW,0.017052,C*5D $PWHMTW,0.153121,C*59 $PWHMTW,0.251564,C*5D $PWHMTW,0.577777,C*5E $PWHMTW,1.032416,C*5F $PWHMTW,1.609285,C*5D $PWHSOS,1500.000*36 $PWHCTD,36.256299,12.512598,485.587769*22 $PWHCTD,36.811789,13.623578,495.345547*26 $PWHCTD,37.342583,14.685167,468.367608*29 $PWHCTD,37.841448,15.682896,492.192721*21 $PWHCTD,38.041757,16.083513,481.599601*21 $PWHCTD,38.483534,16.967067,497.791131*20 $PWHCTD,38.877829,17.755659,469.480821*29 $PWHCTD,39.346987,18.693975,477.767897*29 $PWHCTD,39.605305,19.210610,499.375805*25 ---------------------------------------------------------------------- PART I SECTION 2: STRINGS SENT FROM HOST TO DVLNAV ---------------------------------------------------------------------- Sensor strings are normally generated by the host when a sensor value is received by the host. Some sensors, e.g. sound velocity probe and CTD, may not be present. In this case, the host should not send the corresponding strings. The time string should be transmitted by the host once a second. ---------------------------------------------------------------------- I.2.1: $PWHDEP NMEA DEPTH SENSOR STRING from host to dvlnav ---------------------------------------------------------------------- // 1/12/02 DAS Corrected error in enum FORMAT: $PWHDEP,,,* may contain any number of digits before and after the decimal point. It should be a positive number. A "+" sign is allowed but not required. should an integer, normally 1 or 2, indicating that the sensor reading is from depth sensor 1 or 2. is a character specifying the sensor datum K indicates that sensor value is measured from keel T indicates that sensor value is measured from transducer is the two digit hexadecimal checksum EXAMPLE: $PWHDEP,468.242,1,K*68 $PWHDEP,468.368,1,K*61 $PWHDEP,469.113,1,K*6E $PWHDEP,469.238,2,K*67 $PWHDEP,469.251,2,K*68 $PWHDEP,469.481,1,K*60 $PWHDEP,470.064,2,K*64 $PWHDEP,470.112,2,K*64 $PWHDEP,470.924,1,K*6A $PWHDEP,471.512,1,K*62 $PWHDEP,471.681,2,K*68 $PWHDEP,471.791,2,K*68 $PWHDEP,473.563,1,K*66 $PWHDEP,474.005,2,K*67 $PWHDEP,474.217,2,K*66 $PWHDEP,474.333,1,K*62 $PWHDEP,476.863,1,K*6E $PWHDEP,476.921,2,K*6A $PWHDEP,477.274,2,K*60 DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.2.2: $PWHALT NMEA ALTIMETER ALTITUDE STRING from host to dvlnav ---------------------------------------------------------------------- FORMAT: $PWHALT,,* may contain any number of digits before and after the decimal point. It should be a positive number. A "+" sign is allowed but not required. is a character specifying the sensor datum K indicates that sensor value is measured from keel T indicates that sensor value is measured from transducer is the two digit hexadecimal checksum EXAMPLE: $PWHALT,506.963,K*7C $PWHALT,507.807,K*7E $PWHALT,510.518,K*7B $PWHALT,511.469,K*7D $PWHALT,514.412,K*74 $PWHALT,515.410,K*77 $PWHALT,518.400,K*7B $PWHALT,519.383,K*76 $PWHALT,522.232,K*75 $PWHALT,523.137,K*72 $PWHALT,525.667,K*76 $PWHALT,526.437,K*72 $PWHALT,528.488,K*78 $PWHALT,529.076,K*7C $PWHALT,530.519,K*78 $PWHALT,530.887,K*72 $PWHALT,531.632,K*73 $PWHALT,531.758,K*7E DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.2.3: $PWHLBL NMEA LBL TRAVEL TIME STRING from host to dvlnav ---------------------------------------------------------------------- FORMAT: $PWHLBL,,,,* is the round-trip travel time between the vehicle LBL ducer and the transponder A in positive integer units of microseconds. It can contain any number of digits. It should not contain a decimal point. Units are microseconds (need to check with Alvin boys about this). same format as , but for transponder B. same format as , but for transponder C. same format as , but for transponder D. is the two digit hexadecimal checksum EXAMPLE: $PWHLBL,2055546,1397837,1911208,2996497*04 $PWHLBL,2058602,1401780,1914264,2994357*07 $PWHLBL,2059205,1395915,1910974,2995100*02 $PWHLBL,2059588,1394115,1908726,2997037*0E $PWHLBL,2063857,1397374,1912297,2993600*0C $PWHLBL,2067484,1391127,1909341,2993404*0E $PWHLBL,2071128,1391391,1909711,2992674*00 $PWHLBL,2073126,1388771,1908596,2992443*04 ---------------------------------------------------------------------- I.2.4: $PWHTMP NMEA WATER TEMPERATURE SENSOR STRING from host to dvlnav ---------------------------------------------------------------------- FORMAT: $PWHTMP,,,* may contain any number of digits before and after the decimal point. It should be a positive number. A "+" sign is allowed but not required. is a character specifying the sensor datum C indicates centigrade (use this please) F indicates Fahrenheit (will be converted to C by dvlnav) Ascii string identifying the sensor source. recognized tags are: H High Temp Probe L Low Temp Probe I1 ICL Probe #1 I2 ICL Probe #2 is the two digit hexadecimal checksum EXAMPLE: DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.2.5: $PWHSOS NMEA SOUND VELOCITY SENSOR STRING from host to dvlnav ---------------------------------------------------------------------- FORMAT: $PWHSOS,* may contain any number of digits before and after the decimal point. It should be a positive number. A "+" sign is allowed but not required. is the two digit hexadecimal checksum EXAMPLE: $PWHSOS,1500.000*36 ---------------------------------------------------------------------- I.2.6: $PWHCTD NMEA CTD SENSOR STRING from host to dvlnav ---------------------------------------------------------------------- FORMAT: $PWHCTD,,,* All data fields may contain any number of digits before and after the decimal point. They should be positive numbers. A "+" sign is allowed but not required. is decimal units of Seimens per meter. is decimal units of degrees C. is decimal units of depth in meters. Note: 1 Siemen/meter = 10 mmho/cm. To convert from Siemen/meter to mmho/cm, multiply the Siemen/meter value by 10. To convert from mmho/cm to Siemen/meter, divide the mmho/cm value by 10. is the two digit hexadecimal checksum EXAMPLE: $PWHCTD,36.256299,12.512598,485.587769*22 $PWHCTD,36.811789,13.623578,495.345547*26 $PWHCTD,37.342583,14.685167,468.367608*29 $PWHCTD,37.841448,15.682896,492.192721*21 $PWHCTD,38.041757,16.083513,481.599601*21 $PWHCTD,38.483534,16.967067,497.791131*20 $PWHCTD,38.877829,17.755659,469.480821*29 $PWHCTD,39.346987,18.693975,477.767897*29 $PWHCTD,39.605305,19.210610,499.375805*25 DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.2.7: $PWHTIM TIME STRING from host to dvlnav ---------------------------------------------------------------------- This string is used to send FORMAT: $PWHTIM,//
::,* Where: 1. is a four digit YEAR. 2. is a two digit MONTH, with January=1. 3.
is a two digit DAY OF MONTH. 4. is a two digit HOUR OF DAY in 24 hour format. 5. is a two digit MINUTE OF HOUR. 6. is seconds, in decimal notation to any second resolution. PREFERRED RESOLUTION FOR SECONDS IS 0.001 SECOND! is a character specifying the source of the time stamp H if the time stamp is from the HOST computer D if the time stamp is from the DVLNAV computer is the two digit hexadecimal checksum EXAMPLE: Note: checksum is not valid ont his example: $PWHTIM,2001/06/07 09:39:43.411,H*00 DATA SOURCE FILE: host.h host.cpp ------------------------------------------------------------------------- I.2.8: XBW Format for Crossbow Data (from Jon Howland) ------------------------------------------------------------------------- LOG DATA DESCRIPTION This XBW String logs data from the Crossbow AHRS See Appendix on angle conventions. The crossbow's absolute heading reference is magnetic. The value logged has been corrected by adding the magnetic variation. The applied variation is logged with the data. Reported accelerations and magnetic field strengths are in the instrument coordinate frame. LOG DATA SOURCE This data string is generated by the SIO_crossbow thread of the rov program every time a new Crossbow data message is received. LOG DATA FREQUENCY Between 5 and 10 Hz LOG DATA FIELDS 1. "XBW" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SSS 3. "AHRS" 4. vehicle name as entered into the rov configuration file 5. Heading in degrees (magnetic, NOT TRUE) 6. Pitch in degrees 7. Roll in degrees 8. Heading Rate in degrees/second 9. Pitch Rate in degrees/second 10. Roll Rate in degrees/second 11. X Acceleration in G 12. Y Acceleration in G 13. Z Acceleration in G 14. X Magnetic Field in Gauss 15. Y Magnetic Field in Gauss 16. Z Magnetic Field in Gauss 17. magnetic variation in degrees (already applied to item 5, heading) 18. Temperature in degrees C. 19. Magnetic variation (aka declanation) source code - how was the magnetic variation determined? Codes are: 1000 = USGS tables based on local XY origin Lat and Lon 1001 = Unknown 1002 = config file (manually entered into the config file) 1003 = Jasontalk command (i.e. from pilot gui, engineer gui, or backdoor). 9999 = This variation value is wrong, don't use it. LOG DATA STRING SAMPLE LOG DATA SOURCE FILE SIO_crossbow.c LOG DATA STRING SOURCE CODE ------------------------------------------------------------------------- I.2.9: VIS Format for Magnetometer ------------------------------------------------------------------------- Not implemented. ------------------------------------------------------------------------- I.2.10: VIS Format for SBE37 CTD Data (from Jon Howland) ------------------------------------------------------------------------- LOG DATA DESCRIPTION This String logs data from the Seabird SBE37 Conductivity/ Temperature/Depth instrument The SBE37 can be purchased with or without a depth sensor, so this format will accomodate both varieties. LOG DATA SOURCE This data string is generated by the SIO_seabird thread of the rov program every time a new ctd data message is received. LOG DATA FREQUENCY ? LOG DATA FIELDS 1. "VIS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SS 3. "SBE37" 4. vehicle name as entered into the rov configuration file 5. Conductivity 6. Temperature 7. Depth, if available LOG DATA STRING SAMPLE LOG DATA SOURCE FILE SIO_seabird.c LOG DATA STRING SOURCE CODE ------------------------------------------------------------------------- I.2.11: VDS Format for Paroscientific Data (from Jon Howland) ------------------------------------------------------------------------- LOG DATA DESCRIPTION This string logs data from the Paroscientific depth sensor Depth is logged as positive down LOG DATA SOURCE This data string is generated by the SIO_parosci thread of the rov program every time a new paroscientific data message is received. LOG DATA FREQUENCY Currently in flux--between 5 and 10 Hz LOG DATA FIELDS 1. "VDS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SS 3. "PAR" 4. vehicle name as entered into the rov configuration file 5. Depth in meters LOG DATA STRING SAMPLE LOG DATA SOURCE FILE SIO_parosci.c LOG DATA STRING SOURCE CODE ---------------------------------------------------------------------- I.2.12: $PWHMAG MAGNETOMETER DATA ---------------------------------------------------------------------- DATA DESCRIPTION: Vehicle navigation string sent from HOST to DVLNAV, presently via RS232 and UDP, containing magnetometer data. DATA SOURCE: Host (athena) DATA FREQUENCY: Several hertz once maggie is energized. DATA FORMAT: FORMAT: $PWHMAG,:,,,,,0* YYYY/MM/DD HH:MM:SS.SSS Magnetic component in gauss. Magnetic component in gauss. Magnetic component in gauss. Magnetic component in gauss. Magnitude gauss. ,0 Verbatim dummy data Two digit hexadecimal checksum EXAMPLE: ---------------------------------------------------------------------- I.2.13: PNS Platform Navigation String ---------------------------------------------------------------------- DATA DESCRIPTION: The PNS platform navigation string contains a X, Y, Depth navigation fix of the ROV, SHIP, or the DEPRESSOR (medea). It is sent from an external navigation source (LBL, USBL, GPS, etc) to dvlnav. The ROV's LBL position is set with this external data input. DATA SOURCE: Host DATA FREQUENCY: Determined by the host DATA FORMAT: PNS DATA FIELDS: 1. "PNS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SSS 3. Three letter data source tag indicating the system that generated the data contained in this message. DVLNAV presently logs this information but does not use it. Examples: GPS = Global Positioning System LBL = Long Baseline Acoustic Navigation 4. Three character flag indicating coordinate convention UTM = Universal Transverse Mercator GLL = Latitude and Longitude in decimal degrees NEN = LBL XY coordinates, meters Dvlnav uses this field to convert the fix data into its internal representation of XY. 5. Three character vehicle label. Presently supported are: ROV = The ROV LBL position FSH = The ROV LBL position SHP = The SHIP's position MED = The depressor weight's posision 6. Vehicle X East in meters (UTM and NEN) or decimal degrees longitude (GLL) 7. Vehicle Y North in meters (UTM and NEN) or decimal degrees latitude (GLL) 8. Vehicle Z Depth in meters 9. GPS Pdop. This field should be zero for non-gos navigation sources. 10. GPS # Satellites. This field should be zero for non-GPS navigation sources. EXAMPLE: GPS fix for the SHIP in Lat/Lon: PNS 02/07/22 18:02:51.20 WRN GLL SHP 45.828080 -125.130062 20.60 1.1 8 GPS fix for the SHIP in UTM: PNS 02/07/22 18:02:51.20 GPS UTM SHP 334555.37 5077152.58 20.60 1.1 08 LBL fix for the depressor weight Medea in LBL XY coordinates: PNS 02/07/22 18:02:12.00 LBL NEN MED 334567.50 5077138.79 1619.31 0.0 0 LBL fix for the ROV in LBL XY coordinates: PNS 02/07/22 18:02:22.00 LBL NEN ROV 334568.32 5077137.85 1618.46 0.0 00 ---------------------------------------------------------------------- I.2.14: PAS Platform Atitude String ---------------------------------------------------------------------- DATA DESCRIPTION: The PAS platform navigation string contains a heading, pitch, and roll fix for the SHIP, or the DEPRESSOR (medea). It is sent from an external navigation source (GYRO, Asgtek GPS, etc) to dvlnav. Note: The ROV's atitude cannot be set with this input. To set the ROV's atitude, use one of the gyro or mag compass stings. DATA SOURCE: Host DATA FREQUENCY: Determined by the host DATA FORMAT: PAS DATA FIELDS: 1. "PAS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SSS 3. Three character vehicle label. Presently supported are: ROV = The ROV LBL position FSH = The ROV LBL position SHP = The SHIP's position MED = The depressor weight's posision 6. Vehicle Heading in Degrees TRUE. 7. Pitch in Degrees. +Pitch is bow UP. -Pitch is bow DOWN. 8. Roll in Degrees. +Roll is Starboard side DOWN. -Roll is Starboard side UP. EXAMPLE: Example of data from ships gyro with no roll or pitch information: PAS 02/07/22 18:02:52.84 SHP 352.1 0.0 0.0 PAS 02/07/22 18:04:05.62 SHP 352.2 0.0 0.0 ---------------------------------------------------------------------- PART I SECTION 3: STRINGS SENT HOST FROM DVLNAV ---------------------------------------------------------------------- ---------------------------------------------------------------------- I.3.1: $PWHGYRO OCTANS HEADING AND ATTITUDE STRING sent from dvlnav to host ---------------------------------------------------------------------- This string contains the octans attitude. FORMAT: $PWHGYRO,,,,,* is the vehicle heading in degrees TRUE. is the vehicle pitch in degrees. is the vehicle roll in degrees. See Appendix on attitude conventions. All angles are reported to a precision of 0.001 degree, with a leading + or - character. is the time in seconds since this heading reading was received from the octans. Normally under 0.1 second. If the octans is turned off, for example, the time will increase. is an 8-digit hexadecimal octans status word. A value of ALL ZEROS indicates normal operation. Nonzero values indicate various errors. See the OCTANS interface manual for a description of the octans $PHINF string, page 6, for a description of the bit map of this status word. When the octans is first powered up, the status word is non-zero for 2-5 minutes while the unit finds north. If the OCTANS status is persists with a non-zero value more than 5-minutes after power-on, with any of the bits bit 0 through bit 5 set, check that you have correctly configured DVLNAV with the site origin latitude. DVLNAV sends this latitude to the OCTANS. If the configured latitude is not within a degree or so of the true latitude, the octans staus bits will remain set (non-zero) indicating the error. Per the the OCTANS interface manual description of the octans $PHINF string, page 6, the bit map of this status word is: Bit 0 Heading not valid Bit 1 Roll not valid Bit 2 Pitch not valid Bit 3 Position (Heave, surge and sway) not valid Bit 4 Position calculation starting Bit 5 Initialization Bit 6 Reserved Bit 7 Reserved Bit 8 FOG X1 Error Bit 9 FOG X2 Error Bit 10 FOG X3 Error Bit 11 Optical source error Bit 12 Accelerometer X1 error Bit 13 Accelerometer X2 error Bit 14 Accelerometer X3 error Bit 15 Analog input A or B error Bit 16 Serial input A error Bit 17 Serial input B error Bit 18 Serial input C error Bit 19 FIFO Full Bit 20 Serial output A full Bit 21 Serial output B full Bit 22 Serial output C full Bit 23 Manual log used Bit 24 Manual latitude used is the two digit hexadecimal checksum FREQUENCY: Two Hertz. EXAMPLE: $PWHGYRO,+1.546,-0.038,-0.008,0.030,00000000*4D DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.3.2: $PWHMAGD DOPPLER HEADING AND ATTITUDE STRING sent from dvlnav to host ---------------------------------------------------------------------- FORMAT: $PWHMAGD,,,,,,* is the vehicle heading in degrees TRUE, computed from the doppler's flux-gate compass, corrected for local variation. is the vehicle pitch in degrees. is the vehicle roll in degrees. is the local variation in decimal degrees. negative indicates WEST local variation positive indicates EAST local variation true heading = mag heading + variation mag heading = true heading - variation All angles are reported to a precision of 0.001 degree, with a leading + or - character. is the time in seconds since this heading reading was received from the sensor. Normally under 0.1 second. If the octans is turned off, for example, the time will increase. is a decimal status flag 0 indicates that this string data is GOOD 1 indicates that this string data is BAD is the two digit hexadecimal checksum EXAMPLE: $PWHMAGD,+0.000,+0.000,+0.000,992278787.134,0.000,0*74 DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.3.3: $PWHLBX LBL NAV STRING sent from dvlnav to host ---------------------------------------------------------------------- FORMAT: $PWHLBX,,,,,,,,,, ,,,,,, ,,,, ,,,, * The floating point fields may contain any number of digits before and after the decimal point. X and Y will be prefixed with a + or - to indicate sign vehicle LBL X coordinate in local XY frame, meters, float. vehicle LBL Y coordinate in local XY frame, meters, float. Vehicle depth using presently selected depth sensor, meters, float. latitude in decimal degrees, +=North, -=Soutn longitude in decimal degrees, +=East, -=West user-selected altitude, meters, float. Vertical velocity, filtered, in METERS/MINUTE. +=UP, -=Down Time at surface in GMT HH:MM:SS Time at bottom in GMT HH:MM:SS Status of this LBL fix, integer: RANGE_UNKNOWN = 0 <- bad RANGE_GOOD = 1 <- this means a good fix RANGE_OLD = 2 <- bad RANGE_TOO_LONG = 3 <- bad RANGE_TOO_SHORT = 4 <- bad RANGE_FAILED_MEDIAN = 5 <- bad RANGE_HIGH_ERROR = 6 <- bad LBL solution method, integer: LBL_XPNDR2 = 0 two transponder solution Alvin normally uses LBL_XPNDR2 LBL_AUTO = 1 automatic 2-4 transponder solution The label (A,B,C,D) of the first transponder of the baseline when in two-transponder LBL_XPNDR2 mode. The label (A,B,C,D) of the first transponder of the baseline when in two-transponder LBL_XPNDR2 mode. Baseline side of this fix, integer: CW = 0 CCW = 1 ON_BASELINE = 2 SIDE_UNKNOWN = 3 Speed of sound used in this fix, meters/second, float. Range to transponder A, meters, float. Range to transponder B, meters, float. Range to transponder C, meters, float. Range to transponder D, meters, float. Range status to transponder A, integer. Range status to transponder B, integer. Range status to transponder C, integer. Range status to transponder D, integer. Range status codes are as follows: RANGE_UNKNOWN = 0 RANGE_GOOD = 1 RANGE_OLD = 2 RANGE_TOO_LONG = 3 RANGE_TOO_SHORT = 4 RANGE_FAILED_MEDIAN = 5 RANGE_HIGH_ERROR = 6 Time in seconds since this fix was computed Normally under 0.01 second. is the two digit hexadecimal checksum EXAMPLE: DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.3.4: $PWHDOP DOPPLER NAV STRING sent from dvlnav to host ---------------------------------------------------------------------- FORMAT: $PWHDOP,,,,,,,, ,,,,, ,,,,, ,,,,,,, * The floating point fields may contain any number of digits before and after the decimal point. X and Y will be prefixed with a + or - to indicate sign Vehicle Doppler X coordinate in local XY frame, meters, float. This is the position of the Vehicle frame origin, not necessarily the doppler instrument, in world coordinates. Vehicle Doppler Y coordinate in local XY frame, meters, float. This is the position of the Vehicle frame origin, not necessarily the doppler instrument, in world coordinates. Vehicle depth using presently selected depth sensor, meters, float. latitude in decimal degrees, +=North, -=Soutn longitude in decimal degrees, +=East, -=West Doppler altitude, meters, float. Zero if no lock. Vertical velocity, filtered, in METERS/MINUTE. +=UP, -=Down Time at surface in GMT HH:MM:SS Time at bottom in GMT HH:MM:SS Method of this Doppler fix, integer: NONE (bad) = 0 BOTTOM TRACK = 1 WATER TRACK = 2 Number of Bottom Track beams locked on bottom. Need minimum of three for good bt fix. Integer. Number of Water Track beams locked on water column. Need minimum of three for good wt fix. Integer. Time since this fix. Time since doppler track was reset to LBL, seconds, float. Doppler World X velocity in local XY frame, meters per sec, float. Doppler World Y velocity in local XY frame, meters per sec, float. Doppler World Z velocity in local XY frame, meters per sec, float. Note that the above velocities are the velocities of the Doppler instrument in world coordiantes, not the vehicle origin velocity. Vehicle course over ground, degrees TRUE, float. Only valid if have 3 or 4 bottom track beams. Vehicle speed over ground, METERS/MINUTE, float. Only valid if have 3 or 4 bottom track beams. Vehicle course over water, degrees TRUE, float. Only valid if have 3 or 4 water track beams. Vehicle speed over water, METERS/MINUTE, float. Only valid if have 3 or 4 water track beams. Water column course over ground, degrees TRUE, float. This is the water current direction w/respect to earth. Only valid if have 3 or 4 water track beams and 3 or 4 bottom track beams. Water column speed over water, METERS/MINUTE, float. This is the water current speed w/respect to earth. Only valid if have 3 or 4 water track beams and 3 or 4 bottom track beams. Temp sensor in DVL, Centigrade Speed of sound employed in dvl fix computation is the two digit hexadecimal checksum EXAMPLE: DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.3.5: $PWHTRB TARGET RANGE AND BEARING STRING sent from dvlnav to host ---------------------------------------------------------------------- The range/bearing function will normally be used with the the vehicle selected as the ORIGIN, and a numbered Target selected as the destination. Targets 0-998 are loaded from the DVLNAV config file, or dropped interactively during a dive. Target 0 is the current vehicle position. target 999 is the current position of the DVLNAV map cursor. Note that at present the following fields of this string are computed and transmitted properly: 1) Origin target number 2) Destination target number 3) Range 4) Bearing 5) Slant range 6) Vertical range 7) Origin X, Y, Depth 8) Destination X, Y, Depth 9) Origin label 10) Destination Label At present the cross-track error, velocities, and time fields (e.g. time to go) are not computed and are reported as zero. FORMAT: $PWHTRB,,,, ,,,,, ,,,, ,,, ,,, ,, ,,* Status of this range and bearing, integer: GOOD = 1 BAD = 0 Target NAME or number of origin for range, integer. The vehicle position is Target number 0. Target NAME or number of destination for range, integer. Bearing in degrees TRUE from origin to destination, float. Horizontal Range in meters from origin to destination, float. Horizontal cross track of vehicle in meters w/respect to line from origin to destination, float. Positive when vehicle is to right of line. Negative when vehicle is to right of line. Horizontal component of vehicle velocity along line from origin to destination in m/s,float. Positive for motion from origin toward dest. Negative for motion from dest toward origin. Horizontal time to goal in seconds, float. XYrange/XYrangevel. Maximum of 86400 seconds (24 hours). Destination depth minus origin depth. Vehicle vertical velocity in m/s, float. Vertical time to goal in seconds, float. Zrange/Zvel. Slant range in meters, float. Origin X in local XY frame, meters, float. Origin Y in local XY frame, meters, float. Origin Depth, meters, float. Destination X in local XY frame, meters, float. Destination Y in local XY frame, meters, float. Destination depth, meters, float. Number of characters in origin label, integer. Minimum of 1. ASCII string label for the origin. It is variable length. It will never be zero length. It is delimited by normal NMEA comma characters. It may contain spaces. If the original label is empty (no characters) then the label will read "NO LABEL". If the original label string contains any comma characters they are suppressed and have been converted to space characters. Number of characters in destination label. Minimum of 1. ASCII string label for the destination. See . is the two digit hexadecimal checksum EXAMPLE: $PWHTRB,1,0,2,+44.928,+11.531,+0.000,+0.000,+0.000,-500.833,+0.000,+0.000,+500.966,+1.824,+1.803,+500.833,+9.967,+9.967,+0.000,5,Alvin,12,New Target 1*00 DATA SOURCE FILE: host.h host.cpp ---------------------------------------------------------------------- I.3.6: $PWHTIM TIME STRING sent from DVLNAV to HOST ---------------------------------------------------------------------- See Section I.3.6 for specification. ---------------------------------------------------------------------- I.3.7: VNS VEHICLE NAVIGATION STRING from DVLNAV to HOST ---------------------------------------------------------------------- DATA DESCRIPTION: Vehicle navigation string sent to HOST, presently via UDP only to the DSL topside host This string contains the "best estimate" of vehicle position based on currently selected DVLNAV navigation method. LOG DATA SOURCE: dvlnav DATA FREQUENCY: Once every time a new LBL travel time arrives. and Once periodically, usually this is once a second. DATA FORMAT: VNS LOG DATA FIELDS: 1. "VNS" 2. Date/time string: YYYY/MM/DD HH:MM:SS.SSS 3. "DVN UTM FSH" 4-6. Vehicle X,Y, DEPTH Position in UTM coordinates Vehicle "best estimate" vehicle position based on most recent data and dvlnav operating mode. Order is X, Y, DEPTH. Units are UTM and depth. Float. 7-9. Vehicle Xvel, Yvel, DepthVel Vehicle "best estimate" vehicle velocity based on most recent data and dvlnav operating mode. order is Xdot, Ydot, Depth_dot Units are meters/second w/respec to UTM axes. Float. 10. UTM zone The UTM zone in which the vehicle is operating. Integer. 11. Fix status - this fix was generated in response to 0 = 1 hertz timer message 1 = new lbl or layback nav data 2 = new dvl data Integer. 12-14. Vehicle position source Sensor from which the orginal vehicle position data originated ASCII STRING. 15-17. Vehicle position source Sensor from which the orginal vehicle velocity data originated ASCII STRING. FILE: dvlnav.cpp SOURCE CODE: /* ---------------------------------------------------------------------- Function for printing standard VNS string to send to topside MODIFICATION HISTORY DATE WHO WHAT ----------- -------------- ---------------------------- 09 JUN 2001 Louis Whitcomb Created and Written ---------------------------------------------------------------------- */ int dvlnav_vns_sprintf(dvlnav_t * dvlnav, char * msg, int data_flag) { int dof; int msglen = 0; char dsl_time_string[256]; /* read the system clock and print a GMT date/time string */ rov_sprintf_dsl_time_string(dsl_time_string); /* construct the dsl log string header*/ msglen += sprintf(&msg[msglen],"VNS %s ",dsl_time_string); msglen += sprintf(&msg[msglen],"DVN UTM FSH",dsl_time_string); // log cooked vehicle 3-dof pos for(dof=0; dof<3; dof++) msglen += sprintf(&msg[msglen]," %lf", dvlnav->world_vehicle.pos[dof] * rad_to_deg); // log cooked vehicle 3-dof vel for(dof=0; dof<3; dof++) msglen += sprintf(&msg[msglen]," %lf", dvlnav->world_vehicle.vel[dof] * rad_to_deg); // utm zone msglen += sprintf(&msg[msglen], " %d",dvlnav->cfg_utm_zone ); // this was generated in response to // 0 = 1 hertz timer message // 1 = new lbl or layback nav data // 2 = new dvl data msglen += sprintf(&msg[msglen], " %d",data_flag ); // pos source names for(dof=0; dof<3; dof++) msglen += sprintf(&msg[msglen], " pos_src[%s]=%s", DOF_NAME(dof), DATA_SOURCE_NAME(dvlnav->world_vehicle.pos_source[dof])); // vel source names for(dof=0; dof<3; dof++) msglen += sprintf(&msg[msglen], " vel_src[%s]=%s", DOF_NAME(dof), DATA_SOURCE_NAME(dvlnav->world_vehicle.vel_source[dof])); msglen += sprintf(&msg[msglen], "\r\n"); static int first_time = 1; if(first_time) { int fields = 1; char * s = msg; first_time = 0; while( *s != 0) { // detect fields by transition from space to non-space if((*s == ' ') && (*(s+1) != ' ')) fields++; s++; } stderr_printf("DVLNAV VNS contains %d chars and %d space-delimited fields including the PNS and date/time fields.", strlen(msg), fields ); stderr_printf("DVLNAV VNS string is: %s",msg); } return msglen; } EXAMPLE: VNS 2001/06/10 15:23:20.693 DVN UTM FSH 0.977534 -1.797968 496.030000 0.353075 -0.346054 7.463840 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:21.695 DVN UTM FSH 1.328729 -2.147685 500.000000 0.352591 -0.348850 0.937656 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:22.696 DVN UTM FSH 1.691652 -2.487447 497.791000 0.375240 -0.326993 -3.952618 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:23.698 DVN UTM FSH 2.091485 -2.784075 488.531000 0.420471 -0.259949 -9.155001 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:24.699 DVN UTM FSH 2.552934 -2.968099 480.617000 0.489219 -0.100897 -9.907730 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:25.701 DVN UTM FSH 3.051417 -2.936968 470.924000 0.528391 0.149136 -6.597500 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:26.702 DVN UTM FSH 3.495545 -2.712979 468.242000 0.414692 0.278367 -2.177500 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:27.703 DVN UTM FSH 3.883430 -2.398588 471.512000 0.370344 0.335211 5.077500 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST VNS 2001/06/10 15:23:28.705 DVN UTM FSH 4.242716 -2.051478 477.768000 0.353762 0.353121 8.587501 43 0 pos_src[DOF_X]=SRC_DOPPLER_BT pos_src[DOF_Y]=SRC_DOPPLER_BT pos_src[DOF_Z]=SRC_HOST vel_src[DOF_X]=SRC_DOPPLER_BT vel_src[DOF_Y]=SRC_DOPPLER_BT vel_src[DOF_Z]=SRC_HOST ---------------------------------------------------------------------- I.3.8: $PWHCFG SITE CONFIGURATION DATA ---------------------------------------------------------------------- DATA DESCRIPTION: Vehicle navigation string sent from DVLNAV to HOST, presently via RS232 and UDP. This string contains the site data from the DVLNAV ini file LOG DATA SOURCE: dvlnav DATA FREQUENCY: Once a minute. DATA FORMAT: FORMAT: $PWHCFG,,,,,, , ,,,,,