From c94a0f3b977aa597f7fa51f19d151953cfee7d00 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Thu, 22 Feb 2024 14:06:43 -0800 Subject: [PATCH 01/20] add UDP .ALL ingest support for Kongsberg M3 sonar (WIP, incomplete) --- src/mbio/mbsys_simrad3.h | 49 ++++ src/mbtrnutils/mbtrnpp.c | 470 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 519 insertions(+) diff --git a/src/mbio/mbsys_simrad3.h b/src/mbio/mbsys_simrad3.h index 4c9f66581..37574a442 100644 --- a/src/mbio/mbsys_simrad3.h +++ b/src/mbio/mbsys_simrad3.h @@ -393,6 +393,55 @@ #define EM3_INVALID_U_INT 0xFFFFFFFF #define EM3_INVALID_INT 0x7FFFFFFF +/* M3 datagram types */ + +struct mbsys_simrad3_header { + /* Definition of general datagram header */ + unsigned int numBytesDgm; /* Datagram length in bytes. + * The length field at the start (4 bytes) and end of the datagram (4 bytes) + * are included in the length count. */ + mb_u_char dgmSTX; /* start ID e.g. 0x02 */ + mb_u_char dgmType; /* datagram type definition, e.g. + Installation (I or i) or r (Remote information): Start = 049h Stop = 069h Remote info = 070h Runtime (R): 052h + Raw range and beam angle 78 (N): 04eh + XYZ88 (X): 058h, or 88d Clock (C): 043h + Attitude (A): 041h + Position (P): 050h + Surface sound speed (G): 047h + */ + unsigned short emModeNum; /* EM model number For M3, use 30. For M3 dual head, use 30D */ + unsigned int date; /* Date (in binary format) = year*10000+Month*100+day (example: April 26, 2016 = 20160426) */ + unsigned int timeMs; /* Time since midnight in milliseconds */ + unsigned short counter; /* Sequential counter associated with each datagram. In M3, it + is the ping sequential counter associated with data. Only + exception is the counter in the installation datagram, where + the counter starts from 0 and increases by 1 whenever a new + installation datagram is received. */ + unsigned short sysSerialNum; /* System serial number. Set it to the lower two bytes of the first M3 head sonar info.*/ + unsigned short secHeadSerialNum; /* Secondary system serial number and only used by Installation parameter. Set it to the lower two bytes of the second M3 sonar info. Currently it is always 0. */ +}; + +struct mbsys_simrad3_footer { + mb_u_char dgmETX; /*End identifier, always 03h*/ + unsigned short checksum; /*Sum of bytes between STX and ETX*/ +}; + +// Enumerate EM datagram types +typedef enum { + /* unknown datagram */ + ALL_UNKNOWN = 0, + ALL_INSTALLATION_U = 'I', + ALL_INSTALLATION_L = 'i', + ALL_REMOTE = 'r', + ALL_RUNTIME = 'R', + ALL_RAW_RANGE_BEAM_ANGLE = 'N', + ALL_XYZ88 = 'X', + ALL_CLOCK = 'C', + ALL_ATTITUDE = 'A', + ALL_POSITION = 'P', + ALL_SURFACE_SOUND_SPEED = 'G' +} mbsys_simrad3_emdgm_type; + /* internal data structure for survey data */ struct mbsys_simrad3_ping_struct { int read_status; /* read status for this structure: diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 1b546ce8b..5ff1d571c 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -7078,6 +7078,476 @@ int mbtrnpp_kemkmall_input_close(int verbose, void *mbio_ptr, int *error) { /* return */ return (status); } + + +/*--------------------------------------------------------------------*/ + +int mbtrnpp_kemall_input_open(int verbose, void *mbio_ptr, char *definition, int *error) { + + /* local variables */ + int status = MB_SUCCESS; + struct mb_io_struct *mb_io_ptr; + + /* print input debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); + fprintf(stderr, "dbg2 Input arguments:\n"); + fprintf(stderr, "dbg2 verbose: %d\n", verbose); + fprintf(stderr, "dbg2 mbio_ptr: %p,%p\n", mbio_ptr, &mbio_ptr); + fprintf(stderr, "dbg2 definition: %s\n", definition); + } + + /* get pointer to mbio descriptor */ + mb_io_ptr = (struct mb_io_struct *)mbio_ptr; + + /* set initial status */ + status = MB_SUCCESS; + + /* set flag to enable Sentry sensordepth kluge */ + int *kluge_set = (int *)&mb_io_ptr->save10; + *kluge_set = 1; + + // Open and initialize the socket based input for reading using function + // mbtrnpp_kemall_input_read(). + // - use mb_io_ptr->mbsp to hold pointer to socket i/o structure + // - the socket definition = "hostInterface:broadcastGroup:port" + int port=-1; + mb_path bcastGrp; + mb_path hostInterface; + struct sockaddr_in localSock; + struct ip_mreq group; + char *token; + char *saveptr; + if ((token = strtok_r(definition, ":", &saveptr)) != NULL) { + strncpy(hostInterface, token, sizeof(mb_path)); + } + if ((token = strtok_r(NULL, ":", &saveptr)) != NULL) { + strncpy(bcastGrp, token, sizeof(mb_path)); + } + if ((token = strtok_r(NULL, ":", &saveptr)) != NULL) { + sscanf(token, "%d", &port); + } + + //sscanf(definition, "%s:%s:%d", hostInterface, bcastGrp, &port); + fprintf(stderr, "Attempting to open socket to Kongsberg sonar multicast at:\n"); + fprintf(stderr, " Definition: %s\n", definition); + fprintf(stderr, " hostInterface: %s\n bcastGrp: %s\n port: %d\n", + hostInterface, bcastGrp, port); + + /* Create a datagram socket on which to receive. */ + int sd = socket(AF_INET, SOCK_DGRAM, 0); + if (sd < 0) + { + perror("Opening datagram socket error"); + + mlog_tprintf(mbtrnpp_mlog_id,"e,datagram socket [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + /* Enable SO_REUSEADDR to allow multiple instances of this */ + /* application to receive copies of the multicast datagrams. */ + int reuse = 1; + if (setsockopt(sd, SOL_SOCKET, SO_REUSEADDR, (char *)&reuse, sizeof(reuse)) < 0) + { + perror("Setting SO_REUSEADDR error"); + close(sd); + mlog_tprintf(mbtrnpp_mlog_id,"e,setsockopt SO_REUSEADDR [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + /* Bind to the proper port number with the IP address */ + /* specified as INADDR_ANY. */ + memset((char *) &localSock, 0, sizeof(localSock)); + localSock.sin_family = AF_INET; + localSock.sin_port = htons(port); + localSock.sin_addr.s_addr = INADDR_ANY; + if (bind(sd, (struct sockaddr*)&localSock, sizeof(localSock))) { + perror("Binding datagram socket error"); + close(sd); + mlog_tprintf(mbtrnpp_mlog_id,"e,bind [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + /* Join the multicast group on the specified */ + /* interface. Note that this IP_ADD_MEMBERSHIP option must be */ + /* called for each local interface over which the multicast */ + /* datagrams are to be received. */ +// group.imr_multiaddr.s_addr = inet_addr(bcastGrp); +// group.imr_interface.s_addr = inet_addr(hostInterface); +// +// if(setsockopt(sd, IPPROTO_IP, IP_ADD_MEMBERSHIP, +// (char *)&group, sizeof(group)) < 0) { +// perror("Adding multicast group error"); +// close(sd); +// mlog_tprintf(mbtrnpp_mlog_id,"e,setsockopt IP_ADD_MEMBERSHIP [%d/%s]\n",errno,strerror(errno)); +// status=MB_FAILURE; +// *error=MB_ERROR_OPEN_FAIL; +// return status; +// } + + // save the socket within the mb_io structure + int *sd_ptr = NULL; + status &= mb_mallocd(verbose, __FILE__, __LINE__, sizeof(sd), (void **)&sd_ptr, error); + *sd_ptr = sd; + mb_io_ptr->mbsp = (void *) sd_ptr; + + /*initialize buffer for fragmented MWZ and MRC datagrams*/ + memset(mRecordBuf, 0, sizeof(mRecordBuf)); + + /* print output debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); + fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 error: %d\n", *error); + fprintf(stderr, "dbg2 Return status:\n"); + fprintf(stderr, "dbg2 status: %d\n", status); + } + + MST_COUNTER_INC(app_stats->stats->events[MBTPP_EV_MB_CONN]); + + /* return */ + return (status); +} + +/*--------------------------------------------------------------------*/ + +int mbtrnpp_kemall_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { + struct mbsys_simrad3_header *header = NULL; + mbsys_simrad3_emdgm_type *emdgm_type = NULL; + int index = 0; + + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); + fprintf(stderr, "dbg2 Input arguments:\n"); + fprintf(stderr, "dbg2 verbose: %d\n", verbose); + fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); + fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); + fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); + } + + /* get pointer to header structure */ + header = (struct mbsys_simrad3_header *)header_ptr; + emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; + + /* extract the data */ + index = 0; + mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); + index += 4; + header->dgmSTX = buffer[index]; + index++; + header->dgmType = buffer[index]; + index++; + mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); + index += 2; + mb_get_binary_int(true, &buffer[index], &(header->date)); + index += 4; + mb_get_binary_int(true, &buffer[index], &(header->timeMs)); + index += 4; + mb_get_binary_short(true, &buffer[index], &(header->counter)); + index += 2; + mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); + index += 2; + mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); + index += 2; + + /* identify/validate the datagram type */ + switch(header->typeDatagram){ + + case ALL_INSTALLATION_U: + case ALL_INSTALLATION_L: + case ALL_REMOTE: + case ALL_RUNTIME: + case ALL_RAW_RANGE_BEAM_ANGLE: + case ALL_XYZ88: + case ALL_CLOCK: + case ALL_ATTITUDE: + case ALL_POSITION: + case ALL_SURFACE_SOUND_SPEED: + *emdgm_type = header->typeDatagram; + break; + default: + *emdgm_type = UNKNOWN; + break; + }; + + + if (verbose >= 5) { + fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); + fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); + fprintf(stderr, "dbg5 dgmSTX : %02X\n", header->dgmSTX); + fprintf(stderr, "dbg5 dgmType: %02X\n", header->dgmType); + fprintf(stderr, "dbg5 emModeNum: %hu\n", header->emModeNum); + fprintf(stderr, "dbg5 date: %u\n", header->date); + fprintf(stderr, "dbg5 timeMs: %u\n", header->timeMs); + fprintf(stderr, "dbg5 counter: %hu\n", header->counter); + fprintf(stderr, "dbg5 sysSerialNum: %hu\n", header->sysSerialNum); + fprintf(stderr, "dbg5 secHeadSerialNum: %hu\n", header->secHeadSerialNum); + } + + int status = MB_SUCCESS; + + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); + fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 dgmType: %.4s\n", header->dgmType); + fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); + fprintf(stderr, "dbg2 error: %d\n", *error); + fprintf(stderr, "dbg2 Return status:\n"); + fprintf(stderr, "dbg2 status: %d\n", status); + } + + /* return status */ + return (status); +}; + +/*--------------------------------------------------------------------*/ + +/* read footer */ +//int mbtrnpp_kemall_rd_ftr(int verbose, char *buffer, void *footer_ptr, void *emdgm_checksum_ptr, int *error) { +// struct mbsys_simrad3_footer *footer = NULL; +// short unsigned int *emdgm_checksum_ptr = (short unsigned int)emdgm_checksum_ptr; +// int index = 0; +// +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); +// fprintf(stderr, "dbg2 Input arguments:\n"); +// fprintf(stderr, "dbg2 verbose: %d\n", verbose); +// fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); +// fprintf(stderr, "dbg2 footer_ptr: %p\n", (void *)footer_ptr); +// } +// +// /* get pointer to header structure */ +// footer = (struct mbsys_simrad3_header *)footer_ptr; +// +// /* extract the data */ +// index = 0; +// footer->dgmETX = buffer[index]; +// index++; +// mb_get_binary_short(true, &buffer[index], &(footer->checksum)); +// index += 2; +// +// *emdgm_checksum_ptr = footer->checksum; +// +// if (verbose >= 5) { +// fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); +// fprintf(stderr, "dbg5 dgmSTX : %02X\n", footer->dgmSTX); +// fprintf(stderr, "dbg5 checksum : %04X\n", footer->checksum); +// } +// +// int status = MB_SUCCESS; +// +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); +// fprintf(stderr, "dbg2 Return values:\n"); +// fprintf(stderr, "dbg2 dgmETX: %02X\n", footer->dgmETX); +// fprintf(stderr, "dbg2 checksum: %04X\n", *emdgm_checksum_ptr); +// fprintf(stderr, "dbg2 error: %d\n", *error); +// fprintf(stderr, "dbg2 Return status:\n"); +// fprintf(stderr, "dbg2 status: %d\n", status); +// } +// +// /* return status */ +// return (status); +//}; + +/*--------------------------------------------------------------------*/ + +int mbtrnpp_kemall_input_read(int verbose, void *mbio_ptr, size_t *size, + char *buffer, int *error) { + + /* local variables */ + int status = MB_SUCCESS; + + /* print input debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); + fprintf(stderr, "dbg2 Input arguments:\n"); + fprintf(stderr, "dbg2 verbose: %d\n", verbose); + fprintf(stderr, "dbg2 mbio_ptr: %p\n", mbio_ptr); + fprintf(stderr, "dbg2 size: %zu\n", *size); + fprintf(stderr, "dbg2 buffer: %p\n", buffer); + } + + /* get pointer to mbio descriptor */ + struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; + + /* set initial status */ + status = MB_SUCCESS; + + // Read from the socket. + int *sd_ptr = (int *)mb_io_ptr->mbsp; + struct mbsys_simrad3_header header; + unsigned int num_bytes_dgm_checksum=0; + mbsys_simrad3_emdgm_type emdgm_type=UNKNOWN; + memset(buffer, 0, *size); + int readlen = read(*sd_ptr, buffer, *size); + if (readlen <= 0) { + status = MB_FAILURE; + *error = MB_ERROR_EOF; + } + + if (status == MB_SUCCESS) { + + status = mbtrnpp_kemall_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); + + if (status == MB_SUCCESS && emdgm_type != UNKNOWN && header.numBytesDgm <= *size) { + + // read checksum (which indicates bytes between STX and ETX) + mb_get_binary_int(true, &buffer[header.numBytesDgm-2], &num_bytes_dgm_checksum); + + // checksum should equal numBytes - size of fields: numBytes(4) + STX(1) + ETX(1) + checksum(2) + if (num_bytes_dgm_checksum != header.numBytesDgm - 8) { + status = MB_FAILURE; + *error = MB_ERROR_UNINTELLIGIBLE; + } + } else { + status = MB_FAILURE; + *error = MB_ERROR_UNINTELLIGIBLE; + } + } + + if (status == MB_SUCCESS) { + *size = header.numBytesDgm; + } + else { + *size = 0; + } + +#if 0 + /*handle multi-packet MRZ and MWC records*/ + if (emdgm_type == MRZ || emdgm_type == MWC) { + unsigned short numOfDgms=0; + unsigned short dgmNum=0; + + mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE], &numOfDgms); + mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE+2], &dgmNum); + if (numOfDgms > 1) { + static int dgmsReceived=0; + static unsigned int pingSecs, pingNanoSecs; + static int totalDgms; + + /* if we get a M record of a multi-packet sequence, and its numOfDgms + or ping time don't match the ping we are looking for, flush the + current read and start over with this packet */ + if (header.time_sec != pingSecs + || header.time_nanosec != pingNanoSecs + || numOfDgms != totalDgms) { + dgmsReceived = 0; + } + + if (!dgmsReceived){ + pingSecs = header.time_sec; + pingNanoSecs = header.time_nanosec; + totalDgms = numOfDgms; + dgmsReceived = 1; + } + else { + dgmsReceived++; + } + if(dgmNum>0){ + memcpy(mRecordBuf[dgmNum-1], buffer, header.numBytesDgm); + } else { + fprintf(stderr,"%s: ERR - dgNum<0\n",__func__); + } + + if (dgmsReceived == totalDgms) { + + int totalSize = sizeof(struct mbsys_kmbes_m_partition) + + sizeof(struct mbsys_kmbes_header) + 4; + int rsize = 0; + for (int dgm = 0; dgm < totalDgms; dgm++) { + mb_get_binary_int(true, mRecordBuf[dgm], &rsize); + totalSize += rsize - sizeof(struct mbsys_kmbes_m_partition) + - sizeof(struct mbsys_kmbes_header) - 4; + } + + /*copy data into new buffer*/ + if (status == MB_SUCCESS) { + int index = 0; + status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[0], (void *)&header, (void *)&emdgm_type, error); + memcpy(buffer, mRecordBuf[0], header.numBytesDgm); + index = header.numBytesDgm - 4; + + for (int dgm=1; dgm < totalDgms; dgm++) { + status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[dgm], (void *)&header, (void *)&emdgm_type, error); + int copy_len = header.numBytesDgm - sizeof(struct mbsys_kmbes_m_partition) + - sizeof(struct mbsys_kmbes_header) - 4; + void *ptr = (void *)(mRecordBuf[dgm]+ + sizeof(struct mbsys_kmbes_m_partition)+ + sizeof(struct mbsys_kmbes_header)); + memcpy(&buffer[index], ptr, copy_len); + index += copy_len; + } + mb_put_binary_int(true, totalSize, &buffer[0]); + mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)]); + mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)+2]); + mb_put_binary_int(true, totalSize, &buffer[index]); + dgmsReceived = 0; /*reset received counter back to 0*/ + } + } + } + } +#endif + + /* print output debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); + fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 error: %d\n", *error); + fprintf(stderr, "dbg2 Return status:\n"); + fprintf(stderr, "dbg2 status: %d\n", status); + } + + /* return */ + return (status); +} + +/*--------------------------------------------------------------------*/ + +int mbtrnpp_kemall_input_close(int verbose, void *mbio_ptr, int *error) { + + /* local variables */ + int status = MB_SUCCESS; + struct mb_io_struct *mb_io_ptr; + + /* print input debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); + fprintf(stderr, "dbg2 Input arguments:\n"); + fprintf(stderr, "dbg2 verbose: %d\n", verbose); + fprintf(stderr, "dbg2 mbio_ptr: %p\n", mbio_ptr); + } + + /* get pointer to mbio descriptor */ + mb_io_ptr = (struct mb_io_struct *)mbio_ptr; + + /* set initial status */ + status = MB_SUCCESS; + + // Close the socket based input + int *sd_ptr = (int *)mb_io_ptr->mbsp; + close(*sd_ptr); + status &= mb_freed(verbose, __FILE__, __LINE__, (void **)&sd_ptr, error); + + /* print output debug statements */ + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); + fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 error: %d\n", *error); + fprintf(stderr, "dbg2 Return status:\n"); + fprintf(stderr, "dbg2 status: %d\n", status); + } + + /* return */ + return (status); +} + #ifdef WITH_MB1_READER /*--------------------------------------------------------------------*/ int mbtrnpp_mb1r_input_open(int verbose, void *mbio_ptr, char *definition, int *error) From 00d54423264751a43d4fb2f32c46de8eb87a1ed9 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Thu, 29 Feb 2024 16:28:47 -0800 Subject: [PATCH 02/20] WIP: concept for simple em710raw open/read/close --- src/mbtrnutils/mbtrnpp.c | 592 ++++++++++++++++++++++++++------------- 1 file changed, 392 insertions(+), 200 deletions(-) diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 5ff1d571c..f28190302 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -53,6 +53,7 @@ #include "mb_io.h" #include "mbsys_ldeoih.h" #include "mbsys_kmbes.h" +#include "mbsys_simrad3.h" #include "mframe.h" #include "merror.h" @@ -887,6 +888,9 @@ int mbtrnpp_reson7kr_input_close(int verbose, void *mbio_ptr, int *error); int mbtrnpp_kemkmall_input_open(int verbose, void *mbio_ptr, char *definition, int *error); int mbtrnpp_kemkmall_input_read(int verbose, void *mbio_ptr, size_t *size, char *buffer, int *error); int mbtrnpp_kemkmall_input_close(int verbose, void *mbio_ptr, int *error); +int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, int *error); +int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, char *buffer, int *error); +int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error); #ifdef WITH_MB1_READER int mbtrnpp_mb1r_input_open(int verbose, void *mbio_ptr, char *definition, int *error); int mbtrnpp_mb1r_input_read(int verbose, void *mbio_ptr, size_t *size, char *buffer, int *error); @@ -3684,6 +3688,11 @@ int main(int argc, char **argv) { mbtrnpp_input_close = &mbtrnpp_mb1r_input_close; } #endif // WITH_MB1_READER + else if (mbtrn_cfg->format == MBF_EM710RAW) { + mbtrnpp_input_open = &mbtrnpp_em710raw_input_open; + mbtrnpp_input_read = &mbtrnpp_em710raw_input_read; + mbtrnpp_input_close = &mbtrnpp_em710raw_input_close; + } else{ fprintf(stderr,"ERR - Invalid output format [%d]\n",mbtrn_cfg->format); } @@ -7082,7 +7091,7 @@ int mbtrnpp_kemkmall_input_close(int verbose, void *mbio_ptr, int *error) { /*--------------------------------------------------------------------*/ -int mbtrnpp_kemall_input_open(int verbose, void *mbio_ptr, char *definition, int *error) { +int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, int *error) { /* local variables */ int status = MB_SUCCESS; @@ -7217,94 +7226,94 @@ int mbtrnpp_kemall_input_open(int verbose, void *mbio_ptr, char *definition, int /*--------------------------------------------------------------------*/ -int mbtrnpp_kemall_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { - struct mbsys_simrad3_header *header = NULL; - mbsys_simrad3_emdgm_type *emdgm_type = NULL; - int index = 0; - - if (verbose >= 2) { - fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); - fprintf(stderr, "dbg2 Input arguments:\n"); - fprintf(stderr, "dbg2 verbose: %d\n", verbose); - fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); - fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); - fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); - } - - /* get pointer to header structure */ - header = (struct mbsys_simrad3_header *)header_ptr; - emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; - - /* extract the data */ - index = 0; - mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); - index += 4; - header->dgmSTX = buffer[index]; - index++; - header->dgmType = buffer[index]; - index++; - mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); - index += 2; - mb_get_binary_int(true, &buffer[index], &(header->date)); - index += 4; - mb_get_binary_int(true, &buffer[index], &(header->timeMs)); - index += 4; - mb_get_binary_short(true, &buffer[index], &(header->counter)); - index += 2; - mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); - index += 2; - mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); - index += 2; - - /* identify/validate the datagram type */ - switch(header->typeDatagram){ - - case ALL_INSTALLATION_U: - case ALL_INSTALLATION_L: - case ALL_REMOTE: - case ALL_RUNTIME: - case ALL_RAW_RANGE_BEAM_ANGLE: - case ALL_XYZ88: - case ALL_CLOCK: - case ALL_ATTITUDE: - case ALL_POSITION: - case ALL_SURFACE_SOUND_SPEED: - *emdgm_type = header->typeDatagram; - break; - default: - *emdgm_type = UNKNOWN; - break; - }; - - - if (verbose >= 5) { - fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); - fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); - fprintf(stderr, "dbg5 dgmSTX : %02X\n", header->dgmSTX); - fprintf(stderr, "dbg5 dgmType: %02X\n", header->dgmType); - fprintf(stderr, "dbg5 emModeNum: %hu\n", header->emModeNum); - fprintf(stderr, "dbg5 date: %u\n", header->date); - fprintf(stderr, "dbg5 timeMs: %u\n", header->timeMs); - fprintf(stderr, "dbg5 counter: %hu\n", header->counter); - fprintf(stderr, "dbg5 sysSerialNum: %hu\n", header->sysSerialNum); - fprintf(stderr, "dbg5 secHeadSerialNum: %hu\n", header->secHeadSerialNum); - } - - int status = MB_SUCCESS; - - if (verbose >= 2) { - fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); - fprintf(stderr, "dbg2 Return values:\n"); - fprintf(stderr, "dbg2 dgmType: %.4s\n", header->dgmType); - fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); - fprintf(stderr, "dbg2 error: %d\n", *error); - fprintf(stderr, "dbg2 Return status:\n"); - fprintf(stderr, "dbg2 status: %d\n", status); - } - - /* return status */ - return (status); -}; +//int mbtrnpp_kemall_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { +// struct mbsys_simrad3_header *header = NULL; +// mbsys_simrad3_emdgm_type *emdgm_type = NULL; +// int index = 0; +// +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); +// fprintf(stderr, "dbg2 Input arguments:\n"); +// fprintf(stderr, "dbg2 verbose: %d\n", verbose); +// fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); +// fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); +// fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); +// } +// +// /* get pointer to header structure */ +// header = (struct mbsys_simrad3_header *)header_ptr; +// emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; +// +// /* extract the data */ +// index = 0; +// mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); +// index += 4; +// header->dgmSTX = buffer[index]; +// index++; +// header->dgmType = buffer[index]; +// index++; +// mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); +// index += 2; +// mb_get_binary_int(true, &buffer[index], &(header->date)); +// index += 4; +// mb_get_binary_int(true, &buffer[index], &(header->timeMs)); +// index += 4; +// mb_get_binary_short(true, &buffer[index], &(header->counter)); +// index += 2; +// mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); +// index += 2; +// mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); +// index += 2; +// +// /* identify/validate the datagram type */ +// switch(header->typeDatagram){ +// +// case ALL_INSTALLATION_U: +// case ALL_INSTALLATION_L: +// case ALL_REMOTE: +// case ALL_RUNTIME: +// case ALL_RAW_RANGE_BEAM_ANGLE: +// case ALL_XYZ88: +// case ALL_CLOCK: +// case ALL_ATTITUDE: +// case ALL_POSITION: +// case ALL_SURFACE_SOUND_SPEED: +// *emdgm_type = header->typeDatagram; +// break; +// default: +// *emdgm_type = UNKNOWN; +// break; +// }; +// +// +// if (verbose >= 5) { +// fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); +// fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); +// fprintf(stderr, "dbg5 dgmSTX : %02X\n", header->dgmSTX); +// fprintf(stderr, "dbg5 dgmType: %02X\n", header->dgmType); +// fprintf(stderr, "dbg5 emModeNum: %hu\n", header->emModeNum); +// fprintf(stderr, "dbg5 date: %u\n", header->date); +// fprintf(stderr, "dbg5 timeMs: %u\n", header->timeMs); +// fprintf(stderr, "dbg5 counter: %hu\n", header->counter); +// fprintf(stderr, "dbg5 sysSerialNum: %hu\n", header->sysSerialNum); +// fprintf(stderr, "dbg5 secHeadSerialNum: %hu\n", header->secHeadSerialNum); +// } +// +// int status = MB_SUCCESS; +// +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); +// fprintf(stderr, "dbg2 Return values:\n"); +// fprintf(stderr, "dbg2 dgmType: %.4s\n", header->dgmType); +// fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); +// fprintf(stderr, "dbg2 error: %d\n", *error); +// fprintf(stderr, "dbg2 Return status:\n"); +// fprintf(stderr, "dbg2 status: %d\n", status); +// } +// +// /* return status */ +// return (status); +//}; /*--------------------------------------------------------------------*/ @@ -7357,14 +7366,14 @@ int mbtrnpp_kemall_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emd //}; /*--------------------------------------------------------------------*/ - -int mbtrnpp_kemall_input_read(int verbose, void *mbio_ptr, size_t *size, - char *buffer, int *error) { - - /* local variables */ +int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, + char *buffer, int *error) +{ + // local variables int status = MB_SUCCESS; + struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; - /* print input debug statements */ + // print input debug statements if (verbose >= 2) { fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); fprintf(stderr, "dbg2 Input arguments:\n"); @@ -7374,143 +7383,326 @@ int mbtrnpp_kemall_input_read(int verbose, void *mbio_ptr, size_t *size, fprintf(stderr, "dbg2 buffer: %p\n", buffer); } - /* get pointer to mbio descriptor */ - struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; + // Read the requested number of bytes (= size) off the input and place + // those bytes into the buffer. + // This requires reading full MB1 records from the socket, storing the data + // in buffer (implemented here), and parceling those bytes out as requested. - /* set initial status */ - status = MB_SUCCESS; + // use the socket reader + // read and return single frame + int64_t rbytes=-1; + uint32_t sync_bytes=0; - // Read from the socket. - int *sd_ptr = (int *)mb_io_ptr->mbsp; - struct mbsys_simrad3_header header; - unsigned int num_bytes_dgm_checksum=0; - mbsys_simrad3_emdgm_type emdgm_type=UNKNOWN; - memset(buffer, 0, *size); - int readlen = read(*sd_ptr, buffer, *size); - if (readlen <= 0) { - status = MB_FAILURE; - *error = MB_ERROR_EOF; + // mbsp points to UDP socket + int *mbsp = (int *)mb_io_ptr->mbsp; + + // frame buffer for byte-wise reads + static byte *frame_buf = NULL; + static struct mbsys_simrad3_header *fb_phdr = NULL; + static byte *fb_pread=NULL; + static size_t bytes_read=0; + static bool read_frame=true; + bool read_err = false; + + if(NULL == frame_buf) + { + frame_buf = (byte *)malloc(MB_UDP_SIZE_MAX); + memset(frame_buf, 0, MB_UDP_SIZE_MAX); + fb_pread = frame_buf; + fb_phdr = (struct mbsys_simrad3_header *)frame_buf; + bytes_read = 0; } - if (status == MB_SUCCESS) { - status = mbtrnpp_kemall_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); + // if valid reader... + if(NULL != mbsp && NULL != frame_buf) + { + if(read_frame) + { + // read frame into buffer + memset(frame_buf, 0, MB_UDP_SIZE_MAX); + fb_pread = frame_buf; - if (status == MB_SUCCESS && emdgm_type != UNKNOWN && header.numBytesDgm <= *size) { + // read UDP datagram from the socket + // returns number of bytes read or -1 error + // UDP datagrams don't include 4-byte total size + // we'll calculate it and include it at the start of the buffer. + if ( (rbytes = recv(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0)) >= 0) + { + // set datagram size (first 4 bytes of buffer) + unsigned int *pDgmSize = (unsigned int *)frame_buf; + *pDgmSize = rbytes + 4; - // read checksum (which indicates bytes between STX and ETX) - mb_get_binary_int(true, &buffer[header.numBytesDgm-2], &num_bytes_dgm_checksum); + int errors = 0; + // validate + uint16_t checksum = 0; + byte *pstx = (byte *)&fb_phdr->dgmSTX; + byte *petx = frame_buf + 4 + rbytes - 2; + byte *cur = pstx + 1; + uint16_t *pchk = (uint16_t *)(petx + 1); - // checksum should equal numBytes - size of fields: numBytes(4) + STX(1) + ETX(1) + checksum(2) - if (num_bytes_dgm_checksum != header.numBytesDgm - 8) { - status = MB_FAILURE; - *error = MB_ERROR_UNINTELLIGIBLE; - } - } else { - status = MB_FAILURE; - *error = MB_ERROR_UNINTELLIGIBLE; - } - } + if(rbytes > 0 && rbytes <= MB_UDP_SIZE_MAX){ - if (status == MB_SUCCESS) { - *size = header.numBytesDgm; - } - else { - *size = 0; - } + while(cur < pstx){ + checksum += *cur; + cur++; + } + if(checksum != *pchk) + errors++; + + switch(fb_phdr->dgmType){ + case ALL_INSTALLATION_L: + case ALL_REMOTE: + case ALL_RUNTIME: + case ALL_RAW_RANGE_BEAM_ANGLE: + case ALL_XYZ88: + case ALL_CLOCK: + case ALL_ATTITUDE: + case ALL_POSITION: + case ALL_SURFACE_SOUND_SPEED: + // is valid type + break; + default: + errors++; + } + } -#if 0 - /*handle multi-packet MRZ and MWC records*/ - if (emdgm_type == MRZ || emdgm_type == MWC) { - unsigned short numOfDgms=0; - unsigned short dgmNum=0; - - mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE], &numOfDgms); - mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE+2], &dgmNum); - if (numOfDgms > 1) { - static int dgmsReceived=0; - static unsigned int pingSecs, pingNanoSecs; - static int totalDgms; - - /* if we get a M record of a multi-packet sequence, and its numOfDgms - or ping time don't match the ping we are looking for, flush the - current read and start over with this packet */ - if (header.time_sec != pingSecs - || header.time_nanosec != pingNanoSecs - || numOfDgms != totalDgms) { - dgmsReceived = 0; + if(errors == 0) + { + // update frame read pointers + fb_pread = frame_buf; + read_frame = false; + read_err = false; + MX_LPRINT(MBTRNPP, 3, "read frame len[%zu]:\n",(size_t)rbytes); + } else { + // frame invalid + read_err = true; + MX_LPRINT(MBTRNPP, 3, "invalid frame rbytes[%zu] checksum[%hu/%hu]\n",(size_t)rbytes, checksum, *pchk); + } + } else { + // read error + read_err = true; + MX_LPRINT(MBTRNPP, 3, "mb1r_read_frame failed rbytes[%zu]\n",(size_t)rbytes); } + } else { + // there's a frame in the buffer + size_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; + size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); + MX_LPRINT(MBTRNPP, 3, "reading framebuf size[%zu] rlen[%zu] rem[%zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); + } - if (!dgmsReceived){ - pingSecs = header.time_sec; - pingNanoSecs = header.time_nanosec; - totalDgms = numOfDgms; - dgmsReceived = 1; - } - else { - dgmsReceived++; - } - if(dgmNum>0){ - memcpy(mRecordBuf[dgmNum-1], buffer, header.numBytesDgm); + if(!read_err){ + int64_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; + size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); + if(readlen > 0){ + memcpy(buffer, fb_pread, readlen); + *size = (size_t)readlen; + *error = MB_ERROR_NO_ERROR; + // update frame cursor + fb_pread += readlen; + bytes_rem -= readlen; + if(bytes_rem <= 0) + { + MX_LPRINT(MBTRNPP, 4, "* buffer empty rem[%"PRId64"]\n", bytes_rem); + // if nothing left, read a frame next time + read_frame = true; + } } else { - fprintf(stderr,"%s: ERR - dgNum<0\n",__func__); + // buffer empty + status = MB_FAILURE; + *error = MB_ERROR_EOF; + *size = (size_t)0; + read_frame = true; + MX_LPRINT(MBTRNPP, 4, "buffer empty readlen[%zu] rem[%"PRId64"]\n", readlen, bytes_rem); } + } + } else { + fprintf(stderr, "%s : ERR - frame buffer or socket is NULL\n", __func__); + } + + if(read_err) + { + status = MB_FAILURE; + *error = MB_ERROR_EOF; + *size = (size_t)0; - if (dgmsReceived == totalDgms) { + MST_METRIC_START(app_stats->stats->metrics[MBTPP_CH_MB_GETFAIL_XT], mtime_dtime()); + MX_LPRINT(MBTRNPP, 4, "read kemall UDP socket failed: sync_bytes[%d] status[%d] err[%d]\n",sync_bytes,status, *error); - int totalSize = sizeof(struct mbsys_kmbes_m_partition) - + sizeof(struct mbsys_kmbes_header) + 4; - int rsize = 0; - for (int dgm = 0; dgm < totalDgms; dgm++) { - mb_get_binary_int(true, mRecordBuf[dgm], &rsize); - totalSize += rsize - sizeof(struct mbsys_kmbes_m_partition) - - sizeof(struct mbsys_kmbes_header) - 4; - } + MST_COUNTER_INC(app_stats->stats->events[MBTPP_EV_EMBFRAMERD]); + MST_COUNTER_ADD(app_stats->stats->status[MBTPP_STA_MB_SYNC_BYTES],sync_bytes); - /*copy data into new buffer*/ - if (status == MB_SUCCESS) { - int index = 0; - status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[0], (void *)&header, (void *)&emdgm_type, error); - memcpy(buffer, mRecordBuf[0], header.numBytesDgm); - index = header.numBytesDgm - 4; - - for (int dgm=1; dgm < totalDgms; dgm++) { - status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[dgm], (void *)&header, (void *)&emdgm_type, error); - int copy_len = header.numBytesDgm - sizeof(struct mbsys_kmbes_m_partition) - - sizeof(struct mbsys_kmbes_header) - 4; - void *ptr = (void *)(mRecordBuf[dgm]+ - sizeof(struct mbsys_kmbes_m_partition)+ - sizeof(struct mbsys_kmbes_header)); - memcpy(&buffer[index], ptr, copy_len); - index += copy_len; - } - mb_put_binary_int(true, totalSize, &buffer[0]); - mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)]); - mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)+2]); - mb_put_binary_int(true, totalSize, &buffer[index]); - dgmsReceived = 0; /*reset received counter back to 0*/ - } - } - } + // TODO: check connection status, only reconnect if disconnected + // ... + MST_METRIC_LAP(app_stats->stats->metrics[MBTPP_CH_MB_GETFAIL_XT], mtime_dtime()); } -#endif - /* print output debug statements */ + // print output debug statements if (verbose >= 2) { fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 size: %zu\n", *size); + fprintf(stderr, "dbg2 buffer: %p\n", buffer); fprintf(stderr, "dbg2 error: %d\n", *error); fprintf(stderr, "dbg2 Return status:\n"); fprintf(stderr, "dbg2 status: %d\n", status); } - /* return */ return (status); } +//int mbtrnpp_kemall_input_read_orig(int verbose, void *mbio_ptr, size_t *size, +// char *buffer, int *error) { +// +// /* local variables */ +// +// /* print input debug statements */ +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); +// fprintf(stderr, "dbg2 Input arguments:\n"); +// fprintf(stderr, "dbg2 verbose: %d\n", verbose); +// fprintf(stderr, "dbg2 mbio_ptr: %p\n", mbio_ptr); +// fprintf(stderr, "dbg2 size: %zu\n", *size); +// fprintf(stderr, "dbg2 buffer: %p\n", buffer); +// } +// +// /* get pointer to mbio descriptor */ +// struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; +// +// /* set initial status */ +// status = MB_SUCCESS; +// +// // Read from the socket. +// int *sd_ptr = (int *)mb_io_ptr->mbsp; +// struct mbsys_simrad3_header header; +// unsigned int num_bytes_dgm_checksum=0; +// mbsys_simrad3_emdgm_type emdgm_type=UNKNOWN; +// memset(buffer, 0, *size); +// int readlen = read(*sd_ptr, buffer, *size); +// if (readlen <= 0) { +// status = MB_FAILURE; +// *error = MB_ERROR_EOF; +// } +// +// if (status == MB_SUCCESS) { +// +// status = mbtrnpp_kemall_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); +// +// if (status == MB_SUCCESS && emdgm_type != UNKNOWN && header.numBytesDgm <= *size) { +// +// // read checksum (which indicates bytes between STX and ETX) +// mb_get_binary_int(true, &buffer[header.numBytesDgm-2], &num_bytes_dgm_checksum); +// +// // checksum should equal numBytes - size of fields: numBytes(4) + STX(1) + ETX(1) + checksum(2) +// if (num_bytes_dgm_checksum != header.numBytesDgm - 8) { +// status = MB_FAILURE; +// *error = MB_ERROR_UNINTELLIGIBLE; +// } +// } else { +// status = MB_FAILURE; +// *error = MB_ERROR_UNINTELLIGIBLE; +// } +// } +// +// if (status == MB_SUCCESS) { +// *size = header.numBytesDgm; +// } +// else { +// *size = 0; +// } +// +//#if 0 +// /*handle multi-packet MRZ and MWC records*/ +// if (emdgm_type == MRZ || emdgm_type == MWC) { +// unsigned short numOfDgms=0; +// unsigned short dgmNum=0; +// +// mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE], &numOfDgms); +// mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE+2], &dgmNum); +// if (numOfDgms > 1) { +// static int dgmsReceived=0; +// static unsigned int pingSecs, pingNanoSecs; +// static int totalDgms; +// +// /* if we get a M record of a multi-packet sequence, and its numOfDgms +// or ping time don't match the ping we are looking for, flush the +// current read and start over with this packet */ +// if (header.time_sec != pingSecs +// || header.time_nanosec != pingNanoSecs +// || numOfDgms != totalDgms) { +// dgmsReceived = 0; +// } +// +// if (!dgmsReceived){ +// pingSecs = header.time_sec; +// pingNanoSecs = header.time_nanosec; +// totalDgms = numOfDgms; +// dgmsReceived = 1; +// } +// else { +// dgmsReceived++; +// } +// if(dgmNum>0){ +// memcpy(mRecordBuf[dgmNum-1], buffer, header.numBytesDgm); +// } else { +// fprintf(stderr,"%s: ERR - dgNum<0\n",__func__); +// } +// +// if (dgmsReceived == totalDgms) { +// +// int totalSize = sizeof(struct mbsys_kmbes_m_partition) +// + sizeof(struct mbsys_kmbes_header) + 4; +// int rsize = 0; +// for (int dgm = 0; dgm < totalDgms; dgm++) { +// mb_get_binary_int(true, mRecordBuf[dgm], &rsize); +// totalSize += rsize - sizeof(struct mbsys_kmbes_m_partition) +// - sizeof(struct mbsys_kmbes_header) - 4; +// } +// +// /*copy data into new buffer*/ +// if (status == MB_SUCCESS) { +// int index = 0; +// status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[0], (void *)&header, (void *)&emdgm_type, error); +// memcpy(buffer, mRecordBuf[0], header.numBytesDgm); +// index = header.numBytesDgm - 4; +// +// for (int dgm=1; dgm < totalDgms; dgm++) { +// status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[dgm], (void *)&header, (void *)&emdgm_type, error); +// int copy_len = header.numBytesDgm - sizeof(struct mbsys_kmbes_m_partition) +// - sizeof(struct mbsys_kmbes_header) - 4; +// void *ptr = (void *)(mRecordBuf[dgm]+ +// sizeof(struct mbsys_kmbes_m_partition)+ +// sizeof(struct mbsys_kmbes_header)); +// memcpy(&buffer[index], ptr, copy_len); +// index += copy_len; +// } +// mb_put_binary_int(true, totalSize, &buffer[0]); +// mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)]); +// mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)+2]); +// mb_put_binary_int(true, totalSize, &buffer[index]); +// dgmsReceived = 0; /*reset received counter back to 0*/ +// } +// } +// } +// } +//#endif +// +// /* print output debug statements */ +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); +// fprintf(stderr, "dbg2 Return values:\n"); +// fprintf(stderr, "dbg2 error: %d\n", *error); +// fprintf(stderr, "dbg2 Return status:\n"); +// fprintf(stderr, "dbg2 status: %d\n", status); +// } +// +// /* return */ +// return (status); +//} + /*--------------------------------------------------------------------*/ -int mbtrnpp_kemall_input_close(int verbose, void *mbio_ptr, int *error) { +int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error) { /* local variables */ int status = MB_SUCCESS; From 6b6c61d91d069a7777be3e744f70c58d9f276ad9 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Sat, 2 Mar 2024 22:12:30 -0800 Subject: [PATCH 03/20] WIP: beta implementation of em710raw UDP support; UDP ingest works, but sometimes violates an assertion (mbsys_simrad3_makess, file mbsys_simrad3.c, line 3853) --- src/mbio/mbr_em710raw.c | 378 ++++++++++++++++++++++++++++++++++++++- src/mbio/mbsys_simrad3.h | 3 +- src/mbtrn/CMakeLists.txt | 11 +- src/mbtrnutils/mbtrnpp.c | 95 ++++++---- 4 files changed, 448 insertions(+), 39 deletions(-) diff --git a/src/mbio/mbr_em710raw.c b/src/mbio/mbr_em710raw.c index 5b2cf59ed..c79ce9782 100644 --- a/src/mbio/mbr_em710raw.c +++ b/src/mbio/mbr_em710raw.c @@ -3961,6 +3961,355 @@ int mbr_em710raw_rd_wc(int verbose, void *mbio_ptr, int swap, struct mbsys_simra return (status); } /*--------------------------------------------------------------------*/ +int mbr_em710raw_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { + struct mbsys_simrad3_header *header = NULL; + mbsys_simrad3_emdgm_type *emdgm_type = NULL; + + int index = 0; + + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); + fprintf(stderr, "dbg2 Input arguments:\n"); + fprintf(stderr, "dbg2 verbose: %d\n", verbose); + fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); + fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); + fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); + } + + // get pointer to header structure + header = (struct mbsys_simrad3_header *)header_ptr; + emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; + + index = 0; + mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); + index += 4; + header->dgmSTX = buffer[index]; + index ++; + header->dgmType = buffer[index]; + index ++; + mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); + index += 2; + mb_get_binary_int(true, &buffer[index], &(header->date)); + index += 4; + mb_get_binary_int(true, &buffer[index], &(header->timeMs)); + index += 4; + mb_get_binary_short(true, &buffer[index], &(header->counter)); + index += 2; + mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); + index += 2; + mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); + index += 2; + + switch(header->dgmType){ + + + case ALL_UNKNOWN: + case ALL_INSTALLATION_U: + case ALL_INSTALLATION_L: + case ALL_REMOTE: + case ALL_RUNTIME: + case ALL_RAW_RANGE_BEAM_ANGLE: + case ALL_XYZ88: + case ALL_CLOCK: + case ALL_ATTITUDE: + case ALL_POSITION: + case ALL_SURFACE_SOUND_SPEED: + *emdgm_type = header->dgmType; + break; + default: + *emdgm_type = ALL_UNKNOWN; + break; + }; + + if (verbose >= 5) { + fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); + fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); + } + + int status = MB_SUCCESS; + + if (verbose >= 2) { + fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); + fprintf(stderr, "dbg2 Return values:\n"); + fprintf(stderr, "dbg2 dgmType: %02x/%c\n", header->dgmType, header->dgmType); + fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); + fprintf(stderr, "dbg2 error: %d\n", *error); + fprintf(stderr, "dbg2 Return status:\n"); + fprintf(stderr, "dbg2 status: %d\n", status); + } + + /* return status */ + return (status); + +} + +//int mbr_em710raw_rd_udp_data(int verbose, void *mbio_ptr, void *store_ptr, int *error) +//{ +// int *databyteswapped; +// int record_size; +// int *record_size_save; +// int bytes_read; +// char *label; +// int *label_save_flag; +// char *record_size_char; +// bool *ignore_snippets; +// short type; +// short sonar; +// int *version; +// short *typelast; +// short *sonarlast; +// int *nbadrec; +// int good_end_bytes; +// size_t read_len; +// int skip = 0; +// int *num_sonars; +// char junk; +// +// if (verbose >= 2) { +// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); +// fprintf(stderr, "dbg2 Input arguments:\n"); +// fprintf(stderr, "dbg2 verbose: %d\n", verbose); +// fprintf(stderr, "dbg2 mbio_ptr: %p\n", (void *)mbio_ptr); +// fprintf(stderr, "dbg2 store_ptr: %p\n", (void *)store_ptr); +// } +// +// // get pointer to mbio descriptor +// struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; +// +// // get pointer to raw data structure +// struct mbsys_simrad3_struct *store = (struct mbsys_simrad3_struct *)store_ptr; +// int *mbsp = mb_io_ptr->mbsp; +// +// // get saved values +// databyteswapped = (int *)&mb_io_ptr->save1; +// record_size_save = (int *)&mb_io_ptr->save2; +// label = (char *)mb_io_ptr->save_label; +// version = (int *)(&mb_io_ptr->save3); +// label_save_flag = (int *)&mb_io_ptr->save_label_flag; +// typelast = (short *)&mb_io_ptr->save6; +// sonarlast = (short *)&mb_io_ptr->save7; +// nbadrec = (int *)&mb_io_ptr->save8; +// num_sonars = (int *)&mb_io_ptr->save10; +// record_size_char = (char *)&record_size; +// ignore_snippets = (bool *)&mb_io_ptr->save4; +// // *ignore_snippets = true; +// +// // set file position +//// mb_io_ptr->file_pos = mb_io_ptr->file_bytes; +// +// // set flag to swap bytes if necessary +// int swap = *databyteswapped; +// +// // if a ping structure was previously flagged as complete then reset the structure to empty +// for (int i = 0; i < MBSYS_SIMRAD3_NUM_PING_STRUCTURES; i++) { +// if (store->pings[i].read_status == MBSYS_SIMRAD3_PING_COMPLETE) { +// store->pings[i].read_status = MBSYS_SIMRAD3_PING_NO_DATA; +// store->pings[i].png_bath_read = false; +// store->pings[i].png_raw_read = false; +// store->pings[i].png_quality_read = false; +// store->pings[i].png_ss_read = false; +// } +// } +// +// int status = MB_SUCCESS; +// +// // loop over reading data until a record is ready for return +// *error = MB_ERROR_NO_ERROR; +// bool done = false; +// struct +// static unsigned char *dgm_buffer = NULL; +// char **bufferptr = NULL; +// char *buffer = NULL; +// size_t *bufferalloc = NULL; +// +// bufferptr = (char **)&mb_io_ptr->raw_data; +// bufferalloc = (size_t *)&mb_io_ptr->structure_size; +// buffer = (char *)*bufferptr; +// struct mbsys_simrad3_header header; +// mbsys_simrad3_emdgm_type emdgm_type; +// +// while (!done) { +// read_len = MB_UDP_SIZE_MAX; +// +// if (*bufferalloc <= read_len) { +// status = mb_reallocd(verbose, __FILE__, __LINE__, read_len, (void **)bufferptr, error); +// if (status != MB_SUCCESS) { +// *bufferalloc = 0; +// done = true; +// } +// else { +// buffer = (char *)*bufferptr; +// *bufferalloc = read_len; +// } +// } +// +// // read the next valid datagram +// memset(buffer, 0, read_len); +// read_len = *bufferalloc; +// status = mb_fileio_get(verbose, mbio_ptr, (void *)buffer, &read_len, error); +// +// // save datagram bytes read +// size_t dgm_bytes = read_len; +// +// if (status == MB_SUCCESS) { +// dgm_bytes = read_len; +// mb_io_ptr->file_pos += read_len; +// status = mbr_em710raw_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); +// store->time_d = 0; // TODO: parse time +// mb_get_date(verbose, store->time_d, store->time_i); +// } +// +// // datagram should be in buffer +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "\nabove mbr_em710raw_rd_data loop:\n"); +// fprintf(stderr, "label_save_flag:%d status:%d\n", *label_save_flag, status); +//#endif +// +// if (!*label_save_flag) { +// // set read len (same for both record body size and label) +// read_len = 4; +// +// // point cursor to start of datagram body +// unsigned char *cur = buffer + sizeof(mbsys_simrad3_header); +// // read record size +// memcpy(record_size, cur, read_len); +// // read label +// memcpy(label, (cur + read_len), read_len); +// status = MB_SUCCESS; +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], skip, status); +//#endif +// while (status == MB_SUCCESS && mbr_em710raw_chk_label(verbose, mbio_ptr, label, &type, &sonar) != +// MB_SUCCESS){ +// cur++; +// if( dgm_bytes - (cur - buffer) >= 2*read_len){ +// // stop if bytes remaining < (record_size + label) +// status = MB_ERROR_UNINTELLIGIBLE; +// continue; +// } else { +// status = MB_SUCCESS; +// } +// memcpy(record_size, cur, read_len); +// memcpy(label, (cur + read_len), read_len); +// skip++; +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], skip, status); +//#endif +// } +// // report problem +// if (skip > 0 && verbose > 0) { +// if (*nbadrec == 0) +// fprintf(stderr, "\nThe MBF_EM710RAW module skipped data between identified\n\ +//data records. Something is broken, most probably the data...\n\ +//However, the data may include a data record type that we\n\ +//haven't seen yet, or there could be an error in the code.\n\ +//If skipped data are reported multiple times, \n\ +//we recommend you send a data sample and problem \n\ +//description to the MB-System team \n\ +//(caress@mbari.org and dale@ldeo.columbia.edu)\n\ +//Have a nice day...\n"); +// fprintf(stderr, "MBF_EM710RAW skipped %d bytes between records %4.4hX:%d and %4.4hX:%d\n", skip, *typelast, +// *typelast, type, type); +// (*nbadrec)++; +// } +// +// *typelast = type; +// *sonarlast = sonar; +// +// // set flag to swap bytes if necessary +// swap = *databyteswapped; +// +// // get record_size +// if (*databyteswapped != mb_io_ptr->byteswapped) +// record_size = mb_swap_int(record_size); +// *record_size_save = record_size; +// +// } else { +// // use saved label +// *label_save_flag = false; +// type = *typelast; +// sonar = *sonarlast; +// record_size = *record_size_save; +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "use previously read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], +// skip, status); +//#endif +// } +// +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "\nstart of mbr_em710raw_rd_data loop:\n"); +// fprintf(stderr, "skip:%d type:%x sonar:%d recsize:%u done:%d\n", skip, type, sonar, *record_size_save, done); +//#endif +//#ifdef MBR_EM710RAW_DEBUG3 +// if (skip > 0) +// fprintf(stderr, "SKIPPED BYTES: %d\n", skip); +// fprintf(stderr, "type:%x sonar:%d recsize:%u done:%d ", type, sonar, *record_size_save, done); +//#endif +// +// // allocate secondary data structure for extraparameters data if needed +// if (status == MB_SUCCESS && (type == EM3_EXTRAPARAMETERS) && store->extraparameters == NULL) { +// status = mbsys_simrad3_extraparameters_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for heading data if needed +// if (status == MB_SUCCESS && (type == EM3_HEADING) && store->heading == NULL) { +// status = mbsys_simrad3_heading_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for attitude data if needed +// if (status == MB_SUCCESS && (type == EM3_ATTITUDE) && store->attitude == NULL) { +// status = mbsys_simrad3_attitude_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for netattitude data if needed +// if (status == MB_SUCCESS && (type == EM3_NETATTITUDE) && store->netattitude == NULL) { +// status = mbsys_simrad3_netattitude_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for ssv data if needed +// if (status == MB_SUCCESS && (type == EM3_SSV) && store->ssv == NULL) { +// status = mbsys_simrad3_ssv_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for tilt data if needed +// if (status == MB_SUCCESS && (type == EM3_TILT) && store->tilt == NULL) { +// status = mbsys_simrad3_tilt_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// // allocate secondary data structure for water column data if needed +// if (status == MB_SUCCESS && (type == EM3_WATERCOLUMN)) { +// if (store->wc == NULL) +// status = mbsys_simrad3_wc_alloc(verbose, mbio_ptr, store_ptr, error); +// } +// +// +// // read the appropriate data records +// if (status == MB_FAILURE) { +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "call nothing, read failure\n"); +//#endif +// done = true; +// record_size = 0; +// *record_size_save = record_size; +// } +// else if (type != EM3_PU_ID && type != EM3_PU_STATUS && type != EM3_PU_BIST && type != EM3_EXTRAPARAMETERS && +// type != EM3_ATTITUDE && type != EM3_CLOCK && type != EM3_BATH && type != EM3_SBDEPTH && type != EM3_RAWBEAM && +// type != EM3_SSV && type != EM3_HEADING && type != EM3_START && type != EM3_TILT && type != EM3_CBECHO && +// type != EM3_RAWBEAM4 && type != EM3_QUALITY && type != EM3_POS && type != EM3_RUN_PARAMETER && type != EM3_SS && +// type != EM3_TIDE && type != EM3_SVP2 && type != EM3_SVP && type != EM3_SSPINPUT && type != EM3_BATH2 && +// type != EM3_SS2 && type != EM3_RAWBEAM2 && type != EM3_RAWBEAM3 && type != EM3_HEIGHT && type != EM3_STOP && +// type != EM3_WATERCOLUMN && type != EM3_NETATTITUDE && type != EM3_REMOTE && type != EM3_SSP && +// type != EM3_BATH_MBA && type != EM3_SS_MBA && type != EM3_BATH2_MBA && type != EM3_SS2_MBA && +// type != EM3_BATH3_MBA) { +//#ifdef MBR_EM710RAW_DEBUG +// fprintf(stderr, "call nothing, try again\n"); +//#endif +// done = false; +// } +// +// } // while(!done) +//} + /*--------------------------------------------------------------------*/ int mbr_em710raw_rd_data(int verbose, void *mbio_ptr, void *store_ptr, int *error) { int *databyteswapped; int record_size; @@ -4529,7 +4878,17 @@ store->pings[store->ping_index].png_ss_count); done = true; /* if necessary read over unread but expected bytes */ - bytes_read = ftell(mbfp) - mb_io_ptr->file_bytes - 4; + if(mbfp != NULL){ + // reading from file + bytes_read = ftell(mbfp) - mb_io_ptr->file_bytes - 4; + } +// else if(mbsp != NULL) { +// // reading from socket +// bytes_read = 0; +// } else { +// // error: neither file nor socket set +// } + if (!*label_save_flag && !good_end_bytes && bytes_read < record_size) { #ifdef MBR_EM710RAW_DEBUG fprintf(stderr, "skip over %d unread bytes of supported datagram type %x\n", record_size - bytes_read, type); @@ -4541,8 +4900,8 @@ store->pings[store->ping_index].png_ss_count); } #ifdef MBR_EM710RAW_DEBUG - fprintf(stderr, "record_size:%d bytes read:%ld file_pos old:%ld new:%ld\n", record_size, - ftell(mbfp) - mb_io_ptr->file_bytes, mb_io_ptr->file_bytes, ftell(mbfp)); + if(mbfp != NULL) + fprintf(stderr, "record_size:%d bytes read:%ld file_pos old:%ld new:%ld\n", record_size, ftell(mbfp) - mb_io_ptr->file_bytes, mb_io_ptr->file_bytes, ftell(mbfp)); fprintf(stderr, "done:%d status:%d error:%d\n", done, status, *error); fprintf(stderr, "end of mbr_em710raw_rd_data loop:\n\n"); #endif @@ -4552,10 +4911,15 @@ store->pings[store->ping_index].png_ss_count); #endif /* get file position */ - if (*label_save_flag) - mb_io_ptr->file_bytes = ftell(mbfp) - 2; - else - mb_io_ptr->file_bytes = ftell(mbfp); + if (*label_save_flag) { + if(mbfp != NULL) { + mb_io_ptr->file_bytes = ftell(mbfp) - 2; + } + } else { + if(mbfp != NULL){ + mb_io_ptr->file_bytes = ftell(mbfp); + } + } } if (verbose >= 2) { diff --git a/src/mbio/mbsys_simrad3.h b/src/mbio/mbsys_simrad3.h index 37574a442..55a4cc955 100644 --- a/src/mbio/mbsys_simrad3.h +++ b/src/mbio/mbsys_simrad3.h @@ -394,7 +394,7 @@ #define EM3_INVALID_INT 0x7FFFFFFF /* M3 datagram types */ - +#pragma pack(push,1) struct mbsys_simrad3_header { /* Definition of general datagram header */ unsigned int numBytesDgm; /* Datagram length in bytes. @@ -425,6 +425,7 @@ struct mbsys_simrad3_footer { mb_u_char dgmETX; /*End identifier, always 03h*/ unsigned short checksum; /*Sum of bytes between STX and ETX*/ }; +#pragma pack(pop) // Enumerate EM datagram types typedef enum { diff --git a/src/mbtrn/CMakeLists.txt b/src/mbtrn/CMakeLists.txt index 5c3892dac..d4adcb9bc 100644 --- a/src/mbtrn/CMakeLists.txt +++ b/src/mbtrn/CMakeLists.txt @@ -170,8 +170,17 @@ target_link_libraries(mb1-cli PRIVATE mbtrnframe mb1r mb1 m pthread) # #------------------------------------------------------------------------------ # +add_executable(empub utils/em710pub.c) +target_include_directories(empub PRIVATE ${CMAKE_SOURCE_DIR}/src/mbtrnframe + ${CMAKE_SOURCE_DIR}/src/mbio + ${CMAKE_SOURCE_DIR}/src/mbtrnutils) +target_link_libraries(empub PRIVATE mbtrnframe m pthread) +# +#------------------------------------------------------------------------------ +# install(TARGETS r7kr mb1r DESTINATION ${CMAKE_INSTALL_LIBDIR}) # -install(TARGETS udps udpc mbtnav_cli stream7k emu7k r7kr_test trnc tbinx mb1conv mb12csv mb1r_test mb1-cli DESTINATION ${CMAKE_INSTALL_BINDIR}) +install(TARGETS udps udpc mbtnav_cli stream7k emu7k r7kr_test trnc tbinx mb1conv mb12csv mb1r_test mb1-cli empub DESTINATION ${CMAKE_INSTALL_BINDIR}) # #------------------------------------------------------------------------------ +# diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index f28190302..04305ea42 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -752,6 +752,9 @@ FILE *output_trn_fp = NULL; #endif // WITH_MBTNAV +struct sockaddr_in em_sock_addr; +socklen_t em_sock_len; + typedef enum{RF_NONE=0,RF_FORCE_UPDATE=0x1,RF_RELEASE=0x2}mb_resource_flag_t; // profiling - event channels @@ -7123,7 +7126,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i int port=-1; mb_path bcastGrp; mb_path hostInterface; - struct sockaddr_in localSock; +// struct sockaddr_in localSock; struct ip_mreq group; char *token; char *saveptr; @@ -7144,7 +7147,8 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i hostInterface, bcastGrp, port); /* Create a datagram socket on which to receive. */ - int sd = socket(AF_INET, SOCK_DGRAM, 0); + int sd = -1; + sd = socket(AF_INET, SOCK_DGRAM, 0); if (sd < 0) { perror("Opening datagram socket error"); @@ -7157,6 +7161,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i /* Enable SO_REUSEADDR to allow multiple instances of this */ /* application to receive copies of the multicast datagrams. */ +// fcntl(sd, F_SETFL, O_NONBLOCK); int reuse = 1; if (setsockopt(sd, SOL_SOCKET, SO_REUSEADDR, (char *)&reuse, sizeof(reuse)) < 0) { @@ -7170,12 +7175,14 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i /* Bind to the proper port number with the IP address */ /* specified as INADDR_ANY. */ - memset((char *) &localSock, 0, sizeof(localSock)); - localSock.sin_family = AF_INET; - localSock.sin_port = htons(port); - localSock.sin_addr.s_addr = INADDR_ANY; - if (bind(sd, (struct sockaddr*)&localSock, sizeof(localSock))) { - perror("Binding datagram socket error"); + memset(&em_sock_addr, 0, sizeof(em_sock_addr)); + em_sock_addr.sin_family = AF_INET; + em_sock_addr.sin_port = htons(port); + em_sock_addr.sin_addr.s_addr = inet_addr(hostInterface); + + + if (bind(sd, (struct sockaddr*)&em_sock_addr, sizeof(em_sock_addr))) { + perror("bind datagram socket error"); close(sd); mlog_tprintf(mbtrnpp_mlog_id,"e,bind [%d/%s]\n",errno,strerror(errno)); status=MB_FAILURE; @@ -7183,22 +7190,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i return status; } - /* Join the multicast group on the specified */ - /* interface. Note that this IP_ADD_MEMBERSHIP option must be */ - /* called for each local interface over which the multicast */ - /* datagrams are to be received. */ -// group.imr_multiaddr.s_addr = inet_addr(bcastGrp); -// group.imr_interface.s_addr = inet_addr(hostInterface); -// -// if(setsockopt(sd, IPPROTO_IP, IP_ADD_MEMBERSHIP, -// (char *)&group, sizeof(group)) < 0) { -// perror("Adding multicast group error"); -// close(sd); -// mlog_tprintf(mbtrnpp_mlog_id,"e,setsockopt IP_ADD_MEMBERSHIP [%d/%s]\n",errno,strerror(errno)); -// status=MB_FAILURE; -// *error=MB_ERROR_OPEN_FAIL; -// return status; -// } + fprintf(stderr, "%s connected fd %d %s:%d\n", __func__, sd, hostInterface, port); // save the socket within the mb_io structure int *sd_ptr = NULL; @@ -7366,6 +7358,35 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i //}; /*--------------------------------------------------------------------*/ + +static void em710_frame_show(byte *frame_buf) +{ + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + + fprintf(stderr, "numBytesDgm %08u/x%08X\n", header->numBytesDgm, header->numBytesDgm); + fprintf(stderr, "dgmSTX %02X\n", header->dgmSTX); + fprintf(stderr, "dgmType %02X/%c\n", header->dgmType, header->dgmType); + fprintf(stderr, "emModeNum %04hu/x%04X\n", header->emModeNum, header->emModeNum); + fprintf(stderr, "date %08u/x%08X\n", header->date, header->date); + fprintf(stderr, "timeMs %08u/x%08X\n", header->timeMs, header->timeMs); + fprintf(stderr, "counter %04hu/x%04X\n", header->counter, header->counter); + fprintf(stderr, "sysSerialNum %04hu/x%04X\n", header->sysSerialNum, header->sysSerialNum); + fprintf(stderr, "secHeadSerialNum %04hu/x%04X\n", header->secHeadSerialNum, header->secHeadSerialNum); + byte *bp = (byte *)frame_buf; + byte *petx = (bp + (header->numBytesDgm + 1)); + byte *pchk = (petx+1); + fprintf(stderr, "dgmETX %02X\n", *((unsigned char *)petx)); + fprintf(stderr, "chksum %04X\n", *((unsigned short *)pchk)); + fprintf(stderr, "\nframe bytes:\n"); + for (int i=0;inumBytesDgm + 4;i++) + { + if(i%16 == 0) + fprintf(stderr, "\n%08X: ",i); + fprintf(stderr, "%02x ",bp[i]); + } + fprintf(stderr, "\n\n"); +} + int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, char *buffer, int *error) { @@ -7413,7 +7434,6 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, bytes_read = 0; } - // if valid reader... if(NULL != mbsp && NULL != frame_buf) { @@ -7427,23 +7447,37 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // returns number of bytes read or -1 error // UDP datagrams don't include 4-byte total size // we'll calculate it and include it at the start of the buffer. - if ( (rbytes = recv(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0)) >= 0) + +// struct sockaddr_in localSock; +// memset((char *) &localSock, 0, sizeof(localSock)); +// localSock.sin_family = AF_INET; +// localSock.sin_port = htons(10001); +// localSock.sin_addr.s_addr = INADDR_ANY; +// socklen_t len; + MX_PRINT("%s - recv frame fd %d\n", __func__, *mbsp); + + if ( (rbytes = recvfrom(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0, (struct sockaddr *)&em_sock_addr, &em_sock_len)) >= 0) { + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + // set datagram size (first 4 bytes of buffer) unsigned int *pDgmSize = (unsigned int *)frame_buf; - *pDgmSize = rbytes + 4; + //*pDgmSize = rbytes + 4; + *pDgmSize = rbytes; + int errors = 0; // validate uint16_t checksum = 0; byte *pstx = (byte *)&fb_phdr->dgmSTX; - byte *petx = frame_buf + 4 + rbytes - 2; +// byte *petx = frame_buf + 4 + rbytes - 2; + byte *petx = frame_buf + (header->numBytesDgm + 1); byte *cur = pstx + 1; uint16_t *pchk = (uint16_t *)(petx + 1); if(rbytes > 0 && rbytes <= MB_UDP_SIZE_MAX){ - while(cur < pstx){ + while(cur < petx){ checksum += *cur; cur++; } @@ -7467,6 +7501,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, } } + em710_frame_show(frame_buf); if(errors == 0) { // update frame read pointers @@ -7488,7 +7523,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // there's a frame in the buffer size_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); - MX_LPRINT(MBTRNPP, 3, "reading framebuf size[%zu] rlen[%zu] rem[%zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); +// MX_LPRINT(MBTRNPP, 3, "reading framebuf size[%zu] rlen[%zu] rem[%zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); } if(!read_err){ From 2fd9a2286748f3bd22f6427dadeb4f05f13684ad Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Sat, 2 Mar 2024 22:14:02 -0800 Subject: [PATCH 04/20] em710pub test utility; publishes M3 sonar raw UDP captures or .ALL files to mbtrnpp --- src/mbtrn/utils/em710pub.c | 764 +++++++++++++++++++++++++++++++++++++ 1 file changed, 764 insertions(+) create mode 100644 src/mbtrn/utils/em710pub.c diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c new file mode 100644 index 000000000..9c8ab53d1 --- /dev/null +++ b/src/mbtrn/utils/em710pub.c @@ -0,0 +1,764 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mb_define.h" +#include "mb_io.h" +#include "mbsys_simrad3.h" + +#include "mframe.h" +#include "mlist.h" +#include "mfile.h" +#include "mlog.h" +#include "mxdebug.h" +#include "mxd_app.h" + + +typedef enum { + EM710_INVALID = 0, + EM710_UDP, + EM710_LOG +}data_fmt_t; + +typedef struct app_cfg_s +{ + mlist_t *file_paths; + mlist_t *file_list; + char *host; + int port; + int sock_fd; + int verbose; + data_fmt_t fmt; + uint32_t start_offset; + unsigned long delay_ms; + struct sockaddr_in svr_addr; + struct sockaddr_in cli_addr; + socklen_t cli_len; + bool is_udp; +}app_cfg_t; + + +static void s_show_help(); +static app_cfg_t *s_cfg_new(); +static void s_cfg_destroy(app_cfg_t **pself); +static void s_cfg_show(app_cfg_t *self); +static void s_parse_args(int argc, char **argv, app_cfg_t *cfg); + + +static void s_show_help() +{ + char help_message[] = "\n publish em710 raw UDP data\n"; + char usage_message[] = "\n em710pub [options] file [file...]\n" + "\n Options:\n" + " --verbose=n : verbose output level\n" + " --help : show this help message\n" + " --host=s : host IP address or name\n" + " --port=n : TCP/IP port\n" + " --format=s : log or udp\n" + " --delay=n : delay (msec)\n" + "\n"; + printf("%s",help_message); + printf("%s",usage_message); +} + +static app_cfg_t *s_cfg_new() +{ + app_cfg_t *new_cfg = (app_cfg_t *)malloc(sizeof(app_cfg_t)); + if ( new_cfg != NULL) { + new_cfg->file_paths = mlist_new(); + new_cfg->file_list = mlist_new(); + mlist_autofree(new_cfg->file_paths, free); + + new_cfg-> host = strdup("127.0.0.1"); + new_cfg->port = 10001; + new_cfg->verbose = 0; + new_cfg->sock_fd = -1; + new_cfg->fmt = EM710_LOG; + new_cfg->start_offset = 0; + new_cfg->delay_ms = 0; + // must initialize addr len before recv, + // else it will not fill in and can't send message to cli + memset(&new_cfg->svr_addr, 0, sizeof(new_cfg->svr_addr)); + memset(&new_cfg->cli_addr, 0, sizeof(new_cfg->cli_addr)); + new_cfg->cli_len = sizeof(new_cfg->cli_addr); + } + return new_cfg; +} + +static void s_cfg_destroy(app_cfg_t **pself) +{ + if(pself != NULL) { + app_cfg_t *self = *pself; + if (self != NULL) { + + mfile_file_t *file = (mfile_file_t *)mlist_first(self->file_list); + while (NULL!=file) { + mfile_file_destroy(&file); + file = (mfile_file_t *)mlist_next(self->file_list); + } + mlist_destroy(&self->file_list); + + mlist_destroy(&self->file_paths); + free(self->host); + free(self); + } + *pself = NULL; + } +} + +static void s_cfg_show(app_cfg_t *self) +{ + fprintf(stderr,"verbose %d\n", self->verbose); + fprintf(stderr,"host %s\n", self->host); + fprintf(stderr,"port %d\n", self->port); + const char *fmt; + if(self->fmt == EM710_LOG) + fmt = "EM710_LOG"; + else if(self->fmt == EM710_UDP) + fmt = "EM710_UDP"; + else + fmt = "unknown"; + + fprintf(stderr,"format %s\n", fmt) ; + fprintf(stderr,"delay_ms %lu\n", self->delay_ms); + fprintf(stderr,"paths %p\n", self->file_paths); + fprintf(stderr,"fd %d\n", self->sock_fd); + fprintf(stderr,"files:\n"); + char *path = (char *)mlist_first(self->file_paths); + int i = 0; + while (NULL != path) { + fprintf(stderr, "[%3d] %s\n", i++, path); + path = (char *)mlist_next(self->file_paths); + } + +} + +static void s_parse_args(int argc, char **argv, app_cfg_t *cfg) +{ + extern char WIN_DECLSPEC *optarg; + int option_index; + int c; + bool help=false; + bool version=false; + + static struct option options[] = { + {"verbose", required_argument, NULL, 0}, + {"help", no_argument, NULL, 0}, + {"host", required_argument, NULL, 0}, + {"port", required_argument, NULL, 0}, + {"format", required_argument, NULL, 0}, + {"delay", required_argument, NULL, 0}, + {NULL, 0, NULL, 0}}; + + // process argument list + while ((c = getopt_long(argc, argv, "", options, &option_index)) != -1){ + switch (c) { + // long options all return c=0 + case 0: + // verbose + if (strcmp("verbose", options[option_index].name) == 0) { + sscanf(optarg,"%d",&cfg->verbose); + } + // help + else if (strcmp("help", options[option_index].name) == 0) { + help = true; + } + // host + else if (strcmp("host", options[option_index].name) == 0) { + if (NULL!=cfg->host) { + free(cfg->host); + } + cfg->host=strdup(optarg); + } + // port + else if (strcmp("port", options[option_index].name) == 0) { + sscanf(optarg,"%d",&cfg->port); + } + // format + else if (strcmp("format", options[option_index].name) == 0) { + if(strcasecmp(optarg,"log") == 0) { + cfg->fmt = EM710_LOG; + } else if(strcasecmp(optarg,"udp") == 0) { + cfg->fmt = EM710_UDP; + } else { + fprintf(stderr, "ERR - invalid format %s; use log or udp\n", optarg); + } + } + // delay + else if (strcmp("delay", options[option_index].name) == 0) { + sscanf(optarg,"%lu",&cfg->delay_ms); + } + } + } + + for (int i=optind; ifile_paths,strdup(argv[i])); + } + + if (mlist_size(cfg->file_paths) > 0) { + char *file_path = (char *)mlist_first(cfg->file_paths); + while (file_path != NULL) { + mfile_file_t *file = mfile_file_new(file_path); + mlist_add(cfg->file_list, file); + file_path = (char *)mlist_next(cfg->file_paths); + } + }else{ + fprintf(stderr,"ERR - no input files\n"); + } + +} + +static void header_show(struct mbsys_simrad3_header *header) +{ + fprintf(stderr, "numBytesDgm %08u/x%08X\n", header->numBytesDgm, header->numBytesDgm); + fprintf(stderr, "dgmSTX %02X\n", header->dgmSTX); + fprintf(stderr, "dgmType %02X/%c\n", header->dgmType, header->dgmType); + fprintf(stderr, "emModeNum %04hu/x%04X\n", header->emModeNum, header->emModeNum); + fprintf(stderr, "date %08u/x%08X\n", header->date, header->date); + fprintf(stderr, "timeMs %08u/x%08X\n", header->timeMs, header->timeMs); + fprintf(stderr, "counter %04hu/x%04X\n", header->counter, header->counter); + fprintf(stderr, "sysSerialNum %04hu/x%04X\n", header->sysSerialNum, header->sysSerialNum); + fprintf(stderr, "secHeadSerialNum %04hu/x%04X\n", header->secHeadSerialNum, header->secHeadSerialNum); + byte *bp = (byte *)header; + byte *petx = (bp + (header->numBytesDgm + 1)); + byte *pchk = (petx+1); + fprintf(stderr, "dgmETX %02X\n", *((unsigned char *)petx)); + fprintf(stderr, "chksum %04X\n", *((unsigned short *)pchk)); + fprintf(stderr, "\nframe bytes:\n"); + for (int i=0;inumBytesDgm + 4;i++) + { + if(i%16 == 0) + fprintf(stderr, "\n%08X: ",i); + fprintf(stderr, "%02x ",bp[i]); + } + fprintf(stderr, "\n\n"); +} + +static bool validate(byte *src, unsigned int len, app_cfg_t *cfg) +{ + bool retval = true; + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)src; + + if(cfg->verbose > 1) + header_show(header); + + byte *petx = src + header->numBytesDgm + 1; + byte *psum = (byte *)&header->dgmSTX + 1; + + switch(header->dgmType){ + + case ALL_INSTALLATION_U: + case ALL_INSTALLATION_L: + case ALL_REMOTE: + case ALL_RUNTIME: + case ALL_RAW_RANGE_BEAM_ANGLE: + case ALL_XYZ88: + case ALL_CLOCK: + case ALL_ATTITUDE: + case ALL_POSITION: + case ALL_SURFACE_SOUND_SPEED: + break; + default: + fprintf(stderr, "%s - ERR: invalid type %02x\n", __func__, header->dgmType); + return false; + break; + }; + + if(header->dgmSTX != EM3_START_BYTE) { + fprintf(stderr, "%s - ERR: invalid STX %02X/%02X\n", __func__, header->dgmSTX, EM3_START_BYTE); + return false; + } + + if(*petx != EM3_END_BYTE) { + fprintf(stderr, "%s - ERR: invalid ETX %02X/%02X len(%u)\n", __func__, *petx, EM3_END_BYTE, len); + + + return false; + } + short unsigned int sum = 0; + short unsigned int chk = *((short unsigned int *)(petx + 1)); + + while(psum < petx){ + sum += *psum; + psum++; + } + if(sum != chk){ + fprintf(stderr, "%s - ERR: invalid checksum %04hu/%04hu\n", __func__, sum, chk); + return false; + } + + return retval; +} + +static void pub_file(mfile_file_t *src, app_cfg_t *cfg) +{ + + static byte *frame_buf = NULL; + + if (frame_buf == NULL) { + frame_buf = (byte *)malloc(MB_UDP_SIZE_MAX); + } + + if(frame_buf != NULL) { + memset(frame_buf, 0, MB_UDP_SIZE_MAX); + + uint32_t start_offset = cfg->start_offset; + + off_t file_end = mfile_seek(src, 0, MFILE_END); + + if ((off_t)start_offset >= file_end) { + mfile_seek(src, file_end, MFILE_SET); + start_offset -= file_end; + }else{ + mfile_seek(src, start_offset, MFILE_SET); + start_offset=0; + } + off_t file_cur = mfile_seek(src, 0, MFILE_CUR); + off_t fb_cur = 0; + + if(cfg->fmt == EM710_LOG) { + + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + + while(file_cur < file_end) { + memset(frame_buf, 0, MB_UDP_SIZE_MAX); + fb_cur = 0; + uint32_t read_len = 4; + int64_t rbytes = 0; + off_t file_cur_save = file_cur; + // read datagram size (4 bytes) + if( (rbytes = mfile_read(src, frame_buf, read_len)) == read_len) { + fb_cur += read_len; + // read the rest of the datagram + read_len = header->numBytesDgm; + if( (rbytes = mfile_read(src, frame_buf + fb_cur, read_len)) == read_len) { + fb_cur += read_len; + + if(cfg->verbose > 1){ + fprintf(stderr, "\n"); + header_show(header); + } + if(validate(frame_buf, (header->numBytesDgm + 4), cfg)){ + size_t send_len = header->numBytesDgm; + ssize_t status = send(cfg->sock_fd, frame_buf+4, send_len, 0); + if( status != send_len){ + fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); + } + + } + } + if(cfg->delay_ms > 0){ + struct timespec delay_ms = { + (time_t)(cfg->delay_ms / 1000), + (long)(1000L * (cfg->delay_ms % 1000)) + }; + nanosleep(&delay_ms, NULL); + } + } + file_cur = mfile_seek(src, 0, MFILE_CUR); + } + } else if(cfg->fmt == EM710_UDP) { + + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + + typedef enum { + ST_START = 0, + ST_STX_VALID, + ST_TYPE_VALID, + ST_MODEL_VALID, + ST_ETX_VALID, + ST_CHKSUM_VALID, + ST_ERROR, + ST_COUNT + }state_t; + char *st_names[ST_COUNT] = { + "ST_START", + "ST_STX_VALID", + "ST_TYPE_VALID", + "ST_MODEL_VALID", + "ST_ETX_VALID", + "ST_CHKSUM_VALID", + "ST_ERROR" + }; + state_t state = ST_START; + + int64_t rbytes = 0; + size_t dgram_bytes = 0; + byte *bp = frame_buf + 4; + byte *pstx = frame_buf + 5; + byte *petx = NULL; + bool found_stx = false; + bool found_type = false; + bool found_model = false; + bool found_etx = false; + bool found_chk = false; + uint32_t read_len = 1; + uint64_t fpos_start = 0; + unsigned short int chksum = 0; + + while(file_cur < file_end) { + + // read until STX + + if(state == ST_START) { + memset(frame_buf, 0, MB_UDP_SIZE_MAX); + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + // initialize state + rbytes = 0; + dgram_bytes = 0; + chksum = 0; + bp = frame_buf + 4; + fb_cur = 0; + found_etx = false; + found_chk = false; + found_stx = false; + found_type = false; + found_model = false; + //fpos_start = mfile_seek(src, 0, MFILE_CUR); + mfile_seek(src, fpos_start, MFILE_SET); + MX_BPRINT( (cfg->verbose > 0), "file_pos %llu/x%0llX\n", fpos_start, fpos_start); + + // find STX (datagram start) + + uint64_t skipped = 0; + while(!found_stx) { + read_len = 1; + rbytes = mfile_read(src, bp, read_len); + + if(rbytes > 0) + file_cur += rbytes; + + if(rbytes == read_len){ + if( *bp == EM3_START_BYTE){ + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; +// fprintf(stderr, "found STX %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); + dgram_bytes = read_len; + pstx = bp; + found_stx = true; + bp += read_len; + state = ST_STX_VALID; + fpos_start = mfile_seek(src, 0, MFILE_CUR); + MX_BPRINT( (cfg->verbose > 0),"(skipped %llu bytes)\n", skipped); + } else { + skipped++; + } + } else { + fprintf(stderr, "ERR - file read failed on STX\n"); + state = ST_ERROR; + break; + } + } + } // state START + + if(state == ST_STX_VALID) { + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + // find type + read_len = 1; + rbytes = mfile_read(src, bp, read_len); + + if(rbytes == read_len) { + switch(*bp){ + case ALL_INSTALLATION_U: + case ALL_INSTALLATION_L: + case ALL_REMOTE: + case ALL_RUNTIME: + case ALL_RAW_RANGE_BEAM_ANGLE: + case ALL_XYZ88: + case ALL_CLOCK: + case ALL_ATTITUDE: + case ALL_POSITION: + case ALL_SURFACE_SOUND_SPEED: + found_type = true; + break; + default: + fprintf(stderr, "ERR - invalid type %02X bp=%p fp=%p\n", *bp, bp, frame_buf); + break; + }; + } else { + fprintf(stderr, "ERR - file read failed on STX\n"); + state = ST_ERROR; + } + + if(state != ST_ERROR){ + if(found_type) { + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; + MX_BPRINT( (cfg->verbose > 1), "found TYPE %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); + + bp += read_len; + dgram_bytes += read_len; + state = ST_TYPE_VALID; + } else { + // invalid type, reset just after original start position +// fpos_start++; + state = ST_START; + } + } + } + + if(state == ST_TYPE_VALID) { + // find model + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); +// fprintf(stderr, "type %02X/%c\n", header->dgmType, header->dgmType); + + read_len = 2; + rbytes = mfile_read(src, bp, read_len); + + if(rbytes == read_len) { + short unsigned *model = (short unsigned *)bp; + switch(*model){ + case 0x1E: + case 0x1ED: + found_model = true; + break; + default: + fprintf(stderr, "ERR - invalid model %04X bp=%p fp=%p\n", *model, bp, frame_buf); + break; + }; + } else { + fprintf(stderr, "ERR - file read failed on MODEL\n"); + state = ST_ERROR; + } + + if(state != ST_ERROR){ + if(found_model) { + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; + MX_BPRINT( (cfg->verbose > 1), "found MODEL %04X file_pos x%0llX bp %p ofs %zd\n", *((unsigned short *)bp), fpos, bp, (bp - frame_buf)); + + bp += read_len; + dgram_bytes += read_len; + state = ST_MODEL_VALID; + } else { + // invalid model, reset just after original start position + state = ST_START; + } + } + } + + if(state == ST_MODEL_VALID) { + + // find ETX + // or exceed max datagram size + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); +// fprintf(stderr, "frame_buf %p bp %p bp-frame_buf(%zd) fpos[%llu]\n", frame_buf, bp, (bp - frame_buf), mfile_seek(src, 0, MFILE_CUR)); + + petx = NULL; + read_len = 1; + while(!found_etx) { + rbytes = mfile_read(src, bp, read_len); + + if(rbytes > 0){ + // read/store next byte + if(rbytes == read_len) { + if(*bp == EM3_END_BYTE){ + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; + MX_BPRINT( (cfg->verbose > 1), "found ETX %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); + petx = bp; + + found_etx = true; + } else { + chksum += *bp; + } + bp += read_len; + dgram_bytes += read_len; + } + + } else { + fprintf(stderr, "ERR - file read failed on ETX\n"); + state = ST_ERROR; + break; + } + + if(state != ST_ERROR){ + if(found_etx) { + state = ST_ETX_VALID; + } else { + // invalid ETX, reset just after original start position + state = ST_START; + } + } + + if( dgram_bytes >= MB_UDP_SIZE_MAX || + (bp - frame_buf) >= MB_UDP_SIZE_MAX){ + fprintf(stderr, "ERR - buffer length exceeded type (%02X) dgram_bytes(%zd) bp-frame_buf(%zd)\n", header->dgmType, dgram_bytes, (bp - frame_buf)); + // invalid ETX, reset just after original start position + state = ST_START; + break; + } + } + } + + if(state == ST_ETX_VALID) { + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); +// fprintf(stderr, "frame_buf %p bp %p bp-frame_buf(%zd)\n", frame_buf, bp, (bp - frame_buf)); + + // read checksum + read_len = 2; + rbytes = mfile_read(src, bp, read_len); + unsigned int *pchk = NULL; + + if(rbytes > 0){ + // read/store next byte + if(rbytes == read_len) { + pchk = (unsigned int *)bp; + found_chk = true; + } else { + fprintf(stderr, "ERR - file read failed on CHKSUM\n"); + state = ST_ERROR; + } + + byte *pcs = pstx + 1; + chksum = 0; + while(pcs < petx){ + chksum += *pcs; +// fprintf(stderr, "pcs %p petx %p *pcs %02X chksum %04X\n", pcs, petx, *pcs, chksum); + pcs++; + } + + if(pchk != NULL && *pchk == chksum){ + state = ST_CHKSUM_VALID; + } else { + found_chk = false; + found_etx = false; + // keep looking for ETX + state = ST_MODEL_VALID; + } + dgram_bytes += read_len; + bp += read_len; + } else { + fprintf(stderr, "ERR - file read failed on CHKSUM\n"); + state = ST_ERROR; + } + } + + if(state == ST_CHKSUM_VALID){ + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + // done, success + header->numBytesDgm = dgram_bytes; + MX_BPRINT( (cfg->verbose > 0), "validating frame len[%zd]\n", dgram_bytes); + + if(validate(frame_buf, dgram_bytes, cfg)){ + size_t send_len = header->numBytesDgm; + + ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); + + if( status != send_len){ + int serr = errno; + fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); + } + } + + if(cfg->delay_ms > 0){ + struct timespec delay_ms = { + (time_t)(cfg->delay_ms / 1000), + (long)(1000000L * (cfg->delay_ms % 1000UL)) + }; + nanosleep(&delay_ms, NULL); + } + state = ST_START; + } + + if(state == ST_ERROR){ + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + // error (EOF) + fprintf(stderr, "ERR - EOF or buffer length exceeded; quitting\n"); + break; + } + } + } // if EM710_UDP + } +} + +int connect_udp(app_cfg_t *cfg, int *error) +{ + int status = MB_SUCCESS; + + cfg->sock_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (cfg->sock_fd < 0) + { + perror("Opening datagram socket error"); + +// mlog_tprintf(mbtrnpp_mlog_id,"e,datagram socket [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + // Enable SO_REUSEADDR to allow multiple instances of this + // application to receive copies of the multicast datagrams. + int reuse = 1; + if (setsockopt(cfg->sock_fd, SOL_SOCKET, SO_REUSEADDR, (char *)&reuse, sizeof(reuse)) < 0) + { + perror("Setting SO_REUSEADDR error"); + close(cfg->sock_fd); +// mlog_tprintf(mbtrnpp_mlog_id,"e,setsockopt SO_REUSEADDR [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + // Bind to the proper port number with the IP address + // specified as INADDR_ANY. + memset((char *) &cfg->svr_addr, 0, sizeof(cfg->svr_addr)); + cfg->svr_addr.sin_family = AF_INET; + cfg->svr_addr.sin_port = htons(cfg->port); + cfg->svr_addr.sin_addr.s_addr = inet_addr(cfg->host); + + + MX_BPRINT( (cfg->verbose > 0), "socket connecting fd %d addr:port %s:%d\n", cfg->sock_fd, cfg->host, cfg->port); + + char msg[16] = {0}; + + + if (connect(cfg->sock_fd, (struct sockaddr *)&cfg->svr_addr, sizeof(cfg->svr_addr)) < 0) { + perror("Connecting datagram socket error"); + close(cfg->sock_fd); + //// mlog_tprintf(mbtrnpp_mlog_id,"e,bind [%d/%s]\n",errno,strerror(errno)); + status=MB_FAILURE; + *error=MB_ERROR_OPEN_FAIL; + return status; + } + + MX_BMSG((cfg->verbose > 0), "socket connected\n"); + return status; +} + +int main(int argc, char **argv) +{ + app_cfg_t *cfg = s_cfg_new(); + + s_parse_args(argc, argv, cfg); + + if (cfg->verbose>0) { + s_cfg_show(cfg); + } + + int error = MB_ERROR_NO_ERROR; + int status = connect_udp(cfg, &error); + + mfile_file_t *file = (mfile_file_t *)mlist_first(cfg->file_list); + + while(file != NULL){ + int status = mfile_open(file, MFILE_RONLY); + if(status >= 0){ + pub_file(file, cfg); + mfile_close(file); + } else { + fprintf(stderr, "ERR - could not open file %s stat %d %d/%s\n", file->path, status, errno, strerror(errno)); + } + file = (mfile_file_t *)mlist_next(cfg->file_list); + } + + close(cfg->sock_fd); + + s_cfg_destroy(&cfg); + +} From c29ba095ee10fc8ed07d9436c505c824f0685662 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Sun, 3 Mar 2024 14:56:37 -0800 Subject: [PATCH 05/20] remove cruft (unused test implementations), update verbose output configuration --- src/mbtrn/utils/em710pub.c | 3 + src/mbtrnutils/mbtrnpp.c | 373 +++++-------------------------------- 2 files changed, 49 insertions(+), 327 deletions(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index 9c8ab53d1..9b0aa1141 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -743,12 +743,15 @@ int main(int argc, char **argv) int error = MB_ERROR_NO_ERROR; int status = connect_udp(cfg, &error); + int flist_n = 0; + int flist_len = mlist_size(cfg->file_list); mfile_file_t *file = (mfile_file_t *)mlist_first(cfg->file_list); while(file != NULL){ int status = mfile_open(file, MFILE_RONLY); if(status >= 0){ + MX_BPRINT( (cfg->verbose > 0), "publishing file %s %d/%d stat %d\n", file->path, ++flist_n, flist_len, status); pub_file(file, cfg); mfile_close(file); } else { diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 04305ea42..0c86bd33f 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -7096,11 +7096,11 @@ int mbtrnpp_kemkmall_input_close(int verbose, void *mbio_ptr, int *error) { int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, int *error) { - /* local variables */ + // local variables int status = MB_SUCCESS; struct mb_io_struct *mb_io_ptr; - /* print input debug statements */ + // print input debug statements if (verbose >= 2) { fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); fprintf(stderr, "dbg2 Input arguments:\n"); @@ -7109,13 +7109,13 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i fprintf(stderr, "dbg2 definition: %s\n", definition); } - /* get pointer to mbio descriptor */ + // get pointer to mbio descriptor mb_io_ptr = (struct mb_io_struct *)mbio_ptr; - /* set initial status */ + // set initial status status = MB_SUCCESS; - /* set flag to enable Sentry sensordepth kluge */ + // set flag to enable Sentry sensordepth kluge int *kluge_set = (int *)&mb_io_ptr->save10; *kluge_set = 1; @@ -7126,10 +7126,10 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i int port=-1; mb_path bcastGrp; mb_path hostInterface; -// struct sockaddr_in localSock; struct ip_mreq group; char *token; char *saveptr; + if ((token = strtok_r(definition, ":", &saveptr)) != NULL) { strncpy(hostInterface, token, sizeof(mb_path)); } @@ -7146,7 +7146,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i fprintf(stderr, " hostInterface: %s\n bcastGrp: %s\n port: %d\n", hostInterface, bcastGrp, port); - /* Create a datagram socket on which to receive. */ + // Create a datagram socket on which to receive. int sd = -1; sd = socket(AF_INET, SOCK_DGRAM, 0); if (sd < 0) @@ -7159,9 +7159,9 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i return status; } - /* Enable SO_REUSEADDR to allow multiple instances of this */ - /* application to receive copies of the multicast datagrams. */ -// fcntl(sd, F_SETFL, O_NONBLOCK); + // Enable SO_REUSEADDR to allow multiple instances of this + // application to receive copies of the multicast datagrams. + int reuse = 1; if (setsockopt(sd, SOL_SOCKET, SO_REUSEADDR, (char *)&reuse, sizeof(reuse)) < 0) { @@ -7173,8 +7173,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i return status; } - /* Bind to the proper port number with the IP address */ - /* specified as INADDR_ANY. */ + // Bind to the proper port number with the IP address memset(&em_sock_addr, 0, sizeof(em_sock_addr)); em_sock_addr.sin_family = AF_INET; em_sock_addr.sin_port = htons(port); @@ -7218,148 +7217,7 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i /*--------------------------------------------------------------------*/ -//int mbtrnpp_kemall_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { -// struct mbsys_simrad3_header *header = NULL; -// mbsys_simrad3_emdgm_type *emdgm_type = NULL; -// int index = 0; -// -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); -// fprintf(stderr, "dbg2 Input arguments:\n"); -// fprintf(stderr, "dbg2 verbose: %d\n", verbose); -// fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); -// fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); -// fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); -// } -// -// /* get pointer to header structure */ -// header = (struct mbsys_simrad3_header *)header_ptr; -// emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; -// -// /* extract the data */ -// index = 0; -// mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); -// index += 4; -// header->dgmSTX = buffer[index]; -// index++; -// header->dgmType = buffer[index]; -// index++; -// mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); -// index += 2; -// mb_get_binary_int(true, &buffer[index], &(header->date)); -// index += 4; -// mb_get_binary_int(true, &buffer[index], &(header->timeMs)); -// index += 4; -// mb_get_binary_short(true, &buffer[index], &(header->counter)); -// index += 2; -// mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); -// index += 2; -// mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); -// index += 2; -// -// /* identify/validate the datagram type */ -// switch(header->typeDatagram){ -// -// case ALL_INSTALLATION_U: -// case ALL_INSTALLATION_L: -// case ALL_REMOTE: -// case ALL_RUNTIME: -// case ALL_RAW_RANGE_BEAM_ANGLE: -// case ALL_XYZ88: -// case ALL_CLOCK: -// case ALL_ATTITUDE: -// case ALL_POSITION: -// case ALL_SURFACE_SOUND_SPEED: -// *emdgm_type = header->typeDatagram; -// break; -// default: -// *emdgm_type = UNKNOWN; -// break; -// }; -// -// -// if (verbose >= 5) { -// fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); -// fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); -// fprintf(stderr, "dbg5 dgmSTX : %02X\n", header->dgmSTX); -// fprintf(stderr, "dbg5 dgmType: %02X\n", header->dgmType); -// fprintf(stderr, "dbg5 emModeNum: %hu\n", header->emModeNum); -// fprintf(stderr, "dbg5 date: %u\n", header->date); -// fprintf(stderr, "dbg5 timeMs: %u\n", header->timeMs); -// fprintf(stderr, "dbg5 counter: %hu\n", header->counter); -// fprintf(stderr, "dbg5 sysSerialNum: %hu\n", header->sysSerialNum); -// fprintf(stderr, "dbg5 secHeadSerialNum: %hu\n", header->secHeadSerialNum); -// } -// -// int status = MB_SUCCESS; -// -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); -// fprintf(stderr, "dbg2 Return values:\n"); -// fprintf(stderr, "dbg2 dgmType: %.4s\n", header->dgmType); -// fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); -// fprintf(stderr, "dbg2 error: %d\n", *error); -// fprintf(stderr, "dbg2 Return status:\n"); -// fprintf(stderr, "dbg2 status: %d\n", status); -// } -// -// /* return status */ -// return (status); -//}; - -/*--------------------------------------------------------------------*/ - -/* read footer */ -//int mbtrnpp_kemall_rd_ftr(int verbose, char *buffer, void *footer_ptr, void *emdgm_checksum_ptr, int *error) { -// struct mbsys_simrad3_footer *footer = NULL; -// short unsigned int *emdgm_checksum_ptr = (short unsigned int)emdgm_checksum_ptr; -// int index = 0; -// -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); -// fprintf(stderr, "dbg2 Input arguments:\n"); -// fprintf(stderr, "dbg2 verbose: %d\n", verbose); -// fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); -// fprintf(stderr, "dbg2 footer_ptr: %p\n", (void *)footer_ptr); -// } -// -// /* get pointer to header structure */ -// footer = (struct mbsys_simrad3_header *)footer_ptr; -// -// /* extract the data */ -// index = 0; -// footer->dgmETX = buffer[index]; -// index++; -// mb_get_binary_short(true, &buffer[index], &(footer->checksum)); -// index += 2; -// -// *emdgm_checksum_ptr = footer->checksum; -// -// if (verbose >= 5) { -// fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); -// fprintf(stderr, "dbg5 dgmSTX : %02X\n", footer->dgmSTX); -// fprintf(stderr, "dbg5 checksum : %04X\n", footer->checksum); -// } -// -// int status = MB_SUCCESS; -// -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); -// fprintf(stderr, "dbg2 Return values:\n"); -// fprintf(stderr, "dbg2 dgmETX: %02X\n", footer->dgmETX); -// fprintf(stderr, "dbg2 checksum: %04X\n", *emdgm_checksum_ptr); -// fprintf(stderr, "dbg2 error: %d\n", *error); -// fprintf(stderr, "dbg2 Return status:\n"); -// fprintf(stderr, "dbg2 status: %d\n", status); -// } -// -// /* return status */ -// return (status); -//}; - -/*--------------------------------------------------------------------*/ - -static void em710_frame_show(byte *frame_buf) +static void em710_frame_show(byte *frame_buf, int verbose) { struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; @@ -7377,14 +7235,18 @@ static void em710_frame_show(byte *frame_buf) byte *pchk = (petx+1); fprintf(stderr, "dgmETX %02X\n", *((unsigned char *)petx)); fprintf(stderr, "chksum %04X\n", *((unsigned short *)pchk)); - fprintf(stderr, "\nframe bytes:\n"); - for (int i=0;inumBytesDgm + 4;i++) - { - if(i%16 == 0) - fprintf(stderr, "\n%08X: ",i); - fprintf(stderr, "%02x ",bp[i]); + + if(verbose >= 2 || verbose <= -2){ + fprintf(stderr, "\nframe bytes:\n"); + for (int i=0;inumBytesDgm + 4;i++) + { + if(i%16 == 0) + fprintf(stderr, "\n%08X: ",i); + fprintf(stderr, "%02x ",bp[i]); + } + fprintf(stderr, "\n"); } - fprintf(stderr, "\n\n"); + fprintf(stderr, "\n"); } int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, @@ -7404,15 +7266,19 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, fprintf(stderr, "dbg2 buffer: %p\n", buffer); } - // Read the requested number of bytes (= size) off the input and place - // those bytes into the buffer. - // This requires reading full MB1 records from the socket, storing the data - // in buffer (implemented here), and parceling those bytes out as requested. + // Read the requested number of bytes (= size) off the input and + // place those bytes into the buffer. + // This requires reading full MB1 records from the socket, + // storing the data in buffer (implemented here), and parceling + // those bytes out as requested. // use the socket reader // read and return single frame int64_t rbytes=-1; uint32_t sync_bytes=0; + static uint64_t frame_count = 0; + static uint64_t frame_invalid = 0; + static uint64_t frame_read_err = 0; // mbsp points to UDP socket int *mbsp = (int *)mb_io_ptr->mbsp; @@ -7448,13 +7314,6 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // UDP datagrams don't include 4-byte total size // we'll calculate it and include it at the start of the buffer. -// struct sockaddr_in localSock; -// memset((char *) &localSock, 0, sizeof(localSock)); -// localSock.sin_family = AF_INET; -// localSock.sin_port = htons(10001); -// localSock.sin_addr.s_addr = INADDR_ANY; -// socklen_t len; - MX_PRINT("%s - recv frame fd %d\n", __func__, *mbsp); if ( (rbytes = recvfrom(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0, (struct sockaddr *)&em_sock_addr, &em_sock_len)) >= 0) { @@ -7462,15 +7321,14 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // set datagram size (first 4 bytes of buffer) unsigned int *pDgmSize = (unsigned int *)frame_buf; - //*pDgmSize = rbytes + 4; *pDgmSize = rbytes; int errors = 0; + // validate uint16_t checksum = 0; byte *pstx = (byte *)&fb_phdr->dgmSTX; -// byte *petx = frame_buf + 4 + rbytes - 2; byte *petx = frame_buf + (header->numBytesDgm + 1); byte *cur = pstx + 1; uint16_t *pchk = (uint16_t *)(petx + 1); @@ -7501,7 +7359,11 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, } } - em710_frame_show(frame_buf); + frame_count++; + + if(verbose >= 5 || verbose <= -5 ) + em710_frame_show(frame_buf, verbose); + if(errors == 0) { // update frame read pointers @@ -7511,19 +7373,25 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, MX_LPRINT(MBTRNPP, 3, "read frame len[%zu]:\n",(size_t)rbytes); } else { // frame invalid + frame_invalid++; read_err = true; MX_LPRINT(MBTRNPP, 3, "invalid frame rbytes[%zu] checksum[%hu/%hu]\n",(size_t)rbytes, checksum, *pchk); } } else { // read error + frame_read_err++; read_err = true; MX_LPRINT(MBTRNPP, 3, "mb1r_read_frame failed rbytes[%zu]\n",(size_t)rbytes); } + + MX_LPRINT(MBTRNPP, 2, "%s - read frame fd %3d len[%6u] n[%8llu] invalid[%8llu] read_err[%8llu] \n", __func__, *mbsp, rbytes, frame_count, frame_invalid, frame_read_err); + } else { // there's a frame in the buffer size_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); -// MX_LPRINT(MBTRNPP, 3, "reading framebuf size[%zu] rlen[%zu] rem[%zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); + + MX_LPRINT(MBTRNPP, 4, "reading framebuf size[%2zu] rlen[%2zu] rem[%6zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); } if(!read_err){ @@ -7567,8 +7435,8 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, MST_COUNTER_INC(app_stats->stats->events[MBTPP_EV_EMBFRAMERD]); MST_COUNTER_ADD(app_stats->stats->status[MBTPP_STA_MB_SYNC_BYTES],sync_bytes); - // TODO: check connection status, only reconnect if disconnected - // ... + // TODO: check connection status, only reconnect if disconnected... + MST_METRIC_LAP(app_stats->stats->metrics[MBTPP_CH_MB_GETFAIL_XT], mtime_dtime()); } @@ -7586,155 +7454,6 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, return (status); } -//int mbtrnpp_kemall_input_read_orig(int verbose, void *mbio_ptr, size_t *size, -// char *buffer, int *error) { -// -// /* local variables */ -// -// /* print input debug statements */ -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); -// fprintf(stderr, "dbg2 Input arguments:\n"); -// fprintf(stderr, "dbg2 verbose: %d\n", verbose); -// fprintf(stderr, "dbg2 mbio_ptr: %p\n", mbio_ptr); -// fprintf(stderr, "dbg2 size: %zu\n", *size); -// fprintf(stderr, "dbg2 buffer: %p\n", buffer); -// } -// -// /* get pointer to mbio descriptor */ -// struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; -// -// /* set initial status */ -// status = MB_SUCCESS; -// -// // Read from the socket. -// int *sd_ptr = (int *)mb_io_ptr->mbsp; -// struct mbsys_simrad3_header header; -// unsigned int num_bytes_dgm_checksum=0; -// mbsys_simrad3_emdgm_type emdgm_type=UNKNOWN; -// memset(buffer, 0, *size); -// int readlen = read(*sd_ptr, buffer, *size); -// if (readlen <= 0) { -// status = MB_FAILURE; -// *error = MB_ERROR_EOF; -// } -// -// if (status == MB_SUCCESS) { -// -// status = mbtrnpp_kemall_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); -// -// if (status == MB_SUCCESS && emdgm_type != UNKNOWN && header.numBytesDgm <= *size) { -// -// // read checksum (which indicates bytes between STX and ETX) -// mb_get_binary_int(true, &buffer[header.numBytesDgm-2], &num_bytes_dgm_checksum); -// -// // checksum should equal numBytes - size of fields: numBytes(4) + STX(1) + ETX(1) + checksum(2) -// if (num_bytes_dgm_checksum != header.numBytesDgm - 8) { -// status = MB_FAILURE; -// *error = MB_ERROR_UNINTELLIGIBLE; -// } -// } else { -// status = MB_FAILURE; -// *error = MB_ERROR_UNINTELLIGIBLE; -// } -// } -// -// if (status == MB_SUCCESS) { -// *size = header.numBytesDgm; -// } -// else { -// *size = 0; -// } -// -//#if 0 -// /*handle multi-packet MRZ and MWC records*/ -// if (emdgm_type == MRZ || emdgm_type == MWC) { -// unsigned short numOfDgms=0; -// unsigned short dgmNum=0; -// -// mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE], &numOfDgms); -// mb_get_binary_short(true, &buffer[MBSYS_KMBES_HEADER_SIZE+2], &dgmNum); -// if (numOfDgms > 1) { -// static int dgmsReceived=0; -// static unsigned int pingSecs, pingNanoSecs; -// static int totalDgms; -// -// /* if we get a M record of a multi-packet sequence, and its numOfDgms -// or ping time don't match the ping we are looking for, flush the -// current read and start over with this packet */ -// if (header.time_sec != pingSecs -// || header.time_nanosec != pingNanoSecs -// || numOfDgms != totalDgms) { -// dgmsReceived = 0; -// } -// -// if (!dgmsReceived){ -// pingSecs = header.time_sec; -// pingNanoSecs = header.time_nanosec; -// totalDgms = numOfDgms; -// dgmsReceived = 1; -// } -// else { -// dgmsReceived++; -// } -// if(dgmNum>0){ -// memcpy(mRecordBuf[dgmNum-1], buffer, header.numBytesDgm); -// } else { -// fprintf(stderr,"%s: ERR - dgNum<0\n",__func__); -// } -// -// if (dgmsReceived == totalDgms) { -// -// int totalSize = sizeof(struct mbsys_kmbes_m_partition) -// + sizeof(struct mbsys_kmbes_header) + 4; -// int rsize = 0; -// for (int dgm = 0; dgm < totalDgms; dgm++) { -// mb_get_binary_int(true, mRecordBuf[dgm], &rsize); -// totalSize += rsize - sizeof(struct mbsys_kmbes_m_partition) -// - sizeof(struct mbsys_kmbes_header) - 4; -// } -// -// /*copy data into new buffer*/ -// if (status == MB_SUCCESS) { -// int index = 0; -// status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[0], (void *)&header, (void *)&emdgm_type, error); -// memcpy(buffer, mRecordBuf[0], header.numBytesDgm); -// index = header.numBytesDgm - 4; -// -// for (int dgm=1; dgm < totalDgms; dgm++) { -// status = mbtrnpp_kemkmall_rd_hdr(verbose, mRecordBuf[dgm], (void *)&header, (void *)&emdgm_type, error); -// int copy_len = header.numBytesDgm - sizeof(struct mbsys_kmbes_m_partition) -// - sizeof(struct mbsys_kmbes_header) - 4; -// void *ptr = (void *)(mRecordBuf[dgm]+ -// sizeof(struct mbsys_kmbes_m_partition)+ -// sizeof(struct mbsys_kmbes_header)); -// memcpy(&buffer[index], ptr, copy_len); -// index += copy_len; -// } -// mb_put_binary_int(true, totalSize, &buffer[0]); -// mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)]); -// mb_put_binary_short(true, 1, &buffer[sizeof(struct mbsys_kmbes_header)+2]); -// mb_put_binary_int(true, totalSize, &buffer[index]); -// dgmsReceived = 0; /*reset received counter back to 0*/ -// } -// } -// } -// } -//#endif -// -// /* print output debug statements */ -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); -// fprintf(stderr, "dbg2 Return values:\n"); -// fprintf(stderr, "dbg2 error: %d\n", *error); -// fprintf(stderr, "dbg2 Return status:\n"); -// fprintf(stderr, "dbg2 status: %d\n", status); -// } -// -// /* return */ -// return (status); -//} - /*--------------------------------------------------------------------*/ int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error) { From a68211378a7c25f80804a1a50b90f7cc9f6928da Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 11:27:12 -0800 Subject: [PATCH 06/20] fix bugs: misalignment in LOG mode caused invalid frames. Now LOG (.all) input works --- src/mbtrn/utils/em710pub.c | 201 ++++++++++++++++++++++++++----------- src/mbtrnutils/mbtrnpp.c | 38 ++++--- 2 files changed, 167 insertions(+), 72 deletions(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index 9b0aa1141..c2ee775b4 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -217,7 +217,7 @@ static void s_parse_args(int argc, char **argv, app_cfg_t *cfg) } -static void header_show(struct mbsys_simrad3_header *header) +static void frame_show(struct mbsys_simrad3_header *header, app_cfg_t *cfg) { fprintf(stderr, "numBytesDgm %08u/x%08X\n", header->numBytesDgm, header->numBytesDgm); fprintf(stderr, "dgmSTX %02X\n", header->dgmSTX); @@ -233,26 +233,28 @@ static void header_show(struct mbsys_simrad3_header *header) byte *pchk = (petx+1); fprintf(stderr, "dgmETX %02X\n", *((unsigned char *)petx)); fprintf(stderr, "chksum %04X\n", *((unsigned short *)pchk)); - fprintf(stderr, "\nframe bytes:\n"); - for (int i=0;inumBytesDgm + 4;i++) - { - if(i%16 == 0) - fprintf(stderr, "\n%08X: ",i); - fprintf(stderr, "%02x ",bp[i]); + if(cfg != NULL && cfg->verbose > 2){ + fprintf(stderr, "\nframe bytes:\n"); + for (int i=0;inumBytesDgm + 4;i++) + { + if(i%16 == 0) + fprintf(stderr, "\n%08X: ",i); + fprintf(stderr, "%02x ",bp[i]); + } + fprintf(stderr, "\n"); } - fprintf(stderr, "\n\n"); + fprintf(stderr, "\n"); } -static bool validate(byte *src, unsigned int len, app_cfg_t *cfg) +static bool validate_frame(byte *src, unsigned int len, app_cfg_t *cfg) { bool retval = true; struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)src; - if(cfg->verbose > 1) - header_show(header); - byte *petx = src + header->numBytesDgm + 1; byte *psum = (byte *)&header->dgmSTX + 1; + byte *pbchk = (byte *)petx+1; + unsigned short *pchk = (unsigned short *)pbchk; switch(header->dgmType){ @@ -285,15 +287,19 @@ static bool validate(byte *src, unsigned int len, app_cfg_t *cfg) return false; } short unsigned int sum = 0; - short unsigned int chk = *((short unsigned int *)(petx + 1)); while(psum < petx){ sum += *psum; psum++; } - if(sum != chk){ - fprintf(stderr, "%s - ERR: invalid checksum %04hu/%04hu\n", __func__, sum, chk); + if(sum != *pchk){ + fprintf(stderr, "%s - ERR: invalid checksum %04hu/%04hu\n", __func__, sum, *pchk); return false; + } else { + if(cfg->verbose > 1){ + fprintf(stderr, "%s - petx ofs(%04lX) pchk ofs (%04lx) etx %02X\n", __func__, petx-src, pbchk-src, *petx); + fprintf(stderr, "%s - sum %04hu/%04X checksum %04hu/%04X \n", __func__, sum, sum, *pchk, *pchk); + } } return retval; @@ -329,34 +335,57 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + // iterate over file to find valid datagrams while(file_cur < file_end) { + + // intialize state memset(frame_buf, 0, MB_UDP_SIZE_MAX); fb_cur = 0; uint32_t read_len = 4; int64_t rbytes = 0; off_t file_cur_save = file_cur; + // read datagram size (4 bytes) if( (rbytes = mfile_read(src, frame_buf, read_len)) == read_len) { + fb_cur += read_len; + // read the rest of the datagram read_len = header->numBytesDgm; if( (rbytes = mfile_read(src, frame_buf + fb_cur, read_len)) == read_len) { + fb_cur += read_len; if(cfg->verbose > 1){ + // show header (verbose/debug) fprintf(stderr, "\n"); - header_show(header); + frame_show(header, cfg); } - if(validate(frame_buf, (header->numBytesDgm + 4), cfg)){ - size_t send_len = header->numBytesDgm; - ssize_t status = send(cfg->sock_fd, frame_buf+4, send_len, 0); + + if(validate_frame(frame_buf, (fb_cur), cfg)) { + + byte *petx = frame_buf + fb_cur - 3; + byte *pchk = petx + 1; + + // datagram valid, publish to socket + size_t send_len = fb_cur - 4;//header->numBytesDgm; + + MX_BPRINT( (cfg->verbose > 0), "sending frame len[%zd/%04X] petx fbofs[%zd/%04X] (%02x) pchk fbofs[%zd/%04X] (%04X)\n", send_len, send_len, (petx-frame_buf), (petx-frame_buf), *petx, (pchk-frame_buf), (pchk-frame_buf), *((unsigned short *)pchk) ); + if(cfg->verbose > 4) + frame_show(header, cfg); + + ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); + if( status != send_len){ fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); } - + }else { + fprintf(stderr, "ERR - invalid frame\n"); } } + if(cfg->delay_ms > 0){ + // delay if set struct timespec delay_ms = { (time_t)(cfg->delay_ms / 1000), (long)(1000L * (cfg->delay_ms % 1000)) @@ -364,12 +393,25 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) nanosleep(&delay_ms, NULL); } } + + // update file pointer file_cur = mfile_seek(src, 0, MFILE_CUR); } } else if(cfg->fmt == EM710_UDP) { + // records are raw UDP (record size ommitted) + // must parse using state machine: + // if record has valid STX, datagram type, model + // then find ETX and checksum. + // if header and checksum are valid, publish datagram + // Since STX and ETX can appear in data payloads, + // must detect and resync appropriately (without violating) + // datagram max size or buffer length). + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; + // state machine states + // note: indexes state names array typedef enum { ST_START = 0, ST_STX_VALID, @@ -380,6 +422,8 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) ST_ERROR, ST_COUNT }state_t; + + // state names (indexed using state values) char *st_names[ST_COUNT] = { "ST_START", "ST_STX_VALID", @@ -389,6 +433,8 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) "ST_CHKSUM_VALID", "ST_ERROR" }; + + // initialize state machine state_t state = ST_START; int64_t rbytes = 0; @@ -396,6 +442,8 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) byte *bp = frame_buf + 4; byte *pstx = frame_buf + 5; byte *petx = NULL; + uint64_t stx_ofs = 0; + uint64_t etx_ofs = 0; bool found_stx = false; bool found_type = false; bool found_model = false; @@ -405,14 +453,18 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) uint64_t fpos_start = 0; unsigned short int chksum = 0; + // iterate over file to find valid datagrams while(file_cur < file_end) { - // read until STX if(state == ST_START) { - memset(frame_buf, 0, MB_UDP_SIZE_MAX); + + // find STX (datagram start) + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + // initialize state + memset(frame_buf, 0, MB_UDP_SIZE_MAX); rbytes = 0; dgram_bytes = 0; chksum = 0; @@ -423,33 +475,38 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) found_stx = false; found_type = false; found_model = false; - //fpos_start = mfile_seek(src, 0, MFILE_CUR); mfile_seek(src, fpos_start, MFILE_SET); + uint64_t skipped_bytes = 0; + MX_BPRINT( (cfg->verbose > 0), "file_pos %llu/x%0llX\n", fpos_start, fpos_start); - // find STX (datagram start) + // read until STX found - uint64_t skipped = 0; while(!found_stx) { read_len = 1; rbytes = mfile_read(src, bp, read_len); - if(rbytes > 0) - file_cur += rbytes; - if(rbytes == read_len){ if( *bp == EM3_START_BYTE){ + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; -// fprintf(stderr, "found STX %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); - dgram_bytes = read_len; + + // set point to STX pstx = bp; + // update state found_stx = true; + dgram_bytes = read_len; bp += read_len; state = ST_STX_VALID; + + // update file pointer start location fpos_start = mfile_seek(src, 0, MFILE_CUR); - MX_BPRINT( (cfg->verbose > 0),"(skipped %llu bytes)\n", skipped); + stx_ofs = fpos_start - 1; + + MX_BPRINT( (cfg->verbose > 0),"STX ofs[%llu/%0X] (skipped_bytes %llu)\n", stx_ofs, stx_ofs, skipped_bytes); } else { - skipped++; + // skip byte + skipped_bytes++; } } else { fprintf(stderr, "ERR - file read failed on STX\n"); @@ -460,8 +517,11 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) } // state START if(state == ST_STX_VALID) { + + // find datagram type + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); - // find type + read_len = 1; rbytes = mfile_read(src, bp, read_len); @@ -490,24 +550,28 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) if(state != ST_ERROR){ if(found_type) { - int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; - MX_BPRINT( (cfg->verbose > 1), "found TYPE %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); + if(cfg->verbose > 1){ + int64_t fpos = mfile_seek(src, 0, MFILE_CUR) - read_len; + MX_PRINT("found TYPE %02X file_pos x%0llX bp %p ofs %zd\n", *bp, fpos, bp, (bp - frame_buf)); + } + + // update state bp += read_len; dgram_bytes += read_len; state = ST_TYPE_VALID; } else { - // invalid type, reset just after original start position -// fpos_start++; + // invalid type, return to start state state = ST_START; } } } if(state == ST_TYPE_VALID) { + // find model + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); -// fprintf(stderr, "type %02X/%c\n", header->dgmType, header->dgmType); read_len = 2; rbytes = mfile_read(src, bp, read_len); @@ -537,7 +601,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) dgram_bytes += read_len; state = ST_MODEL_VALID; } else { - // invalid model, reset just after original start position + // invalid model, return to start state state = ST_START; } } @@ -546,9 +610,9 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) if(state == ST_MODEL_VALID) { // find ETX - // or exceed max datagram size + // or stop if max datagram size exceeded + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); -// fprintf(stderr, "frame_buf %p bp %p bp-frame_buf(%zd) fpos[%llu]\n", frame_buf, bp, (bp - frame_buf), mfile_seek(src, 0, MFILE_CUR)); petx = NULL; read_len = 1; @@ -581,15 +645,19 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) if(found_etx) { state = ST_ETX_VALID; } else { - // invalid ETX, reset just after original start position + // invalid ETX, return to start state state = ST_START; } } if( dgram_bytes >= MB_UDP_SIZE_MAX || - (bp - frame_buf) >= MB_UDP_SIZE_MAX){ + (bp - frame_buf) >= MB_UDP_SIZE_MAX) { + fprintf(stderr, "ERR - buffer length exceeded type (%02X) dgram_bytes(%zd) bp-frame_buf(%zd)\n", header->dgmType, dgram_bytes, (bp - frame_buf)); - // invalid ETX, reset just after original start position + + // buffer length or max datagram size exceeded + // return to start state + state = ST_START; break; } @@ -597,10 +665,11 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) } if(state == ST_ETX_VALID) { + + // read, validate checksum + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); -// fprintf(stderr, "frame_buf %p bp %p bp-frame_buf(%zd)\n", frame_buf, bp, (bp - frame_buf)); - // read checksum read_len = 2; rbytes = mfile_read(src, bp, read_len); unsigned int *pchk = NULL; @@ -615,11 +684,12 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) state = ST_ERROR; } + // calculate checksum (sum of bytes between STX and ETX, exclusive) + // and compare to datagram byte *pcs = pstx + 1; chksum = 0; while(pcs < petx){ chksum += *pcs; -// fprintf(stderr, "pcs %p petx %p *pcs %02X chksum %04X\n", pcs, petx, *pcs, chksum); pcs++; } @@ -628,7 +698,8 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) } else { found_chk = false; found_etx = false; - // keep looking for ETX + + // may have found ETX char in data, keep looking state = ST_MODEL_VALID; } dgram_bytes += read_len; @@ -640,38 +711,50 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) } if(state == ST_CHKSUM_VALID){ + + // datagram valid, publish to socket + MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); - // done, success - header->numBytesDgm = dgram_bytes; - MX_BPRINT( (cfg->verbose > 0), "validating frame len[%zd]\n", dgram_bytes); - if(validate(frame_buf, dgram_bytes, cfg)){ - size_t send_len = header->numBytesDgm; + header->numBytesDgm = (petx - frame_buf)-1;//dgram_bytes; + MX_BPRINT( (cfg->verbose > 0), "sending frame len[%zd/%04X] petx ofs[%zd/%04X] (%02X)\n", dgram_bytes, dgram_bytes, (petx-frame_buf), (petx-frame_buf), *petx); - ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); - if( status != send_len){ - int serr = errno; - fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); - } + // a LOG frame length is numBytesDgm+4, so you can read the length, + // then read that number of bytes. + // numBytesDgm should be the number of bytes from STX to the end of the footer + // a UDP frame length doesn't include the length field (4 bytes) + size_t send_len = header->numBytesDgm; + + ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); + + if( status != send_len){ + int serr = errno; + fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); } if(cfg->delay_ms > 0){ + // delay if set struct timespec delay_ms = { (time_t)(cfg->delay_ms / 1000), (long)(1000000L * (cfg->delay_ms % 1000UL)) }; nanosleep(&delay_ms, NULL); } + + // return to start state + fpos_start = mfile_seek(src, 0, MFILE_CUR); state = ST_START; } if(state == ST_ERROR){ - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); // error (EOF) fprintf(stderr, "ERR - EOF or buffer length exceeded; quitting\n"); break; } + + // update file pointer + file_cur = mfile_seek(src, 0, MFILE_CUR); } } // if EM710_UDP } diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 0c86bd33f..0b3dffce1 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -754,6 +754,7 @@ FILE *output_trn_fp = NULL; struct sockaddr_in em_sock_addr; socklen_t em_sock_len; +FILE *em_bin_log = NULL; typedef enum{RF_NONE=0,RF_FORCE_UPDATE=0x1,RF_RELEASE=0x2}mb_resource_flag_t; @@ -7191,6 +7192,8 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i fprintf(stderr, "%s connected fd %d %s:%d\n", __func__, sd, hostInterface, port); + em_bin_log = fopen("em710-raw.bin", "w+"); + // save the socket within the mb_io structure int *sd_ptr = NULL; status &= mb_mallocd(verbose, __FILE__, __LINE__, sizeof(sd), (void **)&sd_ptr, error); @@ -7285,6 +7288,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // frame buffer for byte-wise reads static byte *frame_buf = NULL; + static size_t frame_len = 0; static struct mbsys_simrad3_header *fb_phdr = NULL; static byte *fb_pread=NULL; static size_t bytes_read=0; @@ -7305,7 +7309,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, { if(read_frame) { - // read frame into buffer + // read frame into buffer memset(frame_buf, 0, MB_UDP_SIZE_MAX); fb_pread = frame_buf; @@ -7327,7 +7331,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, int errors = 0; // validate - uint16_t checksum = 0; + uint16_t sum = 0; byte *pstx = (byte *)&fb_phdr->dgmSTX; byte *petx = frame_buf + (header->numBytesDgm + 1); byte *cur = pstx + 1; @@ -7336,14 +7340,17 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, if(rbytes > 0 && rbytes <= MB_UDP_SIZE_MAX){ while(cur < petx){ - checksum += *cur; + sum += *cur; cur++; } - if(checksum != *pchk) - errors++; + if(sum != *pchk) { + MX_LPRINT(MBTRNPP, 3, "invalid checksum %04X/%04X\n", sum, *pchk); + errors++; + } switch(fb_phdr->dgmType){ case ALL_INSTALLATION_L: + case ALL_INSTALLATION_U: case ALL_REMOTE: case ALL_RUNTIME: case ALL_RAW_RANGE_BEAM_ANGLE: @@ -7355,11 +7362,15 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // is valid type break; default: + MX_LPRINT(MBTRNPP, 3, "invalid type x%02X\n", fb_phdr->dgmType); errors++; } } + frame_len = header->numBytesDgm + 4; frame_count++; + fwrite(frame_buf, frame_len, 1, em_bin_log); + fflush(em_bin_log); if(verbose >= 5 || verbose <= -5 ) em710_frame_show(frame_buf, verbose); @@ -7370,32 +7381,32 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, fb_pread = frame_buf; read_frame = false; read_err = false; - MX_LPRINT(MBTRNPP, 3, "read frame len[%zu]:\n",(size_t)rbytes); + MX_LPRINT(MBTRNPP, 3, "read frame len[%zu]\n", frame_len); } else { // frame invalid frame_invalid++; read_err = true; - MX_LPRINT(MBTRNPP, 3, "invalid frame rbytes[%zu] checksum[%hu/%hu]\n",(size_t)rbytes, checksum, *pchk); + MX_LPRINT(MBTRNPP, 3, "invalid frame len[%llu] sum[%hu/%04X] chksum[%hu/%04X]\n", frame_len, sum, sum, *pchk, *pchk); } } else { // read error frame_read_err++; read_err = true; - MX_LPRINT(MBTRNPP, 3, "mb1r_read_frame failed rbytes[%zu]\n",(size_t)rbytes); + MX_LPRINT(MBTRNPP, 3, "em710_read_frame failed rbytes[%lluu]\n", frame_len); } - MX_LPRINT(MBTRNPP, 2, "%s - read frame fd %3d len[%6u] n[%8llu] invalid[%8llu] read_err[%8llu] \n", __func__, *mbsp, rbytes, frame_count, frame_invalid, frame_read_err); + MX_LPRINT(MBTRNPP, 3, "%s - read frame fd %3d len[%6llu] n[%8llu] invalid[%8llu] read_err[%8llu] \n", __func__, *mbsp, frame_len, frame_count, frame_invalid, frame_read_err); } else { // there's a frame in the buffer - size_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; + size_t bytes_rem = frame_buf + frame_len - fb_pread; size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); - MX_LPRINT(MBTRNPP, 4, "reading framebuf size[%2zu] rlen[%2zu] rem[%6zu] err[%c]\n", (size_t)*size, readlen, bytes_rem, (read_err?'Y':'N')); + MX_LPRINT(MBTRNPP, 4, "reading framebuf size[%2zu] frame_len[%6zu] rem[%6zu] err[%c]\n", (size_t)*size, frame_len, bytes_rem, (read_err?'Y':'N')); } if(!read_err){ - int64_t bytes_rem = frame_buf + fb_phdr->numBytesDgm - fb_pread; + int64_t bytes_rem = frame_buf + frame_len - fb_pread; size_t readlen = (*size <= bytes_rem ? *size : bytes_rem); if(readlen > 0){ memcpy(buffer, fb_pread, readlen); @@ -7430,7 +7441,7 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, *size = (size_t)0; MST_METRIC_START(app_stats->stats->metrics[MBTPP_CH_MB_GETFAIL_XT], mtime_dtime()); - MX_LPRINT(MBTRNPP, 4, "read kemall UDP socket failed: sync_bytes[%d] status[%d] err[%d]\n",sync_bytes,status, *error); + MX_LPRINT(MBTRNPP, 4, "read em710raw UDP socket failed: sync_bytes[%d] status[%d] err[%d]\n",sync_bytes,status, *error); MST_COUNTER_INC(app_stats->stats->events[MBTPP_EV_EMBFRAMERD]); MST_COUNTER_ADD(app_stats->stats->status[MBTPP_STA_MB_SYNC_BYTES],sync_bytes); @@ -7490,6 +7501,7 @@ int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error) { fprintf(stderr, "dbg2 status: %d\n", status); } + fclose(em_bin_log); /* return */ return (status); } From bd4de34c2a44f19b1ab5349ef862c98241d4a41a Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 11:37:23 -0800 Subject: [PATCH 07/20] update comment --- src/mbtrnutils/mbtrnpp.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 0b3dffce1..b36268ae9 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -7316,7 +7316,8 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // read UDP datagram from the socket // returns number of bytes read or -1 error // UDP datagrams don't include 4-byte total size - // we'll calculate it and include it at the start of the buffer. + // but valid .ALL datagrams must include it. + // We'll calculate it and include it at the start of the buffer. if ( (rbytes = recvfrom(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0, (struct sockaddr *)&em_sock_addr, &em_sock_len)) >= 0) From 22506bee22d555898dd6c5fcf66da219894d4b7c Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 11:49:46 -0800 Subject: [PATCH 08/20] disable debug em710 frame logging --- src/mbtrnutils/mbtrnpp.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index b36268ae9..58ba2bb0c 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -7370,8 +7370,9 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, frame_len = header->numBytesDgm + 4; frame_count++; - fwrite(frame_buf, frame_len, 1, em_bin_log); - fflush(em_bin_log); + // write frame to log (debug only) +// fwrite(frame_buf, frame_len, 1, em_bin_log); +// fflush(em_bin_log); if(verbose >= 5 || verbose <= -5 ) em710_frame_show(frame_buf, verbose); From e83876514c83011091e479391f5d32b995c37808 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 11:59:53 -0800 Subject: [PATCH 09/20] disable debug em710 frame logging (compile using -DWITH_EM710_FRAME_LOG) --- src/mbtrnutils/mbtrnpp.c | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 58ba2bb0c..9cf798328 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -754,7 +754,11 @@ FILE *output_trn_fp = NULL; struct sockaddr_in em_sock_addr; socklen_t em_sock_len; + +#ifdef WITH_EM710_FRAME_LOG +// log em710 UDP frames (debug) FILE *em_bin_log = NULL; +#endif typedef enum{RF_NONE=0,RF_FORCE_UPDATE=0x1,RF_RELEASE=0x2}mb_resource_flag_t; @@ -7192,7 +7196,9 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i fprintf(stderr, "%s connected fd %d %s:%d\n", __func__, sd, hostInterface, port); +#ifdef WITH_EM710_FRAME_LOG em_bin_log = fopen("em710-raw.bin", "w+"); +#endif // save the socket within the mb_io structure int *sd_ptr = NULL; @@ -7371,8 +7377,10 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, frame_len = header->numBytesDgm + 4; frame_count++; // write frame to log (debug only) -// fwrite(frame_buf, frame_len, 1, em_bin_log); -// fflush(em_bin_log); +#ifdef WITH_EM710_FRAME_LOG + fwrite(frame_buf, frame_len, 1, em_bin_log); + fflush(em_bin_log); +#endif if(verbose >= 5 || verbose <= -5 ) em710_frame_show(frame_buf, verbose); @@ -7503,7 +7511,10 @@ int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error) { fprintf(stderr, "dbg2 status: %d\n", status); } +#ifdef WITH_EM710_FRAME_LOG fclose(em_bin_log); +#endif + /* return */ return (status); } From 75dc701d0bf41c52214c819e1807332af4988077 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 12:02:37 -0800 Subject: [PATCH 10/20] update help comment --- src/mbtrn/utils/em710pub.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index c2ee775b4..4586f4d68 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -56,14 +56,14 @@ static void s_parse_args(int argc, char **argv, app_cfg_t *cfg); static void s_show_help() { - char help_message[] = "\n publish em710 raw UDP data\n"; + char help_message[] = "\n publish em710 .ALL or UDP capture data (emulate M3 UDP output)\n"; char usage_message[] = "\n em710pub [options] file [file...]\n" "\n Options:\n" " --verbose=n : verbose output level\n" " --help : show this help message\n" " --host=s : host IP address or name\n" " --port=n : TCP/IP port\n" - " --format=s : log or udp\n" + " --format=s : log (.ALL file) or udp (M3 UDP stream capture)\n" " --delay=n : delay (msec)\n" "\n"; printf("%s",help_message); From 5aa979b1763d2aae238ba7e9e53ca545d97f3e1d Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 12:30:24 -0800 Subject: [PATCH 11/20] update comments --- src/mbtrn/utils/em710pub.c | 11 ++++++++--- src/mbtrnutils/mbtrnpp.c | 8 ++++++-- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index 4586f4d68..f15872b76 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -354,6 +354,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) read_len = header->numBytesDgm; if( (rbytes = mfile_read(src, frame_buf + fb_cur, read_len)) == read_len) { + // fb_cur points to byte AFTER footer fb_cur += read_len; if(cfg->verbose > 1){ @@ -368,12 +369,16 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) byte *pchk = petx + 1; // datagram valid, publish to socket - size_t send_len = fb_cur - 4;//header->numBytesDgm; + + // send length reflects all datagram bytes, less the numBytesDgm field + size_t send_len = fb_cur - 4; MX_BPRINT( (cfg->verbose > 0), "sending frame len[%zd/%04X] petx fbofs[%zd/%04X] (%02x) pchk fbofs[%zd/%04X] (%04X)\n", send_len, send_len, (petx-frame_buf), (petx-frame_buf), *petx, (pchk-frame_buf), (pchk-frame_buf), *((unsigned short *)pchk) ); + if(cfg->verbose > 4) frame_show(header, cfg); + // send frame starting starting at STX (omit numBytesDgm) ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); if( status != send_len){ @@ -722,8 +727,8 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // a LOG frame length is numBytesDgm+4, so you can read the length, // then read that number of bytes. - // numBytesDgm should be the number of bytes from STX to the end of the footer - // a UDP frame length doesn't include the length field (4 bytes) + // numBytesDgm reflects the number of bytes from STX to the end of the footer (inclusive). + // published UDP frames don't include the length field (4 bytes) size_t send_len = header->numBytesDgm; ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 9cf798328..7193b0174 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -7321,10 +7321,15 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, // read UDP datagram from the socket // returns number of bytes read or -1 error - // UDP datagrams don't include 4-byte total size + + // UDP datagrams don't include 4-byte size field (numBytesDgm), // but valid .ALL datagrams must include it. // We'll calculate it and include it at the start of the buffer. + // The datagram size field (numBytesDgm) reflects the number of bytes + // from STX to the end of the footer (inclusive). + // This enables it to be read, then + // used to read the remainder of the datagram, *including* the footer. if ( (rbytes = recvfrom(*mbsp, (void *) (frame_buf + 4), MB_UDP_SIZE_MAX, 0, (struct sockaddr *)&em_sock_addr, &em_sock_len)) >= 0) { @@ -7334,7 +7339,6 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, unsigned int *pDgmSize = (unsigned int *)frame_buf; *pDgmSize = rbytes; - int errors = 0; // validate From 850c361cdc194cbeefc12dd7135e97bbdc3af0d4 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 13:51:00 -0800 Subject: [PATCH 12/20] remove unused em710raw UDP code --- src/mbio/mbr_em710raw.c | 349 ---------------------------------------- 1 file changed, 349 deletions(-) diff --git a/src/mbio/mbr_em710raw.c b/src/mbio/mbr_em710raw.c index c79ce9782..047ea17c8 100644 --- a/src/mbio/mbr_em710raw.c +++ b/src/mbio/mbr_em710raw.c @@ -3961,355 +3961,6 @@ int mbr_em710raw_rd_wc(int verbose, void *mbio_ptr, int swap, struct mbsys_simra return (status); } /*--------------------------------------------------------------------*/ -int mbr_em710raw_rd_hdr(int verbose, char *buffer, void *header_ptr, void *emdgm_type_ptr, int *error) { - struct mbsys_simrad3_header *header = NULL; - mbsys_simrad3_emdgm_type *emdgm_type = NULL; - - int index = 0; - - if (verbose >= 2) { - fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); - fprintf(stderr, "dbg2 Input arguments:\n"); - fprintf(stderr, "dbg2 verbose: %d\n", verbose); - fprintf(stderr, "dbg2 buffer: %p\n", (void *)buffer); - fprintf(stderr, "dbg2 header_ptr: %p\n", (void *)header_ptr); - fprintf(stderr, "dbg2 emdgm_type_ptr: %p\n", (void *)emdgm_type_ptr); - } - - // get pointer to header structure - header = (struct mbsys_simrad3_header *)header_ptr; - emdgm_type = (mbsys_simrad3_emdgm_type *)emdgm_type_ptr; - - index = 0; - mb_get_binary_int(true, &buffer[index], &(header->numBytesDgm)); - index += 4; - header->dgmSTX = buffer[index]; - index ++; - header->dgmType = buffer[index]; - index ++; - mb_get_binary_short(true, &buffer[index], &(header->emModeNum)); - index += 2; - mb_get_binary_int(true, &buffer[index], &(header->date)); - index += 4; - mb_get_binary_int(true, &buffer[index], &(header->timeMs)); - index += 4; - mb_get_binary_short(true, &buffer[index], &(header->counter)); - index += 2; - mb_get_binary_short(true, &buffer[index], &(header->sysSerialNum)); - index += 2; - mb_get_binary_short(true, &buffer[index], &(header->secHeadSerialNum)); - index += 2; - - switch(header->dgmType){ - - - case ALL_UNKNOWN: - case ALL_INSTALLATION_U: - case ALL_INSTALLATION_L: - case ALL_REMOTE: - case ALL_RUNTIME: - case ALL_RAW_RANGE_BEAM_ANGLE: - case ALL_XYZ88: - case ALL_CLOCK: - case ALL_ATTITUDE: - case ALL_POSITION: - case ALL_SURFACE_SOUND_SPEED: - *emdgm_type = header->dgmType; - break; - default: - *emdgm_type = ALL_UNKNOWN; - break; - }; - - if (verbose >= 5) { - fprintf(stderr, "\ndbg5 Values read in MBIO function <%s>\n", __func__); - fprintf(stderr, "dbg5 numBytesDgm: %u\n", header->numBytesDgm); - } - - int status = MB_SUCCESS; - - if (verbose >= 2) { - fprintf(stderr, "\ndbg2 MBIO function <%s> completed\n", __func__); - fprintf(stderr, "dbg2 Return values:\n"); - fprintf(stderr, "dbg2 dgmType: %02x/%c\n", header->dgmType, header->dgmType); - fprintf(stderr, "dbg2 emdgm_type: %d\n", *emdgm_type); - fprintf(stderr, "dbg2 error: %d\n", *error); - fprintf(stderr, "dbg2 Return status:\n"); - fprintf(stderr, "dbg2 status: %d\n", status); - } - - /* return status */ - return (status); - -} - -//int mbr_em710raw_rd_udp_data(int verbose, void *mbio_ptr, void *store_ptr, int *error) -//{ -// int *databyteswapped; -// int record_size; -// int *record_size_save; -// int bytes_read; -// char *label; -// int *label_save_flag; -// char *record_size_char; -// bool *ignore_snippets; -// short type; -// short sonar; -// int *version; -// short *typelast; -// short *sonarlast; -// int *nbadrec; -// int good_end_bytes; -// size_t read_len; -// int skip = 0; -// int *num_sonars; -// char junk; -// -// if (verbose >= 2) { -// fprintf(stderr, "\ndbg2 MBIO function <%s> called\n", __func__); -// fprintf(stderr, "dbg2 Input arguments:\n"); -// fprintf(stderr, "dbg2 verbose: %d\n", verbose); -// fprintf(stderr, "dbg2 mbio_ptr: %p\n", (void *)mbio_ptr); -// fprintf(stderr, "dbg2 store_ptr: %p\n", (void *)store_ptr); -// } -// -// // get pointer to mbio descriptor -// struct mb_io_struct *mb_io_ptr = (struct mb_io_struct *)mbio_ptr; -// -// // get pointer to raw data structure -// struct mbsys_simrad3_struct *store = (struct mbsys_simrad3_struct *)store_ptr; -// int *mbsp = mb_io_ptr->mbsp; -// -// // get saved values -// databyteswapped = (int *)&mb_io_ptr->save1; -// record_size_save = (int *)&mb_io_ptr->save2; -// label = (char *)mb_io_ptr->save_label; -// version = (int *)(&mb_io_ptr->save3); -// label_save_flag = (int *)&mb_io_ptr->save_label_flag; -// typelast = (short *)&mb_io_ptr->save6; -// sonarlast = (short *)&mb_io_ptr->save7; -// nbadrec = (int *)&mb_io_ptr->save8; -// num_sonars = (int *)&mb_io_ptr->save10; -// record_size_char = (char *)&record_size; -// ignore_snippets = (bool *)&mb_io_ptr->save4; -// // *ignore_snippets = true; -// -// // set file position -//// mb_io_ptr->file_pos = mb_io_ptr->file_bytes; -// -// // set flag to swap bytes if necessary -// int swap = *databyteswapped; -// -// // if a ping structure was previously flagged as complete then reset the structure to empty -// for (int i = 0; i < MBSYS_SIMRAD3_NUM_PING_STRUCTURES; i++) { -// if (store->pings[i].read_status == MBSYS_SIMRAD3_PING_COMPLETE) { -// store->pings[i].read_status = MBSYS_SIMRAD3_PING_NO_DATA; -// store->pings[i].png_bath_read = false; -// store->pings[i].png_raw_read = false; -// store->pings[i].png_quality_read = false; -// store->pings[i].png_ss_read = false; -// } -// } -// -// int status = MB_SUCCESS; -// -// // loop over reading data until a record is ready for return -// *error = MB_ERROR_NO_ERROR; -// bool done = false; -// struct -// static unsigned char *dgm_buffer = NULL; -// char **bufferptr = NULL; -// char *buffer = NULL; -// size_t *bufferalloc = NULL; -// -// bufferptr = (char **)&mb_io_ptr->raw_data; -// bufferalloc = (size_t *)&mb_io_ptr->structure_size; -// buffer = (char *)*bufferptr; -// struct mbsys_simrad3_header header; -// mbsys_simrad3_emdgm_type emdgm_type; -// -// while (!done) { -// read_len = MB_UDP_SIZE_MAX; -// -// if (*bufferalloc <= read_len) { -// status = mb_reallocd(verbose, __FILE__, __LINE__, read_len, (void **)bufferptr, error); -// if (status != MB_SUCCESS) { -// *bufferalloc = 0; -// done = true; -// } -// else { -// buffer = (char *)*bufferptr; -// *bufferalloc = read_len; -// } -// } -// -// // read the next valid datagram -// memset(buffer, 0, read_len); -// read_len = *bufferalloc; -// status = mb_fileio_get(verbose, mbio_ptr, (void *)buffer, &read_len, error); -// -// // save datagram bytes read -// size_t dgm_bytes = read_len; -// -// if (status == MB_SUCCESS) { -// dgm_bytes = read_len; -// mb_io_ptr->file_pos += read_len; -// status = mbr_em710raw_rd_hdr(verbose, buffer, (void *)&header, (void *)&emdgm_type, error); -// store->time_d = 0; // TODO: parse time -// mb_get_date(verbose, store->time_d, store->time_i); -// } -// -// // datagram should be in buffer -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "\nabove mbr_em710raw_rd_data loop:\n"); -// fprintf(stderr, "label_save_flag:%d status:%d\n", *label_save_flag, status); -//#endif -// -// if (!*label_save_flag) { -// // set read len (same for both record body size and label) -// read_len = 4; -// -// // point cursor to start of datagram body -// unsigned char *cur = buffer + sizeof(mbsys_simrad3_header); -// // read record size -// memcpy(record_size, cur, read_len); -// // read label -// memcpy(label, (cur + read_len), read_len); -// status = MB_SUCCESS; -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], skip, status); -//#endif -// while (status == MB_SUCCESS && mbr_em710raw_chk_label(verbose, mbio_ptr, label, &type, &sonar) != -// MB_SUCCESS){ -// cur++; -// if( dgm_bytes - (cur - buffer) >= 2*read_len){ -// // stop if bytes remaining < (record_size + label) -// status = MB_ERROR_UNINTELLIGIBLE; -// continue; -// } else { -// status = MB_SUCCESS; -// } -// memcpy(record_size, cur, read_len); -// memcpy(label, (cur + read_len), read_len); -// skip++; -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], skip, status); -//#endif -// } -// // report problem -// if (skip > 0 && verbose > 0) { -// if (*nbadrec == 0) -// fprintf(stderr, "\nThe MBF_EM710RAW module skipped data between identified\n\ -//data records. Something is broken, most probably the data...\n\ -//However, the data may include a data record type that we\n\ -//haven't seen yet, or there could be an error in the code.\n\ -//If skipped data are reported multiple times, \n\ -//we recommend you send a data sample and problem \n\ -//description to the MB-System team \n\ -//(caress@mbari.org and dale@ldeo.columbia.edu)\n\ -//Have a nice day...\n"); -// fprintf(stderr, "MBF_EM710RAW skipped %d bytes between records %4.4hX:%d and %4.4hX:%d\n", skip, *typelast, -// *typelast, type, type); -// (*nbadrec)++; -// } -// -// *typelast = type; -// *sonarlast = sonar; -// -// // set flag to swap bytes if necessary -// swap = *databyteswapped; -// -// // get record_size -// if (*databyteswapped != mb_io_ptr->byteswapped) -// record_size = mb_swap_int(record_size); -// *record_size_save = record_size; -// -// } else { -// // use saved label -// *label_save_flag = false; -// type = *typelast; -// sonar = *sonarlast; -// record_size = *record_size_save; -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "use previously read label:%x%x%x%x skip:%d status:%d\n", label[0], label[1], label[2], label[3], -// skip, status); -//#endif -// } -// -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "\nstart of mbr_em710raw_rd_data loop:\n"); -// fprintf(stderr, "skip:%d type:%x sonar:%d recsize:%u done:%d\n", skip, type, sonar, *record_size_save, done); -//#endif -//#ifdef MBR_EM710RAW_DEBUG3 -// if (skip > 0) -// fprintf(stderr, "SKIPPED BYTES: %d\n", skip); -// fprintf(stderr, "type:%x sonar:%d recsize:%u done:%d ", type, sonar, *record_size_save, done); -//#endif -// -// // allocate secondary data structure for extraparameters data if needed -// if (status == MB_SUCCESS && (type == EM3_EXTRAPARAMETERS) && store->extraparameters == NULL) { -// status = mbsys_simrad3_extraparameters_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for heading data if needed -// if (status == MB_SUCCESS && (type == EM3_HEADING) && store->heading == NULL) { -// status = mbsys_simrad3_heading_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for attitude data if needed -// if (status == MB_SUCCESS && (type == EM3_ATTITUDE) && store->attitude == NULL) { -// status = mbsys_simrad3_attitude_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for netattitude data if needed -// if (status == MB_SUCCESS && (type == EM3_NETATTITUDE) && store->netattitude == NULL) { -// status = mbsys_simrad3_netattitude_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for ssv data if needed -// if (status == MB_SUCCESS && (type == EM3_SSV) && store->ssv == NULL) { -// status = mbsys_simrad3_ssv_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for tilt data if needed -// if (status == MB_SUCCESS && (type == EM3_TILT) && store->tilt == NULL) { -// status = mbsys_simrad3_tilt_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// // allocate secondary data structure for water column data if needed -// if (status == MB_SUCCESS && (type == EM3_WATERCOLUMN)) { -// if (store->wc == NULL) -// status = mbsys_simrad3_wc_alloc(verbose, mbio_ptr, store_ptr, error); -// } -// -// -// // read the appropriate data records -// if (status == MB_FAILURE) { -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "call nothing, read failure\n"); -//#endif -// done = true; -// record_size = 0; -// *record_size_save = record_size; -// } -// else if (type != EM3_PU_ID && type != EM3_PU_STATUS && type != EM3_PU_BIST && type != EM3_EXTRAPARAMETERS && -// type != EM3_ATTITUDE && type != EM3_CLOCK && type != EM3_BATH && type != EM3_SBDEPTH && type != EM3_RAWBEAM && -// type != EM3_SSV && type != EM3_HEADING && type != EM3_START && type != EM3_TILT && type != EM3_CBECHO && -// type != EM3_RAWBEAM4 && type != EM3_QUALITY && type != EM3_POS && type != EM3_RUN_PARAMETER && type != EM3_SS && -// type != EM3_TIDE && type != EM3_SVP2 && type != EM3_SVP && type != EM3_SSPINPUT && type != EM3_BATH2 && -// type != EM3_SS2 && type != EM3_RAWBEAM2 && type != EM3_RAWBEAM3 && type != EM3_HEIGHT && type != EM3_STOP && -// type != EM3_WATERCOLUMN && type != EM3_NETATTITUDE && type != EM3_REMOTE && type != EM3_SSP && -// type != EM3_BATH_MBA && type != EM3_SS_MBA && type != EM3_BATH2_MBA && type != EM3_SS2_MBA && -// type != EM3_BATH3_MBA) { -//#ifdef MBR_EM710RAW_DEBUG -// fprintf(stderr, "call nothing, try again\n"); -//#endif -// done = false; -// } -// -// } // while(!done) -//} - /*--------------------------------------------------------------------*/ int mbr_em710raw_rd_data(int verbose, void *mbio_ptr, void *store_ptr, int *error) { int *databyteswapped; int record_size; From 075e77f6907682f5f47d7a9e34034ccf18807dd8 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 14:02:40 -0800 Subject: [PATCH 13/20] update comments --- src/mbtrn/utils/em710pub.c | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index f15872b76..9bb808795 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -333,6 +333,10 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) if(cfg->fmt == EM710_LOG) { + // records are .ALL format + // read the datagrams and publish them + // as UDP frames (w/o the numBytesDgm field) + struct mbsys_simrad3_header *header = (struct mbsys_simrad3_header *)frame_buf; // iterate over file to find valid datagrams @@ -355,6 +359,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) if( (rbytes = mfile_read(src, frame_buf + fb_cur, read_len)) == read_len) { // fb_cur points to byte AFTER footer + // i.e. fb_cur - frame_buf = total frame bytes (including size field) fb_cur += read_len; if(cfg->verbose > 1){ @@ -379,7 +384,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) frame_show(header, cfg); // send frame starting starting at STX (omit numBytesDgm) - ssize_t status = send(cfg->sock_fd, frame_buf + 4, send_len, 0); + ssize_t status = send(cfg->sock_fd, (frame_buf + 4), send_len, 0); if( status != send_len){ fprintf(stderr, "ERR - send failed ret[%zd] %d/%s\n", status, errno, strerror(errno)); From 36d1d9a2b109b80cacdd6c971d1352abda20e628 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 14:35:30 -0800 Subject: [PATCH 14/20] update em710pub debug output (shift some output to more verbose); implement separate em710 frame logging in ALL and/or UDP formats using WITH_EM710_ALL_LOG, WITH_EM710_UDP_LOG --- src/mbtrn/utils/em710pub.c | 12 ++++++------ src/mbtrnutils/mbtrnpp.c | 38 ++++++++++++++++++++++++++++---------- 2 files changed, 34 insertions(+), 16 deletions(-) diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/em710pub.c index 9bb808795..640e77847 100644 --- a/src/mbtrn/utils/em710pub.c +++ b/src/mbtrn/utils/em710pub.c @@ -471,7 +471,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // find STX (datagram start) - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); // initialize state memset(frame_buf, 0, MB_UDP_SIZE_MAX); @@ -530,7 +530,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // find datagram type - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); read_len = 1; rbytes = mfile_read(src, bp, read_len); @@ -581,7 +581,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // find model - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); read_len = 2; rbytes = mfile_read(src, bp, read_len); @@ -622,7 +622,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // find ETX // or stop if max datagram size exceeded - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); petx = NULL; read_len = 1; @@ -678,7 +678,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // read, validate checksum - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); read_len = 2; rbytes = mfile_read(src, bp, read_len); @@ -724,7 +724,7 @@ static void pub_file(mfile_file_t *src, app_cfg_t *cfg) // datagram valid, publish to socket - MX_BPRINT( (cfg->verbose > 0), "state %s\n", st_names[state]); + MX_BPRINT( (cfg->verbose > 3), "state %s\n", st_names[state]); header->numBytesDgm = (petx - frame_buf)-1;//dgram_bytes; MX_BPRINT( (cfg->verbose > 0), "sending frame len[%zd/%04X] petx ofs[%zd/%04X] (%02X)\n", dgram_bytes, dgram_bytes, (petx-frame_buf), (petx-frame_buf), *petx); diff --git a/src/mbtrnutils/mbtrnpp.c b/src/mbtrnutils/mbtrnpp.c index 7193b0174..de2c0b4c3 100644 --- a/src/mbtrnutils/mbtrnpp.c +++ b/src/mbtrnutils/mbtrnpp.c @@ -755,9 +755,15 @@ FILE *output_trn_fp = NULL; struct sockaddr_in em_sock_addr; socklen_t em_sock_len; -#ifdef WITH_EM710_FRAME_LOG -// log em710 UDP frames (debug) -FILE *em_bin_log = NULL; +#ifdef WITH_EM710_ALL_LOG +// log em710 frames (debug) +FILE *em_all_log = NULL; +const char *em_all_name="em-all.bin"; +#endif + +#ifdef WITH_EM710_UDP_LOG +FILE *em_udp_log = NULL; +const char *em_udp_name="em-udp.bin"; #endif typedef enum{RF_NONE=0,RF_FORCE_UPDATE=0x1,RF_RELEASE=0x2}mb_resource_flag_t; @@ -7196,8 +7202,11 @@ int mbtrnpp_em710raw_input_open(int verbose, void *mbio_ptr, char *definition, i fprintf(stderr, "%s connected fd %d %s:%d\n", __func__, sd, hostInterface, port); -#ifdef WITH_EM710_FRAME_LOG - em_bin_log = fopen("em710-raw.bin", "w+"); +#ifdef WITH_EM710_ALL_LOG + em_all_log = fopen(em_all_name, "w+"); +#endif +#ifdef WITH_EM710_UDP_LOG + em_all_log = fopen(em_udp_name, "w+"); #endif // save the socket within the mb_io structure @@ -7381,9 +7390,15 @@ int mbtrnpp_em710raw_input_read(int verbose, void *mbio_ptr, size_t *size, frame_len = header->numBytesDgm + 4; frame_count++; // write frame to log (debug only) -#ifdef WITH_EM710_FRAME_LOG - fwrite(frame_buf, frame_len, 1, em_bin_log); - fflush(em_bin_log); +#ifdef WITH_EM710_ALL_LOG + // write .ALL frame + fwrite(frame_buf, frame_len, 1, em_all_log); + fflush(em_all_log); +#endif +#ifdef WITH_EM710_UDP_LOG + // write UDP frame + fwrite(frame_buf+4, frame_len-4, 1, em_udp_log); + fflush(em_udp_log); #endif if(verbose >= 5 || verbose <= -5 ) @@ -7515,8 +7530,11 @@ int mbtrnpp_em710raw_input_close(int verbose, void *mbio_ptr, int *error) { fprintf(stderr, "dbg2 status: %d\n", status); } -#ifdef WITH_EM710_FRAME_LOG - fclose(em_bin_log); +#ifdef WITH_EM710_ALL_LOG + fclose(em_all_log); +#endif +#ifdef WITH_EM710_UDP_LOG + fclose(em_udp_log); #endif /* return */ From 8bced69479ef47ad83a3df937b3f4b94a3a5fda1 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Mon, 4 Mar 2024 17:01:48 -0800 Subject: [PATCH 15/20] fix build issue: add TIRPC find package logic to CMakeLists for em710pub.c --- src/mbtrn/CMakeLists.txt | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/mbtrn/CMakeLists.txt b/src/mbtrn/CMakeLists.txt index d4adcb9bc..61de3be62 100644 --- a/src/mbtrn/CMakeLists.txt +++ b/src/mbtrn/CMakeLists.txt @@ -45,6 +45,13 @@ #. mb1-cli # message("In src/mbtrn") + +if(CMAKE_SYSTEM_NAME STREQUAL Linux) + find_package(TIRPC REQUIRED) +else() + add_library(TIRPC::TIRPC INTERFACE IMPORTED) +endif() + add_compile_definitions( HAVE_CONFIG_H _GNU_SOURCE @@ -174,7 +181,7 @@ add_executable(empub utils/em710pub.c) target_include_directories(empub PRIVATE ${CMAKE_SOURCE_DIR}/src/mbtrnframe ${CMAKE_SOURCE_DIR}/src/mbio ${CMAKE_SOURCE_DIR}/src/mbtrnutils) -target_link_libraries(empub PRIVATE mbtrnframe m pthread) +target_link_libraries(empub PRIVATE TIRPC::TIRPC mbtrnframe m pthread) # #------------------------------------------------------------------------------ # From adac59dff5f47ed05a1b15f82b821b73f421bce2 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Tue, 5 Mar 2024 08:28:40 -0800 Subject: [PATCH 16/20] rename em710pub.c and empub target to emallpub.c and emallpub for consistency --- src/mbtrn/CMakeLists.txt | 8 ++++---- src/mbtrn/utils/{em710pub.c => emallpub.c} | 0 2 files changed, 4 insertions(+), 4 deletions(-) rename src/mbtrn/utils/{em710pub.c => emallpub.c} (100%) diff --git a/src/mbtrn/CMakeLists.txt b/src/mbtrn/CMakeLists.txt index 61de3be62..a42ebff23 100644 --- a/src/mbtrn/CMakeLists.txt +++ b/src/mbtrn/CMakeLists.txt @@ -177,17 +177,17 @@ target_link_libraries(mb1-cli PRIVATE mbtrnframe mb1r mb1 m pthread) # #------------------------------------------------------------------------------ # -add_executable(empub utils/em710pub.c) -target_include_directories(empub PRIVATE ${CMAKE_SOURCE_DIR}/src/mbtrnframe +add_executable(emallpub utils/emallpub.c) +target_include_directories(emallpub PRIVATE ${CMAKE_SOURCE_DIR}/src/mbtrnframe ${CMAKE_SOURCE_DIR}/src/mbio ${CMAKE_SOURCE_DIR}/src/mbtrnutils) -target_link_libraries(empub PRIVATE TIRPC::TIRPC mbtrnframe m pthread) +target_link_libraries(emallpub PRIVATE TIRPC::TIRPC mbtrnframe m pthread) # #------------------------------------------------------------------------------ # install(TARGETS r7kr mb1r DESTINATION ${CMAKE_INSTALL_LIBDIR}) # -install(TARGETS udps udpc mbtnav_cli stream7k emu7k r7kr_test trnc tbinx mb1conv mb12csv mb1r_test mb1-cli empub DESTINATION ${CMAKE_INSTALL_BINDIR}) +install(TARGETS udps udpc mbtnav_cli stream7k emu7k r7kr_test trnc tbinx mb1conv mb12csv mb1r_test mb1-cli emallpub DESTINATION ${CMAKE_INSTALL_BINDIR}) # #------------------------------------------------------------------------------ # diff --git a/src/mbtrn/utils/em710pub.c b/src/mbtrn/utils/emallpub.c similarity index 100% rename from src/mbtrn/utils/em710pub.c rename to src/mbtrn/utils/emallpub.c From ea1774f25a3f5ed33d661655b3c3d60228411453 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Wed, 6 Mar 2024 13:08:24 -0800 Subject: [PATCH 17/20] handle --help option --- src/mbtrn/utils/emallpub.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/mbtrn/utils/emallpub.c b/src/mbtrn/utils/emallpub.c index 640e77847..5eefd396b 100644 --- a/src/mbtrn/utils/emallpub.c +++ b/src/mbtrn/utils/emallpub.c @@ -215,6 +215,9 @@ static void s_parse_args(int argc, char **argv, app_cfg_t *cfg) fprintf(stderr,"ERR - no input files\n"); } + if(help) { + s_show_help(); + } } static void frame_show(struct mbsys_simrad3_header *header, app_cfg_t *cfg) From 3c0d6dc110642f3a1ece249207459ef3fb5471cb Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Wed, 6 Mar 2024 13:49:37 -0800 Subject: [PATCH 18/20] fix docker build error for alpine image on ubuntu 22.04 host (uint8_t not defined) --- src/mbtrnav/terrain-nav/TrnLog.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mbtrnav/terrain-nav/TrnLog.cpp b/src/mbtrnav/terrain-nav/TrnLog.cpp index 7de77ba83..60228c33b 100644 --- a/src/mbtrnav/terrain-nav/TrnLog.cpp +++ b/src/mbtrnav/terrain-nav/TrnLog.cpp @@ -9,6 +9,7 @@ // #include "structDefs.h" #include "TrnLog.h" +#include #define _STR(x) #x #define STR(x) _STR(x) From efb2e984c4f415d0616bb7b1e8906b6f98034860 Mon Sep 17 00:00:00 2001 From: Kent Headley Date: Wed, 6 Mar 2024 14:11:59 -0800 Subject: [PATCH 19/20] move header order --- src/mbtrnav/terrain-nav/TrnLog.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mbtrnav/terrain-nav/TrnLog.cpp b/src/mbtrnav/terrain-nav/TrnLog.cpp index 60228c33b..f070d614b 100644 --- a/src/mbtrnav/terrain-nav/TrnLog.cpp +++ b/src/mbtrnav/terrain-nav/TrnLog.cpp @@ -7,9 +7,9 @@ // //////////////////////////////////////////////////////////////////////////////// // +#include #include "structDefs.h" #include "TrnLog.h" -#include #define _STR(x) #x #define STR(x) _STR(x) From b027b5c02145da53663d5061a0be0e64943b2c45 Mon Sep 17 00:00:00 2001 From: David Caress Date: Sat, 9 Mar 2024 23:57:05 -0800 Subject: [PATCH 20/20] Update ChangeLog.html --- ChangeLog.html | 846 +++++++++++++++++++++++++------------------------ 1 file changed, 440 insertions(+), 406 deletions(-) diff --git a/ChangeLog.html b/ChangeLog.html index ca79c9336..1773bb3dd 100644 --- a/ChangeLog.html +++ b/ChangeLog.html @@ -360,6 +360,7 @@

