Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Common/NMEA.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/141516#include "NMEA.h"1718extern const AP_HAL::HAL &hal;1920/*21formatted print of NMEA message to an allocated string, with22checksum appended23*/24char *nmea_vaprintf(const char *fmt, va_list ap)25{26va_list ap_copy;2728// we print once to nullptr to get the length29va_copy(ap_copy, ap);30int len = hal.util->vsnprintf(nullptr, 0, fmt, ap_copy);31va_end(ap_copy);32if (len <= 0) {33// can't print this format34return nullptr;35}3637// now allocate the right length, including trailer38char *s = (char *)malloc(len+6);39if (s == nullptr) {40// allocation failed41return nullptr;42}4344if (hal.util->vsnprintf(s, len+5, fmt, ap) < len) {45free(s);46// inconsistent formatting47return nullptr;48}4950// calculate the checksum51uint8_t cs = 0;52const uint8_t *b = (const uint8_t *)s+1;53while (*b) {54cs ^= *b++;55}5657hal.util->snprintf(s+len, 6, "*%02X\r\n", (unsigned)cs);58return s;59}6061/*62formatted print of NMEA message to the port, with checksum appended63*/64bool nmea_printf(AP_HAL::UARTDriver *uart, const char *fmt, ...)65{66va_list ap;6768va_start(ap, fmt);69char *s = nmea_vaprintf(fmt, ap);70va_end(ap);71if (s == nullptr) {72return false;73}7475size_t len = strlen(s);76if (uart->txspace() < len) {77free(s);78return false;79}80uart->write((const uint8_t*)s, len);81free(s);82return true;83}848586/*87formatted print of NMEA message to a buffer, with checksum appended.88Returns the length of the string filled into buf. If the NMEA string does not fit in the buffer, returns 089*/90uint16_t nmea_printf_buffer(char* buf, const uint16_t buf_max_len, const char *fmt, ...)91{92va_list ap;9394va_start(ap, fmt);95char *s = nmea_vaprintf(fmt, ap);96va_end(ap);97if (s == nullptr) {98return 0;99}100101size_t len = strlen(s);102if (len > buf_max_len) {103// our string is larger than the buffer we've supplied.104// Instead of populating the buffer with a partial message, just quietly fail and do nothing105len = 0;106} else {107strncpy(buf, s, buf_max_len);108}109free(s);110111return len;112}113114115