MB-System Version 5.8 Releases and Release Notes:


    +
  • Version 5.8.1beta08 March 10, 2024
  • Version 5.8.1beta07 February 24, 2024
  • Version 5.8.1beta04 February 16, 2024
  • Version 5.8.1beta03 February 8, 2024
  • @@ -370,29 +371,62 @@

    MB-System Version 5.8 Releases and Release Notes:


    -

    5.8.1beta07 (February 24, 2024)

    +

    5.8.1beta08 (March 10, 2024)

    + +

    Mbm_grdplot: Added colortable 10, which runs from blue to red and can be used for +plots of seismic reflection or subbottom profiler data when the trace signals are +both positive or negative.

    + +

    SEGY format data: Changed MB-System SEGY traceheader to include a sensordepthtime +float value in bytes 216-219. This will be used to hold the two-way traveltime in +seconds corresponding to the source depth assuming a 1500 m/sec water sound speed. +This value can be used as a trace start delay time in plotting to account for the +source location of subbottom profiler data collected from submerged platforms like +AUVs and ROVs. The MB-System programs mbsegygrid and mbm_grdplot use the source +depth value in meters, but some external packages need the delay time.

    + +

    SEGY format data: MB-System now recognizes file suffixes *.sgy and *.SGY in addition +to *.segy *.SEGY *.seg and *.SEG

    + +

    Mbsegyinfo: Fixed calculation and reporting of trace minimum and maximum values.

    + +

    Mbextractsegy: Now allows output of subbottom analytic data as well as envelope data. +Use of the -S4 command will output three separate segy files, one with the envelope +function, one with the subbottom correlate, and one with the correlate conjugant +(i.e. the Hilbert transform of the correlate). The section plot script generated now +will create plots of all three trace types.

    + +

    Mbpreprocess and mbprocess: Now support merging navigation and attitude from Schmidt +Ocean Institute RVDAS format ROV navigation.

    + +

    Mbpreprocess and format MBFEM710RAW (58): The command --kluge-auv-sentry-sensordepth +now works for format 58 files (3rd generation Kongsberg multibeam data in *.all files) +such that available sensordepth values are embedded in the output format MBFEM710MBA +(59) files.

    + +

    5.8.1beta07 (February 24, 2024)

    CMake build system: Fixed ability to set OTPS location in cmake build system.

    CMake build system: Added installation of header files required for external programs to utilize MB-System libraries.

    -

    5.8.1beta04 (February 16, 2024)

    +

    5.8.1beta04 (February 16, 2024)

    Format 261 (MBF_KEMKMALL): Updated support for Kongsberg Kmall format to match updated specification J.

    -

    5.8.1beta03 (February 8, 2024)

    +

    5.8.1beta03 (February 8, 2024)

    Mbphotomosaic: Fixed priority-heading option that allows image prioritization on the basis of camera heading.

    -

    5.8.1beta02 (February 7, 2024)

    +

    5.8.1beta02 (February 7, 2024)

    Mbphotomosaic: Added options to detect and correct dark images (for when strobe lights partially drop out), to ignore dark images, and to allow image prioritization on the basis of camera heading.

    -

    5.8.1beta01 (February 1, 2024)

    +

    5.8.1beta01 (February 1, 2024)

    Mbpreprocess: Now checks for successive pings/scans with the same timestamp, and adds enough time to the second timestamp (0.0000033 seconds) that these pings/scans @@ -404,7 +438,7 @@

    5.8.1beta01 (February 1, 2024)

    files were ignored. Also fixed a non-initialized pointer bug that produced occasional crashes.

    -

    5.8.0 (January 22, 2024)

    +

    5.8.0 (January 22, 2024)

    Version 5.8.0 is now the current release of MB-System.

    @@ -427,7 +461,7 @@

    5.8.0 (January 22, 2024)


    -

    MB-System Version 5.7 Releases and Release Notes:

    +

    MB-System Version 5.7 Releases and Release Notes:


    @@ -578,7 +612,7 @@

    MB-System Version 5.7 Releases and Release Notes:


    -

    5.7.9beta72 (January 13, 2024)

    +

    5.7.9beta72 (January 13, 2024)

    Build Systems: Made building and installing deprecated programs optional for both the CMake and Autoconf build systems.

    @@ -590,13 +624,13 @@

    5.7.9beta72 (January 13, 2024)

    Mbm_route2mission: Now works with both old and new format route files.

    -

    5.7.9beta71 (January 3, 2024)

    +

    5.7.9beta71 (January 3, 2024)

    CMake build system: Fixed creating the levitus.h header file used by mblevitus and mbconfig to define the location of the Levitus database and the OTPS installation, thereby making mblevitus and mbconfig work properly.

    -

    5.7.9beta70 (January 2, 2024)

    +

    5.7.9beta70 (January 2, 2024)

    Mblist: Added capability to output beam travel times, angles and other values needed to recaclulate bathymetry by raytracing.

    @@ -606,7 +640,7 @@

    5.7.9beta70 (January 2, 2024)

    was faulty, so an incorrect roll value was used in calculating the beam raytracing takeoff angles.

    -

    5.7.9beta69 (December 17, 2023)

    +

    5.7.9beta69 (December 17, 2023)

    Format 192 (MBF_IMAGEMBA): Fixed correction of beam amplitude values (previously corrected values were not successfully inserted into the data structure).

    @@ -622,7 +656,7 @@

    5.7.9beta69 (December 17, 2023)

    Mbsslayout: Fixed bug in which a command to swap the starboard and port sidescan channels was ignored.

    -

    5.7.9beta68 (November 30, 2023)

    +

    5.7.9beta68 (November 30, 2023)

    CMake build system: It turns out that the GSF i/o module was not getting built and used by default. The build system has been fixed so that the GSF format i/o module @@ -634,11 +668,11 @@

    5.7.9beta68 (November 30, 2023)

    Mbtrnpp: Fixed use of covariances from TRN: to get x y z covariances use covariance[2], covariance[0], covariance[5] rather than 0, 1, and 2.

    -

    5.7.9beta66 (November 18, 2023)

    +

    5.7.9beta66 (November 18, 2023)

    Mbdatalist: Fixed an unitialized string causing intermittent failure.

    -

    5.7.9beta65 (November 17, 2023)

    +

    5.7.9beta65 (November 17, 2023)

    Mbinfo and mblist: Fixed bug introduced with the alternate navigation capability that caused mbinfo and mblist to fail when running on single files rather than through datalists.

    @@ -656,7 +690,7 @@

    5.7.9beta65 (November 17, 2023)

    CMake build system: Fixed the unit testing, and enabled building unit tests by default. After "make all" is run, the unit tests can be run with "make test".

    -

    5.7.9beta64 (November 16, 2023)

    +

    5.7.9beta64 (November 16, 2023)

    Reading GMT grids: Fixed a very significant bug that caused GMT grids to be read into memory incorrectly by mbreadgmtgrd() in src/mbaux/mbreadwritegrd.c. The problem was @@ -666,7 +700,7 @@

    5.7.9beta64 (November 16, 2023)

    the problem came when the grids were read in by mbgrdviz, mbanglecorrect, mbprocess, and mbnavadjust.

    -

    5.7.9beta63 (November 10, 2023)

    +

    5.7.9beta63 (November 10, 2023)

    Further fixes to the CMake build system, which now actually builds all components of MB-System on MacOs Ventura, Debian 11 and 12, and Ubuntu 20 and 22.

    @@ -675,14 +709,14 @@

    5.7.9beta63 (November 10, 2023)

    files CMakeLists.txt and configure.ac into src/mbio/mb_define.h so that there is only one place to edit the versioning.

    -

    5.7.9beta62 (November 3, 2023)

    +

    5.7.9beta62 (November 3, 2023)

    Fixed the Cmake build system so that all components of the current MB-System source can be built, installed, and run on MacOs using CMake.

    Updated the copyright notices in the several hundred source files.

    -

    5.7.9beta61 (November 2, 2023)

    +

    5.7.9beta61 (November 2, 2023)

    Read functions mbgetall(), mbget(), mbread(): Fixed bug in handling the vertical dimension while applying alternate navigation. Bathymetry were being corrected wrongly for changes @@ -698,7 +732,7 @@

    5.7.9beta61 (November 2, 2023)

    Configure.ac and Configure: Modified to find Proj on CentOs 7 systems.

    -

    5.7.9beta60 (October 22, 2023)

    +

    5.7.9beta60 (October 22, 2023)

    Mbnavadjust: Added an application or use mode to MBnavadjust projects. Projects can now be primary, secondary, or tertiary, with the setting found in the Controls diaglog brought up @@ -779,7 +813,7 @@

    5.7.9beta60 (October 22, 2023)

    existing other programs at this time. We will likely simplify the API at some point in the future when the consequences of an API change are understood and manageable.

    -

    5.7.9beta59 (September 19, 2023)

    +

    5.7.9beta59 (September 19, 2023)

    Mbnavadjustmerge: Made copying of mbnavadjust projects more efficient.

    @@ -790,7 +824,7 @@

    5.7.9beta59 (September 19, 2023)

    Mbcontour: Fixed drawing of survey tracklines - restored to generate thin lines.

    -

    5.7.9beta58 (August 30, 2023)

    +

    5.7.9beta58 (August 30, 2023)

    Mbm_route2mission: Modifications to accomodate changes to Dorado AUV vehicle software.

    @@ -819,7 +853,7 @@

    5.7.9beta58 (August 30, 2023)

    Mbnavadjustmerge: Copying mbnavadjust projects is much more efficient due to use of a fast file copy function replacing a shell call of the program cp.

    -

    5.7.9beta57 (June 27, 2023)

    +

    5.7.9beta57 (June 27, 2023)

    Mbm_route2mission: Added -T option to embed use of Terrain Relative Navigation in MBARI Mapping AUV missions.

    @@ -829,7 +863,7 @@

    5.7.9beta57 (June 27, 2023)

    Mbnavadjust: Fixed bug in the inversion algorithm.

    -

    5.7.9beta53 (June 15, 2023)

    +

    5.7.9beta53 (June 15, 2023)

    Rewrote the CMake build system based on the work of both Tom O'Reilly and Josch. This build system now works on MacOs Ventura. We will continue to augment and test using @@ -869,7 +903,7 @@

    5.7.9beta53 (June 15, 2023)

    Formats 56 (MBFEM300RAW) and 57 (MBFEM300MBA): Fixed catastrophic bug introduced in 5.7.9beta50 that treated many signed values (like acrosstrack distance) as unsigned.

    -

    5.7.9beta52 (March 9, 2023)

    +

    5.7.9beta52 (March 9, 2023)

    Formats 56 (MBFEM300RAW) and 57 (MBFEM300MBA): Fixed catastrophic bug introduced in 5.7.9beta50 that treated many signed values (like acrosstrack distance) as unsigned.

    @@ -887,11 +921,11 @@

    5.7.9beta52 (March 9, 2023)

    start survey behavior alone, and 2 for start survey plus a magnetometer calibration maneuver.

    -

    5.7.9beta51 (February 14, 2023)

    +

    5.7.9beta51 (February 14, 2023)

    Format 89 (MBF_RESON7k3): Removed debug message inadvertently left active in 5.7.9beta50.

    -

    5.7.9beta50 (February 12, 2023)

    +

    5.7.9beta50 (February 12, 2023)

    General: Changed many sprintf() calls to snprintf() calls.

    @@ -910,7 +944,7 @@

    5.7.9beta50 (February 12, 2023)

    been corrected for roll and pitch, and to be consistent with the most recent Hypack users manual released February 2023.

    -

    5.7.9beta49 (January 22, 2023)

    +

    5.7.9beta49 (January 22, 2023)

    Mbmgrdplot, mbmgrd3dplot, mbmhistplot, mbmplot, mbm_xyplot: Made evince one of the default Postscript viewers because it is commonly installed on Ubuntu @@ -944,7 +978,7 @@

    5.7.9beta49 (January 22, 2023)

    Format MBF_MBARIROV (165): Added recognition for new filenaming conventions for MBARI ROV navigation files.

    -

    5.7.9beta48 (December 16, 2022)

    +

    5.7.9beta48 (December 16, 2022)

    Mbmosaic: Fixed parsing of the -Yprioritysource option when prioritysource is a filename.

    @@ -964,7 +998,7 @@

    5.7.9beta48 (December 16, 2022)

    Mbnavadjust: Fixed interpolation of global ties to create the starting navigation model during inversions. Fixed several actions in section and reference grid mode.

    -

    5.7.9beta47 (November 15, 2022)

    +

    5.7.9beta47 (November 15, 2022)

    Mbnavadjust: Individual survey grids are now sized to the region of those surveys rather than the entire project. When the individual surveys are @@ -974,12 +1008,12 @@

    5.7.9beta47 (November 15, 2022)

    Mbnavadjustmerge: Added options set the mode (XYZ vs XY vs Z) of all global ties.

    -

    5.7.9beta46 (November 11, 2022)

    +

    5.7.9beta46 (November 11, 2022)

    Mbnavadjust: Added ability to import and use multiple reference grids for picking global ties of individual swath data sections.

    -

    5.7.9beta45 (November 6, 2022)

    +

    5.7.9beta45 (November 6, 2022)

    FNV files: The fast navigation or *.fnv files are created as ancillary files allowing navigation to be read without reading the full swath files. The *.fnv @@ -1020,7 +1054,7 @@

    5.7.9beta45 (November 6, 2022)

    Mbprocess: Modified the threaded processing function process_file() so that each instance carries a thread id that can be checked during debugging.

    -

    5.7.9beta44 (August 9, 2022)

    +

    5.7.9beta44 (August 9, 2022)

    Mbphotomosaic: Fixed problem in which an image correction model from mbgetphotocorrection was read but not applied.

    @@ -1028,7 +1062,7 @@

    5.7.9beta44 (August 9, 2022)

    Mbeditviz: Fixed display of beam info when picking in info mode in the 3D soundings display.

    -

    5.7.9beta43 (July 29, 2022)

    +

    5.7.9beta43 (July 29, 2022)

    Mblist and mbnavlist: Fixed failure to deallocate proj object.

    @@ -1055,7 +1089,7 @@

    5.7.9beta43 (July 29, 2022)

    that will provide an alternative to the existing AutoTools based build system. Updated documentation for both build systems is not included yet.

    -

    5.7.9beta42 (June 26, 2022)

    +

    5.7.9beta42 (June 26, 2022)

    Format 261 (MBF_KEMKMALL): Fixed bug in handling beam amplitude data from null beams.

    @@ -1066,18 +1100,18 @@

    5.7.9beta42 (June 26, 2022)

    linear interpolation of global ties to create a starting model for the inversion. Fixed picking on tie offsets in the modelplot window.

    -

    5.7.9beta41 (June 22, 2022)

    +

    5.7.9beta41 (June 22, 2022)

    Mbm_makedatalist: Fixed to work with *.kmall files, and added -Bsize option to impose a size threshold for files included in the output datalist.

    TRN: Several fixes to the TRN (terrain relative navigation) capability.

    -

    5.7.9beta40 (June 18, 2022)

    +

    5.7.9beta40 (June 18, 2022)

    Mbtrnpp: Fixed decimation algorithm more so it doesn't crash in Linux.

    -

    5.7.9beta38 (June 18, 2022)

    +

    5.7.9beta38 (June 18, 2022)

    Mbtrnpp: Added option --auv-sentry-em2040 to configuration file and command line options in order to enable use of the special pressure depth encoding in EM2040 @@ -1086,13 +1120,13 @@

    5.7.9beta38 (June 18, 2022)

    EM2040 multibeam either in realtime or playback modes this option must now be specified.

    -

    5.7.9beta37 (June 17, 2022)

    +

    5.7.9beta37 (June 17, 2022)

    Mbtrnpp: Fixed decimation algorithm.

    Mbgrdtilemaker: Fixed building of this new tool.

    -

    5.7.9beta36 (June 15, 2022)

    +

    5.7.9beta36 (June 15, 2022)

    Mbgrdviz: Fixed export of Risi survey scripts from routes.

    @@ -1102,7 +1136,7 @@

    5.7.9beta36 (June 15, 2022)

    Mbgrdtilemaker: Now copies the source background grid into the directory containing the octree tiles with the name source_grid.grd.

    -

    5.7.9beta35 (June 13, 2022)

    +

    5.7.9beta35 (June 13, 2022)

    Mbtrnpp: Added options to set the TRN search area on the command line and in cfg files. Fixed wrapper script mbtrnpp.sh so that the number of cycles @@ -1118,25 +1152,25 @@

    5.7.9beta35 (June 13, 2022)

    reference grid in a projected coordinate system (like UTM). This tileset can be used by mbtrnpp.

    -

    5.7.9beta34 (June 5, 2022)

    +

    5.7.9beta34 (June 5, 2022)

    Mbtrnpp and other elements of the Terrain Relative Navigation infrastructure: Augment mbtrnpp command set to include new commands for forced TRN resets with specified starting navigation offsets and particle filter spread size.

    -

    5.7.9beta33 (June 5, 2022)

    +

    5.7.9beta33 (June 5, 2022)

    Mbtrnpp and other elements of the Terrain Relative Navigation infrastructure: Test tools and mbtrnpp command set augmented to enable using TRN in an ROV context with realtime bathymetry available via LCM - this development is not complete.

    -

    5.7.9beta32 (June 4, 2022)

    +

    5.7.9beta32 (June 4, 2022)

    Fixes to src/mbtrnav/Makefile.am to allow successful build of TRN tools on Mac Homebrew.

    -

    5.7.9beta30 (June 4, 2022)

    +

    5.7.9beta30 (June 4, 2022)

    Fixes to the Autotools build system allowing MB-System to be built in full on Arm architecture Mac computers running the Monterey OS and fixing the build of @@ -1146,13 +1180,13 @@

    5.7.9beta30 (June 4, 2022)

    reference grid - defined a single section naverr mode but don't have it working yet.

    -

    5.7.9beta29 (May 13, 2022)

    +

    5.7.9beta29 (May 13, 2022)

    Fixes to the Autotools build system allowing MB-System to be built in full on Arm architecture Mac computers running the Monterey OS and fixing the build of the TRN tools on Linux.

    -

    5.7.9beta28 (March 21, 2022)

    +

    5.7.9beta28 (March 21, 2022)

    Mbm_trnplot: Added --display option that immediately displays the plots.

    @@ -1166,7 +1200,7 @@

    5.7.9beta28 (March 21, 2022)

    from +/- 5 m to +/- 1 m. Made progress towards allowing interactive picking of global ties relative to a reference topography grid.

    -

    5.7.9beta27 (February 28, 2022)

    +

    5.7.9beta27 (February 28, 2022)

    Mbtrnpp: Improved TRN result logging, including having all log files from a session placed in the same directory named according to the start time. Also @@ -1199,7 +1233,7 @@

    5.7.9beta27 (February 28, 2022)

    Mbmakeplatform: Fixed header file array definition issue that caused compile failures when testing cmake based builds.

    -

    5.7.9beta26 (January 2, 2022)

    +

    5.7.9beta26 (January 2, 2022)

    Mbphotomosaic: Augmented available commands that can be specified in imagelist files with --priority-weight and section-length-max. The --priority-weight allows @@ -1211,7 +1245,7 @@

    5.7.9beta26 (January 2, 2022)

    image survey directory, as the first three or four images are usually quite dark.

    -

    5.7.9beta25 (December 29, 2021)

    +

    5.7.9beta25 (December 29, 2021)

    Mbphotomosaic: Fixed problem specifying the image correction table file in an imagelist structure.

    @@ -1248,7 +1282,7 @@

    5.7.9beta25 (December 29, 2021)

    or a value specified by the user with the --reference-intensity=intensity and --reference-crcb=cr/cb commands.

    -

    5.7.9beta24 (December 27, 2021)

    +

    5.7.9beta24 (December 27, 2021)

    Mbphotomosaic and mbgetphotocorrection: Altered the image correction table file generated by mbgetphotocorrection and read by mbphotomosaic to include the @@ -1277,7 +1311,7 @@

    5.7.9beta24 (December 27, 2021)

    the lookup table value to a desired reference intensity: C = referenceintensity / tableintensity

    -

    5.7.9beta23 (December 18, 2021)

    +

    5.7.9beta23 (December 18, 2021)

    Mbphotomosaic and mbgetphotocorrection: Another iteration trying to get image gain and exposure correction to work correctly. Altered the imagelist file format @@ -1292,12 +1326,12 @@

    5.7.9beta23 (December 18, 2021)

    for the original camera gain and exposure settings when those are not carried over to the derived color images.

    -

    5.7.9beta22 (December 5, 2021)

    +

    5.7.9beta22 (December 5, 2021)

    Mbphotomosaic and mbgetphotocorrection: Another iteration trying to bet image gain and exposure correction to work correctly.

    -

    5.7.9beta21 (December 4, 2021)

    +

    5.7.9beta21 (December 4, 2021)

    Mbphotomosaic, mbgetphotocorrection, mbphotogrammetry, mbmmakeimagelist: Altered imagelist file format and functions reading recursive imagelist structures. Now @@ -1308,7 +1342,7 @@

    5.7.9beta21 (December 4, 2021)

    Mbphotomosaic, mbgetphotocorrection: Now can correct for image gain and exposure settings.

    -

    5.7.9beta20 (December 1, 2021)

    +

    5.7.9beta20 (December 1, 2021)

    Mblist: Added K and k options to the output, where K prints the fraction of non-null beams that are good (unflagged) and k prints the fraction of all possible beams @@ -1323,18 +1357,18 @@

    5.7.9beta20 (December 1, 2021)

  • --image-quality-filter-length=value
-

5.7.9beta19 (November 7, 2021)

+

5.7.9beta19 (November 7, 2021)

Format 89 (MBF_RESON7K3): Increased the maximum possible number of beams from 512 to 1024.

-

5.7.9beta18 (October 31, 2021)

+

5.7.9beta18 (October 31, 2021)

Mbgrid: Enabled shifting of output grid bounds using a new -Yshiftx/shifty option.

Mbtrnpp: Fixed build issue TRN libraries.

-

5.7.9beta17 (October 16, 2021)

+

5.7.9beta17 (October 16, 2021)

Mbgrid and mbmosaic: Fixed setting output grid format with the -G option. The definition and parsing of the options is now consistent with GMT 6.

@@ -1351,11 +1385,11 @@

5.7.9beta17 (October 16, 2021)

Mbm_grdplot: Fixed so that it does not crash if the input grid has either no valid values (all are NaN) or all valid values are the same.

-

5.7.9beta16 (August 27, 2021)

+

5.7.9beta16 (August 27, 2021)

Mbnavadjust: Made listing of survey vs survey blocks much faster.

-

5.7.9beta15 (August 26, 2021)

+

5.7.9beta15 (August 26, 2021)

Mbnavadjust: Speeded up model tie plots and insured that changes to projects will be saved when users quit.

@@ -1366,7 +1400,7 @@

5.7.9beta15 (August 26, 2021)

Mbm_route2mission: added acoustic modem status signal to MBARI AUV missions immediately at the end of the "start survey" behavior.

-

5.7.9beta14 (July 25, 2021)

+

5.7.9beta14 (July 25, 2021)

Most programs: Fixed possible overflow associated with code that sets user, host, and date information to be included in output files. This functionality has been @@ -1375,19 +1409,19 @@

5.7.9beta14 (July 25, 2021)

Many programs and i/o modules: Increased use of assert() to prevent overflow conditions when using sprintf to construct strings.

-

5.7.9beta13 (July 18, 2021)

+

5.7.9beta13 (July 18, 2021)

Mbextractsegy - fixed plotting so that the last plot is correct.

TRN: updated TRN documentation.

-

5.7.9beta12 (July 4, 2021)

+

5.7.9beta12 (July 4, 2021)

Build system: Fixed location of RPC and XDR headers for Ubuntu 21.

TRN: updated TRN documentation.

-

5.7.9beta11 (June 26, 2021)

+

5.7.9beta11 (June 26, 2021)

Build system: The configure script and the resulting Makefiles are generated using GNU Autotools 2.71 instead of 2.69.

@@ -1407,7 +1441,7 @@

5.7.9beta11 (June 26, 2021)

Fixed thesemacros to work with the new gmt grdinfo output that changed for GMT 6.2.0.

-

5.7.9beta10 (June 16, 2021)

+

5.7.9beta10 (June 16, 2021)

Mbnavadjust: Fixed importation of swath files, which was failing. Fixed crash that happened when a navigation inversion was performed in the same session as @@ -1418,7 +1452,7 @@

5.7.9beta10 (June 16, 2021)

Mbm_grdplot: Fixed histogram equalization in cases where grdhisteq returns an incomplete or short equalized color table.

-

5.7.9beta09 (June 8, 2021)

+

5.7.9beta09 (June 8, 2021)

Mbrt raytracing functions: Added tracking of travel times in arrays returned by mbrt() for plotting raypaths. This adds a parameter to the mbrt() function call, @@ -1456,7 +1490,7 @@

5.7.9beta09 (June 8, 2021)

Mbvoxelclean: Fixed application of acrosstrack and range filters.

-

5.7.9beta07 (May 7, 2021)

+

5.7.9beta07 (May 7, 2021)

mbm_histplot: Fixed the use of the -C option to specify cellwidth for the histogram to be plotted.

@@ -1472,7 +1506,7 @@

5.7.9beta07 (May 7, 2021)

Mblist: Fixed function of the -O%fnv and -O%FNV commands to produce *.fnv files.

-

5.7.9beta06 (March 24, 2021)

+

5.7.9beta06 (March 24, 2021)

Mbpreprocess: Fixed to work with the old s7k format (88) MBF_RESON7KR.

@@ -1483,7 +1517,7 @@

5.7.9beta06 (March 24, 2021)

files in the project directory for ping records (previously data were output for input navigation records as well).

-

5.7.9beta05 (March 8, 2021)

+

5.7.9beta05 (March 8, 2021)

Mbauvloglist: Added available output field of speed calculated from the velocity vector in the kearfott.log log file, with tag calcKSpeed. Also added new -C option: @@ -1504,7 +1538,7 @@

5.7.9beta05 (March 8, 2021)

filesystems that use ACL rather than old style unix file modes - the old stat based readability test in Perl fails on ACL filesystems.

-

5.7.9beta04 (February 21, 2021)

+

5.7.9beta04 (February 21, 2021)

Mbpreprocess: Fixed handling of data formats that do not have specially defined preprocessing functions. This fix was prompted by problems with SeaBeam 2112 data @@ -1523,7 +1557,7 @@

5.7.9beta04 (February 21, 2021)

Mbareaclean: Fixed memory management bug causing crashes.

-

5.7.9beta03 (February 7, 2021)

+

5.7.9beta03 (February 7, 2021)

General changes: Replacing use of strtok() function with strtokr(). Strtok() is intrinsically not thread safe or reentrant and is considered poor use under all @@ -1554,7 +1588,7 @@

5.7.9beta03 (February 7, 2021)

MBeditviz and MBview: Removed unneeded functions from mbview/mb3dsoundings_callbacks.c that were breaking test Cmake builds.

-

5.7.9beta02 (January 27, 2021)

+

5.7.9beta02 (January 27, 2021)

Fixed bug in format 58 and 59 support for bathymetry recalculation. The per beam heave values were being calculated incorrectly when bathymetry was recalculated by raytracing.

@@ -1562,14 +1596,14 @@

5.7.9beta02 (January 27, 2021)

These bugs were introduced during the 2020 code modernization.

-

5.7.9beta01 (January 18, 2021)

+

5.7.9beta01 (January 18, 2021)

Mbedit and mbnavedit: Use extern for Widget definitions in mbeditcreation.h and mbnaveditcreation.h to avoid duplicate symbol link errors when building code according to current C / C++ standards. The other graphical utilities already use this construct.

-

5.7.8 (January 17, 2021)

+

5.7.8 (January 17, 2021)

Version 5.7.8 is now the current release of MB-System. Changes since the 5.7.6 release include:

@@ -1691,14 +1725,14 @@

5.7.8 (January 17, 2021)

Mblist: Added output option 'n' for survey line number. This value is only defined for SEGY format data files (format 160).

-

5.7.8beta01 (January 17, 2021)

+

5.7.8beta01 (January 17, 2021)

The autoconf build system had been changed so that libXt and libX11 come before libXm in the link commands. This fixes runtime errors in all of the graphical utilities on Linux systems. This problem probably relates more directly to the use of the gcc compiler system.

-

5.7.7 (January 17, 2021)

+

5.7.7 (January 17, 2021)

The version 5.7.7 was fatally flawed in that the graphical tools would not run on Linux (or more probably, when built using gcc rather than llvm). The problem @@ -1708,7 +1742,7 @@

5.7.7 (January 17, 2021)

libXm. This problem was fixed rapidly and a new major release 5.7.8 put the same day.

-

5.7.7beta09 (January 17, 2021)

+

5.7.7beta09 (January 17, 2021)

mbdatalist: Fixed memory leak in src/mbio/mbcheckinfo.c that could occur when parsing *.inf files.

@@ -1717,7 +1751,7 @@

5.7.7beta09 (January 17, 2021)

build system in order to circumvent more changes to dependencies installed on Macs using the Homebrew package manager.

-

5.7.7beta08 (January 6, 2021)

+

5.7.7beta08 (January 6, 2021)

Formats 88 (MBFRESON7KR) and 89 (MBFRESON7K3): Fixed bug in handling of PingMotion data records (7012) that caused memory overruns and seg faults.

@@ -1737,12 +1771,12 @@

5.7.7beta08 (January 6, 2021)

Mbm_makedatalist: Now ignores the most recent file when the -L option is used.

-

5.7.7beta06 (December 30, 2020)

+

5.7.7beta06 (December 30, 2020)

Mbprocess: Fixed raytracking library used by mbprocess so that it is thread safe. The relevant code is in mbsystem/src/mbaux/mb_rt.c

-

5.7.7beta05 (December 28, 2020)

+

5.7.7beta05 (December 28, 2020)

Format 261 (MBF_KEMKMALL): Fixed bug in handling version 0 MWC datagrams.

@@ -1768,7 +1802,7 @@

5.7.7beta05 (December 28, 2020)

Mbswath2las: Shell for not-yet-working program to export soundings from swath data to some variant of the LAS format used for point cloud data.

-

5.7.7beta04 (October 28, 2020)

+

5.7.7beta04 (October 28, 2020)

Mbvoxelclean: Added option to filter based on beam amplitude minimum and maximum values.

@@ -1776,7 +1810,7 @@

5.7.7beta04 (October 28, 2020)

Mbeditviz: Fixed coloring of soundings using beam amplitude values (colormap was applied incorrectly).

-

5.7.7beta03 (October 27, 2020)

+

5.7.7beta03 (October 27, 2020)

Mbeditviz: Added option to display the selected sounding point cloud with soundings colored according to associated amplitude value. Also added the @@ -1823,14 +1857,14 @@

5.7.7beta03 (October 27, 2020)

particular to Kongsberg multibeam data as originally logged - files named "9999.all" are now ignored.

-

5.7.7beta02 (October 8, 2020)

+

5.7.7beta02 (October 8, 2020)

Mbotps: Modified mbotps to place temporary files in the user's home directory instead of the current working directory when the latter case results in file paths greater than 80 characters long. This is because OTPS has it's filename variables defined as 80 character strings.

-

5.7.7beta01 (October 7, 2020)

+

5.7.7beta01 (October 7, 2020)

Format 88 (MBFRESON7KR): Fixed handling of the various attitude data record types by function mbextract_nnav(), which in turn allows mbnavlist to work @@ -1839,7 +1873,7 @@

5.7.7beta01 (October 7, 2020)

Mblist: Added output option 'n' for survey line number. This value is only defined for SEGY format data files (format 160).

-

5.7.6 (October 5, 2020)

+

5.7.6 (October 5, 2020)

Version 5.7.6 is now the current release of MB-System. Changes since the 5.7.5 release include:

@@ -1896,7 +1930,7 @@

5.7.6 (October 5, 2020)

installed as part of MB-System. We tentatively plan to remove these programs entirely from MB-System distributions at the time of the 6.0 release.

-

5.7.6preparation (October 4, 2020)

+

5.7.6preparation (October 4, 2020)

Mbnavlist: Fixed bug in parsing -O option that sometimes resulting in the output of undesired values.

@@ -1915,7 +1949,7 @@

5.7.6preparation (October 4, 2020)

so that when picking the bottom return in the sidescan time series, nearfield backscatter can be ignored out to the time interval in seconds given by the value blank.

-

5.7.6beta56 (September 28, 2020)

+

5.7.6beta56 (September 28, 2020)

Mbsegylist: Add print option of 'l' for the line number contained in the segy file header.

@@ -1930,12 +1964,12 @@

5.7.6beta56 (September 28, 2020)

copying a project. This means these triangle files will not need to be remade in the new project.

-

5.7.6beta55 (September 16, 2020)

+

5.7.6beta55 (September 16, 2020)

Mbtrnpp: Fix potential variable overflow and incorrect metrics value assignment in netif code.

-

5.7.6beta54 (September 14, 2020)

+

5.7.6beta54 (September 14, 2020)

Mbnavadjust: Changed "Zero All Z Offsets" action to apply to only the crossings or ties currently displayed in the list, not literally all set ties.

@@ -1946,7 +1980,7 @@

5.7.6beta54 (September 14, 2020)

Mbtrnpp: Add support for trnu client reset callback (does reset using best offset) and supporting metrics, add file swap event to reinit plot

-

5.7.6beta53 (September 13, 2020)

+

5.7.6beta53 (September 13, 2020)

Format 261 (MBF_KEMKMALL): Fix to AUV Sentry mode for kmall format - zero heave in processed ping records (XMT) when platform is an AUV.

@@ -1955,7 +1989,7 @@

5.7.6beta53 (September 13, 2020)

TRN plotting scripts - changed hard coded bash location to /usr/local/bash

-

5.7.6beta52 (September 9, 2020)

+

5.7.6beta52 (September 9, 2020)

mbtrnpp: Added tide model correction. Added metrics covering non-survey data publishing.

@@ -1965,36 +1999,36 @@

5.7.6beta52 (September 9, 2020)

Format 261 (MBF_KEMKMALL): Fixed embedding of changed navigation and sensordepth values by mbprocess - these values needed to be changed in both MRZ and XMT records.

-

5.7.6beta51 (September 4, 2020)

+

5.7.6beta51 (September 4, 2020)

mbtrnpp: Added time stamp and position to TRN status messages generated for pings with no valid soundings. Bug fix: stats and cycle exec time metrics get incorrect values on some platforms, because of mixed reference to real time and precision clocks; now use consistent references

-

5.7.6beta50 (September 2, 2020)

+

5.7.6beta50 (September 2, 2020)

mbtrnpp: Now outputs TRN status messages even when the input data do not include valid soundings and so do not get processed by TRN. Also reduced the debug level of the network interface code.

-

5.7.6beta49 (September 2, 2020)

+

5.7.6beta49 (September 2, 2020)

mbtrnpp: Fixed bugs in parsing commands and also in management shellscript mbtrnpp.sh

-

5.7.6beta48 (September 1, 2020)

+

5.7.6beta48 (September 1, 2020)

mbtrnpp: Fixed bug that opened a new log file at each reinitialization without closing the old log file, eventually using up all of the available file descriptors and crashing. Added some diagnostic output. Updated related test clients and servers used to demonstrate socket based i/o to and from mbtrnpp.

-

5.7.6beta47 (September 1, 2020)

+

5.7.6beta47 (September 1, 2020)

mbtrnpp: Modified the socket based TRN output packet and the related internal representation.

-

5.7.6beta46 (August 31, 2020)

+

5.7.6beta46 (August 31, 2020)

mbtrnpp: Now reinitializes the Terrain Relative Navigation (TRN) filter using the best available position rather than the last estimated navigation offset. @@ -2016,7 +2050,7 @@

5.7.6beta46 (August 31, 2020)

Format 72 (MBF_MBARIMB1): Fixed bug in handling sensordepth values.

-

5.7.6beta45 (August 26, 2020)

+

5.7.6beta45 (August 26, 2020)

Mbtrnpp: Changed most shell output from stdout to stderr. Altered logic for triggering TRN reinits.

@@ -2024,7 +2058,7 @@

5.7.6beta45 (August 26, 2020)

Formats 12 (MBFSBSIOCEN), 13 (MBFSBSIOLSI), 14 (MBFSBURICEN), 15 (MBFSBURIVAX): Fixed string overrun while writing long comment records.

-

5.7.6beta44 (August 24, 2020)

+

5.7.6beta44 (August 24, 2020)

Format 89 (MBF_RESON7K3): Fixed handling and processing of backscatter data, which had a variety of problems. Now, the pseudo-sidescan reported by MB-System @@ -2077,7 +2111,7 @@

5.7.6beta44 (August 24, 2020)

Mbeditviz: Now outputs error message to shell when a file can't be imported because it lacks an *.inf file.

-

5.7.6beta43 (July 23, 2020)

+

5.7.6beta43 (July 23, 2020)

Mbsvplist: Added capability to extract sound velocity profile (SVP) models from MBDATACTD type records as well as MBDATASOUNDVELOCITYPROFILE type records @@ -2100,7 +2134,7 @@

5.7.6beta43 (July 23, 2020)

function to briefly display stereo pairs being read and processed, along with the disparity function calculated for the image pair.

-

5.7.6beta42 (July 21, 2020)

+

5.7.6beta42 (July 21, 2020)

Mbtrn and mbtrnav: Updates and bug fixes to replay-trn_server.

@@ -2121,7 +2155,7 @@

5.7.6beta42 (July 21, 2020)

and alongtrack distances transposed. To fix the problems caused by this bug mbpreprocess and then mbprocess should be rerun.

-

5.7.6beta41 (July 12, 2020)

+

5.7.6beta41 (July 12, 2020)

Mblist: Fixed bug in which output in the CDL format was broken, which in turn broke output in netCDF.

@@ -2133,7 +2167,7 @@

5.7.6beta41 (July 12, 2020)

from the *.cpp suffix to the *.cc suffix to be consistent with other C++ source files in MB-System.

-

5.7.6beta40 (July 7, 2020)

+

5.7.6beta40 (July 7, 2020)

Mbphotomosaic, mbgetphotocorrection, mbphotogrammetry: Added three programs used for processing seafloor photography collected during seafloor mapping surveys @@ -2163,7 +2197,7 @@

5.7.6beta40 (July 7, 2020)

code no longer depends on either the gmt/src/gmtmb.h header file or the obsolete gmtbegin_module() function.

-

5.7.6beta38 (June 8, 2020)

+

5.7.6beta38 (June 8, 2020)

Mblist: Fixed problem in which the centermost (nadir) beam was generally set to 0.

@@ -2183,7 +2217,7 @@

5.7.6beta38 (June 8, 2020)

installations, so we have to allow EM304 and EM712 sonar models with the obsolete format.

-

5.7.6beta37 (May 26, 2020)

+

5.7.6beta37 (May 26, 2020)

Mbnavadjust: Fixed problems in the inversion algorithm. The complexity of this algorithm results from the tendency @@ -2218,7 +2252,7 @@

5.7.6beta37 (May 26, 2020)

Mblevitus: Fixed errors that had been inadvertently created as part of commit #448. Thanks to Joaquim Luis for finding and fixing this.

-

5.7.6beta36 (May 17, 2020)

+

5.7.6beta36 (May 17, 2020)

Mbgrd2obj: Had to add #ifdef's on GMT version because the number of parameters passed to gmtinitmodule() changes between GMT 5.3 through 6.0 and 6.1.

@@ -2232,7 +2266,7 @@

5.7.6beta36 (May 17, 2020)

Mbnavadjustmerge: Added function to merge two adjacent surveys into one with an internal discontinuity.

-

5.7.6beta34 (May 14, 2020)

+

5.7.6beta34 (May 14, 2020)

Mbgrd2obj: New GMT module that converts GMT topographic grids to OBJ format 3D model files that can be imported to visualization software or printed on 3D @@ -2260,7 +2294,7 @@

5.7.6beta34 (May 14, 2020)

a number of other issues in a series of commits. These changes are in src/mbtrn, src/mbtrnav, and src/mbtrnutils.

-

5.7.6beta33 (May 5, 2020)

+

5.7.6beta33 (May 5, 2020)

Mbnavadjust: Changed handling of fixed surveys when updating the project grid or applying the solution. Previously the files of fixed surveys were ignored, @@ -2307,7 +2341,7 @@

5.7.6beta33 (May 5, 2020)

and clean. This approach now works on a Mac. It's time to test on Linux.

-

5.7.6beta32 (April 22, 2020)

+

5.7.6beta32 (April 22, 2020)

Mbgrid: Fixed failure of the two gridding algorithm using beam footprints in which the footprint size blows up at low grazing angles. The fix is to not @@ -2375,7 +2409,7 @@

5.7.6beta32 (April 22, 2020)

Code style: Tom O'Reilly and David Caress added README.md files in each of the subdirectories under src/.

-

5.7.6beta31 (March 2, 2020)

+

5.7.6beta31 (March 2, 2020)

Mbvoxelclean: Fixed memory leak. Added --acrosstrack-minimum and --acrosstrack-maximum filters. Cleaned up shell informational output.

@@ -2401,7 +2435,7 @@

5.7.6beta31 (March 2, 2020)

Code style: Github user abnj contributed some code cleanup by removing $Id tags used when the code was in a Subversion repository.

-

5.7.6beta30 (February 20, 2020)

+

5.7.6beta30 (February 20, 2020)

Mbprocess, mbfilter, mbvoxelclean, mbclean, mbinfo, mbdatalist: Fixed bugs in handling of status values returned by functions that caused early program @@ -2411,7 +2445,7 @@

5.7.6beta30 (February 20, 2020)

practices and adding build tests. The improvements included in this beta release include work on mbview and programs using mbview.

-

5.7.6beta29 (February 17, 2020)

+

5.7.6beta29 (February 17, 2020)

Mbnavadjust: Fixed bugs in mbnavadjust creating by modifying the handling of function status returns.

@@ -2422,7 +2456,7 @@

5.7.6beta29 (February 17, 2020)

practices and adding build tests. The improvements included in this beta release include work on mbview and programs using mbview: mbgrdviz, mbeditviz, mbnavadjust.

-

5.7.6beta28 (February 13, 2020)

+

5.7.6beta28 (February 13, 2020)

Format 89 (MBF_RESON7K3): Added support for data record type 7058. Also added ability to handle s7k data files missing the file header record.

@@ -2443,14 +2477,14 @@

5.7.6beta28 (February 13, 2020)

practices and adding build tests. The improvements included in this beta release include work on mbedit, mbnavedit, and mbnavadjust.

-

5.7.6beta27 (February 3, 2020)

+

5.7.6beta27 (February 3, 2020)

mbpreprocess: Corrected prior fix to error in calculating lever arms, which didn't include all of the sign changes needed in mb_platform.c.

mbgrid: Fixed flaw in min or max weighted mean algorithm that produced array overflows in mbgrid.

-

5.7.6beta26 (February 2, 2020)

+

5.7.6beta26 (February 2, 2020)

Format 181 (MBF_SAMESURF): Fixed compiler warnings, including warnings from a mismatch of 32 bit and 64 bit integer pointers due to the early 1990's vintage @@ -2472,7 +2506,7 @@

5.7.6beta26 (February 2, 2020)

include cleaning up the SURF format library, work on mbedit, mbnavadjust, and the GMT modules mbswath, mbcontour, and mbgrdtiff.

-

5.7.6beta25 (January 20, 2020)

+

5.7.6beta25 (January 20, 2020)

Info files: The top level information files README, ChangeLog, and GPL have been removed. The Markdown format versions (README.md, ChangeLog.md, GPL.md) remain and have been updated.

@@ -2485,7 +2519,7 @@

5.7.6beta25 (January 20, 2020)

and are executed automatically by the Travis CI service integrated with Github whenever commits are made to the Github repository. The current changes mostly consist of cleaning up the code of the graphical utilities such as mbedit, mbnavedit, mbnavadjust.

-

5.7.6beta24 (January 16, 2020)

+

5.7.6beta24 (January 16, 2020)

Build system: The configure.ac file now uses the AXCXXCOMPILESTDCXX(11) macro to require that the code conform to the C++11 standard. Some preprocessor @@ -2509,7 +2543,7 @@

5.7.6beta24 (January 16, 2020)

and are executed automatically by the Travis CI service integrated with Github whenever commits are made to the Github repository.

-

5.7.6beta23 (January 11, 2020)

+

5.7.6beta23 (January 11, 2020)

MBprocess, mbpreprocess, mbmakeinfo(): Altered mbprocess and mbpreprocess so that both run about half as slow (twice as fast) as before. This optimization is @@ -2580,7 +2614,7 @@

5.7.6beta23 (January 11, 2020)

installed as part of MB-System. We tentatively plan to remove these programs entirely from MB-System distributions at the time of the 6.0 release.

-

5.7.6beta21 (December 12, 2019)

+

5.7.6beta21 (December 12, 2019)

GMT modules (mbcontour, mbswath, mbgrdtiff): modified the #ifdefs to allow building with GMT 6.1 and later.

@@ -2590,7 +2624,7 @@

5.7.6beta21 (December 12, 2019)

Code stye: Kurt Schwehr is systematically altering the code to conform to best practices

-

5.7.6beta20 (November 26, 2019)

+

5.7.6beta20 (November 26, 2019)

Mbprocess: Fix to handle temporary failures to read GMT grd files. The GMT grid reading code will now return with an error rather than causing the program to @@ -2605,12 +2639,12 @@

5.7.6beta20 (November 26, 2019)

mbtrnpp: Changes by Kent Headley to mbtrnpp in src/mbtrnutils and supporting source directories src/mbtrn and src/mbtrnav.

-

5.7.6beta19 (November 22, 2019)

+

5.7.6beta19 (November 22, 2019)

Mbprocess: Attempting to fix processing of format 71 files within an mbnavadjust project.

-

5.7.6beta18 (November 21, 2019)

+

5.7.6beta18 (November 21, 2019)

Everything: Now fully compatible with PROJ 6.X. The configure script will detect the presence or absence of PROJ 6 or later - if the PROJ installation predates @@ -2627,7 +2661,7 @@

5.7.6beta18 (November 21, 2019)

mbtrnpp: Fixed a number for formatting and type issues hampering building the TRN code on MacOs.

-

5.7.6beta17 (November 15, 2019)

+

5.7.6beta17 (November 15, 2019)

MBeditviz: Added option to display 3D soundings colored according to the map's coloring (including selected colortabel and any histogram equalization).

@@ -2648,7 +2682,7 @@

5.7.6beta17 (November 15, 2019)

mbtrnpp: Many changes by Kent Headley to this in src/mbtrnutils and supporting source directories src/mbtrn and src/mbtrnav.

-

5.7.6beta16 (October 29, 2019)

+

5.7.6beta16 (October 29, 2019)

MBnavadjust: Fixed bug in calculating the range of contour values and the size of the memory allocation for contours.

@@ -2659,7 +2693,7 @@

5.7.6beta16 (October 29, 2019)

true and false, and changing the type of the associated variables from int to bool.

-

5.7.6beta15 (October 21, 2019)

+

5.7.6beta15 (October 21, 2019)

Format 261 (MBF_KEMKMALL): Fixed preprocessing of Kongsberg multibeam data in the kmall format, particularly with regard to merging WHOI-NDSF processed navigation @@ -2695,7 +2729,7 @@

5.7.6beta15 (October 21, 2019)

true and false, and changing the type of the associated variables from int to bool.

-

5.7.6beta14 (October 8, 2019)

+

5.7.6beta14 (October 8, 2019)

MBnavadjustmerge: Added options --unset-short-section-ties=minlength and --skip-short-section-crossings=minlength that allow the deletion or prevention @@ -2726,7 +2760,7 @@

5.7.6beta14 (October 8, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta12 (September 20, 2019)

+

5.7.6beta12 (September 20, 2019)

Mbset: Fix to mbset so that the mbpnavadjmode is set to MBPNAVADJOFF instead of MBPNAVOFF and MBPNAVADJLLZ instead of MBPNAVON.

@@ -2742,7 +2776,7 @@

5.7.6beta12 (September 20, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta10 (September 18, 2019)

+

5.7.6beta10 (September 18, 2019)

Mbnavadjust: Changed the contouring displayed during analysis of crossings to be based on a triangular mesh representation of the bathymetry data for each @@ -2761,7 +2795,7 @@

5.7.6beta10 (September 18, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta8 (September 9, 2019)

+

5.7.6beta8 (September 9, 2019)

MBIO library beam flagging and detect types: The handling of multi-pick soundings has been modified. This refers to sensors that can report more than @@ -2816,7 +2850,7 @@

5.7.6beta8 (September 9, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta6 (August 26, 2019)

+

5.7.6beta6 (August 26, 2019)

Mbm_route2mission: AUV spiral descent option now includes a behavior to disable DVL aiding of the INS during the descent.

@@ -2831,7 +2865,7 @@

5.7.6beta6 (August 26, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta5 (August 6, 2019)

+

5.7.6beta5 (August 6, 2019)

Integration with PROJ: Reverted to use of deprecated PROJ4 API due to problems with use of projections by the mbview library. This will get fixed, but it's more @@ -2843,7 +2877,7 @@

5.7.6beta5 (August 6, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta4 (August 2, 2019)

+

5.7.6beta4 (August 2, 2019)

Format MBF_GSFGENMB (format 121, Generic Sensor Format, GSF): The version of libgsf used to read and write Generic Sensor Format (GSF) files has been @@ -2879,7 +2913,7 @@

5.7.6beta4 (August 2, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta2 (July 25, 2019)

+

5.7.6beta2 (July 25, 2019)

Formats MBF3DWISSLR (232) and MBF3DWISSLP (233): these i/o modules have been updated to handle both the original (v1.1) and updated (v1.2) 3D at Depth Wide @@ -2889,7 +2923,7 @@

5.7.6beta2 (July 25, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.6beta1 (July 6, 2019)

+

5.7.6beta1 (July 6, 2019)

MBnavadjust: Fixed bug that resulted in Naverr window contours not being displayed when the diference between the minimum and maximum depth of a section @@ -2898,7 +2932,7 @@

5.7.6beta1 (July 6, 2019)

Formats MBF3DWISSLR (232) and MBF3DWISSLP (233): working towards the code successfully reading and writing the 3D at Depth WiSSL *.raa format version 1.2.

-

5.7.5 (June 26, 2019)

+

5.7.5 (June 26, 2019)

Version: Set for release 5.7.5

@@ -2912,13 +2946,13 @@

5.7.5 (June 26, 2019)

mbfilter: update man page

-

5.7.5beta12 (June 24, 2019)

+

5.7.5beta12 (June 24, 2019)

Code stye: Kurt Schwehr is systematically altering the code to conform to best practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.5beta11 (June 16, 2019)

+

5.7.5beta11 (June 16, 2019)

Format 89 (MBF_RESON7K3): Fixed bug in support of the Teledyne 7k version 3 format that caused mbpreprocess to crash.

@@ -2929,11 +2963,11 @@

5.7.5beta11 (June 16, 2019)

practices regarding header inclusion and reduced variable scope, particularly for loop indices.

-

5.7.5beta10 (June 9, 2019)

+

5.7.5beta10 (June 9, 2019)

Build system: Set Autotools build system to force use of standard C (i.e. C99).

-

5.7.5beta9 (June 8, 2019)

+

5.7.5beta9 (June 8, 2019)

Format 89 (MBF_RESON7K3): The Teledyne 7k version 3 format is now supported as format 89. This format is used for all multibeam sonars built by Teledyne, @@ -2960,7 +2994,7 @@

5.7.5beta9 (June 8, 2019)

Mbvelocitytool: Fixed memory leak.

-

5.7.5beta8 (April 11, 2019)

+

5.7.5beta8 (April 11, 2019)

Format 89 (MBF_RESON7K3): Progress towards support of Teledyne 7k version 3 format. The i/o module builds but is not fully functional yet. Most records parse @@ -2969,7 +3003,7 @@

5.7.5beta8 (April 11, 2019)

Format 261 (MBF_KEMKMALL): We are close to complete with support for the new Kongsberg kmall format. Testing and debugging continues.

-

5.7.5beta7 (March 28, 2019)

+

5.7.5beta7 (March 28, 2019)

Windows compatibility: A number of changes from Joaquim Luis that allow building under Windows.

@@ -2979,7 +3013,7 @@

5.7.5beta7 (March 28, 2019)

7k format from Teledyne now used for Teledyne Reson abnd Teledyne Atlas multibeams.

-

5.7.5beta6 (March 26, 2019)

+

5.7.5beta6 (March 26, 2019)

Build system: Modified configure.ac to fix a problem building with the new Proj 6.0.0. MB-System uses a longstanding Proj API that is deprecated in Proj 6. @@ -2987,14 +3021,14 @@

5.7.5beta6 (March 26, 2019)

with the preprocessor macro ACCEPT
USEOFDEPRECATEDPROJAPI_H set. This compiler flag has been added to the autoconf test for usability of this header file.

-

5.7.5beta5 (March 22, 2019)

+

5.7.5beta5 (March 22, 2019)

Mbmgrdplot, mbmgrd3dplot, mbmgrdtiff, mbmhistplot, mbmplot, mbmxyplot: Set these plot macros to use "open" on Macs and on Linux to use "gio open" if available, "xdg-open" if "gio" is not available. Also got rid of another instance of orphan file creation by the plotting shellscripts (e.g. gmt.conf$$).

-

5.7.5beta4 (March 21, 2019)

+

5.7.5beta4 (March 21, 2019)

Mbmgrid: Fixed problem in which execution of mbmgrid left behind an orphaned datalist file. Also changed this macro to output a bash shellscript rather than @@ -3016,12 +3050,12 @@

5.7.5beta4 (March 21, 2019)

These plot macros now embed the user, computer, and time of creation associated with the output plot generation shellscript.

-

5.7.5beta3 (March 14, 2019)

+

5.7.5beta3 (March 14, 2019)

Mbcopy: Fixed problem with fbt file generation by mbcopy that was introduced with 5.7.5beta2

-

5.7.5beta2 (March 4, 2019)

+

5.7.5beta2 (March 4, 2019)

Format 261 (MBF_KEMKMALL): There is progress towards support for the new Kongsberg kmall format. Only EM2040 data supplied by Kongsberg is being @@ -3031,7 +3065,7 @@

5.7.5beta2 (March 4, 2019)

Mbcopy: Changed logic so that in a full copy all data records are passed on to the output even if they generate nonfatal errors (e.g. out of time or location bounds).

-

5.7.5beta1 (February 27, 2019)

+

5.7.5beta1 (February 27, 2019)

Mbm_bpr: Augmented to work with Sonardyne AMT pressure data using PRS data records in addition to PR2 records.

@@ -3039,19 +3073,19 @@

5.7.5beta1 (February 27, 2019)

Mbotps: Fixed some issues with applying a tide station correction to time models.

-

5.7.5beta0 (February 25, 2019)

+

5.7.5beta0 (February 25, 2019)

Format 261 (MBFKEMKMALL): Added support for new Kongsberg kmall format with MBIO id 261 and name MBFKEMKMALL. At this point the support has memory management problems resulting in sporadic and inconsistent crashing.

-

5.7.4 (February 12, 2019)

+

5.7.4 (February 12, 2019)

Plotting macros (mbmgrdplot, mbmgrd3dplot, mbmplot, mbmxyplot, mbmhistplot): Fixed problem with plotting macro mbmplot that caused failure of the plotting shellscript.

-

5.7.3 (February 8, 2019)

+

5.7.3 (February 8, 2019)

Plotting macros (mbmgrdplot, mbmgrd3dplot, mbmplot, mbmxyplot, mbm_histplot): This version changes how automatically displaying the Postscript plot is handled. Previously @@ -3072,7 +3106,7 @@

5.7.3 (February 8, 2019)

preprocessing. This fix works with data already processed through prior versions of MB-System as well as data newly processed from *.all files.

-

5.7.2 (February 4, 2019)

+

5.7.2 (February 4, 2019)

All files: Updated copyright to 2019.

@@ -3100,13 +3134,13 @@

5.7.2 (February 4, 2019)

for that kind of file. On Linux systems, this program is "xdg-open". On MacOs, this program is "open". On Cygwin systems, this program is "cygstart".

-

5.7.1 (December 19, 2018)

+

5.7.1 (December 19, 2018)

Initiated use of version tagging in Git.


-

MB-System Version 5.6 Releases and Release Notes:

+

MB-System Version 5.6 Releases and Release Notes:


@@ -3122,7 +3156,7 @@

MB-System Version 5.6 Releases and Release Notes:


-

5.6.20181218 (December 18, 2018)

+

5.6.20181218 (December 18, 2018)

Generated release package using github

@@ -3130,12 +3164,12 @@

5.6.20181218 (December 18, 2018)

mbm_dslnavfix: Removed, obsolete.

-

5.6.20181217 (December 17, 2018)

+

5.6.20181217 (December 17, 2018)

Memory management: Fixed memory leak associated with allocation and deallocation of edit save file (*.esf) data.

-

5.6.20181214 (December 14, 2018)

+

5.6.20181214 (December 14, 2018)

Format 121 (MBFGSFGENMB): Changed GSFlib version to 3.08. MB-System also now builds and installs the program dumpgsf. Fixed several array overruns in the GSFlib @@ -3152,7 +3186,7 @@

5.6.20181214 (December 14, 2018)

deepest surfaces in the gridded model. These algorithms were specifically added to handle subsea lidar data that maps animals as well as the seafloor.

-

5.6.20181129 (November 29, 2018)

+

5.6.20181129 (November 29, 2018)

MBgrdtiff, mbmgrdtiff: Added -Nnudgex/nudge_y option to apply a positional offset in meters relative to the input grid or mosaic.

@@ -3178,7 +3212,7 @@

5.6.20181129 (November 29, 2018)

rms deviation exceeds the specified threshold, all unflagged soundings in that ping are flagged as bad.

-

5.6.20181016 (October 16, 2018)

+

5.6.20181016 (October 16, 2018)

Many files: Changed type of pingnumber variable from int to unsigned int.

@@ -3196,12 +3230,12 @@

5.6.20181016 (October 16, 2018)

files created and/or modified by mbedit, mbeditviz, mbedit, and \fBmbclean\fP.

-

5.6.002 (September 14, 2018)

+

5.6.002 (September 14, 2018)

Format 88 (MBFRESON7KR): Corrected application of attitude offsets to bathymetry calculation in mbsysreson7k_preprocess().

-

5.6.001 (September 11, 2018)

+

5.6.001 (September 11, 2018)

Format 88 (MBFRESON7KR): Fixed problem in the mbsysreson7k_preprocess() function in which the interpolated and time latency corrected attitude values calculated @@ -3210,7 +3244,7 @@

5.6.001 (September 11, 2018)


-

MB-System Version 5.5 Releases and Release Notes:

+

MB-System Version 5.5 Releases and Release Notes:


@@ -3312,7 +3346,7 @@

MB-System Version 5.5 Releases and Release Notes:


-

5.5.2350 (September 6, 2018)

+

5.5.2350 (September 6, 2018)

Mbnavadjust: Added a sorted ties list view for which the list of ties is ordered from largest misfit magnitude to smallest where the misfit is measured between @@ -3320,19 +3354,19 @@

5.5.2350 (September 6, 2018)

easily inspect the most poorly fit ties. Also augmented stored information about global ties. Also made some changes to the inversion algorithm.

-

5.5.2348 (August 20, 2018)

+

5.5.2348 (August 20, 2018)

Reson 7k V3 support: Added files mbrreson7k3.c mbsysreson7k3.c mbsys_reson7k3.h while working towards support of version 3 7k data (by Christian Ferreira).

-

5.5.2347 (August 17, 2018)

+

5.5.2347 (August 17, 2018)

Mbtrnpreprocess: precruise update of mbtrnpreprocess and related tools used for optional install of AUV terrain relative navigation. Excepting for a few debug print statement changes, this matches the 20180814 mbtrnpreprocess installation of Kent Headly on MBARI Mapping AUV 2.

-

5.5.2346 (August 13, 2018)

+

5.5.2346 (August 13, 2018)

Mbauvloglist: augmented dimensioning of fields array to allow up to 500 data fields.

@@ -3343,7 +3377,7 @@

5.5.2346 (August 13, 2018)

longitude values (the format should use unsigned shorts but clearly data exist using signed values).

-

5.5.2345 (August 10, 2018)

+

5.5.2345 (August 10, 2018)

Mbmakeplatform: Fixed segmentation fault when modifications to the platform model are specified before a command that initializes the platform.

@@ -3361,7 +3395,7 @@

5.5.2345 (August 10, 2018)

Mbnavadjust: Changed so that sensordepth values are included in the navigation points stored in the project file (*.nvh file).

-

5.5.2344 (August 3, 2018)

+

5.5.2344 (August 3, 2018)

Mbcontour, mbswath, mbgrdtiff, mbbackangle, mbprocess, mbgrid, mbmosaic, libmbaux, mbgrdviz, mbeditviz, mbnavadjust, libmbview: Implemented a number of low level @@ -3376,7 +3410,7 @@

5.5.2344 (August 3, 2018)

src/mbtrn: Changes from Kent Headley (these tools and library are being actively developed).

-

5.5.2342 (June 29, 2018)

+

5.5.2342 (June 29, 2018)

Mbgpstide: New program contributed by Gordon Keith. This program generates tide files from the height above ellipsoid data in the 'h' datagrams of Simrad files. @@ -3384,7 +3418,7 @@

5.5.2342 (June 29, 2018)

was funded by Geoscience Australia with the understanding that the code would be made available to the general MB-System distribution.

-

5.5.2340 (June 26, 2018)

+

5.5.2340 (June 26, 2018)

Autoconf build system: Restructured to build successfully with the mbtrn capability enabled using the --enable-mbtrn option of the configure script.

@@ -3402,7 +3436,7 @@

5.5.2340 (June 26, 2018)

Mbnavadjust: now stores only valid, unflagged soundings in the section files, which are format 71. Previously all soundings, including null and flagged, were stored.

-

5.5.2339 (June 25, 2018)

+

5.5.2339 (June 25, 2018)

Mbgrid: Modified to use correct gridding algorithm when reading fbt files lacking the sonar type value.

@@ -3425,7 +3459,7 @@

5.5.2339 (June 25, 2018)

navigation (TRN) client that localizes the AUV position relative to a pre-existing map using the current bathymetry data.

-

5.5.2336 (June 6, 2018)

+

5.5.2336 (June 6, 2018)

Mbpreprocess and format MBF_3DWISSLR (232): Add option --kluge-fix-wissl-timestamps to fix a timestamp problem with the initial version of the 3D at Depth WiSSL (wide @@ -3438,7 +3472,7 @@

5.5.2336 (June 6, 2018)

lon-lat bounds of a topography grid previously loaded using the mb
topogrid_init() function.

-

5.5.2335 (May 6, 2018)

+

5.5.2335 (May 6, 2018)

Mbm_bpr: Added ability to parse pressure data from Sonardyne AMT beacons. Also added optional smoothing of the BPR depth data used to calculate tides.

@@ -3454,7 +3488,7 @@

5.5.2335 (May 6, 2018)

Format 88 (MBF_RESON7KR): Fixed handling of beams when using the version 2 raw detection data records.

-

5.5.2334 (April 18, 2018)

+

5.5.2334 (April 18, 2018)

Mbprocess, mbareaclean, mbclean, mbedit, mbeditviz, mbrphsbias, mbneptune2esf: Reset MBESFMAXTIMEDIFFX10 value in mbprocess.h to 0.0011 to handle old @@ -3462,13 +3496,13 @@

5.5.2334 (April 18, 2018)

Mbareaclean, mbclean, mbrphsbias: Fixed the previous fixes .

-

5.5.2333 (April 18, 2018)

+

5.5.2333 (April 18, 2018)

Mbprocess, mbareaclean, mbclean, mbedit, mbeditviz, mbrphsbias, mbneptune2esf: Decreased time range where multiplicity of pings will consider close records as the same from 100 to 1 microsecond.

-

5.5.2332 (April 17, 2018)

+

5.5.2332 (April 17, 2018)

Mbprocess, mbareaclean, mbclean, mbedit, mbeditviz, mbrphsbias, mbneptune2esf: Fixed problem recocognizing multiplicity of pings when ping times are close to @@ -3476,7 +3510,7 @@

5.5.2332 (April 17, 2018)

SeaBeam 3020 multibeam, but could potentially have impacted data from other sensors.

-

5.5.2331 (April 10, 2018)

+

5.5.2331 (April 10, 2018)

Mbm_makedatalist: Fixed problem with use of perl sort function when handling Kongsberg multibeam data. Also fixed problem with specifying a directory using @@ -3498,7 +3532,7 @@

5.5.2331 (April 10, 2018)

Mbtrnpreprocess: Continued development of this new tool, particularly adding interprocess communication via TCP-IP sockets.

-

5.5.2330 (March 7, 2018)

+

5.5.2330 (March 7, 2018)

Proj: Removed the embedded Proj source package from the MB-System archive and distribution. From now on Proj is strictly a prerequisite for building MB-System.

@@ -3513,7 +3547,7 @@

5.5.2330 (March 7, 2018)

Format MBF_3DWISSLP (233): Many fixes to the code supporting WiSSL lidar data.

-

5.5.2329 (February 12, 2018)

+

5.5.2329 (February 12, 2018)

Format MBF_3DWISSLP (233): Rewrote the processing format for the 3D at Depth wide swath lidar (WiSSL) system delivered to MBARI in December 2017. The new @@ -3531,7 +3565,7 @@

5.5.2329 (February 12, 2018)

Mbmroute2mission: Fixed generation of Dorado AUV missions with waypointbottom behaviours.

-

5.5.2328 (January 31, 2018)

+

5.5.2328 (January 31, 2018)

Edit Save Files (*.esf): The edit save file format has been augmented to include a mode value that can include implicitly setting all soundings not set by a beamflag @@ -3554,16 +3588,16 @@

5.5.2328 (January 31, 2018)

MBinfo: Fixed memory allocation problem that led to crashes reading data in formats MBF3DWISSLR (232) and MBF3DWISSLP (233).

-

5.5.2327 (January 23, 2018)

+

5.5.2327 (January 23, 2018)

Build system: Restructure the use of the mb_config.h file so that compiling on Ubuntu 17 succeeds (issue related to stdint.h includes)

-

5.5.2325 (January 23, 2018)

+

5.5.2325 (January 23, 2018)

MBinfo: Fixed bug in JSON output (Christian Ferreira)

-

5.5.2324 (January 18, 2018)

+

5.5.2324 (January 18, 2018)

MBpreprocess: Added support for the 3D at Depth wide swath lidar (WiSSL) system delivered to MBARI in December 2017.

@@ -3576,11 +3610,11 @@

5.5.2324 (January 18, 2018)

Many source files: Changes to variable names in GMT grid header and CPT structures for GMT 6.

-

5.5.2323 (December 7, 2017)

+

5.5.2323 (December 7, 2017)

MBnavadjust: fixed crashes that happened when files or surveys are held fixed.

-

5.5.2322 (November 25, 2017)

+

5.5.2322 (November 25, 2017)

Mbpreprocess: Now set so that input Imagenex DeltaT data in the vendor format MBFIMAGE83P (191) will be output in the processing format MBFIMAGEMBA (192) @@ -3599,7 +3633,7 @@

5.5.2322 (November 25, 2017)

Added curly brackets, changed beamflag setting calculations, and reformatted some lines in order to silence compiler warnings.

-

5.5.2321 (October 26, 2017)

+

5.5.2321 (October 26, 2017)

Mbgrdviz: fixed bug in displaying overlays.

@@ -3610,17 +3644,17 @@

5.5.2321 (October 26, 2017)

Format 88 (MBF_RESON7KR): Fixed confusion between Depth and Height s7k data records.

-

5.5.2320 (October 18, 2017)

+

5.5.2320 (October 18, 2017)

Mbgrdviz: Now, when overlays are displayed in mbgrdviz, the only areas rendered are those where both the primary and overlay grids are defined.

-

5.5.2319 (October 16, 2017)

+

5.5.2319 (October 16, 2017)

Mbprocess: Fixed bug that caused mbprocess to (sometimes) never finish while continuing to write to the output file.

-

5.5.2318 (September 29, 2017)

+

5.5.2318 (September 29, 2017)

Mbnavadjust: Fixed bug that often, but not always, caused the inversion to blow up and crash the program.

@@ -3690,7 +3724,7 @@

5.5.2318 (September 29, 2017)

only applied to files with the *.all suffix. This capability is applied by default but can be disabled with the -T option.

-

5.5.2314 (August 24, 2017)

+

5.5.2314 (August 24, 2017)

Mbprocess: Fixed bug in which mbprocess sometimes crashed for files that have not had bathymetry edited or filtered.

@@ -3710,13 +3744,13 @@

5.5.2314 (August 24, 2017)

external file(s) but one of those files does not exist, the program terminates with an error message.

-

5.5.2313 (August 9, 2017)

+

5.5.2313 (August 9, 2017)

Format 88 (MBF_RESON7KR): Fixed problem handling Reson data preprocessed or processed using a version older than 5.3.2004 which in some cases causes the alongtrack and acrosstrack values to be swapped.

-

5.5.2312 (July 14, 2017)

+

5.5.2312 (July 14, 2017)

MBedit: Added togglebutton to the View menu that allows to control whether flagged soundings are displayed (previously flagged but valid soundings were @@ -3735,11 +3769,11 @@

5.5.2312 (July 14, 2017)

MBgrdtiff, mbcontour, mbswath, mbps: Changed defines in *.c files to reflect the versioning of GMT 6

-

5.5.2311 (June 20, 2017)

+

5.5.2311 (June 20, 2017)

MBnavadjust: Fixed bug that preventing importing data into a new project.

-

5.5.2309 (June 4, 2017)

+

5.5.2309 (June 4, 2017)

Applied reformatting to all *.c and *.h files using the tool clang-format as suggested by Joaquim Luis.

@@ -3748,14 +3782,14 @@

5.5.2309 (June 4, 2017)

Updated mbotps to use the current best OSU tidal model (atlastpxo81).

-

5.5.2306 (May 27, 2017)

+

5.5.2306 (May 27, 2017)

Format 88 (MBF_RESON7KR): Fixed a couple of bugs in the i/o module identified by Kurt Schwehr.

Format 121 (MBF_GSFGENMB): Fixed handling of attitude records.

-

5.5.2305 (May 13, 2017)

+

5.5.2305 (May 13, 2017)

MBdatalist: Fixed bug involving operating on datalist files other than the default datalist.mb-1.

@@ -3774,7 +3808,7 @@

5.5.2305 (May 13, 2017)

MBinfo: Fix bug in XML output disabling output of minimum good beam counts in some cases.

-

5.5.2304 (May 6, 2017)

+

5.5.2304 (May 6, 2017)

MBpreprocess: Fixed generation of *.baa, *.bsa, and *.bah files so they include only data relevant to the associated swath file, which means samples from @@ -3792,7 +3826,7 @@

5.5.2304 (May 6, 2017)

revision, including adding a new argument. The old version of that function is now available within the API as mbdatalistreadorg().

-

5.5.2303 (April 28, 2017)

+

5.5.2303 (April 28, 2017)

MBpreprocess and MBeditviz: Changed the ancillary files used to store the asynchronous attitude and heading data used by MBeditviz for time latency modeling @@ -3807,7 +3841,7 @@

5.5.2303 (April 28, 2017)

MBswath: Fixed bug that caused occasional crashes.

-

5.5.2302 (April 20, 2017)

+

5.5.2302 (April 20, 2017)

Formats 56 and 57 (MBFEM300RAW and MBFEM300MBA): Fixed handling of sensordepth and heave data by mbpreprocess and mbprocess. Tide correction and recalculation @@ -3822,12 +3856,12 @@

5.5.2302 (April 20, 2017)

Mbdatalist: Now supports long command line options (old short options are deprecated but still work).

-

5.5.2301 (April 17, 2017)

+

5.5.2301 (April 17, 2017)

Mbpreprocess and Format 88 (MBF_RESON7KR): Fixed application of kluge-beam-tweak option for Reson 7k (format 88) data.

-

5.5.2300 (April 15, 2017)

+

5.5.2300 (April 15, 2017)

Formats 58 and 59 (MBFEM710RAW and MBFEM710MBA): Fixed memory leak.

@@ -3838,7 +3872,7 @@

5.5.2300 (April 15, 2017)

Mbm_arc2grd: Rewritten to use GMT modules grdconvert and grdedit.

-

5.5.2299 (April 10, 2017)

+

5.5.2299 (April 10, 2017)

Formats 58 and 59 (MBFEM710RAW and MBFEM710MBA): Fixed handling of sensordepth and heave data during preprocessing. Program mbkongsbergpreprocess is now @@ -3859,7 +3893,7 @@

5.5.2299 (April 10, 2017)

the segment start lines will consist of the character '#' followed by the path to the source datalist file

-

5.5.2297 (April 5, 2017)

+

5.5.2297 (April 5, 2017)

All i/o modules: Added sensordepthsource to the arguments of the mbrinfo_XXXXXXXX() functions in the i/o modules.

@@ -3878,7 +3912,7 @@

5.5.2297 (April 5, 2017)

Mbm_makedatalist: Added option to suppress processed files (e.g. *p.mb88) from inclusion in the output datalist.

-

5.5.2296 (March 31, 2017)

+

5.5.2296 (March 31, 2017)

Mbm_makedatalist: Major capability augmentation for this tool, preparing for automated setup of the processing environment. This macro will now construct @@ -3891,7 +3925,7 @@

5.5.2296 (March 31, 2017)

Mbm_grd2arc: Fix provided by Monica Schwehr for compatibility to *.grd files generated with the current GMT.

-

5.5.2295 (March 26, 2017)

+

5.5.2295 (March 26, 2017)

Mbmplot, mbmgrdplot, mbmxyplot, mbm3dgrdplot: Changes to the manual pages to reflect the new syntax for map scales (the -MGL option in the MB-System plot @@ -3912,11 +3946,11 @@

5.5.2295 (March 26, 2017)

Format 121 (MBF_GSFGENMB): Integrated latest release of GSF from Leidos (3.07)

-

5.5.2294 (March 21, 2017)

+

5.5.2294 (March 21, 2017)

Mbsvpselect: Fixes by Ammar Aljuhne and Christian Ferreira of MARUM.

-

5.5.2293 (March 6, 2017)

+

5.5.2293 (March 6, 2017)

Mb7kpreprocess: Fixed bug in handling old MBARI Mapping AUV with navigation and attitude data in deprecated "Bluefin" records.

@@ -3931,7 +3965,7 @@

5.5.2293 (March 6, 2017)

Format 231 (MBF_3DDEPTHP): Fixed bug in handling angular offset values in preprocessing.

-

5.5.2292 (January 30, 2017)

+

5.5.2292 (January 30, 2017)

Mblist: Added ability to output positions in a projected coordinate system, to output positions of the sensor instead of soundings or pixels, or to output @@ -3943,7 +3977,7 @@

5.5.2292 (January 30, 2017)

Mbnavadjust: Now outputs the altered project less frequently (every tenth new tie instead of every tie).

-

5.5.2291 (January 12, 2017)

+

5.5.2291 (January 12, 2017)

Mbnavedit: interpolation of selected navigation values now also flags the original values so they are not used in calculating a navigation model.

@@ -3954,7 +3988,7 @@

5.5.2291 (January 12, 2017)

Mbnavadjust: prevent occasional corruption of the mbnavadjust project by not allowing excessively large offset values to result from unstable inversions.

-

5.5.2290 (January 2, 2017)

+

5.5.2290 (January 2, 2017)

Mbinfo: applied fixes from Suzanne O'Hara to JSON output from mbinfo.

@@ -3972,7 +4006,7 @@

5.5.2290 (January 2, 2017)

truncation. This will change the behavior of the -Edx/dy/units option, but the resulting grid dimensions will be more consistent with users expectations.

-

5.5.2289 (December 2, 2016)

+

5.5.2289 (December 2, 2016)

Mbnavadjust: Fixed auto set vertical level function to use the same block inversion now used for the first stage of the main inversion. Also set this function so that @@ -3982,7 +4016,7 @@

5.5.2289 (December 2, 2016)

Mbnavadjustmerge: Fixed import and export of tie lists to allow moving ties between projects.

-

5.5.2287 (November 29, 2016)

+

5.5.2287 (November 29, 2016)

Mbm_makesvp: added capability to extract sound speed values from survey data records as well as ctd data records, and to optionall produce sound speed models extending @@ -3997,14 +4031,14 @@

5.5.2287 (November 29, 2016)

Mbprocess: fixed rare singularity in the raytracing code.

-

5.5.2286 (November 8, 2016)

+

5.5.2286 (November 8, 2016)

Mbsvplist: Added -R command to set longitude-latitude bounds within which the -S option will cause ssv values to be output.

Mbgrdviz: Added start5 and end5 waypoint types to routes.

-

5.5.2285 (November 3, 2016)

+

5.5.2285 (November 3, 2016)

Mbnavadjust: Added a first step in the inversion in which mbnavadjust solves for average offsets for each survey ("block"). The offsets associated with this @@ -4012,11 +4046,11 @@

5.5.2285 (November 3, 2016)

smoothing penalty is thus applied to deviations from the average model rather than the full navigation adjustment model.

-

5.5.2284 (October 23, 2016)

+

5.5.2284 (October 23, 2016)

Fixed some typos preparing for full release.

-

5.5.2283 (October 23, 2016)

+

5.5.2283 (October 23, 2016)

mbmakeplatform: fixed bug that caused core dumps when built with gcc.

@@ -4048,7 +4082,7 @@

5.5.2283 (October 23, 2016)

mbprocess: fixed correction of sidescan and amplitude data using topographic grid so that the correction is actually calculated and applied.

-

5.5.2282 (August 25, 2016)

+

5.5.2282 (August 25, 2016)

Mbnavadjustmerge: Added --set-ties-xyonly-by-time=timethreshold option.

@@ -4058,7 +4092,7 @@

5.5.2282 (August 25, 2016)

Mbedit: Changed behavior so that using the slider to change the number of pings viewed also changes the number of pings to step proportionately.

-

5.5.2281 (August 7, 2016)

+

5.5.2281 (August 7, 2016)

Mbnavadjustmerge: Added --unset-skipped-crossings-by-block=survey1/survey2 and --unset-skipped-crossings-between-surveys options, and made the @@ -4068,7 +4102,7 @@

5.5.2281 (August 7, 2016)

Mbclean: Added option to flag outer beams and/or unflag inner beams by acrosstrack distance (-Y option).

-

5.5.2279 (July 8, 2016)

+

5.5.2279 (July 8, 2016)

Bathymetry editing (mbedit, mbeditviz, mbclean, mbareaclean): fixed problem in which mbprocess failed to successfully apply new edits generated using mbeditviz @@ -4078,13 +4112,13 @@

5.5.2279 (July 8, 2016)

Mbm_grdtiff: Added support for image display program feh.

-

5.5.2278 (July 1, 2016)

+

5.5.2278 (July 1, 2016)

Mbkongsbergpreprocess (Formats 58 & 59): Fixed modification of pngxducerdepth value to not include lever arms or heave, as SIS records sensor depth value in height datagrams that are already compensated for lever arms and heave.

-

5.5.2277 (June 25, 2016)

+

5.5.2277 (June 25, 2016)

Mbmxyplot, mbmgrdplot: fixed problem generating plots using linear axes. Recent changes to GMT cause gmt mapproject to generate an error when passed non-map @@ -4118,7 +4152,7 @@

5.5.2277 (June 25, 2016)

lidar data. This filter is accessible from the "action" menu of the 3D sounding window.

-

5.5.2276 (May 31, 2016)

+

5.5.2276 (May 31, 2016)

MBeditviz: Added algorithm to flag isolated soundings by analyzing the 3D distribution of currently selected soundings. Soundings are flagged in voxels @@ -4132,7 +4166,7 @@

5.5.2276 (May 31, 2016)

Format 231 (MBF_3DDEPTHP): Now handles files with broken data records a bit more gracefully.

-

5.5.2275 (May 17, 2016)

+

5.5.2275 (May 17, 2016)

MBnavadjust: Fixed display of navigation in visualization view. Fixed overwriting of zoffsetwidth value when projects are read in. Fixed autopicking when view mode @@ -4145,7 +4179,7 @@

5.5.2275 (May 17, 2016)

General: Fixed several warnings generated by the new gcc version in Ubuntu 16.

-

5.5.2274 (May 5, 2016)

+

5.5.2274 (May 5, 2016)

Configure.cmd and "How to Get" web page: Updated with instructions for installing in Ubuntu, including Ubuntu 16.04.

@@ -4169,7 +4203,7 @@

5.5.2274 (May 5, 2016)

Many source files: Fixed a number of warnings related to typing and prototyping issues.

-

5.5.2271 (April 1, 2016)

+

5.5.2271 (April 1, 2016)

MBnavadjust: Added numbers of crossings and ties to the table listing of survey-vs-survey blocks.

@@ -4177,7 +4211,7 @@

5.5.2271 (April 1, 2016)

Formats 58 and 59 (MBFEM710RAW & MBFEM710MBA): added EM850 to supported third generation Kongsberg multibeams.

-

5.5.2270 (March 24, 2016)

+

5.5.2270 (March 24, 2016)

MBnavadjust: Now plots ties within missions (surveys) in dark blue and ties between mission in light blue in the bathymetry visualization.

@@ -4186,7 +4220,7 @@

5.5.2270 (March 24, 2016)

of a 1.2 safety factor to ensure the new Mapping AUV always makes it to the surface before timing out.

-

5.5.2269 (March 23, 2016)

+

5.5.2269 (March 23, 2016)

MBkongsbergpreprocess, and formats 58 (MBFEM710RAW) and 59 (MBFEM710MBA) for current generation Kongsberg multibeam data: Changed so that the default source @@ -4205,7 +4239,7 @@

5.5.2269 (March 23, 2016)

beam edit code so that no attempt is made to sort zero length arrays of beam flags.

-

5.5.2268 (March 14, 2016)

+

5.5.2268 (March 14, 2016)

Mbnavadjust: Added integrated mbgrdviz-style visualization of the bathymetry in an Mbnavadjust project. Users can select crossings or ties by clicking on the @@ -4227,7 +4261,7 @@

5.5.2268 (March 14, 2016)

dataset collected on the R/V Ewing and available at the archive formally known as NGDC.

-

5.5.2267 (February 11, 2016)

+

5.5.2267 (February 11, 2016)

Mbeditviz: Added capability to do automated optimization for bias parameters from the 3D soundings view. Optimization options are accessed from the "Action" @@ -4245,7 +4279,7 @@

5.5.2267 (February 11, 2016)

Documentation: Corrected instructions for building MB-System on Ubuntu machines.

-

5.5.2264 (February 4, 2016)

+

5.5.2264 (February 4, 2016)

Mbgrid, mbmdslnavfix, mbmgrd2arc, mbmgrd3dplot, mbmgrdplot, mbmgrdtiff, mbmhistplot, mgmplot, mbmutm, mbm_xyplot: Replaced call to "grdinfo" with @@ -4260,7 +4294,7 @@

5.5.2264 (February 4, 2016)

MBnavadjustmerge: Enabled exporting and importing lists of ties.

-

5.5.2263 (January 7, 2016)

+

5.5.2263 (January 7, 2016)

Formats 58 (MBFEM710RAW) and 59 (MBFEM710MBA) for current generation Kongsberg multibeam data: Fixed problems handling tide correction and applying heave when @@ -4297,7 +4331,7 @@

5.5.2263 (January 7, 2016)

--platform-start-time=yyyy/mm/dd/hh/mm/ss.ssssss --platform-end-time=yyyy/mm/dd/hh/mm/ss.ssssss

-

5.5.2259 (October 27, 2015)

+

5.5.2259 (October 27, 2015)

Mbpreprocess: Now called format-specific preprocess function if available and applied generic preprocessing otherwise. The first format specific preprocessing @@ -4313,7 +4347,7 @@

5.5.2259 (October 27, 2015)

Mbeditviz: Fixed application of time latency to sonardepth.

-

5.5.2258 (October 5, 2015)

+

5.5.2258 (October 5, 2015)

Mbnavadjust: Added output of route files including all unfixed ties for each survey and all crossings for each survey.

@@ -4335,7 +4369,7 @@

5.5.2258 (October 5, 2015)

sometimes there are abrupt shifts in the ping time stamps for one to three pings. This mode detects and corrects these time tears.

-

5.5.2257 (September 1, 2015)

+

5.5.2257 (September 1, 2015)

Mbpreprocess: Using platform functions to handle sensor offsets. Read platform file or command line offsets and calculate sensor offsets. Updated bathymetry @@ -4347,7 +4381,7 @@

5.5.2257 (September 1, 2015)

DEEGREES inputs/outputs on mbio/mb
platformmath. Fixed bug on mbplatform_lever.

-

5.5.2256 (August 24, 2015)

+

5.5.2256 (August 24, 2015)

Mbeditviz: Improved the way to handle sensor offsets. Improved mbeditvizapplytimelag the way to handle angles corrections. Cleaned @@ -4357,7 +4391,7 @@

5.5.2256 (August 24, 2015)

mbplatformmathattitudeoffsetcorrectedbynav and mbplatformmathattituderotatebeam to handle sensor offset corrections.

-

5.5.2255 (August 11, 2015)

+

5.5.2255 (August 11, 2015)

Mbnavadjust: Set limits on application of smoothing via penalizing the first and second derivatives of the navigation pertuturbation (particularly the @@ -4368,7 +4402,7 @@

5.5.2255 (August 11, 2015)

Mbprocess: Fixed problem with handling of sensor depth changes due to tide correction or lever arm correction.

-

5.5.2254 (July 23, 2015)

+

5.5.2254 (July 23, 2015)

Autotools build system: Disabled dist and distclean targets in the makefiles produced by the configure script. We do not use the autotools system to @@ -4386,12 +4420,12 @@

5.5.2254 (July 23, 2015)

mbio/mb
platform_math.c to the archive. This source file includes math functions to calculate angular offsets.

-

5.5.2252 (July 1, 2015)

+

5.5.2252 (July 1, 2015)

Mbedit, mbnavedit, mbnavadjust, mbvelocitytool: Fix X11 font initialization problem created in the 2251 commit.

-

5.5.2251 (June 30, 2015)

+

5.5.2251 (June 30, 2015)

Mblist, mbnavlist, mbctdlist: Changed time outputs so that decimal second values will be formatted according to the locale (e.g. decimal delineation by @@ -4401,7 +4435,7 @@

5.5.2251 (June 30, 2015)

preprocessor defines to allow fonts to be defined using the CFLAGS environment variable.

-

5.5.2250 (June 29, 2015)

+

5.5.2250 (June 29, 2015)

Mbedit, mbnavedit, mbvelocitytool, mbgrdviz, mbeditviz: Removed call to X11 function XtSetLanguageProc() in all graphical tools. This call apparently @@ -4422,7 +4456,7 @@

5.5.2250 (June 29, 2015)

is the same, but now the navigation (or trajectory) of the processed files is corrected in addition to the bathymetry.

-

5.5.2249 (June 26, 2015)

+

5.5.2249 (June 26, 2015)

Format 121 (MBF_GSFGENMB): Kluge added to the GSF format i/o module to handle beam angles incorrectly constructed so that angles from vertical are negative @@ -4439,18 +4473,18 @@

5.5.2249 (June 26, 2015)

Mb7kpreprocess: initial implementation using the new platform file and structure definitions.

-

5.5.2248 (May 31, 2015)

+

5.5.2248 (May 31, 2015)

Mbgrdviz and mbview: Fixed casts between int and pointer that seem to be responsible for mbgrdviz crashes.

-

5.5.2247 (May 29, 2015)

+

5.5.2247 (May 29, 2015)

General: Cleaned up missing function prototypes through much of the codebase (excepting externally written libraries gsf, sapi, bsio) in an effort to fix crashes of mbgrdviz and other programs.

-

5.5.2246 (May 27, 2015)

+

5.5.2246 (May 27, 2015)

Mbswath, mbcontour, mbgrdtiff: Updated GMT5 header files in src/gmt to enable building on Ubuntu Linux, CentOs Linux, and CygWin while maintaining @@ -4459,16 +4493,16 @@

5.5.2246 (May 27, 2015)

Mbedit, mbnavedit, mbvelocitytool, mbgrdviz, mbeditviz: Incomplete tweaks to font handling to enable use of fonts other than Helvetica, Times, and Courier.

-

5.5.2243 (May 22, 2015)

+

5.5.2243 (May 22, 2015)

Rewrote the configure.ac file to fix logic flaws in the configure script.

-

5.5.2242 (May 16, 2015)

+

5.5.2242 (May 16, 2015)

Mbswath, mbcontour, mbgrdtiff: Updated files in src/gmt for compatibility with GMT 5.1.2.

-

5.5.2241 (May 12, 2015)

+

5.5.2241 (May 12, 2015)

Format 59 (MBF_EM710MBA): Fixed flag causing erroneous warning that beam flags are not supported for this format (beam flags are supported).

@@ -4476,13 +4510,13 @@

5.5.2241 (May 12, 2015)

Many source files: further changes to precompiler directives suggested by Joaquim Luis in order to enable building under Windows.

-

5.5.2240 (May 8, 2015)

+

5.5.2240 (May 8, 2015)

Format 241 (MBF_WASSPENL): Fixed recognition of *.nwsf suffix.

Mbclean: fixed bug in beam position calculation identified by Joaquim Luis.

-

5.5.2239 (May 6, 2015)

+

5.5.2239 (May 6, 2015)

Format 241 (MBF_WASSPENL): Now supports WASSP multibeam data conforming to the WASSP ICD 2.4. MB-System is storing beam flags in unused bytes in the @@ -4506,7 +4540,7 @@

5.5.2239 (May 6, 2015)

Build system: Fixed bug that caused configure to fail if netCDF has a pkg-config installation while GMT5 is in a specified but nonstandard location.

-

5.5.2238 (April 15, 2015)

+

5.5.2238 (April 15, 2015)

Mbnavadjust: Recast and improved the inversion. Added a "perturbation" model display which does not include the average offsets between the individual surveys @@ -4521,12 +4555,12 @@

5.5.2238 (April 15, 2015)

Mbbackangle: Fixed mbm_grdplot call to no longer use an obsolete option.

-

5.5.2237 (March 23, 2015)

+

5.5.2237 (March 23, 2015)

Mbnavadjust, mbnavedit: Removed references to GMT and netCDF in the Makefile.am file in both source directories.

-

5.5.2236 (March 23, 2015)

+

5.5.2236 (March 23, 2015)

Mbnavadjust, mbnavadjustmerge: Added a new type of constraint referred to as a global tie. Each data section can have one of its navigation points tied to @@ -4555,7 +4589,7 @@

5.5.2236 (March 23, 2015)

Mbm_route2mission: Added multibeam maximum range value.

-

5.5.2234 (March 5, 2015)

+

5.5.2234 (March 5, 2015)

Plot macros (mbmgrdplot, mbmgrd3dplot, mbmgrdtiff, mbmhistplot, mbmplot, mbmxyplot): Now generate plotting scripts that will not attempt to display the @@ -4577,7 +4611,7 @@

5.5.2234 (March 5, 2015)

Mbprocess: Reduced informational output when not in verbose mode to make the output from use of mbm_multiprocess cleaner.

-

5.5.2233 (February 23, 2015)

+

5.5.2233 (February 23, 2015)

Release 5.5.2233

@@ -4587,7 +4621,7 @@

5.5.2233 (February 23, 2015)

Mbmroute2mission: Now allows the maximum planned climb rate of the AUV to be specified with the -U option

-

5.5.2232 (February 21, 2015)

+

5.5.2232 (February 21, 2015)

Mbmplot, mbmgrdplot, mbm_grd3dplot, mbhistplot: Changed handling of gmt defaults so that any local gmt.conf file is deleted before any gmtset calls are made, and @@ -4596,14 +4630,14 @@

5.5.2232 (February 21, 2015)

Mbswath: fixed calculation of beam or pixel footprints in mode requesting real footprint plotting.

-

5.5.2231 (February 20, 2015)

+

5.5.2231 (February 20, 2015)

Mb7kpreprocess: Switched beam angle calculation to the mb_beaudoin() function already used by mbkongsbergpreprocess (contributed by Jonathan Beaudoin).

Mbm_bpr: Made compatible with GMT5.

-

5.5.2230 (February 18, 2015)

+

5.5.2230 (February 18, 2015)

Mbgrdtiff: Fixed ordering of rows and columns in the output image.

@@ -4620,7 +4654,7 @@

5.5.2230 (February 18, 2015)

Mbrolltimelag: Fixed automatically generated roll-slope correlation plot.

-

5.5.2229 (February 14, 2015)

+

5.5.2229 (February 14, 2015)

Format 121 (MBF_GSFGENMB): The i/o module will now allocate and initialize arrays of beamflags and alongtrack distance when those are not included in the input file.

@@ -4636,7 +4670,7 @@

5.5.2229 (February 14, 2015)

Mbcontour, mbswath: More changes for compatibility with GMT5.

-

5.5.2228 (February 6, 2015)

+

5.5.2228 (February 6, 2015)

Installmakefiles: the old installmakefiles build system no longer functions and has been removed.

@@ -4659,7 +4693,7 @@

5.5.2228 (February 6, 2015)


-

MB-System Version 5.4 Releases and Release Notes:

+

MB-System Version 5.4 Releases and Release Notes:


@@ -4722,7 +4756,7 @@

MB-System Version 5.4 Releases and Release Notes:


-

5.4.2219 (December 11, 2014)

+

5.4.2219 (December 11, 2014)

Mbnavadjust: Fixed fixed memory management issue related to fbt files.

@@ -4730,11 +4764,11 @@

5.4.2219 (December 11, 2014)

Mbpreprocess: Moved toward correct handling of sensor offsets.

-

5.4.2218 (December 4, 2014)

+

5.4.2218 (December 4, 2014)

Mbinfo: Fixed JSON format output to file (previously missed final closing bracket).

-

5.4.2217 (December 1, 2014)

+

5.4.2217 (December 1, 2014)

Mbclean: Implemented additional flagging tests contributed by Suzanne O'Hara, including speed range (-Pspeedmin/speedmax), ping navigation bounds @@ -4745,7 +4779,7 @@

5.4.2217 (December 1, 2014)

Format 71 (MBF_MBLDEOIH) and fbt files: fixed a problem with the i/o module as updated in 5.4.2216.

-

5.4.2216 (November 30, 2014)

+

5.4.2216 (November 30, 2014)

Format 251 (MBF_PHOTGRAM): We have added a new data format and associated data system supporting photogrammetric topography calculated from stereo pair @@ -4794,7 +4828,7 @@

5.4.2216 (November 30, 2014)

General: The sort function and related comparison function declarations in MB-System have been corrected to be consistent with qsort() from stdlib.

-

5.4.2213 (November 13, 2014)

+

5.4.2213 (November 13, 2014)

Mbkongsbergpreprocess: Added -E option to allow specification of offsets between the depth sensor and the sonar. This is relevant only to submerged platforms @@ -4809,7 +4843,7 @@

5.4.2213 (November 13, 2014)

Mbnavedit: Strictly define the font definitions for pushbutton widgets (some X11 environments are making bad choices when given latitude).

-

5.4.2210 (November 10, 2014)

+

5.4.2210 (November 10, 2014)

Mbkongsbergpreprocess: Changed handling of water column records. The default behavior is now to not write water column records to the output format 59 files. @@ -4829,7 +4863,7 @@

5.4.2210 (November 10, 2014)

Mbm_grdcut: Fix to the manual page. Contributed by Jenny Paduan.

-

5.4.2209 (November 4, 2014)

+

5.4.2209 (November 4, 2014)

MBnavadjustmerge: Completed the manual page for this new program that allows one to merge and manipulate MBnavadjust projects.

@@ -4837,7 +4871,7 @@

5.4.2209 (November 4, 2014)

Formats 58 (MBFEM710RAW) and 59 (MBFEM710MBA): Recast the i/o architecture to handle the full variablity of multibeam data in these formats.

-

5.4.2208 (October 29, 2014)

+

5.4.2208 (October 29, 2014)

Mbkongsbergpreprocess: Fixed calculation of beam takeoff angles for raytracing from the raw range and angle data records by @@ -4854,7 +4888,7 @@

5.4.2208 (October 29, 2014)

bathymetry in current generation Kongsberg multibeam data appears to work now.

-

5.4.2204 (September 5, 2014)

+

5.4.2204 (September 5, 2014)

Mb7kpreprocess: Changed handling of roll, pitch, and heave compensation to deal with deep water Reson 7150 data.

@@ -4871,7 +4905,7 @@

5.4.2204 (September 5, 2014)

Mbgrdviz and Mbeditviz: Default color and shading settings now can be set using mbdefaults.

-

5.4.2202 (August 25, 2014)

+

5.4.2202 (August 25, 2014)

Format 88 (MBF_RESON7KR): Enlarged the maximum number of beams to 1024 in order to handle 7150 data with >800 beams.

@@ -4880,7 +4914,7 @@

5.4.2202 (August 25, 2014)

lines before parsing - this allows reading Hydrosweep DS data in the form held by NIO.

-

5.4.2201 (August 20, 2014)

+

5.4.2201 (August 20, 2014)

Mbm_grdplot: Added two "sealevel" color palletes that use Haxby colors for negative values (e.g. topography below sea level) and either greens or browns @@ -4898,12 +4932,12 @@

5.4.2201 (August 20, 2014)

Mb7kpreprocess: Added kluge function to "tweak" the beam angles as if the speed of sound used for beamforming had been wrong.

-

5.4.2200 (July 24, 2014)

+

5.4.2200 (July 24, 2014)

Format 121 (MBF_GSFGENMB): Fixed bug in which null sensor depth and altitude values are handled incorrectly.

-

5.4.2199 (July 20, 2014)

+

5.4.2199 (July 20, 2014)

Format 121 (MBFGSFGENMB): Modified GSF 3.06 source files gsf.c gsfindx.c to disable recasting of fundamental file io functions (fopen(), fseek(), ftell(), @@ -4917,7 +4951,7 @@

5.4.2199 (July 20, 2014)

mbpreprocess: Fixed bug in merging of asynchronous attitude data. This program is not ready for general use.

-

5.4.2196 (July 14, 2014)

+

5.4.2196 (July 14, 2014)

mbotps: Added -P option to specify the location of the OTPS package.

@@ -4930,7 +4964,7 @@

5.4.2196 (July 14, 2014)

mbextractsegy: Made to work (again) with Reson 7k data with embedded Edgetech sidescan and subbottom data.

-

5.4.2195 (July 9, 2014)

+

5.4.2195 (July 9, 2014)

Format 88 (MBFRESON7KR): Fixed bug in mbsysreson7kextractaltitude().

@@ -4948,7 +4982,7 @@

5.4.2195 (July 9, 2014)

often on a 3D seafloor topographic model. Achieved functionality, at least for use with Edgetech sidescan data in Jstar format.

-

5.4.2194 (July 8, 2014)

+

5.4.2194 (July 8, 2014)

Format 121 (MBF_GSFGENMB): Updated source files in src/gsf/ to GSF release 3.06.

@@ -4958,12 +4992,12 @@

5.4.2194 (July 8, 2014)

Formats 58 (MBFEM710RAW) and 59 (MBFEM710MBA) to support EM2040D data, in which dual sonars ping simulatneously.

-

5.4.2191 (June 4, 2014)

+

5.4.2191 (June 4, 2014)

Install_makefiles: Fixed old build system so that it successfully compiles and links the new, unfinished program mbsslayout.

-

5.4.2189 (June 4, 2014)

+

5.4.2189 (June 4, 2014)

Format 121 (MBF_GSFGENMB): Fixed bug that caused programs reading GSF data to hang when the GSF file ends with a partial or corrupted data record.

@@ -4975,7 +5009,7 @@

5.4.2189 (June 4, 2014)

MB7kpreprocess: Added support for pitch stabilization in Reson 7k data.

-

5.4.2188 (May 31, 2014)

+

5.4.2188 (May 31, 2014)

Format 121 (MBF_GSFGENMB): Fixed bug that caused crashes when the GSF file contains a zero length comment.

@@ -4985,7 +5019,7 @@

5.4.2188 (May 31, 2014)

MBnavadjust: Fixed bug that reset the selected survey while doing autopicks.

-

5.4.2187 (May 28, 2014)

+

5.4.2187 (May 28, 2014)

Format 201 (MBF_HYSWEEP1): Added code to ignore bad RMB records found in some NOAA HSX data.

@@ -4998,13 +5032,13 @@

5.4.2187 (May 28, 2014)

MBnavadjustmerge: Fixed to handle projects not in the current working directory.

-

5.4.2186 (May 26, 2014)

+

5.4.2186 (May 26, 2014)

MBeditviz: Fixed interactive application of pitch bias and heading bias changes.

MBnavadjustmerge: New program to merge two existing MBnavadjust projects.

-

5.4.2185 (May 17, 2014)

+

5.4.2185 (May 17, 2014)

MBrolltimelag: Now checks for case when all beams are flagged.

@@ -5015,7 +5049,7 @@

5.4.2185 (May 17, 2014)

GSF library: Updated to new release 03.05. This release is licensed using LGPL 2.1.

-

5.4.2185 (May 11, 2014)

+

5.4.2185 (May 11, 2014)

Several programs: Fixed formatting error in printing system timetm.tvsec values.

@@ -5059,11 +5093,11 @@

5.4.2185 (May 11, 2014)

library to be the new 3.05 release. This includes for the first time a proper open source license (LGPL 2.1).

-

5.4.2184 (April 22, 2014)

+

5.4.2184 (April 22, 2014)

src/bsio/Makefile.in: Added to archive (previously mistakenly left out).

-

5.4.2183 (April 16, 2014)

+

5.4.2183 (April 16, 2014)

Many programs: Fixed handling of system time character string provided by function ctime() to prevent occasional overflows.

@@ -5075,7 +5109,7 @@

5.4.2183 (April 16, 2014)

(format id 222) contributed by David Finlayson. This was formerly known as mbsxppreprocess.

-

5.4.2182 (April 8, 2014)

+

5.4.2182 (April 8, 2014)

Format 231 (MBF_3DDEPTHP): Added new raw Lidar record to be used by 3DatDepth.

@@ -5086,14 +5120,14 @@

5.4.2182 (April 8, 2014)

that interpolates navigation and speed from internal runnings lists assuming the navigation is in eastings and northings rather than longitude and latitude.

-

5.4.2181 (April 4, 2014)

+

5.4.2181 (April 4, 2014)

Release 5.4.2181

htmlsrc/mbsystemhome.html & htmlsrc/mbsystemfaq.html: Actually committed pictures of Christian Ferreira and Krystle Anderson to the archive

-

5.4.2180 (April 2, 2014)

+

5.4.2180 (April 2, 2014)

htmlsrc/mbsystemhome.html & htmlsrc/mbsystemfaq.html: Updated references to the MB-System team in the html documentation to include Christian Ferreira @@ -5129,11 +5163,11 @@

5.4.2180 (April 2, 2014)

MBroutetime: Now exits with error message if no start line or end line waypoints are read from the input route file.

-

5.4.2176 (March 18, 2014)

+

5.4.2176 (March 18, 2014)

Release 5.4.2176

-

5.4.2175 (March 18, 2014)

+

5.4.2175 (March 18, 2014)

Configure.ac: Removed reference to src/mbsvptool (src/mbsvptool/mbsvptool.c was moved to src/utilities/mbsvpselect.c for 5.4.2173).

@@ -5157,7 +5191,7 @@

5.4.2175 (March 18, 2014)

All source files: Updated copyright notices to 2014.

-

5.4.2173 (March 17, 2014)

+

5.4.2173 (March 17, 2014)

MBsvpselect: Added program contributed by Ammar Aljuhne and Christian Ferreira of MARUM (University of Bremen). This program chooses and implements the best @@ -5173,7 +5207,7 @@

5.4.2173 (March 17, 2014)

MBpreprocess: Added an incomplete manual page for this incomplete MB-System 6 program.

-

5.4.2172 (March 14, 2014)

+

5.4.2172 (March 14, 2014)

MBmosaic: Added option to apply priorities based on the platform heading.

@@ -5207,15 +5241,15 @@

5.4.2172 (March 14, 2014)

underway geophysical data files with tab delimiters and "\r\n" characters at the ends of the data records.

-

5.4.2168 (February 19, 2014)

+

5.4.2168 (February 19, 2014)

Mbinfo: Fixed bug in variance calculation (memory overwrites of the relevant arrays).

-

5.4.2165 (February 18, 2014)

+

5.4.2165 (February 18, 2014)

Format 241 (MBF_WASSPENL): Made format suffix ".000" recognizable as format 241.

-

5.4.2164 (February 15, 2014)

+

5.4.2164 (February 15, 2014)

Format 241 (MBF_WASSPENL): added new format for WASSP multibeam sonar.

@@ -5226,7 +5260,7 @@

5.4.2164 (February 15, 2014)

Mbauvloglist: added capability to merge navigation from external files.

-

5.4.2163 (January 31, 2014)

+

5.4.2163 (January 31, 2014)

Format 71 (MBF_MBLDEOIH): fixed a recently introduced error in scaling of bathymetry values. This error impacts the fbt files, and consequently will @@ -5236,7 +5270,7 @@

5.4.2163 (January 31, 2014)

MBextractsegy: Fixed so correct navigation is inserted in both the source and group position fields in the segy traceheader.

-

5.4.2162 (January 24, 2014)

+

5.4.2162 (January 24, 2014)

Format 88 (MBF_RESON7KR): fixed crash when generating sidescan from pings with no valid beams.

@@ -5244,22 +5278,22 @@

5.4.2162 (January 24, 2014)

Build system: Altered so the configure script works with standard options.

-

5.4.2161 (January 21, 2014)

+

5.4.2161 (January 21, 2014)

MBedit: fixed use of beamflag setting macros that were messed up yesterday.

-

5.4.2160 (January 20, 2014)

+

5.4.2160 (January 20, 2014)

General: fixed many compiler warnings.

General: implemented changes suggested by Joaquim Luis in order to enable building MB-System on Windows systems.

-

5.4.2159 (January 18, 2014)

+

5.4.2159 (January 18, 2014)

Release 5.4.2159.

-

5.4.2158 (January 18, 2014)

+

5.4.2158 (January 18, 2014)

Many changes, including: - Support for new format of lidar data @@ -5274,7 +5308,7 @@

5.4.2158 (January 18, 2014)

- using --disable-gsf now works properly to build without any use of or entanglement with libgsf.

-

5.4.2157 (October 14, 2013)

+

5.4.2157 (October 14, 2013)

Mbm_makesvp: New macro to extract sound speed and depth data from a datalist of swath files, and generate a sound velocity profile model from averages of the @@ -5283,7 +5317,7 @@

5.4.2157 (October 14, 2013)

mapping data from submerged platforms (e.g. ROVs and AUVs) carrying CTD or sound speed sensors.

-

5.4.2155 (October 13, 2013)

+

5.4.2155 (October 13, 2013)

MBvelocitytool: Fixed problems with bad calculations after loading more than one swath data.

@@ -5299,7 +5333,7 @@

5.4.2155 (October 13, 2013)

from a specified dataset. There is no documentation yet as the program currently does nothing but compile and read data.

-

5.4.2154 (September 26, 2013)

+

5.4.2154 (September 26, 2013)

MBkongsbergpreprocess, MB7kpreprocess, MBhysweeppreprocess, mbprocess: Fixed errors in navigation interpolation introduced in 5.4.2152.

@@ -5308,11 +5342,11 @@

5.4.2154 (September 26, 2013)

Committed from CCGS Sir Wilfrid Laurier at 116d 04.4876' W, 68d 57.30' N.

-

5.4.2153 (September 22, 2013)

+

5.4.2153 (September 22, 2013)

Format 201 (Hysweep HSX): fixed sign error in handling of pitch values.

-

5.4.2152 (September 16, 2013)

+

5.4.2152 (September 16, 2013)

Formats 58 (Kongsberg raw), 59 (Kongsberg extended), 88 (Reson 7k): Fixed problem with interpolation of heading for Kongsberg and Reson data. @@ -5326,7 +5360,7 @@

5.4.2152 (September 16, 2013)

Build system: Applied patch contributed by Frank Delahoyde with additional fixes to configure.ac and the src/*/Makefile.am files.

-

5.4.2151 (September 12, 2013)

+

5.4.2151 (September 12, 2013)

Many *.c files: hundreds of small changes to eliminate compiler warning messages on various types of systems.

@@ -5334,23 +5368,23 @@

5.4.2151 (September 12, 2013)

Build system: Changes to configure.ac, autogen.sh, and src/*/Makefile.am files based on suggestions from Frank Delahoyde of SIO and Kurt Schwehr of Google.

-

5.4.2149 (September 2, 2013)

+

5.4.2149 (September 2, 2013)

Src directories src/mbio and src/utilities: Fixed a number of debug print statements that treated pointer values as %ul rather than %p.

-

5.4.2148 (August 28, 2013)

+

5.4.2148 (August 28, 2013)

Buildsystem: More tweaking of configure.ac file, including making the comments output more sensible.

-

5.4.2147 (August 27, 2013)

+

5.4.2147 (August 27, 2013)

Buildsystem: More tweaking of configure.in file trying to get MB-System to build on Ubuntu 12.04.02LTS. Moved configure.in to configure.ac to conform to current autoconf file naming conventions.

-

5.4.2144 (August 26, 2013)

+

5.4.2144 (August 26, 2013)

Buildsystem: Added src/mbgrdviz/Makefile.in and src/mbeditviz/Makefile.in to the subversion source archive.

@@ -5363,23 +5397,23 @@

5.4.2144 (August 26, 2013)

Format 121 (GSF): Now recognizes and appropriately treats null values for position, attitude, speed, and sonar depth.

-

5.4.2143 (August 24, 2013)

+

5.4.2143 (August 24, 2013)

MBsxppreprocess: Added nonfunctional stub for program mbsxppreprocess to be developed by David Finlayson.

-

5.4.2141 (August 24, 2013)

+

5.4.2141 (August 24, 2013)

Build system, MBgrdviz, MBeditviz, MBview: Moved source files for MBgrdviz and MBeditviz from src/mbview to src/mbgrdviz and src/mbeditviz, respectively. This move separates the application source files for MBgrdviz and MBeditviz from the source files of the mbview library.

-

5.4.2139 (August 19, 2013)

+

5.4.2139 (August 19, 2013)

Build system: Further modification to the src/mbview/Makefile.am file.

-

5.4.2138 (August 18, 2013)

+

5.4.2138 (August 18, 2013)

Build system: Further modifications to the Makefile.am files.

@@ -5391,26 +5425,26 @@

5.4.2138 (August 18, 2013)

MBgrdviz: Added capability to launch mbnavedit and mbvelocitytool on selected swath data (contributed by Christian Ferreira).

-

5.4.2137 (August 9, 2013)

+

5.4.2137 (August 9, 2013)

Build system: Still attempting to fix problems with the autoconf build system on Ubuntu machines. Change mbsystem/src/opts/Makefile.am so that building this utility does not depend on GMT libraries (since it doesn't).

-

5.4.2136 (August 8, 2013)

+

5.4.2136 (August 8, 2013)

Build system: Attempted to fix problems with the autoconf build system on Ubuntu machines. Reset the automake version to 2.65 from 2.69 as specified in the mbsystem/configure.in file. Also added a conditional reference to libmbgsf to the requirements for mbcopy in mbsystem/src/utilities/Makefile.am.

-

5.4.2135 (August 7, 2013)

+

5.4.2135 (August 7, 2013)

Mbdatalist: Fixed generation of old-format fbt files.

Web page documentation: Updated basic web pages included in the distribution.

-

5.4.2134 (July 31, 2013)

+

5.4.2134 (July 31, 2013)

Heading and nav interpolation (src/mbaux/mbspline.c): Fixed function mblinearinterpdegrees() so that negative latitude values are allowed.

@@ -5418,7 +5452,7 @@

5.4.2134 (July 31, 2013)

Mbkongsbergpreprocess: Added checking so that interpolated heading and navigation are in the correct domains.

-

5.4.2133 (July 29, 2013)

+

5.4.2133 (July 29, 2013)

Heading and nav interpolation (src/mbaux/mbspline.c): Modified function mblinearinterpdegrees() so that return values must be in the range @@ -5433,7 +5467,7 @@

5.4.2133 (July 29, 2013)

using software other than MB-System) using mbgetesf and then applied to a different set of files (presumably as part of MB-System processing).

-

5.4.2132 (July 26, 2013)

+

5.4.2132 (July 26, 2013)

Format 88 (Reson s7k): Fixed layout of snippet backscatter into sidescan in the near-nadir region.

@@ -5457,7 +5491,7 @@

5.4.2132 (July 26, 2013)

records was flipped port to starboard. Also fixed layout of backscatter in the near-nadir region.

-

5.4.2129 (July 8, 2013)

+

5.4.2129 (July 8, 2013)

Build system: Attempted to implement changes to the build system suggested by Kurt Schwehr and Hamish Bowman.

@@ -5478,7 +5512,7 @@

5.4.2129 (July 8, 2013)

rays without rounding errors producing a square root of a negative number. This fixed problems with sample EM1002 data.

-

5.4.2128 (June 18, 2013)

+

5.4.2128 (June 18, 2013)

Mblist: Fixed bug that flagged as bad all sidescan pixels with negative values.

@@ -5502,7 +5536,7 @@

5.4.2128 (June 18, 2013)

interpolation, but once again does the primary interpolation stage at full resolution.

-

5.4.2123 (June 10, 2013)

+

5.4.2123 (June 10, 2013)

Many changes implementing fixes to the new build system from Bob Covill, Hamish Bowman, and Christian Ferreira. Moved key auto-generated header file @@ -5520,7 +5554,7 @@

5.4.2123 (June 10, 2013)

Changed the header of the mbm_* perl macros to #!/usr/bin/env perl as suggested by Hamish Bowman and Kurt Schwehr.

-

5.4.2082 (May 24, 2013)

+

5.4.2082 (May 24, 2013)

Configure.cmd: Added -DBYTESWAPPED to the recommended pre-options for the configure script on Macs.

@@ -5528,7 +5562,7 @@

5.4.2082 (May 24, 2013)

MBFEM710RAW (format 58) and MBFEM710MBA (format 59): Added EM2045 to the list of supported Kongsberg multibeam sonars (also known as the EM2040D).

-

5.4.2081 (May 23, 2013)

+

5.4.2081 (May 23, 2013)

Build System: Have implemented an autotools-based build system with a configure script, following on the initial work by Bob Covill and others. @@ -5537,7 +5571,7 @@

5.4.2081 (May 23, 2013)


-

MB-System Version 5.3 Releases and Release Notes:

+

MB-System Version 5.3 Releases and Release Notes:


@@ -5576,11 +5610,11 @@

MB-System Version 5.3 Releases and Release Notes:


-

5.3.2062 (May 17, 2013)

+

5.3.2062 (May 17, 2013)

Mbprocess: Fixed a couple more mistakes on lines 5659 and 5662 in mbprocess.c.

-

5.3.2061 (May 16, 2013)

+

5.3.2061 (May 16, 2013)

Perl macros: Renamed all perl source files in mbsystem/src/macros by removing the *.pl suffix. This is another change to allow use of the GNU autotools for @@ -5588,12 +5622,12 @@

5.3.2061 (May 16, 2013)

to just copy them to the bin directory; renaming the scripts is harder to set up.

-

5.3.2060 (May 14, 2013)

+

5.3.2060 (May 14, 2013)

Mbsvplist: Added -N option to limit the number of SVP profiles that can be output. (contributed by Suzanne O'Hara)

-

5.3.2059 (May 14, 2013)

+

5.3.2059 (May 14, 2013)

Mbprocess: Fixed bug in mbprocess in which angle rotation calculations mixed degrees and radians when attitude is merged as part of an external navigation @@ -5602,7 +5636,7 @@

5.3.2059 (May 14, 2013)

Mbsvplist: Added -T option to output CSV delimited table (contributed by Suzanne O'Hara)

-

5.3.2056 (May 7, 2013)

+

5.3.2056 (May 7, 2013)

Formats 221 and 222: Added empty i/o module files to ultimately support two new formats, both handling data from SEA SWATHplus interferometric sonars: @@ -5614,7 +5648,7 @@

5.3.2056 (May 7, 2013)

mbio/mbrswplssxi.c mbio/mbrswplssxp.c

-

5.3.2055 (May 7, 2013)

+

5.3.2055 (May 7, 2013)

Many files: fixed issues that result in compiler warnings.

@@ -5628,7 +5662,7 @@

5.3.2055 (May 7, 2013)

Format 121 (GSF): Added fix from Christian Ferreira to reset the depth_corrector value to zero if necessary

-

5.3.2053 (April 4, 2013)

+

5.3.2053 (April 4, 2013)

Mb7k2ss: Fixed line breakouts so that the first line is output separate from the second.

@@ -5648,7 +5682,7 @@

5.3.2053 (April 4, 2013)

Mbdatalist: Recast the output format for the -S option. One now gets a single line of output for each file unless the -V option is also specified.

-

5.3.2051 (March 20, 2013)

+

5.3.2051 (March 20, 2013)

Formats 58 and 59 (mbf): The calculation of "sidescan" from raw backscatter samples has been improved. The sidescan can now be successfully @@ -5677,7 +5711,7 @@

5.3.2051 (March 20, 2013)

Mbm_plot: Updated macros to derive system defaults from mbdefaults.

-

5.3.2042 (March 12, 2013)

+

5.3.2042 (March 12, 2013)

MBkongsbergpreprocess: Fixed calculation of transmit time for sector subpings.

@@ -5687,18 +5721,18 @@

5.3.2042 (March 12, 2013)

MBgrdviz: Added export of routes to Hypack lnw format and to degrees + decimal minutes format.

-

5.3.2017 (March 3, 2013)

+

5.3.2017 (March 3, 2013)

Mb7k2ss: Program exits if topography grid specified but reading the file fails.

-

5.3.2016 (March 2, 2013)

+

5.3.2016 (March 2, 2013)

Mb7k2ss: Fixed plotting correlation functions.

Mbm_xyplot: Fixed handling of NaN values in input data - no longer includes NaN inputs in sorting to determine min max.

-

5.3.2015 (March 1, 2013)

+

5.3.2015 (March 1, 2013)

Format 88 (mbf_reson7kr): Fixed some debugging print statements of hexadecimal values.

@@ -5728,21 +5762,21 @@

5.3.2015 (March 1, 2013)

Format 21 (mbf_hsatlraw): Fixed failure to initialize the internal storage structure.

-

5.3.2013 (January 29, 2013)

+

5.3.2013 (January 29, 2013)

Format 94 (mbf_l3xseraw): Fixed bug causing memory faults in Linux when data with large svp records are encountered. SVP records can now have as many as 8192 entries.

-

5.3.2012 (January 25, 2013)

+

5.3.2012 (January 25, 2013)

Mbkongsbergpreprocess: Fixed bug causing seg faults on Linux

-

5.3.2011 (January 17, 2013)

+

5.3.2011 (January 17, 2013)

Format 88 (mbf_reson7kr): Removed debug messages left in by mistake

-

5.3.2010 (January 14, 2013)

+

5.3.2010 (January 14, 2013)

Format 88 (mbf_reson7kr): Fixed reporting of angular beam widths, particularly for pre-2009 data in which the alongtrack value was reported incorrectly.

@@ -5750,24 +5784,24 @@

5.3.2010 (January 14, 2013)

Mbgrid: Changed the weighted footprint algorithm to correctly use the beamwidth scaling parameter set with the -W option.

-

5.3.2009 (January 10, 2013)

+

5.3.2009 (January 10, 2013)

Format 88 (mbf_reson7kr): Fixed a bug introduced at 5.3.2004 in first-time parsing of current Reson 7k data that caused erroneous flagging of some beams.

-

5.3.2008 (January 6, 2013)

+

5.3.2008 (January 6, 2013)

-

5.3.2007 (January 5, 2013)

+

5.3.2007 (January 5, 2013)

Mbkongsbergpreprocess: Fixed -O option to direct all output to a single file. Mb7kpreprocess: Fixed -O option to direct all output to a single file.

-

5.3.2006 (January 4, 2013)

+

5.3.2006 (January 4, 2013)

Mbkongsbergpreprocess: Fixed -D option to put output files in the specified directory.

-

5.3.2005 (December 31, 2012)

+

5.3.2005 (December 31, 2012)

Mbsvplist: Added -M option to control SVP printing. If mode=0 (the default), then the first SVP of each file will be output, plus any SVP that is different from @@ -5796,7 +5830,7 @@

5.3.2005 (December 31, 2012)

Mbprocess: Altered mbprocess so that input SVP files are checked for zero thickness layers.

-

5.3.2004 (December 12, 2012)

+

5.3.2004 (December 12, 2012)

Mbsvplist: Added -S option to output surface sound speed from survey data rather

@@ -5821,7 +5855,7 @@

5.3.2004 (December 12, 2012)

Mbmosaic: Fixed azimuthal priority weighting so that directional mosaicing is more reliable.

-

5.3.2000 (November 14, 2012)

+

5.3.2000 (November 14, 2012)

Mbinfo: Changed mbinfo to gracefully handle the situation of reading a file that has no data records while the -P option is specified (gracefully means not @@ -5829,7 +5863,7 @@

5.3.2000 (November 14, 2012)

Mbmosaic: fixed bug in the use of the azimuth weighting factor.

-

5.3.1999 (November 13, 2012)

+

5.3.1999 (November 13, 2012)

Mbm_route2mission: Added multibeam pulse length as a command line argument.

@@ -5839,7 +5873,7 @@

5.3.1999 (November 13, 2012)

Format 88 (mbf_reson7kr): Fixed bug that caused seg faults with pings that have no valid soundings.

-

5.3.1998 (November 6, 2012)

+

5.3.1998 (November 6, 2012)

Mb7kpreprocess: Added -C option to apply roll bias and pitch bias during preprocessing. Fixed rotation calculations so that side-looking and up looking mapping data can be handled @@ -5858,9 +5892,9 @@

5.3.1998 (November 6, 2012)

Formats 56 (mbfem300raw) and 57 (mbfem300mba): added support for asynchronous attitude output, in particular by mbnavlist -K18.

-

5.3.1995 (October 27, 2012)

+

5.3.1995 (October 27, 2012)

-

5.3.1994 (October 27, 2012)

+

5.3.1994 (October 27, 2012)

Mbfilter: when filtering sidescan the output file now includes any bathymetry available in the original file. The bathymetry can be used by mbmosaic for calculating apparent grazing @@ -5898,7 +5932,7 @@

5.3.1994 (October 27, 2012)

factor. For instance, specifying factor = 1.1 means the grid is expanded 5% to the west, east, south and north for a total expansion of 0.1 or 10%.

-

5.3.1989 (October 4, 2012)

+

5.3.1989 (October 4, 2012)

Mbmgrdplot & mbmgrdtiff: Fixed application of strict color table bounds in mbmgrdplot and mbmgrdtiff.

@@ -5915,7 +5949,7 @@

5.3.1989 (October 4, 2012)

for a low resolution grid and then resampling this onto the desired full resolution grid using bilinear interpolation.

-

5.3.1988 (September 29, 2012)

+

5.3.1988 (September 29, 2012)

Format 71 (mbf_mbldeoih): Implemented automatic scaling of sidescan values to improve fidelity of stored values to the original values.

@@ -5940,7 +5974,7 @@

5.3.1988 (September 29, 2012)

in the 7k data file (previously these values derived from asynchronous navigation, heading, attitude, etc, records).

-

5.3.1986 (September 12, 2012)

+

5.3.1986 (September 12, 2012)

MBnavadjust now treats data from interferometric sonars different than data from other sonars. When interferometric bathymetry is imported, the many soundings @@ -5966,7 +6000,7 @@

5.3.1986 (September 12, 2012)

Added -MXexcludepercent option to mblist to exclude a user defined percentage of outer beams from mblist output. (contributed by Suzanne O'Hara)

-

5.3.1982 (August 15, 2012)

+

5.3.1982 (August 15, 2012)

Fixed significant issue in mb7kpreprocess and in Reson 7k format support in general. The code was not handling the current raw detection data records correctly.

@@ -5994,7 +6028,7 @@

5.3.1982 (August 15, 2012)

unless there is a problem.

-

5.3.1981 (August 2, 2012)

+

5.3.1981 (August 2, 2012)

Fixed problem with mbprocess in which the heading was unexpectedly replaced by course-made-good. Now this can only happen with HEADINGMODE:1 or HEADINGMODE:2 in the parameter file.

@@ -6002,7 +6036,7 @@

5.3.1981 (August 2, 2012)

Fixed error in the definition of the OMG HDCS format in mbf_omghdcsj.h This fix provided by Bob Covill.

-

5.3.1980 (July 13, 2012)

+

5.3.1980 (July 13, 2012)

Augmented support for L3 XSE format (94) so that data from recent SeaBeam 3000 and SeaBeam 3050 multibeams can be processed.

@@ -6045,7 +6079,7 @@

5.3.1980 (July 13, 2012)

horizontal. Also fixed the module so that the profile tile angle parameter is used correctly.

-

5.3.1955 (May 16, 2012)

+

5.3.1955 (May 16, 2012)

Removed ($[) = 0 initializations from all perl macros for compatibility with the current version of perl.

@@ -6100,7 +6134,7 @@

5.3.1955 (May 16, 2012)

impact of speed variations and deemphasizes data where the sonar platform moved slowly or stopped.

-

5.3.1941 (March 6, 2012)

+

5.3.1941 (March 6, 2012)

Fixed sidescan filtering with mbfilter. The filtered sidescan output in format 71 files had incorrect acrosstrack locations.

@@ -6121,7 +6155,7 @@

5.3.1941 (March 6, 2012)

Added output of raw values from current generation Kongsberg data (formats 58 and 59) to mblist.

-

5.3.1937

+

5.3.1937

Changed the resolution of navigation in fbt (format 71) files and fnv files to be 1e-9 degrees, equivalent to about 0.1 mm. Similarly change @@ -6163,7 +6197,7 @@

5.3.1937

Bug fixes to mbr_mstiffss.c related to reading Marine Sonics sidescan data. This fix provided by Val Schmidt of CCOM/JHC at University of New Hampshire.

-

5.3.1917 (January 10, 2012)

+

5.3.1917 (January 10, 2012)

Added preliminary support for HYSWEEP HSX format as MBIO format 201. Added program mbhysweeppreprocess to preprocess the HSX data.

@@ -6171,7 +6205,7 @@

5.3.1917 (January 10, 2012)

GSF 3.03 update.

-

5.3.1912 (November 19, 2011)

+

5.3.1912 (November 19, 2011)

Formats 58 and 59 (third generation Kongsberg multibeam data): Augmented code to handle bathymetry data in which beams are reported @@ -6182,7 +6216,7 @@

5.3.1912 (November 19, 2011)

Fixes to the handling of attitude ecords, particularly with regard to writing the records.

-

5.3.1909 (November 16, 2011)

+

5.3.1909 (November 16, 2011)

Program mbnavlist: Fixed attitude record output so that use of -K18, -K55, -K56, or -K57 @@ -6194,7 +6228,7 @@

5.3.1909 (November 16, 2011)

records identified as MBDATAATTITUDE1, MBDATAATTITUDE2, or MBDATAATTITUDE3.

-

5.3.1907 (November 9, 2011)

+

5.3.1907 (November 9, 2011)

Program mblist: Added output of beam bottom detection algorithm (amplitude or phase) @@ -6230,7 +6264,7 @@

5.3.1907 (November 9, 2011)

while ancillary records will be identified as MBDATAATTITUDE1 (55), MBDATAATTITUDE2 (56), or MBDATAATTITUDE3(57).

-

5.3.1906 (September 28, 2011)

+

5.3.1906 (September 28, 2011)

Program mbnavadjust: Added -D option to invert foreground (normally black) and background @@ -6476,7 +6510,7 @@

5.3.1906 (September 28, 2011)


-

MB-System Version 5.2 Releases and Release Notes:

+

MB-System Version 5.2 Releases and Release Notes:


@@ -6484,9 +6518,9 @@

MB-System Version 5.2 Releases and Release Notes:

  • Version 5.2.1880 December 30, 2010
  • -

    +

    -

    5.2.1880 (December 30, 2010)

    +

    5.2.1880 (December 30, 2010)

    Augmented mbotps to output tide in both time_d tide @@ -6523,7 +6557,7 @@

    5.2.1880 (December 30, 2010)


    -

    MB-System Version 5.1 Releases and Release Notes:

    +

    MB-System Version 5.1 Releases and Release Notes:


    @@ -6576,7 +6610,7 @@

    MB-System Version 5.1 Releases and Release Notes:


    -

    5.1.3beta1875

    +

    5.1.3beta1875

    Altered -P option in mbsvplist. Previously this option (which turns on bathymetry recalculation by raytracing in mbprocess using the water sound @@ -6621,7 +6655,7 @@

    5.1.3beta1875

    is, well, unsatisfying and wrong. The bad option is there because I took the time to code it to see how well it would work.

    -

    5.1.3beta1874

    +

    5.1.3beta1874

    The function mbgetinfo() now properly applies the lonflip value. This in turn allows mbgrid to infer correct bounds in situations where the @@ -6690,7 +6724,7 @@

    5.1.3beta1874

    Updating in preparation for beta release version 5.1.3beta1874.

    -

    5.1.3beta1862

    +

    5.1.3beta1862

    Moved src/mbaux/mbrt.c to src/mbio/mbrt.c and made this raytracing code part of libmbio rather than libmbaux.

    @@ -6728,14 +6762,14 @@

    5.1.3beta1862

    Fixed issues with a number of manual pages.

    -

    5.1.3beta1860

    +

    5.1.3beta1860

    Further changes to mbnavadjust: - The inversion stops if it is diverging rather than converging on a navigation adjustment model solution. - The program will insure that all crossings have the later section second by flipping the order of crossings if necessary while reading an old project. - The program also resorts the crossings when it reads a project.

    -

    5.1.3beta1858

    +

    5.1.3beta1858

    Slight modification to mbm_grdplot map annotation scheme (degrees + minutes for maps up to 4 degrees across where only degrees shown before for maps @@ -6761,13 +6795,13 @@

    5.1.3beta1858

    Mostly fixed handling of attitude data in bathymetry recalculation. There still seems to be a problem with handling heading data.

    -

    5.1.3beta1855

    +

    5.1.3beta1855

    Fixed error in beam angle calculation for third generation Simrad multibeam data (formats 58 and 59, EM710, EM302, EM122) that made bathymetry recalculation by raytracing badly wrong.

    -

    5.1.3beta1851

    +

    5.1.3beta1851

    Fixed problem where mb7kpreprocess made beams that should have been null valid but flagged.

    @@ -6792,13 +6826,13 @@

    5.1.3beta1851

    MBprocess. Also, MBgetesf is now used by MBeditviz to get the original beam flag state of raw swath bathymetry when processed files are read.

    -

    5.1.3beta1844

    +

    5.1.3beta1844

    Fixed yet another bug in MBnavadjust - this time getting the importation of old project files correct and, more importantly, getting the z-offset sign correct in the Naverr display.

    -

    5.1.3beta1843

    +

    5.1.3beta1843

    Updated mb7k2ss man page.

    @@ -6832,7 +6866,7 @@

    5.1.3beta1843

    MBnavadjust now outputs version 3.0 nvh project files, but will transparently read and translate earlier version nvh project files.

    -

    5.1.3beta1829

    +

    5.1.3beta1829

    From now on beta releases will be named according to the corresponding source archive revision in the MB-System Subversion source code archive. @@ -6866,11 +6900,11 @@

    5.1.3beta1829

    Changed print format for unsigned long values from %ld to %lu to avoid copious warning messages in Ubuntu.

    -

    +

    -

    MB-System Version 5.1.2 Release Notes:

    +

    MB-System Version 5.1.2 Release Notes:

    -

    +

    Fixed pixel calculation algorithm in mbmosaic. Previously, sidescan data from each pixel were being treated as extending over a @@ -6930,7 +6964,7 @@

    Changed licensing from GPL version 2 to GPL version 3.

    -

    5.1.2beta07

    +

    5.1.2beta07

    Fixed MB-System compatibility with GMT 4.5.0

    @@ -6939,7 +6973,7 @@

    5.1.2beta07

    MBgrdviz now displays ping/shot numbers when navigation is picked. MBextractsegy now embeds line numbers into the output segy files.

    -

    5.1.2beta08

    +

    5.1.2beta08

    Fixed mbauvloglist to work with all MBARI AUV logs.

    @@ -6955,7 +6989,7 @@

    5.1.2beta08

    large datasets. This locking functionality will be extended to the processing tools mbedit, mbeditviz, and mbnavedit in the future.

    -

    5.1.2beta09

    +

    5.1.2beta09

    Fixed bug in SeaBeam 2112 support that misplaced some sidescan data on little-endian machines.

    @@ -6974,7 +7008,7 @@

    5.1.2beta09

    Greatly increased speed of reading third generation Simrad data (formats 58 & 59, EM710, EM302, EM122).

    -

    5.1.2beta11

    +

    5.1.2beta11

    Fixed mb7k2ss to avoid creating shadow zones in the extracted sidescan.

    @@ -6985,7 +7019,7 @@

    5.1.2beta11

    executed in conjunction with creating ancillary files with the -O or -N options.

    -

    5.1.2beta12

    +

    5.1.2beta12

    Updated proj library to 4.7.0 release. If the installing user chooses to use the proj distributed with MB-System, then the programs proj and geod @@ -7039,7 +7073,7 @@

    5.1.2beta12

    versus time (x-axis). One PSD is calculated for each trace in the segy file. This program requires linking with the FFTW (Fastest FFT in The West) package.

    -

    5.1.2beta13

    +

    5.1.2beta13

    Fixed many more issues relating to clean compiles on 64 bit machines. In particular, store GSF and netCDF data stream id's in their own @@ -7052,20 +7086,20 @@

    5.1.2beta13

    as Windows 64 bit C has a different type model than the rest of the universe (e.g. long = 32 bit on Windows but long = 64 bit for gcc).

    -

    5.1.2beta14

    +

    5.1.2beta14

    Fixed a few more issues relating to clean compiles on 64 bit machines. We're iterating towards a working version by getting problem reports from people like Hamish Bowman, Bob Arko, and Bob Covill.

    -

    5.1.2beta15

    +

    5.1.2beta15

    Fixed EM3002 support to reliably detect whether data comes from a single or double head sonar (formats 56 & 57).

    Fixed problem with EM710 support (formats 58 & 59).

    -

    5.1.2

    +

    5.1.2

    Incorporates all changes listed above.

    @@ -7073,7 +7107,7 @@

    5.1.2


    -

    MB-System Version 5.1.1 Release Notes:

    +

    MB-System Version 5.1.1 Release Notes:


    @@ -7298,7 +7332,7 @@

    MB-System Version 5.1.1 Release Notes:


    -

    MB-System Version 5.1.0 Release Notes:

    +

    MB-System Version 5.1.0 Release Notes:


    @@ -7423,7 +7457,7 @@

    MB-System Version 5.1.0 Release Notes:


    -

    MB-System Version 5.0 Releases and Release Notes:

    +

    MB-System Version 5.0 Releases and Release Notes:


    @@ -7478,7 +7512,7 @@

    MB-System Version 5.0 Releases and Release Notes:


    -

    MB-System Version 5.0.9 Release Notes:

    +

    MB-System Version 5.0.9 Release Notes:


    @@ -7501,7 +7535,7 @@

    MB-System Version 5.0.9 Release Notes:


    -

    MB-System Version 5.0.8 Release Notes:

    +

    MB-System Version 5.0.8 Release Notes:


    @@ -7668,7 +7702,7 @@

    MB-System Version 5.0.8 Release Notes:


    -

    MB-System Version 5.0.7 Release Notes:

    +

    MB-System Version 5.0.7 Release Notes:


    @@ -7740,7 +7774,7 @@

    MB-System Version 5.0.7 Release Notes:


    -

    MB-System Version 5.0.6 Release Notes:

    +

    MB-System Version 5.0.6 Release Notes:


    @@ -7809,7 +7843,7 @@

    MB-System Version 5.0.6 Release Notes:


    -

    MB-System Version 5.0.5 Release Notes:

    +

    MB-System Version 5.0.5 Release Notes:


    @@ -7893,9 +7927,9 @@

    MB-System Version 5.0.5 Release Notes:

    Problems with the MGD77 format i/o module have been fixed according to suggestions from Bob Covill.

    -

    +

    -

    MB-System Version 5.0.4 Release Notes:

    +

    MB-System Version 5.0.4 Release Notes:


    @@ -7932,7 +7966,7 @@

    MB-System Version 5.0.4 Release Notes:


    -

    MB-System Version 5.0.3 Release Notes:

    +

    MB-System Version 5.0.3 Release Notes:


    @@ -7953,7 +7987,7 @@

    MB-System Version 5.0.3 Release Notes:


    -

    MB-System Version 5.0.2 Release Notes:

    +

    MB-System Version 5.0.2 Release Notes:


    @@ -7969,7 +8003,7 @@

    MB-System Version 5.0.2 Release Notes:


    -

    MB-System Version 5.0.1 Release Notes:

    +

    MB-System Version 5.0.1 Release Notes:


    @@ -7988,7 +8022,7 @@

    MB-System Version 5.0.1 Release Notes:


    -

    MB-System Version 5.0.0 Release Notes:

    +

    MB-System Version 5.0.0 Release Notes: